前言:
前几天在弄stm32与ros进行串口通信的时候,因为网上感觉能用的太少了,所以一开始使用的裸机通过串口直接与ros进行通信,但只有有一个缺点,就是需要自己写相关的数据包协议,还无法直接订阅话题,需要通过串口转发.但是昨天在看rtthread官网的时候,偶然发现rtt有现成的软件包rosserial与ros通信,但是在移植过程中还是遇到了一些问题,使用想写一篇博客分享一些自己的心得和移植过程
一、ros端环境准备
1.安装ROS桌面完整版
sudo apt install ros-<distro>-desktop-full
2.安装rosserial组件
sudo apt install ros-<distro>-rosserial ros-<distro>-rosserial-msgs
二.rtt端移植rosserial包
1.创建工程
这个我建议使用RT_Thread4.1.1版本,因为rtthreadstudio在5.0以上有一些报误,而且在所以chubemx生成驱动包时,使用过程中4.1.1版本也比较友好
2.添加软件包rosserial
3.修改配置项
rosserial支持使用串口和tcp进行通信,按照实际选择,但是版本那里,根据使用使用过程中建议选择melodic,因为我一开始默认选择的是nietic版本(因为我ros版本也是noetic),但实际发现根本与ros建立连接不上,后来试了好久选择melodic才成功
4.修改串口通信相关配置
这里根据实际使用串口和波特率修改(前面在RT-Thread Settings修改的串口号好像没有作用)
4.ros节点实现
首先创建一个cpp文件,因为roserial包大多是cpp文件(提示:创建cpp源文件的时候,建议不要与.c文件名相同,这样RT-Thread Studio这个软件会自动忽略同名文件,这个博主也是踩了很多坑)
这里我发送一个话题chatter,发送"hello ros"
订阅了一个速度话题cmd_vel
mymain.cpp:
/*
* Copyright (c) 2006-2021, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2025-05-28 print the first version
*/
#include <rtthread.h>
#include <rtdevice.h>
#include <board.h>
#include <ros.h>
#include <std_msgs/String.h> // 仅保留字符串消息头文件
#include <geometry_msgs/Twist.h>
//#include <my_app/motor.h>
#define DBG_TAG "main"
#define DBG_LVL DBG_LOG
#include <rtdbg.h>
//小车速度
float vle_x = 0,vle_y = 0,vle_z = 0;
bool msgRecieved = false;
// 创建ROS节点句柄
ros::NodeHandle nh;
// 新增话题发布者
std_msgs::String hello_msg; // 字符串消息对象
ros::Publisher hello_pub("chatter", &hello_msg); // 新话题发布者
// 接收到命令时的回调函数
void velCB( const geometry_msgs::Twist& twist_msg)
{
vle_x = twist_msg.linear.x;
vle_y = twist_msg.linear.y;
vle_z = twist_msg.angular.z;
rt_kprintf("vle_x:%.2f vle_y:%.2f vle_z:%d\n",vle_x,vle_y,vle_z);
msgRecieved = true;
}
//Subscriber
ros::Subscriber<geometry_msgs::Twist> sub("cmd_vel", velCB );
static void rosserial_thread_entry(void *parameter)
{
// 初始化ROS节点
nh.initNode();
// 注册新发布者
nh.advertise(hello_pub);
// 订阅了一个话题 /cmd_vel 接收控制指令
nh.subscribe(sub);
while (1)
{
// 如果接收到了控制指令
if (msgRecieved)
{
//velX *= mtr.maxSpd;
//mtr.moveBot(velX, turnBias);
//set_motion_state(vle_x,vle_y,vle_z);
msgRecieved = false;
}
// 发布新话题
hello_msg.data = "hello ros"; // 设置消息内容
hello_pub.publish(&hello_msg); // 发布消息
// 处理ROS回调
nh.spinOnce();
// 控制发布频率(100ms)
rt_thread_mdelay(100);
}
}
int cppmain(void)
{
// 创建ROS通信线程
rt_thread_t thread = rt_thread_create(
"rosserial", // 线程名
rosserial_thread_entry, // 入口函数
RT_NULL, // 参数
2048, // 堆栈大小
8, // 优先级
10 // 时间片
);
if (thread != RT_NULL)
{
rt_thread_startup(thread);
rt_kprintf("[rosserial] 新线程 rosserial\n");
}
else
{
rt_kprintf("[rosserial] 创建线程 rosserial失败\n");
}
return RT_EOK;
}
INIT_APP_EXPORT(cppmain);
三.ros端
1.打开ros节点
roscore
2.建立串口联系
rosrun rosserial_python serial_node.py _port:=/dev/ttyACM0 _baud:=115200
这里根据需要的串口号和波特率
3.查看话题
rostopic list
可以看到单片机发送的话题"chatter"
4.查看话题数据
rostopic echo /chatter
可以看到可以正确接收到话题留
四.大功告成
常见问题处理
- 连接超时检查:
- 确认串口设备路径正确
- 验证波特率设置一致
- 检查硬件连接稳定性
- 数据丢失解决方案:
- 增大串口缓冲区大小
- 优化消息发布频率
- 使用硬件流控制(RTS/CTS)
- 消息解析错误:
- 验证消息数据结构一致性
- 检查.endianness配置
- 确认消息版本匹配