平台:Ubuntu18.04 ROS melodic ros_serial工具包

目的:采用ros工具包实现串口通信与解析

下载依赖

利用ros工具包实现串口通信与解析

  • 常用的ch340驱动安装已经在之前的文章讲过了,有需要可以自行查找

  • 由于国内网络问题,ros的下载可能需要用到魔法上网或者其他方法,以后会单开一篇说明

  • 下载串口工具包

1
sudo apt-get install ros-melodic-serial

下载完成后重启shell,输入以下命令来测试

1
roscd serial

新建工程

  • 利用catkin工具包生成相关工程

  • 首先生成工作环境

1
2
3
4
5
6
7
8
mkdir -p ~/catkin_ws/src
cd ~/catkin_ws/src/
catkin_init_workspace
cd ~/catkin_ws/
catkin_make
echo "source ~/catkin_ws/devel/setup.bash">>~/.bashrc
source ~/.bashrc
echo $ROS_PACKAGE_PATH
  • 添加ros工具包
1
2
cd ~/catkin_ws/src/
catkin_create_pkg serial_port roscpp rospy std_msgs serial
  • 以上工具包依次为ros对于c++语言和python语言包的支持以及message传输包和串口包

  • 按照程序组成依次生成以下文件

1
2
3
4
5
6
7
8
9
10
11
12
13
serial_port
├── CMakeLists.txt
├── include
│ └── serial_port
│ ├── serialport.hpp
│ ├── serialpost.hpp #节点通信测试,可忽略
│ └── serialread.hpp
├── package.xml
└── src
├── answer.cpp #节点通信测试,可忽略
├── serialport.cpp
├── serialpost.cpp #节点通信测试,可忽略
└── serialread.cpp
  • 实现串口收发主程序c++代码源文件serialport.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
#include "serialport.hpp"

//main body
int main(int argc, char** argv)
{
ros::init(argc, argv, "serial_port_basic");
//create a nodehandle
ros::NodeHandle n;
//create a serial class
serial::Serial sp;
//create the timeout warning
serial::Timeout to = serial::Timeout::simpleTimeout(10);
//edit the port (for the first serial port the ch340 connected is ttyUSB0)
sp.setPort("/dev/ttyUSB0");
//set baudrate
sp.setBaudrate(115200);
//set seial timeout
sp.setTimeout(to);

try{
//open port
sp.open();
}
catch(serial::IOException& e){
ROS_ERROR_STREAM("Unable to open port.");
return -1;
}

if(sp.isOpen()){
ROS_INFO_STREAM("serial is opened.");
}else{
return -1;
}

//control the rate of loop
ros::Rate loop_rate(100);

//use for test
uint8_t buffer_test[6]={0xAE,0xAA,0x11,0x22,0x22,0XFF};
sp.write(buffer_test, 6);

while(ros::ok())
{ //open the subscriber for once
ros::spinOnce();
//read from linux buffer
size_t n = sp.available();
if(n!=0)
{
//the lagest buffer place is 64 x hex
uint8_t buffer[64];
//put the data into buffer
n = sp.read(buffer, n);
// printf for test
// for(int i=0; i<n; i++){
// printf("the origin buffer is %x",buffer[i]) ;
// }
// std::cout << std::endl;
int err = buffer_read(buffer);
//write back for test
sp.write(buffer, n);
}
//wait for the next turn
loop_rate.sleep();
}
//close the port
sp.close();
return 0;
}

serialport对应的c++头文件

1
2
3
4
5
6
7
8
9
10
11
#ifndef  __PORT_H__
#define __PORT_H__

#include <ros/ros.h>
#include <serial/serial.h>
#include <iostream>
#include<stdio.h>
#include "serialread.hpp"
#include "serialpost.hpp"

#endif
  • 对于读入数据简单解析serialread.cpp(可拓展)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
#include "serialread.hpp"

int buffer_read(uint8_t *buffer){
int max_size=64;
int status=0;
//the head of the serial port is 0xAE
if(buffer[0]==0xAE){
status=1;
}else {
return 0;
}
//choose the mod of the receiving data
switch(buffer[1]){
case 0xAA:
status=2;
break;
default:
return 0;
break;
}
//the fuction that write for an example
if(status==2){
if(buffer[5]==0xFF){
printf("roll=%d,yaw=%d,pitch=%d\n",buffer[2],buffer[3],buffer[4]);
}else{
return 0;
}
}else{
return 0;
}
//report error
return status;

}
  • 对应的头文件
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
#ifndef  __READ_H__
#define __READ_H__

#include <ros/ros.h>
#include <serial/serial.h>
#include <iostream>
#include<stdio.h>
#include "serialread.hpp"
#include "serialpost.hpp"

//the example write to analyse the hex code
int buffer_read(uint8_t *buffer);

//crc
//

#endif
  • 注意修改cmake文件,在文件结尾加上
1
2
3
4
5
add_executable(serial_port  src/serialport.cpp 
src/serialpost.cpp src/serialread.cpp)
target_link_libraries(serial_port ${catkin_LIBRARIES})
add_executable(answer src/answer.cpp)
target_link_libraries(answer ${catkin_LIBRARIES})
  • 利用catkin编译
1
2
3
4
cd ~/catkin_ws
catkin_make
. ~/catkin_ws/devel/setup.bash
rosrun serial_port serial_port
  • 可以看到数据像疯狗一样涌来