机器谱

【R255月球车底盘

作者:机器谱

图文展示3264(1)(1)

图文展示3264(1)(1)

副标题

概述
全地形爆破赛
全地形赛

1.运动功能说明

      255号底盘可以通过左侧3个驱动轮和右侧3个驱动轮的 差速运动 配合来实现前进、后退、原地转向、大半径转向等基本行驶功能。由于摇臂的作用,255号机构的抓地力更强,因此具有极强的牵引能力和爬坡能力。同时摇臂和车架的悬挂,使它具有非常强的越障能力,可以在复杂的地形中行驶,甚至可以攀爬楼梯。

3.运动功能实现


3.1 电子硬件

在这个示例中,我们采用了以下硬件,请大家参考:

2.结构说明

     255号机构是一个“被动摇臂”型6轮6驱底盘,由于摇臂结构和月球车的类似(月球车一般用主动摇臂),因此也被称为月球车底盘。它有6个直流驱动轮模组 ,分别安装在两侧的摇臂上。摇臂固定在连杆组构成的悬架上,使它整体的悬挂性能特别出色。

3.2 编写程序

编程环境:Arduino 1.8.19

前进功能的代码(点击查看:Forward.ino

主控板Basra(兼容Arduino Uno)
扩展板Bigfish2.1
电池7.4V锂电池


资料清单

序号

内容
1
样机3D文件
2
例程源代码
点击打包下载


4.扩展样机

   本样机也有一些扩展,如为它增加了外观后会更像月球车。如下图所示:

5.资料下载

后退功能的代码(点击查看:Backward.ino

原地转向功能的代码(点击查看:TurnInPlace.ino

大半径转向功能的代码(点击查看:BigTurn.ino

      由于同侧的驱动轮的运动状态始终是一样的。因此同侧的3个直流电机可以通过1拖3杜邦线(可以自制)共用1个直流电机接口。先将同侧直流电机接在一条1拖3电机线上,然后在分别接在两个直流电机接口上,两个直流电机接口的针脚号分别为(D5,D6)以及(D9,D10),并将主控板和电池在车身固定好。

概述

全地形爆破赛

1. 比赛场地

      场地中设定四种五个不同特点、不同难度的障碍物,每种障碍物均有一定的分值,参赛队根据比赛规则自主设计制作全地形小车,完成穿越各个障碍物的比赛。

      障碍物分别为三种颜色的气球、楼梯、管道、窄桥,各障碍物由黑色引导线连接,形成完整的比赛赛道,并设置比赛起点和终点,比赛场地由组委会统一布置。

      全地形小车启动后自动行驶并跨越其他三种障碍物(管道,窄桥,楼梯)后,需识别颜色板上随机色卡的颜色并扎破对应颜色气球。

图 1:场地整体图

(1)场地地面为 408cm×175cm(尺寸误差±3cm) 的宝丽布(如图 2),四周有高度为 18cm 的围栏。场地地面设有起点线和终止线,距离边缘 90cm。部分障碍前后20cm 设有标志线,供参赛队伍参考使用。距离长边 60cm 的两条红线为装饰线。5 个 障碍物按图 1、图 2 所示种类、数量和位置安放,并以双面胶固定在场地地面上,不可移动。黑线用 3.8cm 宽低反光绝缘胶带铺设。

图2:场地地面尺寸图

(2)窄桥尺寸图:

                         单位:cm

                         材料:发泡 EVA

                         颜色:黑色

(3)台阶尺寸图:

                         单位:cm

                         材料:发泡 EVA

                         颜色:黑色

(4)管道尺寸图:

                         单位:cm

                         材料:亚克力颜色:透明

(5)气球:

           单位:cm

           材料:橡胶

           颜色:红、蓝、绿各一个

           关于窄桥和台阶障碍:表面贴磨砂砂纸。

           气球布置说明(其中尺寸标注±10mm):

关于气球说明:

气球颜色为:深红、深绿、深蓝

气球大小(宽):22cm和26cm之间,测量宽度方向以下图黑线示意为参考(横向最宽距离);

气球安装角度:气球横放,气嘴朝向终点线反方向,气球底面中部与场地布紧贴,气球 与场地布通过粘度较高的双面胶固定(以侧向拍打不掉落为准),气球固定位置距离气球底面中点误差±5cm;

关于扎气球的装置说明:扎气球装置末端可采用细小尖锐物体,如曲别针、图钉、牙签等,机器人上场前将对扎气球装置进行检验;


关于挡板布置,如下图蓝色外框(其中尺寸标注误差±10mm)

关于色卡:色卡长×高=100mm×200mm,表面覆亚光膜,竖直放置在地面上。

2. 示例样机

      本文采用的示例样机是基于255号样机改造的。在255C样机的基础上,在四个前后轮上缠绕了履带片以增大轮径,提高越障的性能。另外,在车身上增加了一个舵机驱动的摆杆,摆杆的顶部可以安装针甚至排针,用来刺破气球。

3. 示例程序

电子模块: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.h>        //调用舵机库函数

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();

 

}

/*********************接线方式

TCS3473x   Arduino_Uno

  SDA         A4

  SCL         A5

  VIN         5V

  GND         GND

*************************/

#include <Wire.h>        //调用IIC库函数

#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);

}

Motor_Gray_Control.ino

void Motor_Sensor_Init()

{

  for(int i=0;i<Car_Head_Gray_SensorPin_Num;i++) {//初始化灰度传感器

     pinMode(Gray_SensorPin[i],INPUT);

     delay(20);

  }

  for(int i=0;i<motor_num;i++) {//初始化 电机

     pinMode(Car_DC_Motor_Pin[i],OUTPUT);

     delay(20);

  }

}


void Serialprint_gray_sensor_data_analogRead()

{

   int data_sensor[3]={0,0,0};

   for(int i=0;i<3;i++)

   {

     Serial.print(Gray_SensorPin[i]);Serial.print(": ");

     Serial.print(analogRead(Gray_SensorPin[i]));

     Serial.print(" | ");

   }

   Serial.println();  

}


void Serialprint_gray_sensor_data()

{

   int data_sensor[3]={0,0,0};

   for(int i=0;i<3;i++)

   {

     Serial.print(Gray_SensorPin[i]);Serial.print(": ");

     Serial.print(digitalRead(Gray_SensorPin[i]));

     Serial.print(" | ");

   }

   Serial.println();  

}


/*-----------------------------------------------------------------------

  A2         A3         A4

  ----------------------------------

  0          0          0      0x00   表示三个传感器都没有触发

  0          0          1      0x01   表示小车右边一个传感器触发

  0          1          0      0x02   表示小车中间传感器触发

  0          1          1      0x03   表示小车右边两个传感器都触发

  1          0          0      0x04   表示小车左边一个传感器触发

  1          0          1      0x05  

  1          1          0      0x06   表示小车左边两个传感器都触发

  1          1          1      0x07   表示小车三个传感器都触发  

------------------------------------------------------------------------*/

int Detection_tracking() //灰度传感器A4,A3,A2,用来小车巡线时,返回传感器数值;

{

  int num = 0;

  for(int i=0;i<Car_Head_Gray_SensorPin_Num;i++)

  {

    num |= ( (!digitalRead(Gray_SensorPin[i]) ) << i);

  }

  Serial.println(num);

  return num;

}


void Tracking_Automatic_Tracking(unsigned long delay_tracking_time)

{

  unsigned long now_times = millis();

  while(millis()-now_times<delay_tracking_time)

  {

    Automatic_Tracking();

  }

}


void Automatic_Tracking() //小车前方两个灰度传感器用来寻迹(即小车巡线)。

{

  int Get_Data = 0;

  Get_Data = Detection_tracking();

  switch(Get_Data)

  {   

    case 0x00: Car_Move(Forward,Forward_Left_Speed,Forward_Right_Speed);break;//forward

    case 0x01: Car_Move(Right,   Right_Left_Speed,   Right_Right_Speed   );break;//RIGHT   

    case 0x02: Car_Move(Forward,Forward_Left_Speed,Forward_Right_Speed);break;//forward

    case 0x03: Car_Move(Right,   Right_Left_Speed,   Right_Right_Speed   );break;//right

    case 0x04: Car_Move(Left,   Left_Left_Speed,   Left_Right_Speed   );break;//left

    case 0x06: Car_Move(Left,   Left_Left_Speed,   Left_Right_Speed   );break;//LEFT

    case 0x07: //Gray_Three ++;

               Car_Move(Forward,Forward_Left_Speed,Forward_Right_Speed);break;//forward

    default: break;     

  }

}


int Detection_tracking_analogRead() //灰度传感器A4,A3,A2,用来小车巡线时,返回传感器数值;

{

  int num = 0;

  int analogRead_data[3] = {0,0,0};

  for(int i=0;i<Car_Head_Gray_SensorPin_Num;i++)

  {

    analogRead_data[i] = analogRead(Gray_SensorPin[i]);

//    if( analogRead_data[0] <=300 ){analogRead_data[0] = 1;} else{analogRead_data[0] = 0;}//18

//    if( analogRead_data[1] <=300 ){analogRead_data[1] = 1;} else{analogRead_data[1] = 0;}//17

//    if( analogRead_data[2] <=170 ){analogRead_data[2] = 1;} else{analogRead_data[2] = 0;} //16

    if( analogRead_data[i] <=240 ){analogRead_data[i] = 1;} else{analogRead_data[i] = 0;}

    num |= ( (analogRead_data[i]) << i);

  }

  //Serial.println(num);

  return num;

}



void Automatic_Tracking_analogRead() //小车前方两个灰度传感器用来寻迹(即小车巡线)。

{

  int Get_Data = 0;

  Get_Data = Detection_tracking_analogRead();

  switch(Get_Data)

  {   

    case 0x00: Car_Move(Forward,Forward_Left_Speed,Forward_Right_Speed);break;//Led_shine(0,0, 0, 1);break;//forward

    case 0x01: Car_Move(Right,   Right_Left_Speed,   Right_Right_Speed   );break;//Led_shine(0,0, 1, 1);break;//RIGHT   

    case 0x02: Car_Move(Forward,Forward_Left_Speed,Forward_Right_Speed);break;//Led_shine(0,1, 0, 1);break;//forward

    case 0x03: Car_Move(Right,   Right_Left_Speed,   Right_Right_Speed   );break;//Led_shine(0,1, 1, 1);break;//right

    case 0x04: Car_Move(Left,   Left_Left_Speed,   Left_Right_Speed   );break;//Led_shine(1,0, 0, 1);break;//left

    case 0x06: Car_Move(Left,   Left_Left_Speed,   Left_Right_Speed   );break;//Led_shine(1,1, 0, 1);break;//LEFT

    case 0x07:

           {

             Gray_Three ++; Car_Move(Forward,Forward_Left_Speed,Forward_Right_Speed);

             if(Gray_Three == 3)

             {

               road_one();

//               road_three();

             }

             if(Gray_Three == 2)

             {

               road_two();

             }             

             if(Gray_Three == 1)

             {

               road_three();

             }

    }break;

    default: break;     

  }

}


void road_one()

{

  Car_Move(Forward,253,212);delay(3500);

  Car_move_state_delaytime(Tracking_automatic,4000);

}


void road_two()

{

  Car_Move(Forward,255,200);delay(3500);

  Car_move_state_delaytime(Tracking_automatic,4000);

}


void road_three()

{

    Tracking_Automatic_Tracking(456);

    Car_Move(Stop,Car_speed_stop,Car_speed_stop);delay(3000);

    return_color_card(); //小车走到色卡开始识别色卡

   

    Tracking_Automatic_Tracking(1266);Car_Move(Stop,Car_speed_stop,Car_speed_stop);delay(500);

    return_color_ballon();

    if(color_detection_card == color_detection_ballon){

      Zha_Qi_Qiu(2);

      finish = false;

      finish_all = false;

    }//小车走到第一个气球区域,并判断气球颜色。


    if(finish_all){

        Tracking_Automatic_Tracking(1324);Car_Move(Stop,Car_speed_stop,Car_speed_stop);delay(500);

        return_color_ballon();

        if( (color_detection_card == color_detection_ballon) && finish ){

          Zha_Qi_Qiu(2);

          finish = false;

          finish_all = false;

      }//小车走到第二个气球区域,并判断气球颜色。

    }


    if(finish_all){

        Tracking_Automatic_Tracking(1236);Car_Move(Stop,Car_speed_stop,Car_speed_stop);delay(500);

        return_color_ballon();

       

        if( (color_detection_card == color_detection_ballon) && finish ){

          Zha_Qi_Qiu(2);

          finish = false;

          finish_all = false;

      }//小车走到第三个气球区域,并判断气球颜色。

    }

    Car_Move(Stop,Car_speed_stop,Car_speed_stop);delay(3000);

}



void Car_Move(int Mode,int LeftSpeed,int RightSpeed)                                                                           

{

  switch(Mode)

  {

    case Forward:{analogWrite(Car_DC_Motor_Pin[0],LeftSpeed);analogWrite(Car_DC_Motor_Pin[1],0);analogWrite(Car_DC_Motor_Pin[2],RightSpeed);analogWrite(Car_DC_Motor_Pin[3],0); }break;

    case Back:   {analogWrite(Car_DC_Motor_Pin[0],0);analogWrite(Car_DC_Motor_Pin[1],LeftSpeed);analogWrite(Car_DC_Motor_Pin[2],0);analogWrite(Car_DC_Motor_Pin[3],RightSpeed);}break;  

    case Left:   {analogWrite(Car_DC_Motor_Pin[0],0);analogWrite(Car_DC_Motor_Pin[1],LeftSpeed);analogWrite(Car_DC_Motor_Pin[2],RightSpeed);analogWrite(Car_DC_Motor_Pin[3],0); } break;

    case Right:   {analogWrite(Car_DC_Motor_Pin[0],LeftSpeed);analogWrite(Car_DC_Motor_Pin[1],0);analogWrite(Car_DC_Motor_Pin[2],0);analogWrite(Car_DC_Motor_Pin[3],RightSpeed); }break;  

    case Stop:   {analogWrite(Car_DC_Motor_Pin[0],LeftSpeed);analogWrite(Car_DC_Motor_Pin[1],LeftSpeed);analogWrite(Car_DC_Motor_Pin[2],RightSpeed);analogWrite(Car_DC_Motor_Pin[3],RightSpeed);} break;

    default: break;   

  }

}


void Car_Move_Test()

{

  Car_Move(Forward,Forward_Left_Speed,Forward_Right_Speed);delay(1500);Car_Move(Stop,Car_speed_stop,Car_speed_stop);delay(1500);

  Car_Move(Back,Forward_Left_Speed,Forward_Right_Speed);delay(1500);Car_Move(Stop,Car_speed_stop,Car_speed_stop);delay(1500);

  Car_Move(Left,Left_Left_Speed,   Left_Right_Speed);delay(1500);Car_Move(Stop,Car_speed_stop,Car_speed_stop);delay(1500);

  Car_Move(Right,Right_Left_Speed,   Right_Right_Speed);delay(1500);Car_Move(Stop,Car_speed_stop,Car_speed_stop);delay(1500);

}



void Car_Stop(int delay_time)

{

  Car_Move(Stop,Car_speed_stop,Car_speed_stop);

  delay(delay_time);

}

void Car_move_state_delaytime(int Mode,int delay_time)

{

switch(Mode)

{

case Forward:{ unsigned long time_now1 = millis();while( (millis() - time_now1) < delay_time ){Car_Move(Forward,Forward_Left_Speed,Forward_Right_Speed);}}break;

case Back: { unsigned long time_now2 = millis();while( (millis() - time_now2) < delay_time ){Car_Move(Back,Forward_Left_Speed,Forward_Right_Speed);}}break;

case Left: { unsigned long time_now3 = millis();while( (millis() - time_now3) < delay_time ){Car_Move(Left,Left_Left_Speed, Left_Right_Speed);}}break;

case Right: { unsigned long time_now4 = millis();while( (millis() - time_now4) < delay_time ){Car_Move(Right,Right_Left_Speed, Right_Right_Speed);}}break;

case Tracking_automatic:{ unsigned long time_now5 = millis();while( (millis() - time_now5) < delay_time ){Automatic_Tracking();}}break;

default: break;

}

}


void Car_state_adjust_speed(int mode, int leftspeed_start, int leftspeed_end, int rightspeed_start, int rightspeed_end, int delay_time)

{

switch(mode)

{

case Forward:

{

int max_delta_data = 0;

int left_flag = 0;

int right_flag = 0;

int delta_time = 0;

int L_speed_delta = 0;

int R_speed_delta = 0;

int delta_subtract_left = abs( leftspeed_start - leftspeed_end );

int delta_subtract_right = abs( rightspeed_start - rightspeed_end );

max_delta_data = delta_subtract_left > delta_subtract_right ? delta_subtract_left : delta_subtract_right;

delta_time = delay_time / max_delta_data ;

left_flag = leftspeed_start - leftspeed_end >0 ? -1 : 1;

right_flag = rightspeed_start - rightspeed_end >0 ? -1 : 1;

unsigned long time_delay = millis();

for( int i = 0; i< max_delta_data; i++ )

{

L_speed_delta = leftspeed_start + i*left_flag;

R_speed_delta = rightspeed_start + i*right_flag;

if( (L_speed_delta<= leftspeed_end) || (L_speed_delta>= leftspeed_end) )

{

L_speed_delta = leftspeed_end;

}

if( (R_speed_delta<= rightspeed_end) || (R_speed_delta>= rightspeed_end) )

{

R_speed_delta = rightspeed_end;

}

analogWrite(Car_DC_Motor_Pin[0],L_speed_delta);

analogWrite(Car_DC_Motor_Pin[1],0);

analogWrite(Car_DC_Motor_Pin[2],R_speed_delta);

analogWrite(Car_DC_Motor_Pin[3],0);

delay(delta_time);

}

}break;

}

}


void Car_Debug_Test()////程序进入调试模式(检测色卡颜色、检测气球颜色、检测灰度传感器、检测小车走直线)

{

while(1)

{

#ifdef Debug_Color_Card

// return_color_card();

color();

#endif


#ifdef Debug_Color_Balloon

return_color_ballon();

#endif


#ifdef Debug_Gray_Sensor

Serialprint_gray_sensor_data_analogRead();

#endif


#ifdef Debug_Car_Forward

Car_Move(Forward,Forward_Left_Speed,Forward_Right_Speed);

#endif

delay(10);

}

}

Servo_Move_Control.ino

//===================舵机========================舵机=======================舵机=======================舵机===========================舵机==========================舵机==============================舵机==============================舵机

//====舵机===========================舵机======================舵机=======================舵机=========================舵机==========================舵机============================舵机==================================舵机=============

//===================舵机========================舵机=======================舵机=======================舵机===========================舵机==========================舵机==============================舵机==============================舵机

//void Servo_Init()

//{

//   for(int i=0;i<servo_num;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<servo_num;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<delta_servo_angle;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<servo_num;i++){

//    value_delta[i] = (value_arguments[i] - value_init[i]) / f;

//   }  

//   for(int i=0;i<f;i++){

//    for(int k=0;k<servo_num;k++){

//      value_init[k] = value_delta[k] == 0 ? value_arguments[k] : value_init[k] + value_delta[k];

//    }

//    for(int j=0;j<servo_num;j++){

//      ServoGo(j,value_init[j]);

//    }

//    delay(delaytimes/f);

//   }

//}


void Zha_Qi_Qiu(int Numbers)

{

  for(int i=0;i<Numbers;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);

  }

}

4. 资料下载

资料清单

序号

内容
1

全地形排爆车样机3D文件(255e)

2全地形排爆车完整程序(255e样机+IIC传感器)
3

全地形排爆车完整程序(255e样机+TCS3200传感器)

4全地形排爆车例程配套函数库
5全地形爆破赛-场地制作文件
点击打包下载


Color_detection.ino

全地形

1. 比赛场地

      场地中设定四种五个不同特点、不同难度的障碍物,每种障碍物均有一定的分值,参赛队根据比赛规则自主设计制作机器人,完成穿越各个障碍物的比赛。

      障碍物分别为模拟工业用栅格地毯、楼梯、管道、独木桥,各障碍物由黑色引导线连接,形成完整的比赛赛道,并设置比赛起点和终点,比赛场地由组委会统一布置。

      比赛场地及四种障碍物(栅格地面,管道,窄桥,楼梯)尺寸标记(含引导黑线、比赛起点和终点)。

(1)场地整体图:

(2)窄桥尺寸图:

                        单位:cm

                        材料:发泡EVA

                        颜色:黑色

(3)台阶尺寸图:

                    单位:cm

                    材料:发泡EVA

                    颜色:黑色

(4)管道尺寸图:

                        单位:cm

                        材料:亚克力

                        颜色:透明

(5)栅格地面尺寸图:

                               单位:cm

                               材料:工程塑料

                               颜色:蓝色

2. 示例样机

     本文采用的示例样机是由255C样机改造而来的。在四个前后轮上缠绕了履带片以增大轮径,提高越障的性能。

      两侧摇臂用零件(下图所示蓝色零件)固定在了一起,单侧摇臂不能单独摆动,只能同时摆动,损失了一些灵活性,但是增加了行驶中的稳定性,尤其是增加了攀爬越障时的稳定性,车身不容易跑偏。

车头位置并排安装3个灰度传感器。

3. 示例程序

电子模块:Arduino UNO(Basra控制板)×1,Bigfish扩展板×1,灰度传感器×3。

编程环境:Arduino1.8.19

程序源代码如下:

/*------------------------------------------------------------------------------------

  版权说明:Copyright 2022 Robottime(Beijing) Technology Co., Ltd. All Rights Reserved.

           Distributed under MIT license.See file LICENSE for detail or copy at

           https://opensource.org/licenses/MIT

           by 机器谱 2022-5-26 https://www.robotway.com/

  --------------------------------

  实验功能:

          实现小车沿黑线行驶,遇到黑线构成的路口能够按既定策略执行.

          假想循迹场地,有直线、左转弯、右转弯、十字路口;

  --------------------------------

  实验接线:

      小车车头并排安装三个灰度传感器

                车头

             .------------.

             |        |

             |        |

     左侧轮   |        |   右侧轮

      D5, D6 *------------* D9, D10

     

----------------------------------------------------------------------------------*/


//

//;


int pin[3] = {A4, A3, A0};           //按车头前进方向,从右至左定义,后面经过公式计算,会转化为从左至右的顺序

int s;

void setup()

{

  pinMode( 5 , OUTPUT);

  pinMode( 6 , OUTPUT);

  pinMode( 9 , OUTPUT);

  pinMode( 10 , OUTPUT);

}


void loop()

{

   s = 0;

        for(int i=0; i<3; i++)                 //循环获取三个传感器的值

        {

            s|= (!digitalRead(pin[i]) << i);   //经过左移运算和或运算后,按照A0、A3、A4的顺序产生一个三位2进制数值,表示3个传感器的组合触发状态

        }

        switch (s)

        {

          case 0x00: //三个均未触发

          Forwards();

          break;

          case 0x01: //右侧传感器触发,直线上摆动或遇到右转弯

          Right();

          break;

          case 0x02: //中间传感器触发,直线上直行

          Forwards();

          break;

          case 0x03: //右侧两个触发,遇到右转弯

          Right();

          break;

          case 0x04: //左侧传感器触发,直线上摆动或遇到左转弯

          Left();

          break;

          case 0x06: //左侧两个触发,遇到左转弯

          Left();

          break;

          case 0x07: //三个同时触发,遇到十字路口

          Forwards();

          break;

          default:;break;

        }

  }

void Left()

{

digitalWrite( 5 , HIGH );

digitalWrite( 6 , LOW );

digitalWrite( 9 , LOW );

digitalWrite( 10 , LOW );

}


void Right()

{

digitalWrite( 5 , LOW );

digitalWrite( 6 , LOW );

digitalWrite( 9 , HIGH );

digitalWrite( 10 , LOW );

}


void Forwards()

{

digitalWrite( 5 , HIGH );

digitalWrite( 6 , LOW );

digitalWrite( 9 , HIGH );

digitalWrite( 10 , LOW );

}

4. 样机扩展

也可以使用探索者的各类兼容零件制作样机(255c-3.stp)。

资料清单

序号

内容
1

【255】月球车底盘-全地形比赛-样机3D文件(255c-2、225c-3)

2【255】月球车底盘-全地形比赛-例程文件
3全地形赛-场地制作文件
点击打包下载


5. 资料下载

© 2022 机器时代(北京)科技有限公司  版权所有
机器谱——机器人共享方案网站
学习  开发  设计  应用