这是一个用于通过 USB-RS485 转换模块控制 ZLAC8015D 电机驱动器的 ROS2 包,能将驱动器数据转换为 ROS2 消息格式
- 速度控制: 通过
/cmd_vel话题接收geometry_msgs/msg/Twist消息控制机器人运动 - 里程计发布: 发布
/odom话题 (nav_msgs/msg/Odometry) 提供机器人位姿信息 - 关节状态: 发布
/joint_states话题 (sensor_msgs::msg::JointState) 提供轮子关节状态 - 电机状态监控: 读取电机转速、编码器位置和错误状态
- Modbus 通信: 通过 RS485 接口与电机驱动器通信
# 核心依赖
sudo apt install ros-humble-rclcpp
sudo apt install ros-humble-std-msgs
sudo apt install ros-humble-nav-msgs
sudo apt install ros-humble-geometry-msgs
sudo apt install ros-humble-tf2
sudo apt install ros-humble-tf2-geometry-msgs
sudo apt install ros-humble-sensor-msgs
sudo apt install ros-humble-serial# 串口通信库(已包含在serial包中)
# sudo apt install libserial-dev # 可选,如果遇到问题可以安装系统版本
# 可能需要的其他工具
sudo apt install build-essential cmake
# 可视化相关依赖(用于URDF和RViz2)
sudo apt install ros-humble-robot-state-publisher
sudo apt install ros-humble-joint-state-publisher
sudo apt install ros-humble-joint-state-publisher-gui
sudo apt install ros-humble-rviz2
sudo apt install ros-humble-xacro- ZLAC8015D 驱动器: 双通道伺服驱动器
- USB-RS485 转换器: 连接电脑和驱动器
- 推荐使用 CH340 或 FT232 芯片的转换器
- 连接线序: A↔A, B↔B, GND↔GND
- 电机连接: 左右电机分别连接到驱动器的两个通道
# 添加用户到 dialout 组以访问串口
sudo usermod -a -G dialout $USER
# 重新登录生效项目包含两个包:
motor driver- ZLAC8015D电机驱动包(主包)serial- 串口通信库(依赖包)
如果您是从源码安装:
cd ~/ros2_ws/src
# 确保两个包都在src目录下
ls motor driver serial由于依赖关系,需要先编译serial包,再编译主包:
cd ~/ros2_ws
# 先编译serial库
colcon build --packages-select serial
# 再编译主驱动包
colcon build --packages-select zlac8015d_serial
# 或者一次性编译所有包
colcon buildsource ~/ros2_ws/install/setup.bash
# 验证安装
ros2 pkg list | grep zlac8015d_serial
ros2 pkg executables zlac8015d_serial# 启动主节点
ros2 run zlac8015d_serial zlac_run# 在另一个终端中发送速度命令
ros2 topic pub /cmd_vel geometry_msgs/msg/Twist "linear: {x: 0.5, y: 0.0, z: 0.0}
angular: {x: 0.0, y: 0.0, z: 0.2}"# 查看里程计数据
ros2 topic echo /odom
# 查看关节状态
ros2 topic echo /joint_states# 运行基础测试程序
ros2 run zlac8015d_serial example
# 运行模拟器(无硬件测试)
ros2 run zlac8015d_serial zlac_run_dummy// 串口配置
#define SERIAL_PORT_NAME "/dev/ttyUSB0" // 串口设备名
#define BAUDRATE 115200 // 波特率
#define MODBUS_ID 0x01 // Modbus 设备ID
// 话题配置
#define TWIST_SUB_TOPIC_NAME "cmd_vel" // 速度控制话题
#define ODOM_PUB_TOPIC_NAME "odom" // 里程计话题
#define JOINT_PUB_TOPIC_NAME "joint_states" // 关节状态话题
// 坐标系配置
#define ODOM_FRAME_ID "odom" // 里程计坐标系
#define ODOM_CHILD_FRAME_ID "base_link" // 子坐标系
// 机器人参数(需要根据实际情况调整)
#define WHEEL_RAD 0.100 // 轮子半径 (米)
#define WHEEL_BASE 0.525 // 轮距 (米)
#define ONE_REV_TRAVEL 0.6283 // 轮子周长 (米)
#define PULSE_PER_ROT 16385 // 编码器每转脉冲数要修改配置,请编辑 src/zlac_run.cpp 文件中的相关宏定义,然后重新编译:
cd ~/ros2_ws
colcon build --packages-select zlac8015d_serial
source install/setup.bash# 检查设备权限
ls -l /dev/ttyUSB0
# 如果需要,临时添加权限
sudo chmod 666 /dev/ttyUSB0
# 永久解决方案:添加用户到dialout组
sudo usermod -a -G dialout $USER如果 USB-RS485 转换器使用 CH340 芯片,可能与 brltty 服务冲突:
# 禁用 brltty 服务
sudo systemctl stop brltty
sudo systemctl disable brltty
# 或者卸载(如果不需要屏幕阅读功能)
sudo apt remove brltty- 检查 USB 连接是否稳定
- 确认 RS485 线序正确 (A-A, B-B, GND-GND)
- 检查驱动器电源是否正常
# 检查串口设备
dmesg | grep tty
ls /dev/tty*
# 测试串口通信
sudo apt install minicom
sudo minicom -D /dev/ttyUSB0 -b 115200uint8_t init(std::string port, int baudrate, uint8_t ID, bool DEBUG_MSG_SET);
// 初始化电机驱动器连接uint8_t enable(); // 启用电机
uint8_t disable(); // 禁用电机
uint8_t set_vel_mode(); // 设置速度模式
uint8_t set_double_rpm(int16_t Lrpm, int16_t Rrpm); // 设置左右轮转速
uint8_t set_acc_time(uint16_t acc_time_ms, std::string side); // 设置加速时间
uint8_t set_decc_time(uint16_t decc_time_ms, std::string side); // 设置减速时间MOT_DATA get_rpm(); // 获取当前转速
MOT_DATA get_position(); // 获取编码器位置
uint16_t get_error(); // 获取错误状态0000h: 无错误0001h: 过压0002h: 欠压0004h: 过流0008h: 过载0020h: 编码器异常0040h: 速度异常0400h: 电机温度过高
程序自动将 Twist 消息中的线速度 linear.x 和角速度 angular.z 转换为左右轮的目标转速:
左轮转速 (RPM) = (linear.x - angular.z * WHEEL_BASE/2) / WHEEL_RAD * 60/(2π)
右轮转速 (RPM) = (linear.x + angular.z * WHEEL_BASE/2) / WHEEL_RAD * 60/(2π)
基于编码器反馈计算机器人位姿,发布在 /odom 话题中。
修改 DEBUG_ENABLE 为 true:
#define DEBUG_ENABLE true# 运行节点并查看输出
ros2 run zlac8015d_serial zlac_run
# 或查看日志
ros2 topic echo /rosout可以继承或参考 ZLAC 类来开发自定义的机器人控制节点。
- ZLAC8015D 官方文档: http://www.zlrobotmotor.com/info/401.html
- Modbus 协议: 支持标准 Modbus RTU 通信
- 原始项目: https://github.com/oxcarxierra/ROS2_ZLAC8015D_serial
- 当前维护者: DENPAFROG (denpafrog@gmail.com)
MIT License - 允许自由使用和修改
motor driver/ # 主包 - ZLAC8015D电机驱动
├── src/ # 源代码
│ ├── zlac8015d.cpp # 电机驱动类实现
│ ├── zlac_run.cpp # 主节点程序
│ ├── zlac_run_dummy.cpp # 模拟节点程序
│ └── example.cpp # 示例程序
├── include/ # 头文件
│ ├── zlac8015d.h # 电机驱动类头文件
│ └── Comm/ # 通信相关
├── urdf/ # 机器人URDF模型
├── rviz/ # RViz2配置文件
├── launch/ # 启动文件
├── config/ # 配置文件
├── 使用说明.md # 主要使用说明
└── URDF和RViz2使用说明.md # 可视化说明
serial/ # 串口通信库(依赖包)
├── include/ # 串口头文件
├── src/ # 串口实现
├── package.xml # 包描述
└── CMakeLists.txt # 构建文件
由于项目现在分为两个包,编译时需要特别注意依赖关系:
# 方法1:分别编译
cd ~/ros2_ws
colcon build --packages-select serial
colcon build --packages-select zlac8015d_serial
# 方法2:一次性编译所有包
colcon build
# 方法3:只编译修改的包
colcon build --packages-up-to zlac8015d_serial- 基础 ZLAC8015D 驱动器控制
- ROS2 消息转换
- 里程计和关节状态发布
- 基础错误处理
- 完整的URDF机器人模型
- RViz2可视化支持