Linux串口编程主要流程 :1、open打开串口设备,获取串口设备文件描述符(Linux一切都是文件)-->2、设置set波特率,初始化ini等-->3、对数据解码-->4、read()、write()操作文件描述符进行串口通信
在主函数中,初始化ros节点,启动,定义发布消息的名称。 构造函数,初始化接口名称以及波特率(每秒钟传送的码元符号的个数),从而初始化这个类
while循环,只要节点在运行就接收和解码数据,并输出到topic中。
int main(int argc, char** argv) {
ROS_INFO("[info] init begin");
ros::init(argc, argv, "virtual_serial"); //初始化节点
ros::NodeHandle n; //启动节点
ros::Publisher chatter_pub = n.advertise<gripper_send::rec_num_msgs>("gripper_send", 1000); //定义发布消息的名称及sulv
ros::Rate loop_rate(50); //控制发布速度,与sleep配合使用,每0.02秒休息一次
DataGripper data_gripper(dev_name, 115200); //构造函数,看串口是否打开并初始化
while (ros::ok()) { //检查节点是否关闭
//read uart data
data_gripper.DataReceive(); //接收数据
data_gripper.DataDecode(); //解码数据
//write to msg;
gripper_send::rec_num_msgs msg;
msg.finger1_state_Value[0] = data_gripper.motor1_state_Value_[0];
msg.finger2_state_Value[0] = data_gripper.motor2_state_Value_[0];
msg.finger3_state_Value[0] = data_gripper.motor3_state_Value_[0];
msg.finger1_state_Value[1] = data_gripper.motor1_state_Value_[1];
chatter_pub.publish(msg);
ros::spinOnce();
loop_rate.sleep();
}
return 0;
}
以下是gripper_send.h文件,主要包括一个结构体,和一个类,具体见备注。
#ifndef SRC_UART_TUTORIAL_INCLUDE_GRIPPER_REC_H_
#define SRC_UART_TUTORIAL_INCLUDE_GRIPPER_REC_H_
#include <ros/ros.h> // 包含ROS的头文件
#include <iostream>
#include <queue>
constexpr int RX_USB_SIZE = 150; //设置临时存储的字节容量
struct RecStruct { //设置一个结构体,包括布尔值,临时存储的数组,计数器
bool isValue = false;
char buffer[16];
uint16_t buff_ptr = 0;
};
class DataGripper {
public:
DataGripper(char *dev_name, uint32_t baund); //构造函数,判断串口是否成功打开和初始化
~DataGripper(); //析构函数
bool DataReceive(); //判断是否接受到信号
void DataDecode(); //判断帧头帧尾,将中间的有效数据存在rec_decode_.buffer中
void GetData(char *effective_data); //对信号进行解码
short motor1_state_Value_[3]; //三个电机的状态
short motor2_state_Value_[3];
short motor3_state_Value_[3];
private:
char rcv_buf_[RX_USB_SIZE];
std::queue<char> rec_que_;
char slide_windows_[4]; //滑动窗口
int fd_ = -1; //文件描述符
int uart_open_err_ = false;
struct RecStruct rec_decode_;
};
#endif // SRC_UART_TUTORIAL_INCLUDE_GRIPPER_REC_H_
串口协议是:
A0 B8 21 0A XX XX XX XX XX XX XX XX XX XX XX 59 A6
------帧头-------- ------------------------有效数据--------------- --帧尾--
- 接收函数:data_gripper.DataReceive()
会接收到很多数据,利用UARTO_Recv 统计出此次接收数据的数量,之后利用for循环,将每一个数据都存入rec_que_中,
UART0_Recv函数的第一个输入fd_是文件描述符,第二个是临时存储数据的数组,第三个是历史存储数据的大小。输出是,有效数据的长度。
最后把数据都存在rec_que_中,
bool DataGripper::DataReceive() {
int len = 0;
len = UART0_Recv(fd_, rcv_buf_, 100);
if (len > 0) {
for (int i = 0; i < len; i++) {
rec_que_.push(rcv_buf_[i]);
}
return true;
}
return false;
}
- 判断帧头帧尾并提取有效数据:void DataGripper::DataDecode()
思路:只要rec_que_队列不为空,就把头位置的数据pop出来,存入rec_temp中。之后创立一个滑动窗口(大小与帧头相同),将每次的新数据从后向前一次更新一次,每次更新后,都判断是否滑动窗口里的每个值都与帧头完全重合。若完全重合,则布尔值rec_decode_.isValue 为真,执行下一个if操作。若不为真,则说明还未找到帧头,需要重新从rec_que_中重新取一个数据,继续判断帧头。这里无论成功与否,rec_decode_.buff_ptr(计数器)都会归零。
如果找到帧头之后,执行if内的操作, 有效数据一共是11个,加上针尾一共是13个,由于使用滑动窗口时,我们可以把帧头的最后一位也统计了进来,所以一共是14个。由于++操作在后面,所以当rec_decode_.buff_ptr(计数器) 等于13的时候,开始判断帧尾(总结一个公式:总数据长度 - 帧头长度),容纳后判断帧尾,判断成功之后,使用GetData(&rec_decode_.buffer[2]) 进行解码。(第一位是帧头的最后一位,然后有效数据的第一位没有用,所以从第三位开始,所以是2)。
void DataGripper::DataDecode() {
char rec_temp;
while (!rec_que_.empty()) {
rec_temp = rec_que_.front();
rec_que_.pop();
for (int i = 0; i < 3; i++)
slide_windows_[i] = slide_windows_[i + 1];
slide_windows_[3] = rec_temp;
for(int i=0; i<4; ++i)
slide_windows_[i] = static_cast<uint8_t>(slide_windows_[i]);
while (1) {
if (static_cast<uint8_t>(slide_windows_[0]) != 0xa0) break;
if (static_cast<uint8_t>(slide_windows_[1]) != 0xb8) break;
if (static_cast<uint8_t>(slide_windows_[2]) != 0x21) break;
if (static_cast<uint8_t>(slide_windows_[3]) != 0x0a) break;
rec_decode_.buff_ptr = 0;
rec_decode_.isValue = true;
break;
}
if (rec_decode_.isValue == true) {
rec_decode_.buffer[rec_decode_.buff_ptr] = rec_temp;
if (rec_decode_.buff_ptr == 13) {
if (static_cast<uint8_t>(rec_decode_.buffer[12]) == 0x59 && static_cast<uint8_t>(rec_decode_.buffer[13]) == 0xA6) {
GetData(&rec_decode_.buffer[2]);
//std::cout<<motor1_state_Value[0]<<" "<<motor1_state_Value[1]<< " "<<motor2_state_Value[0]<<" "<<motor3_state_Value[0]<<std::endl;
}
rec_decode_.buff_ptr = 0;
rec_decode_.isValue = false;
} else {
rec_decode_.buff_ptr++;
}
}
}
}
- 解码:void DataGripper::GetData(char *effective_data)
解码目标:motor1_state_Value_[0](电机1的位置)为32个字节,四个有效数据拼在一起, motor1_state_Value_[1](电机1的电流)为16个字节,两个有效数据
拼在一起。motor2_state_Value_[0](电机2的位置)为16个字节,motor3_state_Value_[0](电机3的位置),为16个字节。
void DataGripper::GetData(char *effective_data) {
short pos_long_h = 0;
short pos_long_l = 0;
pos_long_h = effective_data[0];
pos_long_h = (pos_long_h << 8 ) | effective_data[1];
pos_long_l = effective_data[2];
pos_long_l = (pos_long_l << 8 ) | effective_data[3];
long motor1_pos = pos_long_h;
motor1_pos = (motor1_pos << 16) | pos_long_l;
short motor1_cur = effective_data[4];
motor1_cur = (motor1_cur << 8) | effective_data[5];
short motor2_pos = effective_data[6];
motor2_pos = (motor2_pos << 8) | effective_data[7];
short motor3_pos = effective_data[8];
motor3_pos = (motor3_pos << 8) | effective_data[9];
motor1_state_Value_[0] = static_cast<short>(motor1_pos);
motor1_state_Value_[1] = motor1_cur;
motor2_state_Value_[0] = motor2_pos;
motor3_state_Value_[0] = motor3_pos;
}
最后把解码后的数据,输出到msg,保存到名字是gripper_send 的 ros topic里边。