ROS2 Serial Driver庫
ROS1串口庫1.1
這是ROS1的庫,但是也可以從第三方源碼編譯這個庫,用於ROS2.
http://wjwwood.io/serial/doc/1.1.0/index.html
ROS2串口庫1.2
顧名思義,是一個串口包,
該庫適用於ROS Humble和ROS Jazzy版本。
官方詳解:
https://docs.ros.org/en/humble/p/serial_driver/generated/index.html#
https://index.ros.org/p/serial_driver/
下面是根據官方文檔手搓的教程(截至教程出之前,還沒有任何一個像樣的教程)
SerialDriver庫特點
該庫主要基於Boost.Asio庫,所以説原理就是Boost.Asio庫的特點:
事件驅動 Boost.Asio 使用操作系統提供的底層 I/O 複用機制(如 Linux 的 epoll、Windows 的 I/O Completion Ports)來監控文件描述符(如串口、套接字等)是否有可用的數據。當數據到達時,觸發相應的事件。
回調機制 用户調用異步方法(如 async_read 或 async_receive)時,傳入一個回調函數。當指定的事件(如數據接收完成)發生後,Boost.Asio 會自動調用用户提供的回調函數。
I/O 服務對象 Boost.Asio 的核心是一個 io_service 或 io_context 對象,它管理所有的異步操作和回調的調度。異步接收時:
- 用户將操作(如
async_receive)註冊到io_context。 io_context將異步操作掛起,並等待 I/O 事件的觸發。- 當 I/O 事件觸發時,
io_context調用對應的回調函數。
不阻塞主線程 異步操作不會阻塞調用線程。主線程可以繼續執行其他任務,而異步操作在後台完成。
基於Boost.Asio庫的優點
Boost.Asio庫是靠系統IO進行事件觸發的,並且單獨開了一個線程去幹這件事,所以這就使boost庫擁有單片機的串口中斷的特點,又擁有真多線程的特點。
而單片機的串口中斷,雖然也能通過IO進行事件觸發,但是由於單片機只有一個真線程,所以在進入中斷時,一定會阻塞主線程,造成效率損失。
如果在主線程裏直接接收並加上死循環和延時,這種效率往往是最低的,並且有很大的安全風險,非常不建議使用。
效率:Boost.Asio接收 >> 單片機串口中斷 >> 多線程阻塞式接收 >> 單線程阻塞式接收(在傳輸速度非常快的情況下,全都是遠遠大於>>)
安裝ROS2串口包
serial_driver 是一個封裝了串口通信功能的庫,它分為兩個部分:
- ROS2 依賴版本 :用於 ROS2 環境中,依賴於 ROS2 的通信機制(如
rclcpp)。 - 獨立庫版本 :不依賴 ROS2,可以直接在普通的 C++ 項目中使用。(未經測試)
方式一:在ROS2中安裝
sudo apt install ros-<ros2-distro>-asio-cmake-module
sudo apt install ros-<ros2-distro>-serial-driver
#humble
sudo apt install ros-humble-asio-cmake-module
sudo apt install ros-humble-serial-driver
#jazzy
sudo apt install ros-jazzy-asio-cmake-module
sudo apt install ros-jazzy-serial-driver
方式二:通用(該方法未經測試,如果你測試了,請幫忙刪掉本句話)
如果你在ROS1或者説其他地方使用,而且沒有安裝ROS2,請選擇該方法。
克隆倉庫
首先,克隆 transport_drivers 倉庫(包含 serial_driver):
https://github.com/ros-drivers/transport\_drivers
git clone https://github.com/ros-drivers/transport_drivers.git
安裝依賴
serial_driver 依賴於 ASIO 庫(一個跨平台的 C++ 網絡編程庫)。確保系統中已安裝 ASIO:
sudo apt install libasio-dev
編譯獨立庫
進入 serial_driver 目錄並編譯:
cd transport_drivers/serial_driver
mkdir build
cd build
cmake ..
make
sudo make install
安裝完畢後,在CMake里正常添加該包就可以。
其他準備工作
串口調試助手安裝(Linux版) (如果需要Windows版,問控制組要去)
sudo apt-get install cutecom
權限
# 将用户权限提高
sudo usermod -aG dialout $USER
newgrp dialout
有關Linux的USB設備的更多操作請看Vinci機器人隊Linux入門教程
初始化詳解
- 創建功能包
ros2 pkg create cpp01_serial --build-type ament_cmake --dependencies rclcpp serial_driver --node-name demo01_uart_send
- 引用頭文件:
#include "serial_driver/serial_driver.hpp" - 首先要初始化串口:




串口初始化函數init_port()有倆參數,
第一個參數device_name 是端口名稱
第二個參數config 是串口參數設置
device_name是個字符串,是填/dev下的設備名


ls /dev | grep USB
有關Linux的USB設備的更多操作請看Vinci機器人隊Linux入門教程
config是個類對象,所以要創建一下這個類對象如下:
這玩意是個輕量化的類,沒必要放在堆區,直接在棧區裏創建即可。

SerialPortConfig(uint32_t baud_rate, drivers::serial_driver::FlowControl flow_control , drivers::serial_driver::Parity parity, drivers::serial_driver::StopBits stop_bits)
從這個重載函數可以看到(參數不懂的問控制組)
第一個參數baud_rate 波特率
第二個參數flow_control 流控制
第三個參數parity 奇偶效驗
第四個參數stop_bits 停止位
具體的參數在serial_port.hpp中有

這樣串口就初始化成功了。
發送代碼詳解
- 發送主邏輯
我們接下來寫發送主邏輯,首先要創建一個延時,不要使用while(true)這種死循環延遲,ROS2提供了定時器。
先創建定時器(創建定時器不用詳解了,不懂的回顧上面趙老師的視頻)
就需要注意一個點,我們用的是 毫秒milliseconds ,不是 微秒microseconds 。


發送核心函數是這個send函數,可以看到,入口參數是vector類型的向量,

#include "rclcpp/rclcpp.hpp"
#include "serial_driver/serial_driver.hpp"
class Serial_Node : public rclcpp::Node
{
public:
Serial_Node() : Node("serial_node_cpp")
{
// 等设备准备好再初始化
// std::this_thread::sleep_for(std::chrono::milliseconds(500));
// 串口设备名(根据实际设备调整)
const std::string device_name = "/dev/ttyUSB0";
RCLCPP_INFO(this->get_logger(), "Serial port Node Open!");
// 创建串口配置对象
// 波特率115200;不开启流控制;无奇偶效验;停止位1。
drivers::serial_driver::SerialPortConfig config(
9600,
drivers::serial_driver::FlowControl::NONE,
drivers::serial_driver::Parity::NONE,
drivers::serial_driver::StopBits::ONE);
// 初始化串口
try
{
io_context_ = std::make_shared<drivers::common::IoContext>(1);
// 初始化 serial_driver_
serial_driver_ = std::make_shared<drivers::serial_driver::SerialDriver>(*io_context_);
serial_driver_->init_port(device_name, config);
serial_driver_->port()->open();
RCLCPP_INFO(this->get_logger(), "Serial port initialized successfully");
RCLCPP_INFO(this->get_logger(), "Using device: %s", serial_driver_->port().get()->device_name().c_str());
RCLCPP_INFO(this->get_logger(), "Baud_rate: %d", config.get_baud_rate());
}
catch (const std::exception &ex)
{
RCLCPP_ERROR(this->get_logger(), "Failed to initialize serial port: %s", ex.what());
return;
}
// 设置发送定时器
send_timer_ = this->create_wall_timer(
std::chrono::milliseconds(500),
std::bind(&Serial_Node::send_message_timer_callback, this));
}
private:
void send_message_timer_callback()
{
// 发送一串字符串
const std::string message = "Hello from ROS 2!\n";
std::vector<uint8_t> data(message.begin(), message.end());
// std::vector<uint8_t> hex_data = {0x48, 0x65, 0x6C, 0x6C, 0x6F}; // "Hello" in ASCII
auto port = serial_driver_->port();
try
{
size_t bytes_sent_size = port->send(data);
RCLCPP_INFO(this->get_logger(), "Sent: %s (%ld bytes)", message.c_str(), bytes_sent_size);
}
catch(const std::exception &ex)
{
RCLCPP_ERROR(this->get_logger(), "Error Transmiting from serial port:%s",ex.what());
}
}
std::shared_ptr<drivers::serial_driver::SerialDriver> serial_driver_;
std::shared_ptr<drivers::common::IoContext> io_context_;
rclcpp::TimerBase::SharedPtr send_timer_;
};
int main(int argc, char **argv)
{
rclcpp::init(argc, argv);
auto node = std::make_shared<Serial_Node>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}


接收代碼詳解
定時器方式(低效,不建議用)
#include "rclcpp/rclcpp.hpp"
#include "serial_driver/serial_driver.hpp"
#include <string>
class Serial_Node : public rclcpp::Node
{
public:
Serial_Node() : Node("serial_node_cpp")
{
// 等设备准备好再初始化
// std::this_thread::sleep_for(std::chrono::milliseconds(500));
// 串口设备名(根据实际设备调整)
const std::string device_name = "/dev/ttyUSB0";
RCLCPP_INFO(this->get_logger(), "Serial port Node Open!");
// 创建串口配置对象
// 波特率115200;不开启流控制;无奇偶效验;停止位1。
drivers::serial_driver::SerialPortConfig config(
9600,
drivers::serial_driver::FlowControl::NONE,
drivers::serial_driver::Parity::NONE,
drivers::serial_driver::StopBits::ONE);
// 初始化串口
try
{
io_context_ = std::make_shared<drivers::common::IoContext>(1);
// 初始化 serial_driver_
serial_driver_ = std::make_shared<drivers::serial_driver::SerialDriver>(*io_context_);
serial_driver_->init_port(device_name, config);
serial_driver_->port()->open();
RCLCPP_INFO(this->get_logger(), "Serial port initialized successfully");
RCLCPP_INFO(this->get_logger(), "Using device: %s", serial_driver_->port().get()->device_name().c_str());
RCLCPP_INFO(this->get_logger(), "Baud_rate: %d", config.get_baud_rate());
}
catch (const std::exception &ex)
{
RCLCPP_ERROR(this->get_logger(), "Failed to initialize serial port: %s", ex.what());
return;
}
// 设置发送定时器
receive_timer_ = this->create_wall_timer(
std::chrono::milliseconds(3),
std::bind(&Serial_Node::receive_message_timer_callback, this));
}
private:
void receive_message_timer_callback()
{
std::vector<uint8_t> data(100); // "Hello" in ASCII
auto port = serial_driver_->port();
try
{
size_t bytes_receive_size = port->receive(data);
if(bytes_receive_size > 0)
{
std::string message(data.begin(),data.begin() + bytes_receive_size);
RCLCPP_INFO(this->get_logger(), "Receive: %s (%ld bytes)", message.c_str(), bytes_receive_size);
}
}
catch(const std::exception &ex)
{
RCLCPP_ERROR(this->get_logger(), "Error Receiving from serial port:%s",ex.what());
}
}
std::shared_ptr<drivers::serial_driver::SerialDriver> serial_driver_;
std::shared_ptr<drivers::common::IoContext> io_context_;
rclcpp::TimerBase::SharedPtr receive_timer_;
};
int main(int argc, char **argv)
{
rclcpp::init(argc, argv);
auto node = std::make_shared<Serial_Node>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}

異步方式(高效)
#include "rclcpp/rclcpp.hpp"
#include "serial_driver/serial_driver.hpp"
#include <string>
class Serial_Node : public rclcpp::Node
{
public:
Serial_Node() : Node("serial_node_cpp")
{
// 等设备准备好再初始化
// std::this_thread::sleep_for(std::chrono::milliseconds(500));
// 串口设备名(根据实际设备调整)
const std::string device_name = "/dev/ttyUSB0";
RCLCPP_INFO(this->get_logger(), "Serial port Node Open!");
// 创建串口配置对象
// 波特率115200;不开启流控制;无奇偶效验;停止位1。
drivers::serial_driver::SerialPortConfig config(
9600,
drivers::serial_driver::FlowControl::NONE,
drivers::serial_driver::Parity::NONE,
drivers::serial_driver::StopBits::ONE);
// 初始化串口
try
{
io_context_ = std::make_shared<drivers::common::IoContext>(1);
// 初始化 serial_driver_
serial_driver_ = std::make_shared<drivers::serial_driver::SerialDriver>(*io_context_);
serial_driver_->init_port(device_name, config);
serial_driver_->port()->open();
RCLCPP_INFO(this->get_logger(), "Serial port initialized successfully");
RCLCPP_INFO(this->get_logger(), "Using device: %s", serial_driver_->port().get()->device_name().c_str());
RCLCPP_INFO(this->get_logger(), "Baud_rate: %d", config.get_baud_rate());
}
catch (const std::exception &ex)
{
RCLCPP_ERROR(this->get_logger(), "Failed to initialize serial port: %s", ex.what());
return;
}
async_receive_message();
}
private:
void async_receive_message() //创建一个函数更方便重新调用
{
auto port = serial_driver_->port();
// 设置接收回调函数
port->async_receive([this](const std::vector<uint8_t> &data,const size_t &size)
{
if (size > 0)
{
// 处理接收到的数据
std::string received_message(data.begin(), data.begin() + size);
RCLCPP_INFO(this->get_logger(), "Received: %s (%ld bytes)", received_message.c_str(),size);
}
// 继续监听新的数据
async_receive_message();
}
);
}
std::shared_ptr<drivers::serial_driver::SerialDriver> serial_driver_;
std::shared_ptr<drivers::common::IoContext> io_context_;
std::vector<uint8_t> receive_data_buffer = std::vector<uint8_t>(1024); // 接收缓冲区
};
int main(int argc, char **argv)
{
rclcpp::init(argc, argv);
auto node = std::make_shared<Serial_Node>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}

總代碼(又發又收)
#include "rclcpp/rclcpp.hpp"
#include "serial_driver/serial_driver.hpp"
#include <string>
class Serial_Node : public rclcpp::Node
{
public:
Serial_Node() : Node("serial_node_cpp")
{
// 等设备准备好再初始化
// std::this_thread::sleep_for(std::chrono::milliseconds(500));
// 串口设备名(根据实际设备调整)
const std::string device_name = "/dev/ttyUSB0";
RCLCPP_INFO(this->get_logger(), "Serial port Node Open!");
// 创建串口配置对象
// 波特率115200;不开启流控制;无奇偶效验;停止位1。
drivers::serial_driver::SerialPortConfig config(
9600,
drivers::serial_driver::FlowControl::NONE,
drivers::serial_driver::Parity::NONE,
drivers::serial_driver::StopBits::ONE);
// 初始化串口
try
{
io_context_ = std::make_shared<drivers::common::IoContext>(1);
// 初始化 serial_driver_
serial_driver_ = std::make_shared<drivers::serial_driver::SerialDriver>(*io_context_);
serial_driver_->init_port(device_name, config);
serial_driver_->port()->open();
RCLCPP_INFO(this->get_logger(), "Serial port initialized successfully");
RCLCPP_INFO(this->get_logger(), "Using device: %s", serial_driver_->port().get()->device_name().c_str());
RCLCPP_INFO(this->get_logger(), "Baud_rate: %d", config.get_baud_rate());
}
catch (const std::exception &ex)
{
RCLCPP_ERROR(this->get_logger(), "Failed to initialize serial port: %s", ex.what());
return;
}
// 设置发送定时器
transmit_timer_ = this->create_wall_timer(
std::chrono::milliseconds(5000),
std::bind(&Serial_Node::send_message_timer_callback, this));
async_receive_message(); //进入异步接收
}
private:
void send_message_timer_callback()
{
// 发送一串字符串
const std::string transmitted_message = "Hello from ROS 2!\n";
transmit_data_buffer = std::vector<uint8_t>(transmitted_message.begin(), transmitted_message.end());
// std::vector<uint8_t> hex_data = {0x48, 0x65, 0x6C, 0x6C, 0x6F}; // "Hello" in ASCII
auto port = serial_driver_->port();
try
{
size_t bytes_transmit_size = port->send(transmit_data_buffer);
RCLCPP_INFO(this->get_logger(), "Transmitted: %s (%ld bytes)", transmitted_message.c_str(), bytes_transmit_size);
}
catch(const std::exception &ex)
{
RCLCPP_ERROR(this->get_logger(), "Error Transmiting from serial port:%s",ex.what());
}
}
void async_receive_message() //创建一个函数更方便重新调用
{
auto port = serial_driver_->port();
// 设置接收回调函数
port->async_receive([this](const std::vector<uint8_t> &data,const size_t &size)
{
if (size > 0)
{
// 处理接收到的数据
std::string received_message(data.begin(), data.begin() + size);
RCLCPP_INFO(this->get_logger(), "Received: %s (%ld bytes)", received_message.c_str(),size);
}
// 继续监听新的数据
async_receive_message();
}
);
}
std::shared_ptr<drivers::serial_driver::SerialDriver> serial_driver_;
std::shared_ptr<drivers::common::IoContext> io_context_;
rclcpp::TimerBase::SharedPtr transmit_timer_;
std::vector<uint8_t> transmit_data_buffer = std::vector<uint8_t>(1024); // 发送缓冲区
std::vector<uint8_t> receive_data_buffer = std::vector<uint8_t>(1024); // 接收缓冲区
};
int main(int argc, char **argv)
{
rclcpp::init(argc, argv);
auto node = std::make_shared<Serial_Node>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}



注意事項
- 禁止引用
boost/asio.hpp:由於該庫的原理就是boost庫,而且是ROS2自帶的boost庫,所以你用通用版的boost/asio.hpp,會導致報錯出現很多標誌重複的問題。