# .h定义
//串口指针
std::string serial_port_;
int serial_port_baud_;
boost::shared_ptr<boost::asio::serial_port> serial_ptr_;
boost::system::error_code err_code_;
boost::asio::io_service io_service_;
class TarkbotRobot
{
public:
TarkbotRobot(); //构造函数
~TarkbotRobot(); //析构函数
private:
//串口操作
bool openSerialPort();
void closeSerialPort();
//串口发送数据,塔克X-Protocol协议
void sendSerialPacket(uint8_t *pbuf, uint8_t len, uint8_t num);
//串口多线程接收函数
void recvCallback();
void recvDataHandle(uint8_t* buffer_data);
...
}
# 构造函数
...
//提示信息,串口端口号和波特率
ROS_INFO("Tarkbot Robot Set serial %s at %d baud", serial_port_.c_str(), serial_port_baud_);
//初始化串口
if(openSerialPort())
{
try
{
//启动串口接收线程
boost::thread recvSerial_thread(boost::bind(&TarkbotRobot::recvCallback,this));
}
catch(...)
{
ROS_INFO("Tarkbot Robot can not open recvSerial_thread, Please check the serial port cable ");
//关闭节点
ros::shutdown();
}
}
else
{
//关闭节点
ros::shutdown();
}
...
# 打开串口
/*
* @功 能 初始化串口
*/
bool TarkbotRobot::openSerialPort()
{
//检查串口是否已经被打开
if(serial_ptr_)
{
ROS_INFO("The SerialPort is already opened!\r\n");
return false;
}
//开打串口
serial_ptr_ = serial_ptr(new boost::asio::serial_port(io_service_));
serial_ptr_->open(serial_port_,err_code_);
//串口是否正常打开
if(err_code_)
{
ROS_INFO("Open Port: %s Failed! Aboart!",serial_port_.c_str());
return false;
}
//初始化串口参数
serial_ptr_->set_option(boost::asio::serial_port_base::baud_rate(serial_port_baud_));
serial_ptr_->set_option(boost::asio::serial_port_base::character_size(8));
serial_ptr_->set_option(boost::asio::serial_port_base::stop_bits(boost::asio::serial_port_base::stop_bits::one));
serial_ptr_->set_option(boost::asio::serial_port_base::parity(boost::asio::serial_port_base::parity::none));
serial_ptr_->set_option(boost::asio::serial_port_base::flow_control(boost::asio::serial_port_base::flow_control::none));
return true;
}
# 析构函数
/*
* @功 能 析构函数,对象生命周期结束时系统会调用这个函数
*/
TarkbotRobot::~TarkbotRobot()//加一个~
{
static uint8_t vel_data[11];
static uint8_t beep_data[1];
//发送静止指令
vel_data[0] = 0;
vel_data[1] = 0;
vel_data[2] = 0;
vel_data[3] = 0;
vel_data[4] = 0;
vel_data[5] = 0;
//sendSerialPacket(uint8_t *pbuf, uint8_t len, uint8_t num)
//*pbuf:发送数据指针
// len:发送数据长度个数,长度小于64字节
// num:帧号,帧编码
sendSerialPacket(vel_data, 6, ID_ROS2CTR_VEL);
//数据转换
beep_data[0] = 0;
//发送串口数据
sendSerialPacket(beep_data, 1, ID_ROS2CTR_BEEP);
//关闭串口
closeSerialPort();
//提示信息
ROS_INFO("Tarkbot Robot shutting down.");
}
# 串口关闭函数
/*
* @功 能 关闭串口
*/
void TarkbotRobot::closeSerialPort()
{
//如果串口被打开,则关闭串口
if(serial_ptr_)
{
serial_ptr_->cancel();
serial_ptr_->close();
serial_ptr_.reset();
}
//
io_service_.stop();
io_service_.reset();
}
# 串口发送函数
/*
* @功 能 发送串口数据包,塔克X-Protocol协议
* @参 数 *pbuf:发送数据指针
* len:发送数据长度个数,长度小于64字节
* num:帧号,帧编码
* @返回值 无
*/
void TarkbotRobot::sendSerialPacket(uint8_t *pbuf, uint8_t len, uint8_t num)
{
uint8_t i,cnt;
uint8_t tx_checksum = 0;//发送校验和
uint8_t tx_buf[64];
//判断是否超出长度
if(len <= 64)
{
//获取数据
tx_buf[0] = 0xAA; //帧头
tx_buf[1] = 0x55; //
tx_buf[2] = len+5; //根据输出长度计算帧长度
tx_buf[3] = num; //帧编码
for(i=0; i<len; i++)
{
tx_buf[4+i] = *(pbuf+i);
}
//计算校验和
cnt = 4+len;
for(i=0; i<cnt; i++)
{
tx_checksum = tx_checksum + tx_buf[i];
}
tx_buf[i] = tx_checksum;
//计算帧长度
cnt = len+5;
//发送数据
boost::asio::write(*serial_ptr_.get(),boost::asio::buffer(tx_buf,cnt),err_code_);
}
}
# 串口接受回调函数
//协议解析变量
uint8_t rx_con = 0; //接收计数器
uint8_t rx_checksum; //帧头部分校验和
uint8_t rx_buf[60]; //接收缓冲
/*
* @功 能 串口接收回调函数,接收塔克X-Protocol
*/
void TarkbotRobot::recvCallback()
{
//接收数据
uint8_t res;
while(1)
{
//读取串口数据
boost::asio::read(*serial_ptr_.get(), boost::asio::buffer(&res, 1), err_code_);
//塔克X-Protocol协议解析数据
if(rx_con < 3) //=========接收帧头 + 长度
{
if(rx_con == 0) //接收帧头1 0xAA
{
if(res == 0xAA)
{
rx_buf[0] = res;
rx_con = 1;
}
else
{
}
}else if(rx_con == 1) //接收帧头2 0x55
{
if(res == 0x55)
{
rx_buf[1] = res;
rx_con = 2;
}
else
{
rx_con = 0;
}
}
else //接收数据长度
{
rx_buf[2] = res;
rx_con = 3;
rx_checksum = (0xAA+0x55) + res; //计算校验和
}
}
else //=========接收数据
{
if(rx_con < (rx_buf[2]-1) )
{
rx_buf[rx_con] = res;
rx_con++;
rx_checksum = rx_checksum + res;
}
else //判断最后1位
{
//接收完成,恢复初始状态
rx_con = 0;
//数据校验
if( res == rx_checksum ) //校验正确
{
//调用串口数据处理函数
recvDataHandle(rx_buf);
}
}
}
}
}
# 🔍 代码解析:
boost::asio::read(*serial_ptr_.get(), boost::asio::buffer(&res, 1), err_code_);
# 🧱 每一部分含义如下:
| 部分 | 含义 |
|---|---|
serial_ptr_ |
是一个 boost::asio::serial_port 的智能指针(一般是 std::shared_ptr) |
serial_ptr_.get() |
取出原始指针(serial_port*)来使用 |
*serial_ptr_.get() |
解引用,得到串口对象(相当于你直接用 serial_port) |
boost::asio::buffer(&res, 1) |
创建一个缓冲区,指向变量 res,长度为 1 字节,用于接收数据 |
boost::asio::read(...) |
从串口同步读取数据(阻塞),直到缓冲区满了为止 |
err_code_ |
用于接收是否出错的信息(boost::system::error_code 类型) |
# ✅ 功能总结:
这行代码的作用是:
从串口中读取一个字节,保存到变量
res中。
如果读取成功,就继续;
如果发生错误(串口断开等),err_code_ 会被设置为对应的错误码。
# ⚠️ 注意事项:
- 这是阻塞式读取:如果串口没数据,它会卡在那里;
- 如果你希望更高效或不会阻塞主线程,可以考虑:
- 异步读取(
async_read) - 用线程轮询
- 设置超时
- 异步读取(
# 串口处理函数
/*
* @功 能 串口接收数据处理
*/
void TarkbotRobot::recvDataHandle(uint8_t* buffer_data)
{
//机器人数据
if(buffer_data[3] == ID_CPR2ROS_DATA)
{
//解析IMU加速度数据
imu_data_.acc_x = ((double)((int16_t)(buffer_data[4]*256+buffer_data[5]))*ACC_RATIO);
imu_data_.acc_y = ((double)((int16_t)(buffer_data[6]*256+buffer_data[7]))*ACC_RATIO);
imu_data_.acc_z = ((double)((int16_t)(buffer_data[8]*256+buffer_data[9]))*ACC_RATIO);
//解析IMU陀螺仪数据
imu_data_.gyro_x = ((double)((int16_t)(buffer_data[10]*256+buffer_data[11]))*GYRO_RATIO);
imu_data_.gyro_y = ((double)((int16_t)(buffer_data[12]*256+buffer_data[13]))*GYRO_RATIO);
imu_data_.gyro_z = ((double)((int16_t)(buffer_data[14]*256+buffer_data[15]))*GYRO_RATIO);
//解析机器人速度
vel_data_.linear_x = ((double)((int16_t)(buffer_data[16]*256+buffer_data[17]))/1000);
vel_data_.linear_y = ((double)((int16_t)(buffer_data[18]*256+buffer_data[19]))/1000);
vel_data_.angular_z = ((double)((int16_t)(buffer_data[20]*256+buffer_data[21]))/1000);
//解析电压值
bat_vol_data_ = (double)(((buffer_data[22]<<8)+buffer_data[23]))/100;
//计算里程计数据
pos_data_.pos_x += (vel_data_.linear_x*cos(pos_data_.angular_z) - vel_data_.linear_y*sin(pos_data_.angular_z)) * DATA_PERIOD;
pos_data_.pos_y += (vel_data_.linear_x*sin(pos_data_.angular_z) + vel_data_.linear_y*cos(pos_data_.angular_z)) * DATA_PERIOD;
pos_data_.angular_z += vel_data_.angular_z * DATA_PERIOD; //绕Z轴的角位移,单位:rad
//计算IMU四元数数据
calculateImuQuaternion(imu_data_);
//发布话题消息
publishOdom(); //发布里程计话题
publishImu(); //发布IMU传感器话题
publishBatVol(); //发布电池电压话题
//发布odom里程计TF坐标变换(odom --> base_footprint)
publishOdomTF();
}
}

