场地中设定四种五个不同特点、不同难度的障碍物,每种障碍物均有一定的分值,参赛队根据比赛规则自主设计制作全地形小车,完成穿越各个障碍物的比赛。
障碍物分别为三种颜色的气球、楼梯、管道、窄桥,各障碍物由黑色引导线连接,形成完整的比赛赛道,并设置比赛起点和终点,比赛场地由组委会统一布置。
全地形小车启动后自动行驶并跨越其他三种障碍物(管道,窄桥,楼梯)后,需识别颜色板上随机色卡的颜色并扎破对应颜色气球。
(1)场地地面为 408cm×175cm(尺寸误差±3cm) 的宝丽布,四周有高度为 18cm 的围栏。场地地面设有起点线和终止线,距离边缘 90cm。部分障碍前后20cm 设有标志线,供参赛队伍参考使用。距离长边 60cm 的两条红线为装饰线。5 个 障碍物按图 1、图 2 所示种类、数量和位置安放,并以双面胶固定在场地地面上,不可移动。黑线用 3.8cm 宽低反光绝缘胶带铺设。
(2)窄桥尺寸图:
单位:cm
材料:发泡 EVA
颜色:黑色
(3)台阶尺寸图:
单位:cm
材料:发泡 EVA
颜色:黑色
(4)管道尺寸图:
单位:cm
材料:亚克力颜色:透明
(5)气球:
单位:cm
材料:橡胶
颜色:红、蓝、绿各一个
关于窄桥和台阶障碍:表面贴磨砂砂纸。
气球布置说明(其中尺寸标注±10mm):
关于气球说明:
气球颜色为:深红、深绿、深蓝
气球大小(宽):22cm和26cm之间,测量宽度方向以下图黑线示意为参考(横向最宽距离);
气球安装角度:气球横放,气嘴朝向终点线反方向,气球底面中部与场地布紧贴,气球 与场地布通过粘度较高的双面胶固定(以侧向拍打不掉落为准),气球固定位置距离气球底面中点误差±5cm;
关于扎气球的装置说明:扎气球装置末端可采用细小尖锐物体,如曲别针、图钉、牙签等,机器人上场前将对扎气球装置进行检验;
本文采用的样机是基于月球车样机改造的。在月球车样机的基础上,在四个前后轮上缠绕了履带片以增大轮径,提高越障的性能。另外,在车身上增加了一个舵机驱动的摆杆,摆杆的顶部可以安装针甚至排针,用来刺破气球。
电子模块:Arduino UNO(Basra控制板×1,Bigfish扩展板)×1,灰度传感器×3,IIC颜色识别传感器)×1
编程环境:Arduino1.8.19
函数库:ServoTimer2、Adafruit_GFX、Adafruit_NeoPixel、MH_TCS34725
本程序由4个程序文件构成,其中Hit_Ballon_Car_yeyeyeye.ino为主程序
程序源代码如下:
Hit_Ballon_Car_yeyeyeye.ino
/* *=====================================================================================================* *实验接线: | *=====================================================================================================* * 车头 * 灰度传感器: A2 A3 A4 * *----------------* * | | * | | * | | * | | 右侧 * motor | | 车轮 * 9,10 | | 5,6 * | | * | | * | | * | | * | | * *----------------* * 车尾 * 舵机接线: * 气球舵机:3 * */ #include ServoTimer2 myServo; //声明舵机 #define Forward_Left_Speed 125 //小车前进时左轮速度 #define Forward_Right_Speed 90//小车前进时右轮速度 #define Back_Left_Speed 160 //小车后退时左轮速度 #define Back_Right_Speed 110 //小车后退时右轮速度 #define Left_Left_Speed 235 //小车左转时左轮速度 #define Left_Right_Speed 240 //小车左转时右轮速度 #define Right_Left_Speed 235 //小车右转时左轮速度 #define Right_Right_Speed 240 //小车右转时右轮速度 #define Car_speed_stop 255 //小车刹车制动的速度 #define TrackingSensorNum 3 //小车寻迹时使用的灰度传感器数量 #define DEBUG //程序进入调试模式 #define Debug_Color_Card //检测色卡颜色 //#define Debug_Color_Balloon //检测气球颜色 //#define Debug_Gray_Sensor //检测灰度传感器 //#define Debug_Car_Forward //检测小车走直线 int servo_num = 1;//定义舵机数量 int servo_port = 8;//定义舵机引脚 float value_init = 5;//定义舵机初始角度 int Car_DC_Motor_Pin[4] = {9,10,5,6};//直流电机引脚 int Gray_SensorPin[3]={A4,A3,A2};//寻迹、检测路口传感器 int f = 60; //定义舵机每个状态间转动的次数,以此来确定每个舵机每次转动的角度 int motor_num = sizeof(Car_DC_Motor_Pin) / sizeof(Car_DC_Motor_Pin[0]);//定义电机数量 int Car_Head_Gray_SensorPin_Num = sizeof(Gray_SensorPin)/sizeof(Gray_SensorPin[0]);//定义gray数量 bool finish=true; int Gray_Three = 0; //记录三个灰度传感器同时触发的次数(即记录小车经过特殊路口的次数) bool finish_all = true;//判断小车是否结束比赛(true表示没有结束比赛,false表示结束比赛) int color_detection_card = 0; //记录颜色传感器识别到色卡的数值(红色为1,蓝色为2,绿色为3) int color_detection_ballon = 0; //记录颜色传感器识别到气球的数值(红色为1,蓝色为2,绿色为3) enum{Forward=1,Back,Left,Right,Stop,ForwardSpeedDown,BackSpeedDown,ForwardRoad,Tracking_automatic};//小车各种模式状态 void setup() { delay(1500);Serial.begin(9600);//打开串口并启用9600波特率 Motor_Sensor_Init();//电机及传感器引脚初始化 Servo_Init(); //舵机引脚初始化 Color_Init();delay(1000);//颜色引脚初始化 #ifdef DEBUG //判断小车是否要进入调试模式 Car_Debug_Test(); #endif } void loop() { Automatic_Tracking_analogRead(); } |
Color_detection.ino
/*********************接线方式 TCS3473x Arduino_Uno SDA A4 SCL A5 VIN 5V GND GND *************************/ #include #include "MH_TCS34725.h" //调用颜色识别传感器库函数 //颜色传感器不同通道值设置 MH_TCS34725 tcs = MH_TCS34725(TCS34725_INTEGRATIONTIME_50MS, TCS34725_GAIN_4X); //设置颜色传感器采样周期50毫秒 void Color_Init() { if (tcs.begin()) { //如果检测到颜色传感器模块 Serial.println("Found sensor"); //串口打印 Found sensor } else { //如果没有检测到颜色传感器模块 Serial.println("No TCS34725 found ... check your connections");//串口打印:没有找到颜色识别传感器模块 while (1); // halt! //程序陷入死循环 } } /* * color_judge[0] red green * color_judge[0] green red */ void return_color_ballon() { int numbers_count = 0; int color_judge[12]={0,0,0,0,0,0,0,0,0,0,0,0}; int red_summer,green_summer,blue_summer; Serial.println("---------------Start---------------"); unsigned long time_now = millis(); while( (millis() - time_now ) < 2000) { numbers_count ++; uint16_t clear, red, green, blue; tcs.getRGBC(&red, &green, &blue, &clear); if(red>=blue){color_judge[0] = color_judge[0] +1;} else{color_judge[1] = color_judge[1] +1;} if(red>=green){color_judge[2] = color_judge[2] +1;} else{color_judge[3] = color_judge[3] +1;} if(blue>=red){color_judge[4] = color_judge[4] +1;} else{color_judge[5] = color_judge[5] +1;} if(blue>=green){color_judge[6] = color_judge[6] +1;} else{color_judge[7] = color_judge[7] +1;} if(green>=red){color_judge[8] = color_judge[8] +1;} else{color_judge[9] = color_judge[9] +1;} if(green>=blue){color_judge[10] = color_judge[10] +1;} else{color_judge[11] = color_judge[11] +1;} } Serial.println(); if( (color_judge[0] > color_judge[1]) && ((color_judge[2] > color_judge[3])) ) { #ifdef DEBUG Serial.println("The color is red"); #endif color_detection_ballon = 1; } else if( (color_judge[4] > color_judge[5]) && ((color_judge[6] > color_judge[7])) ) { #ifdef DEBUG Serial.println("The color is blue"); #endif color_detection_ballon = 2; } else if( (color_judge[8] > color_judge[9]) && ((color_judge[10] > color_judge[11])) ) { #ifdef DEBUG Serial.println("The color is green"); #endif color_detection_ballon = 3; } else { #ifdef DEBUG Serial.println("None color"); #endif } } void return_color_card() { int numbers_count = 0; int color_judge[12]={0,0,0,0,0,0,0,0,0,0,0,0}; int red_summer,green_summer,blue_summer; Serial.println("---------------Start---------------"); unsigned long time_now = millis(); while( (millis() - time_now ) < 2000) { numbers_count ++; uint16_t clear, red, green, blue; tcs.getRGBC(&red, &green, &blue, &clear); if(red>=blue){color_judge[0] = color_judge[0] +1;} else{color_judge[1] = color_judge[1] +1;} if(red>=green){color_judge[2] = color_judge[2] +1;} else{color_judge[3] = color_judge[3] +1;} if(blue>=red){color_judge[4] = color_judge[4] +1;} else{color_judge[5] = color_judge[5] +1;} if(blue>=green){color_judge[6] = color_judge[6] +1;} else{color_judge[7] = color_judge[7] +1;} if(green>=red){color_judge[8] = color_judge[8] +1;} else{color_judge[9] = color_judge[9] +1;} if(green>=blue){color_judge[10] = color_judge[10] +1;} else{color_judge[11] = color_judge[11] +1;} } Serial.println(); if( (color_judge[0] > color_judge[1]) && ((color_judge[2] > color_judge[3])) ) { #ifdef DEBUG Serial.println("The color is red"); #endif color_detection_card = 1; } else if( (color_judge[4] > color_judge[5]) && ((color_judge[6] > color_judge[7])) ) { #ifdef DEBUG Serial.println("The color is blue"); #endif color_detection_card = 2; } else if( (color_judge[8] > color_judge[9]) && ((color_judge[10] > color_judge[11])) ) { #ifdef DEBUG Serial.println("The color is green"); #endif color_detection_card = 3; } else { #ifdef DEBUG Serial.println("None color"); #endif } } void color() { uint16_t clear, red, green, blue; tcs.getRGBC(&red, &green, &blue, &clear); Serial.print("red:");Serial.print(red);Serial.print(" | "); Serial.print("blue:");Serial.print(blue);Serial.print(" | "); Serial.print("green:");Serial.println(green); } |
Servo_Move_Control.ino
//===================舵机========================舵机=======================舵机=======================舵机===========================舵机==========================舵机==============================舵机==============================舵机 //====舵机===========================舵机======================舵机=======================舵机=========================舵机==========================舵机============================舵机==================================舵机============= //===================舵机========================舵机=======================舵机=======================舵机===========================舵机==========================舵机==============================舵机==============================舵机 //void Servo_Init() //{ // for(int i=0;i // { myServo[i].attach(servo_port[i]); myServo[i].write(map(value_init[i],0,180,500,2500)); delay(20); // myServo.attach(servo_port[i]); // myServo.write(map(value_init[i],0,180,500,2500)); // delay(20); // } //} void Servo_Init() { for(int i=0;i { // myServo[i].attach(servo_port[i]); // myServo[i].write(map(value_init[i],0,180,500,2500)); // delay(20); myServo.attach(servo_port); myServo.write(map(value_init,0,180,500,2500)); delay(20); } } //void ServoStop(int which){//释放舵机 // myServo[which].detach(); // digitalWrite(servo_port[which],LOW); //} void ServoStop(){//释放舵机 myServo.detach(); digitalWrite(servo_port,LOW); } //void ServoGo(int which , float where){//打开并给舵机写入相关角度 // if(where!=200){ // if(where==201) ServoStop(which); // else{ // myServo[which].write(map(where,0,180,500,2500)); // } // } //} void ServoGo(float where){//打开并给舵机写入相关角度 if(where!=200){ if(where==201) ServoStop(); else{ myServo.write(map(where,0,180,500,2500)); } } } void Servo_Move_Single(int Start_angle,int End_angle,unsigned long Servo_move_time) { int servo_flags = 0; int delta_servo_angle = abs(Start_angle-End_angle); if( (Start_angle - End_angle)<0 ) { servo_flags = 1; } else{ servo_flags = -1; } for(int i=0;i { myServo.write(map( Start_angle+(servo_flags*i) ,0,180,500,2500)); delay(Servo_move_time); } } //void servo_move(float value0, float value1, float value2,int delaytimes){ //舵机动作函数 // float value_arguments[] = {value0, value1, value2}; // float value_delta[servo_num]; // for(int i=0;i // value_delta[i] = (value_arguments[i] - value_init[i]) / f; // } // for(int i=0;i // for(int k=0;k // value_init[k] = value_delta[k] == 0 ? value_arguments[k] : value_init[k] + value_delta[k]; // } // for(int j=0;j // ServoGo(j,value_init[j]); // } // delay(delaytimes/f); // } //} void Zha_Qi_Qiu(int Numbers) { for(int i=0;i { // myServo.write(map( 130 ,0,180,500,2500));delay(350); myServo.write(map( 175 ,0,180,500,2500));delay(1000); myServo.write(map( 5 ,0,180,500,2500));delay(1000); // Servo_Move_Single(130,,2);delay(1000); // Servo_Move_Single(30,130,3);delay(1000); } } |
资料内容:全地形排爆车样机3D文件、全地形排爆车完整程序、全地形排爆车例程配套函数库、全地形爆破赛-场地制作文件(详情请参考全地形爆破赛-月球车)