机器谱

S066】环保型搬运回收能手

图文展示3264(1)

图文展示3264(1)

副标题

作品说明

      根据国际青年人工智能大赛评审方案,利用“探索者”系列硬件设备搭建了可以进行物件搬运的自主小车以及可以利用无限遥控模块进行手动控制的物件搬运辅助。借助 arduino软件图形化编程,对小车控制在软件和硬件层面上实现了在复杂地形下实现垃圾捡拾和垃圾搬运以及自动车在可行动范围内的黑线循迹。随后根据比赛要求对两辆车在电机行进、舵机转动、以及各种传感器配合等方面的相关算法进行合理优化,以达到最佳的垃圾捡拾效率。

      关键词:“探索者”装配图形化编程最优路径策略Arduino

1. 作品概述

      作品是一套环保工具,我们称之为环保型垃圾搬运与回收能手,它主要是一款在复杂地形下实现垃圾搬运和垃圾回收的机器人。采用两个机器人小车相互配合的方式完成垃圾捡拾和垃圾搬运。甲车(遥控车)由人为操控,主要负责在不同地形下(如野外,崎岖路段,陡坡路段等)捡拾垃圾,并将垃圾放置于临时存放点。乙车(自主车)自主移动,负责到甲车放置垃圾的指定位置搬运垃圾,并将其放入垃圾回收站。通过自主车和遥控车配合作业,遥控车用于将垃圾物品捡拾并放置在垃圾临时存放点;自主车通过与遥控车通讯将临时存放点的垃圾搬运到垃圾回收站。机器人可以在实际中夹取与模拟垃圾大小类似大部分物品,包括塑料水瓶,易拉罐等,在物体倒置时,也能够夹起来。后续改进主要致力于从数据中学习提升自己的判断能力以及分类识别能力。这样一来就大大方便了环卫工人,他们可以不用在室外受太阳的暴晒,只需要在控制室休息就可以了。它的设计不仅实现了劳动力的解放,也实现了垃圾捡拾分类和回收,符合节能减排理念,为人们的生活创造更健康更美好的环境。

2. 结构方案

2.1 作品结构简图

2.1.1 遥控车结构图

作者:石苏雅 陈凯莉 荣山雨

单位:山东大学(威海)

指导老师:庞豹

作品说明

遥控车结构图

2.1.2 自主车结构图

自主车结构图

2.2 设计思路

2.2.1 底座及驱动轮

      遥控车和自主车的底盘均使用7*11孔平板,并且采用四驱设计。根据两车活动空间及范围不同,遥控车和自主车的驱动轮采用不同的设计。其中遥控车前轮使用大轮外绕一圈履带作为其驱动轮,后轮采用小轮,这一设计有助于遥控车很好的爬上楼梯,有助于夹取更高处的工件;而自主车主要是循迹行进,对其车身高度以及越障能力要求不高,因此自主车使用小轮胎作为其驱动轮。智能车的底盘及驱动轮设计在完成基本任务的前提下,尽量做到了精简,这即可提高小车的灵敏度又可减轻工作量。

2.2.2 机械手爪

      遥控车机械手部分使用两个舵机来完成,共有两个自由度。一个舵机是对机械臂的抬起与下放进行控制,活动角度为0~120°,基本实现了各个工件所在位置的全覆盖;另外一个舵机控制机械爪的开合,机械手爪由多个套件连接并采用齿轮咬合结构驱动,末端也适当加长,保证了夹取时的稳定性。两个舵机相互配合,从而达到准确夹取工件的目的。

      自主车部分有两个机械爪,顶部机械爪由两个舵机控制其位置,方便放入顶部的回收点,爪的内部加了两根铝棒,使得自主车在夹取时能够将工件牢牢抓住;底部机械爪没有选用自由度较高的机械爪进行装配,而是选择了将工件推进装配位的策略。为了防止在推工件的过程中,由于摩擦力过大等环境因素导致的工件倾斜状况的出现,在设计推工件的装置时,安装位置较为靠下,尽可能降低了由于重心偏移而产生工件倾斜状况的出现概率,并且装置的内部也加了两根铝棒,以便后期将工件推入装配箱。

2.2.3 传感器以及模块选取

      自主车循迹部分采用两个灰度传感器,通过传感器的配合使用,在实现常见循迹功能之余,在面对赛道上的路口时也能准确做出判断。在自主车较高位置使用了触碰传感器,此传感器的高度与装配工件的黑箱上沿大致相同,通过对触碰传感器返回信号的读取与判断,实现自主车在装配完成后能够后退、转弯、直行,然后继续循迹。

      为了实现遥控车与手柄的通信,分别在遥控车主控板以及手柄模块安装NRF24L04无线通信模块以实现通过无线手柄控制遥控车运动的功能。


3. 控制方案

3.1 模块化设计

      整个控制方案遵循模块化设计,将机器人的每个动作包装成各个子程序,既方便调试也方便改动,操作起来直观整洁。两部车也可以共用一部分控制函数,更方便于从顶层设计整个项目,大幅度提高效率。

3.2 控制系统设计

3.2.1 控制系统设计思路

      控制系统分为遥控车无线手柄控制、自主车自主运动控制部分。

      遥控车无线手柄控制,包括Bigfish扩展板以及Birdmen手柄扩展板,两个NRF无线串口模块分别用于控制信号的发送和接收。Birdmen手柄扩展板两个手柄可以分别在两个方向上检测0~1024的模拟量,然后将得到的数值映射至0~3,可以将手柄的控制位置进行区域的二维简单划分,并合理利用手柄扩展板上的LED模块及两个按键,可以实现非常个性化的电机以及舵机控制。本队利用左手柄控制电机(即遥控车车身的前进、后退、转弯),右手柄控制舵机(即遥控车车爪的起落以及抓取和松开),对于不同的地形采用不同的操作方式使得小车有更好的抓取效果。

1遥控机器人的结构设计

      整体平台与驱动机构

      传统的四轮车式平台,宽阔的平台上可以安装控制主板、机械臂等一系列功能控件;驱动机构与自主机器人一致,采用电机驱动,不同的是,采取四电机驱动,能够有效、稳定地为爬坡提供动力。

控制机器人平台

抓取机构

      本作品的抓取机构是一个简易的机械臂。机械臂由舵机驱动,使用齿轮和曲连杆组成抓手。通过舵机输出正、负角位移,来控制机械臂抓取放开动作。

抓取机构

2自主机器人的结构设计

      自主车自主运动控制部分。该部分以场地为基础并加入合适的逻辑步骤,以让小车完成物件的检测和搬运工作。根据比赛要求,首先利用三个灰度传感器模块进行黑线寻迹的基础操作。其中左中右三个灰度传感器返回的数值,根据场地的光照和阴影所确定的阈值可分为黑、白两种选择。当中间的灰度传感器为黑色时,即证明小车灰度传感器安装区域的中心在黑线上方,否则不是在黑线上方。当左右分别为黑、白或者白、黑时,根据是否在黑线上方来判定此处应该进行拐弯还是应该原地调整以进行直行。当小车行驶到相应的位置后、使用遥控车来触发自主车(利用触须传感器或红外传感器),自主车即进入下一个状态从而进行物件的抓取和推送。当推送结束后,利用传感器检测是否到达目标位置,再进行相应的后退或转向操作,进而进行下一个物件的搬运,以此重复三次即可。

整体平台

      以两个常规轮和一个万向轮为支点,用两块铝板拼接作为主承载平台;在万向轮一端两侧拼接两块突出铝板,作为传感器的承载平台;在运动前端拼接一块装配版,用于装配零件,辅助推动动作正确执行。

自主机器人平台

驱动机构

      使用电机,配合常规轮与电池使机器人运动。

驱动机构

传感机构

      使用灰度传感器、触碰传感器对地面标识、是否触碰进行判别,将信号传回控制器。传感机构是自主机器人的眼睛,是最重要的机构单元。

3.2.2程序流程图

遥控车控制

遥控车控制程序流程图

自主车控制

自主车控制程序流程图

3.2.3 创新点

      ① 通过给自主机器人的平台前端外侧增加两个固定架,使两个传感器之间的距离固定,且恰到好处的使标识留在两个传感器的内侧,让传感器对标识的识别更加准确

      控制机器人的机械臂更短,使得机械臂在转动上更迅速,能够更快的对工件进行抓取。

      设置了具有最短路径的自主车运行路线,并对自主车和遥控车搬运物件的时间分配策略进行了优化,在自主车搬运的过程中让遥控车进行下一个物件的抓取放置。

      根据比赛规则,本队采用推而非抓的方式让自主车将物件转移到目标地点。一方面可以避免使用复杂的控制算法,从而降低了控制的复杂度;另一方面能够更加有效地节省时间。同时设置了比较出色的物件推动爪,使得在物件推动过程中能够使物件可以平滑稳定的移动,而不产生重心偏移、侧翻的问题。

4. 设计及制作过程

4.1 场地分析

竞赛场地

4.2 装配策略制定

装配

优先级

工件

优先级

1

窄桥

2

左,右

2

草地

1

1

管道

3


      对于遥控车而言,事先抓取草地上的物件,后在自主车进行搬运的过程中将窄桥或者管道上的物件抓取,后两者相对于草地要更多的时间,所以将其顺序相应的后延。当花费一定时间进行抓取之后,手动将物件放在预先设置在算法中的位置上,给自主车以相应的信号进行后续的操作。

4.3 机械结构的安装

4.3.1 车轮、机械爪等零件组装

车轮组装

机械爪安装

4.3.2 底座及配件安装

遥控车底座

自主车底座

4.4 控制程序的编写

4.4.1 控制功能分析

      采用NRF24L01进行无线通信时,对于控制模块(即遥控器对应Basra板内部的程序),需要设置程序能够对遥控手柄的不同方位进行判断,并发出对应的控制信号;对于接收模块(即受控小车对应的Basra板),需要在接收遥控器的信号后,进行对应的动作。对于自主小车,需要能够有通过黑线来寻迹的功能,同时也需要有相应的移动算法来辅佐遥控车的装配工作。

4.4.2 程序框图绘制

总体控制流程图

5. 总结及评价

5.1 自我评价

      对于遥控车,能够实现前进,小幅度转弯,后退以及机械爪的起落和抓取。在通信部分做到了实时通信收发信号,改进了传统的电机停止方法,在小车控制停止的方面做到了即动即停,为了便于通信,在遥控车和手柄机械结构上都做了相应的适配性调整。但不足之处在于将1024的值映射到了0-3上,以至于在移动手柄时无法做到定量加速减速。同样的将手柄划分成不同的区域,以及手柄控制的自身硬件上的某些误差也会导致手柄控制遥控车速度不是很精准,在无线传输具有一定的延迟的前提下,可以完成给定的任务,但对于抓取的灵敏度和速度方面暂时没有更好的改进。

      对于自主车,虽然实现了小车的黑线寻迹,但为了实现更加高效的物件搬运,有的时候并不需要总是沿着场地上的黑线走。同时小车在遇到直角转弯以及十字路口的各种决策问题还有待优化。同时,传感器的使用受到场地的光照以及温度影响,需要提前测定场地的各种参数,并在比赛前临时更改为合适的阈值,才能达到更好的比赛效果。

5.2 指导教师评价

      该队伍使用“探索者”套件,完成了自主车和遥控车的硬件组装及软件控制。硬件组装能做到充分考虑机械设计的要求及原则,保证符合竞赛标准及功能可靠性的前提下,能考虑简化小车,尽量使小车轻量化。编程时,队伍成员表现出清晰的算法思路及扎实的控制理论。最终实现了小车遥控及自动循迹功能,两辆小车流畅配合,能够快速准确完成工件装配任务。

6. 示例程序

① 遥控车部分:遥控信号发送代码子程序

void SerialPrint()

{

  if (( ( ( _ABVAR_1_Forward ) == ( 3 ) ) && ( ( _ABVAR_2_Side ) == ( 1 ) ) ))

  {

    Serial.print("1");

    Serial.println();

  }//向左前方行驶

  if (( ( ( _ABVAR_1_Forward ) == ( 3 ) ) && ( ( _ABVAR_2_Side ) == ( 2 ) ) ))

  {

    Serial.print("2");

    Serial.println();

  }//直行

  if (( ( ( _ABVAR_1_Forward ) == ( 3 ) ) && ( ( _ABVAR_2_Side ) == ( 3 ) ) ))

  {

    Serial.print("3");

    Serial.println();

  }//向右前方行驶

  if (( ( ( _ABVAR_1_Forward ) == ( 2 ) ) && ( ( _ABVAR_2_Side ) == ( 1 ) ) ))

  {

    Serial.print("4");

    Serial.println();

  }//原地向左旋转

  if (( ( ( _ABVAR_1_Forward ) == ( 2 ) ) && ( ( _ABVAR_2_Side ) == ( 3 ) ) ))

  {

    Serial.print("6");

    Serial.println();

  }//原地向右旋转

  if (( ( ( _ABVAR_1_Forward ) == ( 1 ) ) && ( ( _ABVAR_2_Side ) == ( 1 ) ) ))

  {

    Serial.print("7");

    Serial.println();

  } //向左后方行驶

  if (( ( ( _ABVAR_1_Forward ) == ( 1 ) ) && ( ( _ABVAR_2_Side ) == ( 2 ) ) ))

  {

    Serial.print("8");

    Serial.println();

  }//后退

  if (( ( ( _ABVAR_1_Forward ) == ( 1 ) ) && ( ( _ABVAR_2_Side ) == ( 3 ) ) ))

  {

    Serial.print("9");

    Serial.println();

  }//向右后方行驶

  if (( ( ( _ABVAR_1_Forward ) == ( 2 ) ) && ( ( _ABVAR_2_Side ) == ( 2 ) ) ))

  {

    Serial.print("5");

    Serial.println();

  }//原地停止(即初始和默认状态)

  if (( ( ( _ABVAR_3_Height ) == ( 1 ) ) && ( ( _ABVAR_4_Catch ) == ( 2 ) ) ))

  {

    Serial.print("10");

    Serial.println();

  }//放下爪子

  if (( ( ( _ABVAR_3_Height ) == ( 3 ) ) && ( ( _ABVAR_4_Catch ) == ( 2 ) ) ))

  {

    Serial.print("11");

    Serial.println();

  }//抬起爪子

  if (( ( ( _ABVAR_3_Height ) == ( 2 ) ) && ( ( _ABVAR_4_Catch ) == ( 1 ) ) ))

  {

    Serial.print("12");

    Serial.println();

  }//收紧爪子

  if (( ( ( _ABVAR_3_Height ) == ( 2 ) ) && ( ( _ABVAR_4_Catch ) == ( 3 ) ) ))

  {

    Serial.print("13");

    Serial.println();

  }//松开爪子

}


void RI_RI()//原地向右旋转

{

  analogWrite(5 , 0);

  analogWrite(6 , 250);

  analogWrite(9 , 250);

  analogWrite(10 , 0);

}

void FO_FO()//直行

{

  analogWrite(5 , 250);

  analogWrite(6 , 0);

  analogWrite(9 , 250);

  analogWrite(10 , 0);

}

void Down()//放下爪子

{

  if (( ( _ABVAR_3_UD ) < ( 120 ) ))

  {

    _ABVAR_3_UD = 120 ;

  }

  else

  {

    _ABVAR_3_UD = ( _ABVAR_3_UD - 20 ) ;

  }

  analogWrite(12 , _ABVAR_3_UD);

}

void Tight()//收紧爪子

{

  if (( ( _ABVAR_4_TL ) > ( 180 ) ))

  {

    _ABVAR_4_TL = 180 ;

  }

  else

  {

    _ABVAR_4_TL = ( _ABVAR_4_TL + 15 ) ;

  }

  analogWrite(3 , _ABVAR_4_TL);

}

void LE_LE()//原地向左旋转

{

  analogWrite(5 , 250);

  analogWrite(6 , 0);

  analogWrite(9 , 0);

  analogWrite(10 , 250);

}

void Stop()//原地停止

{

  analogWrite(5 , 0);

  analogWrite(6 , 0);

  analogWrite(9 , 0);

  analogWrite(10 , 0);

}

void Loose()//松开爪子

{

  if (( ( _ABVAR_4_TL ) < ( 50 ) ))

  {

    _ABVAR_4_TL = 50 ;

  }

  else

  {

    _ABVAR_4_TL = ( _ABVAR_4_TL - 15 ) ;

  }

  analogWrite(3 , _ABVAR_4_TL);

}

void LE_BA()//向左后方移动

{

  analogWrite(5 , 0);

  analogWrite(6 , 200);

  analogWrite(9 , 80);

  analogWrite(10 , 0);

}

void BA_BA()//后退

{

  analogWrite(5 , 0);

  analogWrite(6 , 250);

  analogWrite(9 , 0);

  analogWrite(10 , 250);

}

int TURNRIGHT_flag=0;

void forward();

void back();

int flag1;

int flag2=0;

int _ABVAR_4_a;

int op1=80;

int cl1=-25;

int up2=60;

int dn2=100;

int up3=140;

int dn3=80;

int dn22=100;

int dn33=105;

void turn_left();

void turn_right();

void stop();

int servoPin7 = 7;

int servoPin3 = 3;

int servoPin8 = 8;

void setup()

{

  pinMode( 14, INPUT);

  pinMode( 10, OUTPUT);

  pinMode( 6, OUTPUT);

  pinMode( 5, OUTPUT);

  pinMode( 9, OUTPUT);

  pinMode(servoPin7,OUTPUT);

  pinMode(servoPin3,OUTPUT);

  pinMode(servoPin8,OUTPUT);

}

void loop()

{

  while ( true )

  {

    if(flag2==0)

    {   //wanyaozhuaqv

    servo3(70);

    servo7( 120 );

    delay(500);

    servo8( dn3 );

    delay(500);

    forward();

    delay(2000);

    stop();

    servo3( cl1);

    delay(500);

    zhiyaoxingzou();

    flag2=1;

  }

    forward();

    if( (analogRead(18) )<( 150UL ) && (analogRead(17) )<( 350UL ) && (TURNRIGHT_flag==0))

    {

      forward();

      delay(500);

      turn_right();

      delay(2600);

      TURNRIGHT_flag=1;

    }

    if (   (analogRead(17) )<( 350UL )&& (TURNRIGHT_flag==1) )

    {

      turn_left();

    }

   

    if (!( digitalRead(14) ))

    {

      if(flag2==1)

      {

        stop();

        zhiwu();

        delay(200);

        zhiyaoxingzou();

        back();

      flag2=2;

    }

     else if(flag2==2)

        back();   

    }

  }

}

void zhiwu(){  

  for(int i=60;i<=85;i++)

  {

    servo7(i);//140zhengchang,100wangshangtai

    delay(5);

  }

   for(int i=120;i>=85;i--)

  {

  servo8( i );//200zhiliu,120wanyao

  delay(30);

  }

  delay(500);

  for(int i=cl1;i<op1;i++){

  servo3( i );//90shoujin,160songkai

  delay(50);

  }

}

void wanyaojiaqu(){

  servo3( op1 );//90shoujin,160songkai

  delay(1000);

  servo7( dn2 );//140zhengchang,100wangshangtai

  delay(1000);

  servo8( dn3 );//200zhiliu,120wanyao

  delay(1000);

 

  servo3( cl1 );//90shoujin,160songkai

}

void zhiyaoxingzou(){

  servo7(up2);//140zhengchang,100wangshangtai

  delay(500);

  servo8(up3);//200zhiliu,120wanyao

  delay(500);

  //servo3(cl1);//90shoujin,160songkai

}

void turn_left()

{

  for (_ABVAR_4_a=1; _ABVAR_4_a<= ( 2000 ); ++_ABVAR_4_a )

  {

    analogWrite(9 , 150);

    analogWrite(10 , 0);

    analogWrite(5 , 0);

    analogWrite(6 , 150);

  }

}

void turn_right()

{

    analogWrite(9 , 0);

    analogWrite(10 , 100);

    analogWrite(5 , 100);

    analogWrite(6 , 0);

}

void back()

{

  analogWrite(9 , 0);

  analogWrite(10 , 120);

  analogWrite(5 , 0);

  analogWrite(6 , 120);

  delay( 600 );

  analogWrite(9 , 0);

  analogWrite(10 , 120);

  analogWrite( 5 , 120);

  analogWrite(6 , 0);

  delay(1700);

  forward();

  delay(1000);

  flag2=2;

  loop();

}

void forward()

{

  analogWrite(9 , 100);

  analogWrite(10 , 0);

  analogWrite(5 , 100);

  analogWrite(6 , 0);

}

void stop()

{

  analogWrite(9 , 0);

  analogWrite(10 , 0);

  analogWrite(5 , 0);

  analogWrite(6 , 0);

}

void servo7(int angle) {

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

    int pulsewidth = (angle * 11) + 500;

    digitalWrite(servoPin7, HIGH);

    delayMicroseconds(pulsewidth);

    digitalWrite(servoPin7, LOW);

    delayMicroseconds(20000 - pulsewidth);

  }

}

void servo3(int angle) {

  for (int i = 0; i < 30 ; i++) {

    int pulsewidth = (angle * 11) + 500;

    digitalWrite(servoPin3, HIGH);

    delayMicroseconds(pulsewidth);

    digitalWrite(servoPin3, LOW);

    delayMicroseconds(20000 - pulsewidth);

  }

}

void servo8(int angle) {

  for (int i = 0; i < 2; i++) {

    int pulsewidth = (angle * 11) + 500;

    digitalWrite(servoPin8, HIGH);

    delayMicroseconds(pulsewidth);

    digitalWrite(servoPin8, LOW);

    delayMicroseconds(20000 - pulsewidth);

  }

}

遥控车代码:受控小车的决策和动作执行

自主车部分:实现循迹以及放置工件的功能

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

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