最近在使用ubantu读取串口数据,遇到了很多问题,好在最后也一一解决,实现目标,所以想写一下整个流程,进行一个记录分享吧。我用的是ubantu20.04,部署的ROS,希望从ROS中读取到串口数据,并进行发布订阅。
目录
前期准备
安装CuteCom【可选】
下载
添加权限
下载安装ROS自带的Serial库
编写代码
创建功能包
自定义msg消息
创建文件
修改package.xml
修改Cmakelists.txt
读取串口数据并发布
首先,添加需要的头文件
其次,初始化ROS
然后,打开串口
读取串口信息,并定时发送
最后,关闭串口
发布方的完整代码如下
订阅串口数据
修改Cmakelists.txt文件
最终结果
Ubantu系统也有很多串口助手,使用起来也很方便,和Windows差不多,我下载的是CuteCom,可以自动读取串口号,基本不用设置,就可以很轻松的读取到串口数据。
sudo apt-get install cutecom
直接输入代码等他安装就OK了。
下载完之后直接从桌面图标进入即可,也可以用命令行
sudo cutecom
和win一样也是需要找到相对应的串口端口,我们在实际使用的时候,大部分都用了USB转串口。也就是ttyUSB*。(一般直接插上去的第一个都是ttyUSB0)
点击Open,可能会出现“Could not open /dev/ttyUSB0”,这个是没有权限的意思,给他加个权限
sudo chmod 666 /dev/ttyUSB0
就可以读取了。但是实测可能有点慢,需要多等一会。
但是,这样每次USB插拔之后都需要添加权限,可以直接将当前用户添加进组
查看串口信息
ls -l /dev/ttyUSB0
查询当前用户Who am i
whoami
然后将当前用户添加进组
sudo usermod -aG dialout USER
完成之后重启电脑,后面就不需要每次都添加权限了。
这部分比较简单,直接安装即可。我用的是noetic,如果是其他版本记得更改中间的版本名称。
sudo apt install ros-noetic-serial
查询方法,打开终端输入
roscore
然后再打开一个终端,在另一个终端中输入以下代码即可。
rosversion -d
切换到工作空间目录,然后创建功能包
catkin_create_pkg serial_pkg_sc roscpp rospy serial std_msgs
这就在当下目录创建了一个支持C++(roscpp)、Python(rospy)、串口(serial)、标准信息(std_msgs)的功能包了!
我的数据是一个常见字符串,#31.754@这样,#是起始字符,@作为终止字符,中间为有效数据。我也尝试了可以用标准的msg,那个会简单一点。但是本着学习的理念,也了解了一下怎么自定义消息。
首先在功能包目录下新建文件夹msg
然后新建一个sc_sensor.msg的.msg文件,注意一定要是.msg类型的文件,然后往里面添加需要的变量
Header header
float64 sc_double
string sc_str
第一行的Header header表示这是一个标准信息,可以用现成功能。
float64是double类型数据,float32是float类型的,string是字符串等等,这个和C++不太一样,具体可以看官方介绍文档
msg - ROS Wiki
写完之后,记得保存(开个玩笑),然后就是
在相应位置添加以下代码,(相应位置在哪?相信我,你能找到它的。)
message_generation
message_runtime
...
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation
)
...
add_message_files(
DIRECTORY msg
FILES
sc_sensor.msg
)
...
generate_messages(
DEPENDENCIES
std_msgs
)
...
catkin_package(
CATKIN_DEPENDS
roscpp
rospy
std_msgs
message_runtime
)
这四部分建议先找到,然后解除注释,再进行修改,因为顺序不对的话可能会出问题。
这样我们就自定义了一个新的消息类型,修改完可以切换回工作空间目录,catkin_make一下试试,记得要刷新。
ROS中src文件夹一般存放cpp文件,可以在src文件夹下创建一个sc_talker.cpp,这个程序主要实现串口数据的读取并发布,同时将字符串切割保存为浮点数。由于单片机与电脑的读取写入速率不同,所以还需要进行定时发送,否则就会出现一次读取没有数,一次读取一堆数。
具体功能一个一个实现
#include
#include
#include
#include "ros/ros.h"
#include "std_msgs/String.h"
#include "serial/serial.h"
#include "serial_pkg_sc/sc_sensor.h" // 新建功能包名称/消息文件名称
serial::Serial ser; //定义对象
using namespace std; //使用std命名空间
ros::init(argc, argv, "sc_serial_talker"); //定义节点sc_serial_talker
ros::NodeHandle nh;
ros::Rate loop_rate(10); //刷新速率,即串口数据发送速率,单片机数据的采样率。
ros::Publisher sc_pub = nh.advertise("sc_sensor", 1); //发布sc_sensor的话题,每次只处理最新的1条消息
// 打开串口
try
{
ser.setPort("/dev/ttyUSB0"); // 这个端口号就是之前用cutecom看到的端口名称
ser.setBaudrate(115200);
serial::Timeout to = serial::Timeout::simpleTimeout(1000);
ser.setTimeout(to);
ser.open();
}
catch(serial::IOException &e)
{
ROS_INFO_STREAM("Failed to open port ");
return -1;
}
ROS_INFO_STREAM("Succeed to open port" ); //ROS_INFO_STREAM相当于cout
serial_pkg_sc::sc_sensor sc_data; //定义一个对象
string sc_sensors; //储存数据的字符串
while(ros::ok())
{
if (ser.available()) //串口有数据时ser.available()为真
{
//1.读取串口信息:
// ROS_INFO_STREAM("Reading from serial port\n");
//通过ROS串口对象读取串口信息
//std::cout << ser.available();
//std::cout << ser.read(ser.available());
sc_sensors += ser.read(ser.available());
//std::cout <<"strRece:" << strRece << "\n" ;
//strRece = "#31.984@";
//2.截取数据、解析数据:
//SC起始标志
string gstart = "#";
//SC终止标志
string gend = "@";
int i = 0, start = -1, end = -1;
while ( i < sc_sensors.length() )
{
//找起始标志
start = sc_sensors.find(gstart);
if ( start != -1)
//如果找到了起始标志,开始找终止标志
{
//找终止标志
end = sc_sensors.find(gend);
//如果没找到,把起始标志开始的数据留下,前面的数据丢弃,然后跳出循环
if (end == -1)
{
if (end != 0)
sc_sensors = sc_sensors.substr(start);
break;
}
//如果找到了终止标志,把这段有效的数据剪切给解析的函数,剩下的继续开始寻找
else
{
i = end;
//把有效的数据给解析的函数以获取data
double sc_temp;
sc_temp=stod(sc_sensors.substr(start+1,end-start-1));
cout << setiosflags(ios::fixed)<
这部分参考以下文章,我只是做了微不足道的更改,十分感谢作者的分享。
(12条消息) ROS实现串口GPS数据的解析与通信_何伯特的博客-CSDN博客
// 关闭串口
ser.close();
return 0;
#include
#include
#include
#include "ros/ros.h"
#include "std_msgs/String.h"
#include "serial/serial.h"
#include "serial_pkg_sc/sc_sensor.h"
serial::Serial ser;
using namespace std;
int main(int argc, char** argv)
{
ros::init(argc, argv, "sc_serial_talker");
ros::NodeHandle nh;
ros::Rate loop_rate(10);
ros::Publisher sc_pub = nh.advertise("sc_sensor", 1);
// 打开串口
try
{
ser.setPort("/dev/ttyUSB0"); // 这个端口号就是之前用cutecom看到的端口名称
ser.setBaudrate(115200);
serial::Timeout to = serial::Timeout::simpleTimeout(1000);
ser.setTimeout(to);
ser.open();
}
catch(serial::IOException &e)
{
ROS_INFO_STREAM("Failed to open port ");
return -1;
}
ROS_INFO_STREAM("Succeed to open port" );
serial_pkg_sc::sc_sensor sc_data;
string sc_sensors;
while(ros::ok())
{
if (ser.available())
{
//1.读取串口信息:
// ROS_INFO_STREAM("Reading from serial port\n");
//通过ROS串口对象读取串口信息
//std::cout << ser.available();
//std::cout << ser.read(ser.available());
sc_sensors += ser.read(ser.available());
//std::cout <<"strRece:" << strRece << "\n" ;
//strRece = "#31.984@";
//2.截取数据、解析数据:
//SC起始标志
string gstart = "#";
//SC终止标志
string gend = "@";
int i = 0, start = -1, end = -1;
while ( i < sc_sensors.length() )
{
//找起始标志
start = sc_sensors.find(gstart);
//如果没找到,丢弃这部分数据,但要留下最后2位,避免遗漏掉起始标志
if ( start == -1)
{
if (sc_sensors.length() > 2)
sc_sensors = sc_sensors.substr(sc_sensors.length()-3);
break;
}
//如果找到了起始标志,开始找终止标志
else
{
//找终止标志
end = sc_sensors.find(gend);
//如果没找到,把起始标志开始的数据留下,前面的数据丢弃,然后跳出循环
if (end == -1)
{
if (end != 0)
sc_sensors = sc_sensors.substr(start);
break;
}
//如果找到了终止标志,把这段有效的数据剪切给解析的函数,剩下的继续开始寻找
else
{
i = end;
//把有效的数据给解析的函数以获取data
double sc_temp;
sc_temp=stod(sc_sensors.substr(start+1,end-start-1));
cout << setiosflags(ios::fixed)<
订阅方代码就比较简单了,其实发布订阅可以在同一个代码里实现,我主要考虑到后期可能会在其他功能包里使用这个包,所以准备分开发布和订阅,到时候直接用就可以了。
在src文件夹里创建sc_listener.cpp
代码如下:
#include
#include
#include
#include "ros/ros.h"
#include "std_msgs/String.h"
#include "serial/serial.h"
#include "serial_pkg_sc/sc_sensor.h"
serial::Serial ser;
using namespace std;
void SC_SENSORcallback(const serial_pkg_sc::sc_sensor::ConstPtr& msg)
{
ROS_INFO_STREAM("Listener: SC_DATA is :" <sc_str);
// ser.write(msg->sc_str); //发送串口数据
// ROS_INFO_STREAM("Write_serial is OK");
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "sc_serial_listener");
ros::NodeHandle n;
ros::Subscriber sc_sub = n.subscribe("sc_sensor", 1, SC_SENSORcallback);
ros::spin();
return 0;
}
include_directories(
# include
${catkin_INCLUDE_DIRS}
)
add_executable(sc_talker src/sc_talker.cpp)
target_link_libraries(sc_talker serial_pkg_sc_generate_messages_cpp)
add_dependencies(sc_talker ${catkin_LIBRARIES})
add_executable(sc_listener src/sc_listener.cpp)
target_link_libraries(sc_listener serial_pkg_sc_generate_messages_cpp)
add_dependencies(sc_listener ${catkin_LIBRARIES})
最后,切换回工作空间,编译一下,大功告成。
最终一个终端运行roscore,然后打开两个终端,运行talker和listener,即可实现下面的效果。
roscore //终端1
rosrun serial_pjg_sc sc_talker //终端2
rosrun serial_pjg_sc sc_listener //终端3
总的来说,效果还是很不错的,虽然中间也踩了很多坑,但是能自己发现问题解决问题,还是很棒的,最终的结果让我很是欣慰,总算对了!!!