基于Micro-ROS的开源全向移动机器人T-Robot(旭日x3派+ESP32)

仓库地址:https://github.com/z2010012286/T-Robot

视频地址:T-Robot v0.1版本发布!开源全向移动机器人(Based on Micro-ROS)

在这里插入图片描述

0 开源动机

  • 断断续续学习了大约1年的ROS和micro-ROS,总想着动手做点什么
  • 旭日x3派+ROS2有很多有趣的东西,需要有那么一个平台去实现
  • 国内似乎还没有底层采用Micro-ROS的开源移动机器人项目(若有,请忽略…)

1 机器人硬件部分

均为淘宝采购,为避免广告嫌疑,不放链接~

  • 机器人底盘布局

  • 主控esp32 (ESP-WROOM-32)+旭日x3派(2GB)

  • 激光雷达:LD14

  • IMU:MPU9250

  • 电机: WGA12-N20直流减速电机 (12V, 1:50减速比)

  • 电机驱动芯片:4颗RZ7889

  • 编码器:AB双相增量式磁性霍尔编码器

  • 电源:12V锂电池;

    • 12V驱动电机;外置12V转5V模块提供DC-5V输出(最大电流4A);
  • 轮子:4麦轮,直径48mm

  • 结构件:切割亚克力板、3D打印

    2 底层固件部分(核心)

    2.1 lib/config

    包含大部分宏定义,引脚定义等。

    2.2 lib/encoder

    c++封装的适用于esp32的编码器库,原作者仓库地址:ESP32encoder

  • 本项目对其进行了必要修改,增加了getRPM()函数,以直接获取转速信息。

    float ESP32Encoder::getRPM(int counts_per_rev)  //counts_per_rev:每转一圈的编码器计数
    {
      counts_per_rev_ = counts_per_rev;
      int64_t encoder_ticks = getCount();
      // this function calculates the motor's RPM based on encoder ticks and delta time
      unsigned long current_time = micros();
      unsigned long dt = current_time - prev_update_time_;
      // convert the time from milliseconds to minutes
      double dtm = (double)dt / 60000000;
      double delta_ticks = encoder_ticks - prev_encoder_ticks_;
      // calculate wheel's speed (RPM)
      prev_update_time_ = current_time;
      prev_encoder_ticks_ = encoder_ticks;
      return ((delta_ticks / counts_per_rev_) / dtm);
    }
    
  • 可配置实现不同的编码器计数方式:

    //file: ESP32encoder.h
    void attachSingleEdge(int aPintNumber, int bPinNumber); //1倍
    void attachHalfQuad(int aPintNumber, int bPinNumber);  //2倍
    void attachFullQuad(int aPintNumber, int bPinNumber);  //4倍
    

    2.3 lib/imu

  • imu_interface.h

    • 定义了IMU的ros2 imu message格式,可直接发送给ROS/ROS2使用;

    • IMUInterface()构造函数中初始化了imu_msg.header相关信息,不同版本写法略有不同;

    • 抽象了4个虚函数,方便适配不同类型的IMU;

      //file: imu_interface.h
      virtual geometry_msgs__msg__Vector3 readAccelerometer() = 0;
      virtual geometry_msgs__msg__Vector3 readGyroscope() = 0;
      virtual bool startSensor() = 0;
      virtual void calibrateGyro()=0;
      
  • default_imu.h

    • 依赖MPU9250库,该库可通过platformio.ini文件进行自动安装,也可以手动下载添加;

    • imu_interface.h中的4个虚函数进行了实现;

      2.4 lib/kinematics

      c++封装的适用于求解小车底盘正逆运动学的库。适用于两轮差分、阿克曼、麦轮等。该库原地址:kinematics-
      小车轮距、轮径、转速等信息在lib/config中定义;

  • 核心函数1:由线速度和角速度推算小车车轮转速

    rpm getRPM(float linear_x, float linear_y, float angular_z);
    
  • 核心函数2:由小车车轮转速推算线速度和角速度

    velocities getVelocities(int rpm1, int rpm2, int rpm3, int rpm4);
    

    2.5 lib/motor

    motor_interface.h抽象了电机的各个功能,如正转、反转、停机等;-
    motor.h继承了motor_interface并对其各个功能进行了实现,并添加了pwm_offset;-
    pwm_offset是为了解决一些电机在低占空比pwm驱动下,电机不转动的问题;

    2.6 lib/odemetry

    定义了里程计nav_msgs/msg/odometry,用于发布odometry message

  • 核心函数1:获取当前的odometry message数据

    nav_msgs__msg__Odometry Odometry::getData()
    {
      return odom_msg_;
    }
    
  • 核心函数2:传入速度信息,更新odometry message数据

    void update(float vel_dt, float linear_vel_x, float linear_vel_y, float angular_vel_z);
    

    2.7 lib/pid

    顾名思义,电机的PID控制,不多解释了,看代码~

    2.8 lib/micro_ros_arduino

    基于官方的micro_ros_arduino#v2.0.5foxy,对其进行了必要修改,并进行了rebuild:

  • 修改UCLIENT_CUSTOM_TRANSPORT_MTU=1024,使得采用best_effort的传输策略时,可以传输大于512Bytes的数据(主要是odometry message);

  • 修改RMW_UXRCE_MAX_HISTORY=2,减少RAM使用,避免内存溢出;

  • 具体rebuild步骤可参考:https://github.com/micro-ROS/micro_ros_arduino/issues/1221#issuecomment-1329923473

    2.9 src/main.cpp

  • 初始化编码器、pid控制、电机等

  • 创建2个publisher: odom和imu

  • 创建1个subscriber: cmd_vel

  • 创建3个软件定时器:2个用于publisher发布;1个用于控制机器人移动;

    3 ROS2功能包

  • robot_description:机器人的描述文件

  • robot_bringup:启动launch文件,依次启动激光雷达、micro_ros_agent等

  • robot_cartographer: cartographer建图

    4 后续

  • 增加camera,去尝试更多的玩法;刚好旭日x3派的TROS里面有很多有意思的算法;

  • 将会不定期更新

esp32在arduino里下载那些包超慢,有办法解决吗?

科学上网