什么是ros_arduino_bridge

ros_arduino_bridge是自定义通信协议方式来与Arduino进行通信,和大多数控制形式一致,将通信协议固定可以让初学者在使用过程中了解通信协议,由于是自定义通信协议形式,可以即插即用,和rosserial_arduino有本质差别,不过在使用过程中需要自己配置,所以需要有一定的arudino编程基础,早期的EAI dashgo D1采用的就是这种形式,使用这个库可以缩短底盘开发时间,并且Arduino有很多开源包供使用,会相对轻松一些。

为什么使用ros_arduino_bridge

玩了ROS的仿真之后想自己做个雷达车玩玩,奈何自己不会32单片机,买他们的成品又太贵,碰巧会Arduino,所以被迫选择。

在Gazebo仿真成功之后,我们可以将tf坐标关系和topic相关话题试着往实物机器人上面迁移。这个时候我们是需要一块电机驱动板。这块板子需要能驱动电机,同时读取电机的编码器数据回馈,而且速度是需要进行闭环控制的。

我们在仿真系统下,算法层和驱动层的融合部位,我们需要维护的是tf坐标关系,另外就是在底盘驱动的位置需要订阅cmd_vel速度话题并发布Odom里程计话题。

ros_arduino_bridge刚好可以解决这个问题!

我们在Arduino烧录ros_arduino_bridge的固件程序,通过ros_arduino_bridge的驱动功能包就可以完成订阅cmd_vel速度话题并发布Odom里程计话题,当然tf还是要你自己来维护的!

ros_arduino_bridge是怎么实现的

我们玩ROS小车用的电机大多数为直流编码电机,这种电机有六根接线,分别是M+、M-、VCC、GND、A、B。

我们通过电机驱动模块来驱动电机,实现对电机转向和转速的控制。电机的A、B是霍尔测速传感器的,哪个黑乎乎的圆柱是个磁铁均匀分布着N极和S极,磁铁的两侧有霍尔传感器,当检测到对对应的磁极时会有电平的变化。这里有两个霍尔做检测,我们可以得知当前电机是正转还是反转,所以这里的霍尔信号是A和B相,两相之间的相位差为90°(这句听不懂没关系。,知道为晒有两个,起啥作用就够了)。

通过对AB相编码器进行计数,看它俩触发了多少次,我们可以得到电机真实的转了几圈,找到电机转动和轮子转动的关系,就可以计算出小车跑了多远的距离,这就是里程计——Odom。当然这只是轮式里程计,如果出现轮子打滑、堵转等等情况,肯定是要丢数据的。所以在ROS下的里程计,大多数IMU里程计+轮式里程计,有条件可以再加个VO视觉里程计。

电机的速度控制,我们可以用电机驱动模块来实现。我经常用的是TB6612和L928N,两个的用法完全一样,只是L298N的电机最大电流为2A,TB6612的电机最大电流为1A。

这个是TB6612电机驱动模块,AO1、AO2对应一个电机,通过AIN1、AIN2、PWMA三个引脚来控制,其中AIN1、AIN2控制方向,PWMA控制转速;BO1、BO2和BIN1、BIN2、PWMB相同。VM是驱动供电,电机大多是在12V的情况下才能正常驱动,不然会因为电压不足而导致动力不足;VCC是逻辑供电,VCC和GND接在单片机上面,给信号引脚提供一组逻辑电压(参考电压)。最后还有个STBY是正常工作/待机状态的切换,也可以理解为电机的使能控制。

这个就是TB6612驱动模块的所有引脚功能,TB6612的使用真值表如下。

0是低电平,1是高电平,X是任意电平,这个应该不用多说吧!

那么L298N又是什么样的呢,我们来看看!

可以看到和TB6612基本是一样的,逻辑输入部分的IN1、IN2、IN3、IN4来控制两组电机的转向,两个使能通道控制电机的转速。

这两个电机模块都是通过两个IN、一个EN(PWM)来实现对电机转速和转向的控制。这里注意一下TB6612的STBY引脚的功能其实就是L298N的自由停止状态和制动停止状态。

我们通过编码器可以获取转速、里程计等信息,这个就是Odom;我们通过电机驱动模块来驱动电机、控制电机,这个就是cmd_vel。

ros_arduino_bridge是怎么实现的

这里我们先来解读以下ROSArduinoBridge的Arduino代码。

ROSArduinoBridge是主文件,我们对它进行编译并上传到Arduino即可,这文件的内内容我们到最后来说~

我们首先来看下commands.h指令相关的头文件,ros_arduino_bridge固件通讯类似自定义通讯的方式,所定义的通讯指令,我们都可以在这个文件看到~

#ifndef COMMANDS_H
#define COMMANDS_H

#define ANALOG_READ    'a'
#define GET_BAUDRATE   'b'
#define PIN_MODE       'c'
#define DIGITAL_READ   'd'
#define READ_ENCODERS  'e'
#define MOTOR_SPEEDS   'm'
#define PING           'p'
#define RESET_ENCODERS 'r'
#define SERVO_WRITE    's'
#define SERVO_READ     't'
#define UPDATE_PID     'u'
#define DIGITAL_WRITE  'w'
#define ANALOG_WRITE   'x'
#define LEFT            0
#define RIGHT           1

#endif

a指令是模拟值读取;b指令是获取波特率;c指令是设定引脚模型;d指令是数字引脚状态读取;e指令是读取编码器数值;m指令是电机速度控制;p指令是检测设备是否链接成功,能否于软件通讯;r指令会重置编码器的所有数值;s指令是设定舵机角度值;t指令是读取舵机角度值;u指令是更新pid;w指令是设定数字引脚状态;X指令是设定模拟引脚状态。0和1是左右轮的区分标识。

我们在调试的时候发送“m 50 50”指令就可以看到电机的转动,发送e指令可以获取当前编码器的数值,r指令会重置编码器计数等等。

我们再来看下diff_controller.h的内容,如下~

typedef struct {
  double TargetTicksPerFrame;    // target speed in ticks per frame
  long Encoder;                  // encoder count
  long PrevEnc;                  // last encoder count

  int PrevInput;                // last input
  int ITerm;                    //integrated term
  long output;                    // last motor setting
}
SetPointInfo;

SetPointInfo leftPID, rightPID;

/*PID默认参数*/
int Kp = 20;
int Kd = 12;
int Ki = 0;
int Ko = 50;

unsigned char moving = 0;

/*重置PID*/
void resetPID(){
   leftPID.TargetTicksPerFrame = 0.0;
   leftPID.Encoder = readEncoder(LEFT);
   leftPID.PrevEnc = leftPID.Encoder;
   leftPID.output = 0;
   leftPID.PrevInput = 0;
   leftPID.ITerm = 0;

   rightPID.TargetTicksPerFrame = 0.0;
   rightPID.Encoder = readEncoder(RIGHT);
   rightPID.PrevEnc = rightPID.Encoder;
   rightPID.output = 0;
   rightPID.PrevInput = 0;
   rightPID.ITerm = 0;
}

/*执行PID计算*/
void doPID(SetPointInfo * p) {
  long Perror;
  long output;
  int input;
  
  input = p->Encoder - p->PrevEnc;
  Perror = p->TargetTicksPerFrame - input;
  output = (Kp * Perror - Kd * (input - p->PrevInput) + p->ITerm) / Ko;
  
  p->PrevEnc = p->Encoder;
  output += p->output;
  
  if (output >= MAX_PWM)
    output = MAX_PWM;
  else if (output <= -MAX_PWM)
    output = -MAX_PWM;
  else
    p->ITerm += Ki * Perror;

  p->output = output;
  p->PrevInput = input;
}

/*更新PWM数值*/
void updatePID() {
  leftPID.Encoder = readEncoder(LEFT);	//读取左轮编码器数值
  rightPID.Encoder = readEncoder(RIGHT);//读取右轮编码器数值
 
  if (!moving){
    if (leftPID.PrevInput != 0 || rightPID.PrevInput != 0) 
      resetPID();
    return;
  }

  doPID(&rightPID);	//右轮进行计算
  doPID(&leftPID);	//左轮进行计算

  setMotorSpeeds(leftPID.output, rightPID.output);	//设置电机转速
}

这里是关于PID计算的相关实现,将两个轮子的速度值转为PWM值,通过setMotorSpeed函数实现对电机的控制。这里还对最大PWM值做了限位~

这里说到了电机驱动,那我们先来看下motor_driver的文件,motor_driver.h内容如下~

#ifdef L298_MOTOR_DRIVER
  #define RIGHT_MOTOR_BACKWARD 7
  #define LEFT_MOTOR_BACKWARD  4
  #define RIGHT_MOTOR_FORWARD  9
  #define LEFT_MOTOR_FORWARD   6
  #define RIGHT_MOTOR_ENABLE 8
  #define LEFT_MOTOR_ENABLE 5
#endif

void initMotorController();	//初始化电机控制
void setMotorSpeed(int i, int spd);	//设定电机转速
void setMotorSpeeds(int leftSpeed, int rightSpeed);	//设定左右轮转速

这个头文件声明了三个函数和六个常量,我们这里使用L298N、L298P、TB6612等等,只要是符合三根线,两根控制方向、一根控制转速的的驱动器即可。我们在motor_driver.ino文件来看下这部分具体是怎么实现的!

void initMotorController()
{
  	//初始化拉高使能引脚,轮子处于制动状态
	digitalWrite(RIGHT_MOTOR_ENABLE, HIGH);
  	digitalWrite(LEFT_MOTOR_ENABLE, HIGH);
}
  
void setMotorSpeed(int i, int spd) 
{
  	unsigned char reverse = 0;
  	
  	if (spd < 0)	//根据速度值判定判定方向
    {
      spd = -spd;
      reverse = 1;
    }
  
  	if (spd > 255)
      spd = 255;
    
  	if(i == LEFT)	//判定是左轮还是右轮
    { 
    	if(reverse == 0) 	//判定方向
        { 
          	analogWrite(RIGHT_MOTOR_FORWARD, spd); 
          	analogWrite(RIGHT_MOTOR_BACKWARD, 0);
        }else if(reverse == 1) 
        { 
          	analogWrite(RIGHT_MOTOR_BACKWARD, spd); 
          	analogWrite(RIGHT_MOTOR_FORWARD, 0); 
        }
    }else
    {
      	if(reverse == 0) 	//判定方向
        { 
          	analogWrite(LEFT_MOTOR_FORWARD, spd); 
          	analogWrite(LEFT_MOTOR_BACKWARD, 0); 
        }else if(reverse == 1) 
        { 
          	analogWrite(LEFT_MOTOR_BACKWARD, spd); 
          	analogWrite(LEFT_MOTOR_FORWARD, 0); 
        }
    }
}
  
void setMotorSpeeds(int leftSpeed, int rightSpeed) 
{
    setMotorSpeed(LEFT, leftSpeed);
    setMotorSpeed(RIGHT, rightSpeed);
}

setMotorSpeeds函数简直就是套娃,而且这个代码写的不讲武德!

我们之前也聊到了关于L298的真值表,转速是通过使能引脚控制的,这里确是将使能引脚一直处于高电平处于制动状态,通过对方向信号电压的控制实现转速,我觉得有点A4950驱动的感觉~

百思不得姐!!!欢迎小伙伴留言解答~

后续内容持续更新中~