机器谱

S067】“探索者”全地形小车

图文展示3264(1)

图文展示3264(1)

副标题

作品说明

作者:汪光达 刘煜辉 唐仁泽 路恩

单位:西安科技大学

指导老师:白云

      “探索者”全地形小车是以探索机器人智能技术开发平台提供的Arduino Basera主板为主控,进行自主设计创新机械结构,结合灰度传感器,Open MV视觉模块进行色块、气球颜色与位置的判断识别,其运行方式简便,识别准确性好,运行稳定。该全地形小车将会依照巡线路径行驶完整个场地设定路径,其间通过窄桥障碍、管道障碍、楼梯障碍以及气球区四个区域。在气球区停止并进行快速色块识别,并按照规定扎破指定气球。

      关键字:arduino、全地形、Open MV

1. 作品整体介绍

1.1 场景调研

      根据咨询,全球全地形车的主要产量和销量主要集中在北美地区,我国全地形车行业起步较晚,大部分全地形车生产企业以小排量为主,九成以上用于出口。根据中国汽车工业协会统计数据,近年来我国全地形车出口量持续上升,从2013年的13.36万辆增长至2020年的26.99万辆,期间CAGR为10.57%。受益于国外持续稳定增长的市场需求,预期未来全地形车行业仍有较大的发展空间。中国汽车工业协会统计数据显示,2021年上半年,我国全地形车出口21.46万辆,同比增长148.4%,出口金额3.94亿美元,同比增长165.85%。全地形车是指可以在任何地 形上行驶的车辆,在普通车辆难以机动的地形上行走自如。目前该种车型已具备多种用途,且不受道路条件的限制,可行驶于沙滩、河床、林道、溪流以及恶劣的沙漠地形。全地形车作为以休闲娱乐及日常实用为主要目的的动力运动装备,其发展主要依赖于消费者休闲时间的增多和户外作方式、生活方式升级带来的机遇,目前国内市场处于萌芽阶段,需求较为小众,整体规模较小。但随着国内居民可支配收入的提高、消费多元化的升级,全地形车所代表的竞技运动、时尚潮流、生活方式和运动文化正在向百姓生活渗透,同时全地形车除用作休闲娱乐外,还可广泛用于农牧场、矿山、林地、抢险等多种特殊用途,加上旅游租赁业务、专业赛事等发展,预计未来全地形车国内销量有望逐步提升。

1.2 作品介绍

      全地形小车是以arduino为主控制板,以“探索者”套件为基础框架搭建,以PO3型 7.4V锂电池给小车供电,具有过楼梯、管道、窄桥等障碍功能。通过灰度传感器采集的数据进行巡线判断,通过Open MV视觉模块进行色卡、气球颜色与位置的判断识别,并将识别结果发送给主控。主控同时控制舵机转动机械臂,其运行方式简便,识别准确性好,运行稳定,该全地形小车将会依照巡线路径行驶完整个场地设定路径。

作品说明

小车整体结构框架图

1.3 作品结构简图

作品结构简图

2. 作品难点及解决方案

2.1 作品难点

      小车需要顺利沿指定路线通过所模拟的所有障碍如:坡道、楼梯、窄桥、隧道等,并且需要有准确的颜色识别系统,需要有简单的机械臂结构来执行要求操作且需要保证小车的灵活性以及稳定性。

故以下几个部分的设计思路及解决方案进行具体介绍:越障系统,车轮动力与悬挂减震系统,车身主体传感与控制系统,机械臂与爆破系统。

2.2 解决方案

2.2.1 越障系统

      为了使小车能够稳定的跨越楼梯和坡道,我们设计了六轮小车,其中前方四轮绑定为一个整体,与后两轮通过活动轴链接,保证前四轮在上台阶的过程中后两轮仍可以着地为车前进提供动力。避免小车因在台阶上轮胎打滑而造成的动力不足越障失败的情况。活动轴如下图所示:

活动轴

      为了避免在跨越台阶时巡线巡线传感器(传感器组1)使车轮差速导致的动力不足或不均的影响,我们在车前方再次增加了一个灰度传感器(传感器组2)用来检测台阶,通过实验,车可以完美跨越台阶,并且不受传感器组1的影响。

传感器

      为了使小车进入管道后更加顺滑和快速的通过管道,我们在车前方安装了比赛提供的尼龙导轮。通过多次实验我们找到了安装导轮最合适的位置,并且车可以顺滑的通过管道。

尼龙导轮

尼龙导轮使车体不会卡在管道

2.2.2 车轮动力与悬挂减震系统

      我们使用比赛提供的结构件,制作出一种大半径柔性履带轮,这种轮胎与前侧两个电机相连,极大的增加了车面对复杂地形的能力,按要求对中间两轮进行改装,增加了对地面的摩擦力,后两轮较小,用于小车上坡时候的支撑。使用Arduino主控通过电机驱动控制小车灵活的移动与转向,在测试中可稳定爬坡倾斜角为30°的发泡EVA板。大半径柔性履带轮结构如下图所示:

大半径柔性履带轮

      为了使循迹模块与颜色识别模块更好的运行,我们添加了悬挂结构使车身的抖动减小,悬挂结构使用金属孔平板连接两轮,再由弹性塑料螺柱将车身与前后两组孔平板连接,构成悬挂系统。这一结构提升了巡线识别准确率,很好解决了小车巡线不稳定,冲出路线的情况。部分悬挂结构如下图所示:

悬挂减震

      该全地形小车的越障功能主要依靠电机驱动小车的六轮来实现。小车在运行过程中,Arduino主板控制电机为小车提供足够的动力,为防止小车在越障时摩擦底盘而导致卡顿,小车的底盘较高,且主要元器件都置于底板上层,足够小车越过障碍,在小车的前轮之间设置有三个灰度传感模块用以循迹。

2.2.3 车身主体传感与控制系统

      在车身结构上,车身与轮胎之间设置了较大的间隔,用以增高底盘,防止小车在越障时底盘与障碍物发生摩擦碰撞,保证小车稳定越障。同时增高底盘可给Arduino主板提供更多空间,方便相关硬件模块的搭建。小车系统结构图如下所示:

车主体

      传感器主要有灰度传感器与颜色传感器(OpenMV),灰度传感器位于车身前方下侧,车身的结构设计为灰度传感器提供了一个稳定的平台,通过调整三个传感器间距,使其刚好大于纵向循迹线宽度,运行期间小车行驶平稳,不会冲出循迹线外。颜色传感器(OpenMV)位于车身上方左侧,由于小车将识别左侧颜色块与气球颜色,我们将识别模块高度调整至摄像头离地14cm位置,在这里我们能很好的识别色块与气球颜色。传感器位置如下图所示:

openMV

传感器组

2.2.4 机械臂与爆破系统

      在机械臂设计上,通过螺丝将舵机与机械臂稳固连接,保证机械臂的稳定性;当小车处于气球区时,舵机能够精准地控制机械臂刺破气球。当小车正在运动中时,舵机可控制机械臂折叠,避免对小车的正常运动造成干扰。机械臂图如下所示:

舵机

机械臂折叠状态

2.3 整体控制系统设计思路

      走直线时,左右6个轮子速度一致,如果行驶时偏向某侧则通过传感器组1的返回值,找到偏转方向,通过差速使其回到正常路线。通过传感器组2的返回值可进行判断是否进行过窄桥或者过台阶。通过openMV识别颜色,第一个识别的为目标颜色,识别到目标颜色后,让openmv与Arduino通信,让小车减速行驶。当再次识别到颜色处于阈值范围内的气球时,再与Arduino通信,让车停止,开始刺破气球。

① 循迹部分

      系统启动后,程序将会进入循环,小车将会启动前进,同时位于小车前端的三个巡线灰度传感模块将持续进行检测。当主控通过灰度传感模块采集到的值达到设定阈值后,主控将会启动相应的转向函数。该函数将会立即控制小车两侧电机进行变速,使小车向相反的方向偏转,从而调整小车的前进方向。在小车通过障碍的过程中,由于障碍本身为黑色,因此灰度传感模块将持续检测到黑色,若连续检测到信号,主控将使小车继续前进,通过对直行速度的校准小车可以成功通过窄桥。当传感器组2检测到黑色台阶的时候将会停止巡线,使小车全速通过台阶。程序流程图如下所示:

巡线程序流程图

② 色块识别部分

      小车以正常速度前进,OpenMV一直进行颜色识别与距离检测,当OpenMV检测到长方形色卡并且检测到与色卡距离在设定范围内时,便将该颜色作为目标颜色。此时OpenMV与小车通信,使小车减速前进并且进行巡线,当再次检测到在阈值范围内的气球时,OpenMV将刺破气球的信号发送给Arduino主板,主板控制舵机转动到合适的角度,使带有针的机械臂刺破气球。程序流程图如下所示:

颜色识别程序流程图

2.4 关键代码说明

       通过调用舵机函数库,来设定相应的转动角度,通过宏定义来实现舵机零角度的快速校准。

舵机部分代码

      通过调用analogread()函数来实现对指定引脚的模拟量的读取,通过对三个巡线模块的不同阈值的设置来判断是否为黑线或窄桥。通过对台阶灰度传感器阈值的设置来判断是否为台阶。

巡线部分代码

      通过引入SoftwareSerial.h库,调用read函数,来读取软件串口接收到的信息(OpenMV发送的信息),通过传来的不同的字符,来进行相应的操作。其中检测到色卡后,车减速前进,当再次检测到处于阈值范围内的气球时,OpenMV给主控发送信息,主控通过舵机刺破气球。

3. 创新设计说明

      “探索者”全地形小车主要有以下创新点和应用:

① 加长车身

      创新点:加长车身更有利于通过台阶,窄桥等复杂的地形,加长车身可以使车的抓地面积更多,可以轻松面对复杂场景。加大轮胎的半径更有利于越过台阶且不宜打滑。

      应用:某些军用的卡车一般为四轮以上,提高越野能力。大货车一般都是用多个大轮胎,这样既能增加称重又能防止打滑。

② 减震悬挂装置

      针对全地形小车巡线过程中易出现巡线不稳定、路线偏移等情况,设计了减震悬挂装置,配合柔性履带轮胎,有效改善小车的运行稳定性能,对保持小车平衡有积极作用。

      应用:车包含减震结构,可以提高车核心部件的寿命,避免震动带来的影响,提高车运动的稳定性。

③ 多传感器组合

      使用多个传感器的组合,来采集更多的信息,加准确地的识别环境,避免出现偶然情况,导致小车的错误运动。

      应用:雷达系统,分部与车的前后左右,可以使司机全方位观察到车周围的情况。避免司机驾驶时候因为不知道距离障碍物的距离,而导致车的损伤。

④ 摄像头测距和形状检测

      使用摄像头测距,可以避免摄像头被环境因素所影响,导致的错误识别颜色。通过形状的检测来确定是否为色卡。

      应用:部分手机具有测量物体大致尺寸的功能,利用远小近大的原理。人眼也可以通过判断物体的大小来判断物体的远近。

⑤ 多轮驱动

      设计了6个轮胎的车体,可以保证在上台阶的过程中始终有轮胎着地,保证车体的动力。同时可以分担前轮的重量,保证车可以正常越过障碍物。

      应用:大货车一般使用多个轮胎,来提高承重能力和保证动力的充足。

4. 制作过程详细说明

      制造车身整体框架时,考虑到小车的称重能力、过窄桥能力、上台阶能力,我们使小车的结构更加紧凑,整体质量更轻且质量分布更加均匀。每一个零件用防滑螺母紧紧锁死,防止散架。

车机械结构

装上所有的电子器件,烧录了程序,发现小车不能正常巡线。

车巡线失败

更改了代码,正在进行阈值的测量和调整。

正在调整传感器的阈值

调整完阈值后,小车可以正常巡线。

小车巡线成功

小车成功爬上窄桥。

小车成功上窄桥

小车可以上窄桥,但是小车下坡时总是向一侧偏移。

小车下坡时偏移

我们通过多次测试,对轮胎的速度进行校准调节,然后小车可以正常下坡。

小车正常下坡

小车无法爬上台阶。

小车上台阶失败

      通过反复的实验与检查,发现是巡线传感器使车轮胎差速导致的动力不足和不均。于是我们增加了一个检测台阶传感器,避免巡线传感器的影响。

小车上台阶成功

调整后,通过多次对参数的调整,小车可以爬上台阶。

小车成功上台阶

小车成功进入管道。

小成功进入管道

小车在尼龙导轮的作用下成功驶出管道。

小车成功出管道

小车正在进行色卡与气球颜色的阈值调整。

调整阈值

      通过实验发现,在不停车的情况下openmv仍然可以快速识别色牌,于是我们在识别色牌时未进行停车操作,直接发指令让小车减速前进,当再次识别到处于阈值范围内的气球时,则发指令停车,刺破气球。

识别到色卡

小车正在刺破气球(未加针)。

刺破气球

5. 示例程序

全地形小车视觉代码

import sensor, image, time

from pyb import UART

import json

import time

thresholds = [(15, 40, 14, 127, -128, 127), # generic_red_thresholds

              (35, 66, -45, -20, -128, 127), # generic_green_thresholds

              (0, 32, -18, 9, -26, 1)] # generic_blue_thresholds

red_threshold   = (33, 77, 5, 127, -128, 127)

green_threshold   = (42, 70, -44, -8, 12, 36)

blue_threshold   = (33, 70, -29, 3, -29, -4)

single_threshold = (0,0,0,0,0,0)

flag_threshold = (0,0,0,0,0,0)

sensor.reset()

sensor.set_pixformat(sensor.RGB565)

sensor.set_framesize(sensor.QQVGA) #160*120

sensor.skip_frames(10)

sensor.set_auto_whitebal(False)

sensor.set_vflip(True)     #垂直方向翻转

sensor.set_hmirror(True)   #水平方向翻转

clock = time.clock()

uart = UART(3, 9600)

K=157932

length=0

flag=0

while(True):

    clock.tick()

    img = sensor.snapshot()

    if flag==0:

        blobs = img.find_blobs(thresholds)

        if len(blobs) == 1:

            b = blobs[0]

            img.draw_rectangle(b[0:4]) # rect

            img.draw_cross(b[5], b[6]) # cx, cy

            Lm = (b[2]*b[3])

            length = K/Lm

            print(length)

            if length<=40:

                if b.code() == 1: # red

                    print("red")

                    single_threshold = red_threshold

                    flag_threshold = thresholds[0]

                    uart.write("D")

                    flag=1

                if b.code() == 2: # green

                    print("green")

                    single_threshold = green_threshold

                    flag_threshold = thresholds[1]

                    uart.write("D")

                    flag=1

                if b.code() == 4: # blue

                    print("blue")

                    single_threshold = blue_threshold

                    flag_threshold = thresholds[2]

                    uart.write("D")

                    flag=1

    if flag==1:

          area1=(1,0,5,120)

          for blob in img.find_blobs([flag_threshold],roi=area1):

              if(blob):

                  print("still")

                  flag=2

    if flag==2:

        area2=(150,0,1,120)

        for blob in img.find_blobs([single_threshold],roi=area2):

            if(blob):

                print("go")

                flag=3

    if flag==3:

        area3=(100,0,1,120)

        for blob in img.find_blobs([single_threshold],roi=area3):

            if(blob):

                print("go")

                flag=4

    if flag==4:

        area4=(80,0,1,120)

        for blob in img.find_blobs([single_threshold],roi=area4):

            if(blob):

                print("go")

                flag=5

    if flag==5:

        area5=(40,0,1,120)

        for blob in img.find_blobs([single_threshold],roi=area5):

            if(blob):

                print("go")

                flag=6

    if flag==6:

        area6=(20,0,1,120)

        for blob in img.find_blobs([single_threshold],roi=area6):

            if(blob):

                print("go")

                flag=7

    if flag==7:

          area5=(1,0,1,120)

          for blob in img.find_blobs([single_threshold],roi=area5):

              if(blob):

                  print("ok")

                  #time.sleep_ms(5000)

                  uart.write("A")

                  flag=8



#include <Servo.h>

//#include <MsTimer2.h>

#include <SoftwareSerial.h>

Servo myservo;   //创建一个舵机控制对象 , 使用Servo类最多可以控制8个舵机

//定义管脚2/3分别为RX,TX.

SoftwareSerial mySerial(12, 13); // RX, TX

//~~~~~~~~~~~~~一些宏定义~~~~~~~~~~~~~~~~~~

#define servo_turn_pin    11

#define servo_turn_angle   0    // 定义舵机角度临界位置,可以用来校准舵机(刀)的角度

//~~~~~~~~~~~~~函数的定义~~~~~~~~~~~~~~~~~~

void servo_turn();               //调用该函数用于舵机的旋转,旋转九十度

void track_read();

void car_move(int left, int right);

void casespeed(int mode);

//~~~~~~~~~~~~~一些设定值~~~~~~~~~~~~~~~~~~~

int xunxian1[4] = {200, 200, 200, 300}; //循迹的三个临界值950

int xunxian[4] = {450, 450, 450, 300}; //循迹的三个临界值700,600,600

int gray_sensorPin[4] = {A3, A4, A5, A2}; //循迹对应的三个引脚

int aaa = A0;

int readaaa;

//右轮部分

//int ENR=7;

int R1 = 5;

int R2 = 6;

//左轮部分

int ENL = 3;

int L1 = 9;

int L2 = 10;

//电机速度设定

int Forward_left = 255;   //直行左轮

int Forward_right = 255 ; //直行右轮220

int Right_left = 0 ; //右转左轮

int Right_right = -255; //-400   //右转右轮-255==0; >255==400-255

int Left_left   = -255;   //左转左轮0

int Left_right = 0   ;//左转右轮

void servo_turn()

{

  myservo.write(servo_turn_angle);      // 指定舵机转向的角度

  delay(2000);              // 等待1s让舵机到达指定位置

  myservo.write(servo_turn_angle + 160);       // 指定舵机转向的角度140

  delay(2000);              // 等待1s让舵机到达指定位置

}

int read_da[4] = {0, 0, 0, 0};

int read_data[4] = { 0, 0, 0, 0};

void track_read()//

{

  readaaa = analogRead(aaa);

  read_da[0] = analogRead(gray_sensorPin[0]);

  read_da[1] = analogRead(gray_sensorPin[1]);

  read_da[2] = analogRead(gray_sensorPin[2]);

  read_da[3] = analogRead(gray_sensorPin[3]);

  Serial.println(readaaa);

  //Serial.println(read_da[0]);

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

  {

    if (read_da[i] <= xunxian[i] && read_da[i] > xunxian1[i])//300-600

    {

      read_data[i] = 1;

    }

    else if (read_da[i] > xunxian[i] )//大于600

    {

      read_data[i] = 0;

    }

    else if (read_da[i] < xunxian1[i] )//小于300

    {

      read_data[i] = 2;

    }

  }

  //Serial.println(read_data[0]);

}

void car_move(int left, int right) //电机

{

  if (left > 255) {

    left = 255;

  }

  if (right > 255) {

    right = 255;

  }

  if (left < 0) {

    left = 0;

  }

  //   if (right < 0) {

  //    right = 0;

  //   }

  if (right < 0)

  {

    right = -right; analogWrite(R1, 255 - right); analogWrite(R2, 255); //r1=5,r2=6

  }

  else

  {

    analogWrite(R1, 255); analogWrite(R2, 255 - right); //r1=5,r2=6

  }

  analogWrite(ENL, left);

  analogWrite(L1, 255); analogWrite(L2, 0);

  // analogWrite(R1, 255); analogWrite(R2, 255 - right); //r1=5,r2=6

}

void setup()

{

  Serial.begin(9600);//openmv对应波特率

  mySerial.begin(9600);

  myservo.attach(servo_turn_pin);   //初始化舵机

  //电机部分初始化

  pinMode(R1, OUTPUT);

  pinMode(R2, OUTPUT);

  pinMode(ENL, OUTPUT);

  pinMode(L1, OUTPUT);

  pinMode(L2, OUTPUT);

  myservo.write(servo_turn_angle + 160);    // 指定舵机转向的角度

  delay(1350);              // 等待1s让舵机到达指定位置

  car_move(255, 255);

  delay(500);

}

int flag = 0;

int flag_sd = 0;

int flag_mv = 0;

int delay_flag = 0;

int right_flag = 0;

void loop()

{

  track_read();//巡线

  int byteRead = mySerial.read();

  if (byteRead != -1)

  {

    if (byteRead == 'D')

    {

      Forward_left = 100;   //直行左轮

      Forward_right = 100;   //直行右轮220

      car_move(100, 100);

      delay(100);

    }

    if (byteRead == 'A')

    {

      car_move(0, 0);

      delay(1000);

      servo_turn();

      Forward_left = 200;   //直行左轮

      Forward_right = 200;   //直行右轮220

    }

  }

  else

  {

    if (read_data[1] == 1)//

    {

      car_move(190, 190);

    }

     else   if (read_data[2] == 1) //右转

    {

      car_move(200, -200);

    }

    else if (read_data[0] == 1)//左转

    {

      car_move(Forward_left + Left_left, Forward_right + Left_right);

    }

    //全黑<300//坡道

    else if (read_data[0] == 2 || read_data[1] == 2 || read_data[2] == 2)

    {

      car_move(255, 185);//255,180

    }

        else if(read_data[3] == 0)

        {

//           car_move(0, 0);

//            delay(450);

          car_move(255, 225);

          delay(700);

        }

    else

    {

      car_move(Forward_left, Forward_right);

    }

  }

}


小车控制部分代码

* 本项目未获得作者开源授权,无法提供资料下载。

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