小型家庭自主巡检机器人--第二篇:机器人底层驱动板设计

在此系列的首篇中,我已经从整体上对机器人的功能、结构等做了一个大体的介绍。从本篇开始,我将详细的针对机器人的每一个部分来进行介绍,内容包括我的设计思路、想法以及最终实现的过程。

本篇所涉及的文件及代码可见于本人代码仓库:https://github.com/softdream/robot_projects/tree/master/bottom_control_board

本着由底层向上层的开发顺序,我也将按照这个顺序来进行讲解。那么首先要说的就是底层控制板。这是整个机器人的核心之一,由于机器人的外部设备是五花八门的,因此需要对它们进行统一的驱动和管理,因此我设计了一块电路板来专门做这个事情。该电路板采用了一颗esp32单片机作为控制器,在这上面分别实现了对电机的控制功能、与上层控制器的通信功能以及各种传感器数据的采集功能。该控制板可以将采集到的传感器数据打包并通过串口发送到上层控制器中并由上层的控制器进行处理,同时上层控制器会将控制指令通过串口下发到esp32上,esp32需要解析控制指令并控制电机转速从而控制机器人的运动。

关于底层控制板的原理图、pcb文件以及bom表我将上传至github仓库中,感兴趣的小伙伴可以直接自取使用。

而关于底层控制板的程序设计,将是本篇文章的核心内容,接下来将以重点的几个硬件设备为例进行详细的介绍。

1. 直流电机控制及编码器数据采集

本机器人使用了两个有刷直流减速电机,电机在12V供电下的最大转速约为300RPM(转/分钟)。同时每个直流电机的尾部集成了AB相编码器。电机每转一圈编码器会输出234个脉冲信号。玩过智能小车的朋友都知道,有刷直流电机的驱动是比较简单的,我在底层驱动板上使用的电机驱动芯片为TB6612FN,可以使用pwm信号控制电机的转速,同时可以用gpio的电平信号控制电机转动的方向。所以先定义引脚的功能如下:

// 左轮电机
#define IN1 26  // 电机1控制引脚1
#define IN2 27  // 电机1控制引脚2
#define PWMA 14 // 电机1 pwm引脚

// 右轮电机
#define IN3 25 // 电机2控制引脚1
#define IN4 4  // 电机2控制引脚2
#define PWMB 0  // 电机2 pwm引脚

#define LA 13 // 电机1编码器 A 相位
#define LB 12 // 电机1编码器 B 相位
#define RA 2  // 电机2编码器 A 相位
#define RB 15 // 电机2编码器 B 相位

esp32上提供了引脚输出pwm信号的接口,可以直接使用,接口主要有三个:

ledcSetup(pwm_Channel_A, FREQ, resolution); // 设置pwm的通道(pwm_Channel_A)、频率(FREQ)以及分辨率(resoluation)
ledcAttachPin(PWMA, pwm_Channel_A); // 将pwm通道与引脚绑定
ledcWrite(pwm_Channel_A, pwm_value); // 设置pwm信号的占空比,如果分辨率是8的话,那么pwm_value的取值范围是(0~255)  

使用上面的三个接口就能控制电机的转速了,非常方便。但是编码器的数据接收就稍微复杂一些,为了能够在测量电机的转速的同时还能辨别出电机的转动方向,一般编码器上都是是有两个输出的,一个A相输出一个B相输出,A相输出的信号和B相输出的信号会有一个相位差,通过这个能判断出电机的转动方向。在esp32上要开启引脚的外部中断功能,在AB相的脉冲到来时(边沿触发),先通过引脚的电平来判断正反转,然后使用计数器来记录脉冲个数。

// 在外部中断中处理编码器数据
void leftEncoder()
{
  if( digitalRead(LA) && !digitalRead(LB) ){ // A相上升沿并且B相为低电平时为正转
    l_count ++;
  }
  else if( !digitalRead(LA) && digitalRead(LB) ){ // A相下降沿并且B相为高电平时为正转
    l_count ++;
  }
  else { // 其他情况就是反转
    l_count --;   
  }
}

在得到脉冲个数的同时我们就可以使用大M法来对电机进行测速,所谓大M法即统计固定时间段内的脉冲数,并且我们已知了电机转一圈一共有的脉冲数,根据比例即可算出电机在单位时间段内转的圈数。

要实现这个功能,我们首先需要开启esp32上的定时器,幸运的是esp32库中提供了Ticker类,可以直接调用定时器:

Ticker control_timer; // 实例化一个对电机进行控制的定时器

在初始化的时候设置定时器的定时时间和定时器中断函数:

// 打开定时器中断
control_timer.attach_ms( interrupt_time_control, motorControl ); // 其中interrupt_time_control=50,即50ms进入一次定时器中断,motorControl为中断处理函数

在定时器中断函数中使用大M法进行测速:

void motorControl()
{    
  float l_rpm = ( 60 * l_count / ( pulse_number * 0.05 ) ); // 计算做电机的转速
  float r_rpm = -60 * r_count / ( pulse_number * 0.05 );  // 计算右电机的转速
  ......
}

2. 底盘运动学模型

我们通过编码器测出两个轮子的转速之后,就可以根据底盘的运动学模型来计算出机器人运行单位时间内的旋转角度增量以及单位时间内的唯一增量,为后续的里程计估算做一个基础。在这里我们使用两轮差速运动模型:

假设机器人的左轮位移为l_s, 右轮的位移为r_s(这两个值都通过编码器测出),机器人两轮之间的距离为base_width,那么:

位移增量为:(l_s + r_s) / 2;

角度增量为:(r_s - l_s) / base_width;

假设机器人的左轮速度为l_v,右轮的速度为r_v,那么:

线速度:(l_v + r_v) / 2;

角速度:(r_v - l_v) / base_width;

float getDeltaS( long l_count_c, long r_count_c ) // 计算位移增量
{
  float l_s = ((float)l_count_c / pulse_number) * circumference; // 左轮的位移增量
  float r_s = -((float)r_count_c / pulse_number) * circumference; // 右轮的位移增量
  return (l_s + r_s) / 2; 
}

float getDeltaAngle( long l_count_c, long r_count_c ) // 计算机器人旋转的角度增量
{
  float l_s = ((float)l_count_c / pulse_number) * circumference; // 左轮的位移增量
  float r_s = -((float)r_count_c / pulse_number) * circumference; // 右轮的位移增量
  return (r_s - l_s) / base_width;
}

同时我们可以根据运动学模型来解析上层控制器发过来的直流指令,将其解析为左右轮应该具有的转速。控制指令为(线速度,角速度)。

void cacuRPM( float v, float w )
{
  //convert m/s to m/min
  float v_mins = v * 60;
  
  //convert rad/s to rad/min
  float w_mins = w * 60;

  //Vt = ω * radius
  float w_vel = w_mins * base_width;

  float x_rpm = v_mins / circumference;
  float tan_rpm = w_vel / circumference;

  required_rpm_left = x_rpm - tan_rpm * 0.5;
  required_rpm_right = x_rpm + tan_rpm * 0.5;
}

3. PID算法

我们通过cacuRPM(float v, float w)这个函数可以计算出机器人在给定线速度和角速度的条件下,左右轮子应该具有的转速。为了使车轮的转速能够维持在要求的值上,我们还需要使用PID控制算法。PID控制算法应当说是最简单但也是最有效的控制算法之一了。

在本项目中,PID控制算法的实现主要在pid.cpp文件中,其核心代码如下:

const float PID::caculate( const float& target, const float& current )
{
    // error
    float error = target - current;
    
    // Proportional
    float p_out = kp_ * error;

    // Integral
    integral_ += error;
    if( target == 0 && error == 0 ){
      integral_ = 0;
    }
    
    float i_out = ki_ * integral_;

    // Derivative
    float derivative = ( error - pre_error_ );
    float d_out = kd_ * derivative;

    // total output 
    float out = p_out + i_out + d_out;

    // limit
    if( out > max_ ){
            out = max_;
    }
    else if( out < min_ ){
            out = min_;
    }

    // update the pre_error
    pre_error_ = error;

    return out;
}

在每次定时器的中断函数中,我们都通过pid算法分别计算出两个轮子的控制量,然后用这个控制量来作为电机的pwm值即可。

4. IMU控制

我们这里使用的IMU型号为MPU6050,可以测出三轴加速度信息和三轴角速度信息。MPU6050使用IIC协议与ESP32单片机通信,在程序设计时,需要用到“MPU6050_light”这个库,该库提供了IMU的校准,值读取接口,可以直接使用,在本工程中,只需要做简单的封装即可。

首先是IMU的初始化:

void imuInit()
{
  Wire.begin(IMU_SDA, IMU_SCL); // SDA, SCL:这里指定了IIC的引脚
  byte status = mpu.begin(); // 初始化mpu6050

  while(status != 0){ } // 等待初始化完成

  uart1.print("calibration");
  delay(100);
  mpu.calcOffsets(true, true); // mpu6050的简单校准
  delay(2000);

  uart1.print("done");
}

接着对封装一个读取数据的接口:

typedef struct ImuData_ // 定义一个IMU数据结构体,由于机器人在2D空间中移动,因此只关心x轴、y轴加速度以及z轴角速度的数据
{
    float ax; // x轴方向加速度
    float ay; // y轴方向加速度
    float gz; // z轴角速度
}ImuData;

ImuData getImuData()
{
    ImuData imu;
    mpu.update(); // 直接调用api获取mpu6050中测得的数据即可
    imu.ax = mpu.getAccX();
    imu.ay = mpu.getAccY();
    imu.gz = mpu.getGyroZ();
    return imu;
}

5. 串口

在本项目中使用了esp32上的两个串口,串口0主要用于程序下载以及调试。串口1则用于与上层控制器的通信。串口1的初始化为:

HardwareSerial uart1(1); //uart1为全局变量

void uartInit( int baudrate)
{
    uart1.begin( baudrate, SERIAL_8N1, UART1_RX, UART1_TX );
}

我们需要在需要的地方将测得的数据通过串口1发送到上层控制器上,例如我们需要在定时器中断中发送(时间戳,机器人线速度,机器人位置增量,机器人角度增量,z轴角速度,左轮转速,右轮转速)这个数据,那么只需要这样写:

uart1.printf( "meas %ld %.4f %.4f %.4f %.4f %.4f %.4f\n", millis(), velocity, delta_s, delta_angle, imu.gz, l_rpm, r_rpm );

即将整个待发送的信息以字符串的形式发送出去即可。

6. 超声波传感器

超声波传感器起着一个辅助避障的作用。esp32下驱动该传感器的代码也比较简单,其过程如下所示:

float getDistance()
{
    digitalWrite( Trig, HIGH ); // 往Trig引脚写一个高电平
    delayMicroseconds(10); // Trig引脚的高电平至少维持10微秒
    digitalWrite( Trig, LOW ); // 维持10微妙之后拉低Trig引脚

    float dist = pulseIn( Echo, HIGH ) * 0.034 / 2; // pulseIn函数用于检测引脚输出的高低电平的脉冲宽度时间,即超声波传播的时间,该时间*声速/2=距离

    return dist;
} 

7. 主函数分析

void setup()
{
  Serial.begin(115200); // 串口0用于调试和程序下载
  uartInit(230400);  // 初始化串口1,用于与上位机通信
  
  motorGpioInit(); // 电机和编码器的GPIO初始化
  delay(100);
  imuInit(); // IMU的初始化
  delay(100);
  encoderInit(); // 编码器初始化,主要是开启外部中断,并设置为边沿触发模式
  delay(100);
  motorInit(); // 电机初始化,主要是设置pwm控制器参数以及设置定时器参数
  delay(100);

  // 创建任务:获取各个传感器的值
  xTaskCreate(taskSensors,         // 任务函数 
              "sensors",     //  任务名 
              8*1024,            // 任务栈大小,根据需要自行设置
              NULL,              // 参数,入参为空 
              1,                 // 优先级 
              NULL);  // 任务句柄 
}

在setup()中我们主要做了一些初始化工作,并开启了一个新的task。注意在esp32中,可以跑freeRTOS操作系统,因此可以做到多个任务并发执行,而xTaskCreate()即是创建任务的接口函数。

接下来,在loop()函数中,我们主要的工作是非阻塞的接收上层控制器发送过来的指令信息:

void loop()
{
  // 接收串口发过来的指令,主要是线速度和角速度
  int len = uart1.available();
  if( len > 0 ){
    memset(recv_buff, 0, sizeof(recv_buff)); // recv_buff为接收缓存
    uart1.readBytes( recv_buff, len );
    if( len == 8 ){
        Control u;
        memcpy( &u, recv_buff, sizeof(u) ); 
        cacuRPM( u.v, u.w ); // 根据控制指令设置左右轮需要的转速
    }
  }
  delay(100);
}

另外在上面我们还创建了一个名为"sensors"的新任务,在这个任务中,我们来轮询读取各个传感器的值,这块的代码可以根据实际情况进行修改:

// 用来获取传感器数据的任务
void taskSensors(void *parameter)
{
  ultraSonicInit();
  delay(100);
  
  while(1){
    int humidity = 0;
    int temperature = 0;
    getHumidityAndTemperature( humidity, temperature ); // 获取温湿度值

    float distance = getDistance(); // 获取超声波距离值

    float voltage = getBatteryVoltage(); // 获取电压值

    uart1.printf( "sens %d %d %.2f %.2f\n", humidity, temperature, distance, voltage ); // 发送到上位机
    
    vTaskDelay(100); // 10Hz频率
  } 

  vTaskDelete(NULL);
}

以上就是整个底层控制板的程序分析。在下一篇中,我将介绍上层控制器是如何接收这些数据并对其进行处理的。

坐等更新

底层控制板的原理图、pcb文件以及bom表没看到,能否上传下,我去打个版

来了来了

好的,我整理好了放上去,等我下

我也没看到,能不能放下,感谢啊