第 13.1.2 節

ROS2 Serial Driver Library

0瀏覽次數0訪問次數--跳出率--平均停留

ROS1 Serial Library 1.1

This is a ROS1 library, but it can also be compiled from third-party source code for use with ROS2.

http://wjwwood.io/serial/doc/1.1.0/index.html

ROS2 Serial Library 1.2

As the name suggests, it is a serial port packet.

This library is compatible with ROS Humble and ROS Jazzy versions.

Official Detailed Explanation:

https://docs.ros.org/en/humble/p/serial_driver/generated/index.html#

https://index.ros.org/p/serial_driver/

Below is a tutorial handcrafted based on the official documentation (as of the time this tutorial was created, there wasn't a single decent tutorial available yet).

The SerialDriver library features

This library is primarily based on the Boost.Asio library, so the underlying principle is the characteristic of Boost.Asio:

Event-driven Boost.Asio uses the underlying I/O multiplexing mechanisms provided by the operating system (such as Linux's epoll, Windows' I/O Completion Ports) to monitor file descriptors (e.g., serial ports, sockets) for available data. When data arrives, the corresponding event is triggered.

Callback Mechanism When a user calls an asynchronous method (such as async_read or async_receive), a callback function is passed in. When the specified event (such as data reception completion) occurs, Boost.Asio automatically invokes the user-provided callback function.

I/O Service Object The core of Boost.Asio is an io_service or io_context object that manages all asynchronous operations and the scheduling of callbacks. When receiving asynchronously:

  • The user registers operations (such as async_receive) into io_context.
  • io_context suspends the asynchronous operation and waits for an I/O event to trigger.
  • When an I/O event is triggered, io_context calls the corresponding callback function.

Does not block the main thread Asynchronous operations do not block the calling thread. The main thread can continue executing other tasks while the asynchronous operation completes in the background.

Based on the advantages of the Boost.Asio library

The Boost.Asio library triggers events through system I/O and spawns a separate thread to handle this task. As a result, the Boost library combines the characteristics of a microcontroller's serial port interrupt with the features of true multithreading.

However, although the serial port interrupt of a microcontroller can also trigger events through I/O, since the microcontroller has only one real thread, entering an interrupt will inevitably block the main thread, resulting in a loss of efficiency.

If you directly receive data in the main thread and add an infinite loop with delays, this approach is often the least efficient and carries significant security risks. It is strongly not recommended.

Efficiency: Boost.Asio reception >> Microcontroller serial interrupt >> Multithreaded blocking reception >> Single-threaded blocking reception (when transmission speed is very fast, all are far greater than >>)

Install the ROS2 serial package

serial_driver is a library that encapsulates serial communication functionality, and it is divided into two parts:

  • ROS2 Dependency Version: Used in the ROS2 environment, it relies on ROS2 communication mechanisms (such as rclcpp).
  • Standalone Library Version: Does not depend on ROS2 and can be used directly in a regular C++ project. (Untested)
Method 1: Install in 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
Method 2: General (This method has not been tested. If you test it, please help delete this sentence.)

If you are using ROS1 or another environment and have not installed ROS2, please choose this method.

Clone the repository

First, clone the transport_drivers repository (which includes serial_driver):

https://github.com/ros-drivers/transport\_drivers

git clone https://github.com/ros-drivers/transport_drivers.git

Install Dependencies

serial_driver depends on the ASIO library (a cross-platform C++ network programming library). Make sure ASIO is installed on your system:

sudo apt install libasio-dev

Compiling a Standalone Library

Enter the serial_driver directory and compile:

cd transport_drivers/serial_driver
mkdir build
cd build
cmake ..
make
sudo make install

Once installed, simply add the package normally in CMake.

Other preparatory work

Serial Debug Assistant Installation (Linux Version) (If you need the Windows version, ask the control group)

sudo apt-get install cutecom

Permissions


# 将用户权限提高
sudo usermod -aG dialout $USER
newgrp dialout

For more operations related to Linux USB devices, please refer to the Vinci Robotics Team Linux Beginner Tutorial.

Initialization Details

  1. Create a function package
ros2 pkg create cpp01_serial --build-type ament_cmake --dependencies rclcpp serial_driver --node-name demo01_uart_send
  1. Include the header file: #include "serial_driver/serial_driver.hpp"
  2. First, initialize the serial port:

The serial port initialization function init_port() has two parameters.

The first parameter device_name is the port name.

The second parameter, config, is the serial port parameter settings.

device_name is a string that should be filled with the device name under /dev.

ls /dev | grep USB

For more operations related to Linux USB devices, please refer to the Vinci Robotics Team Linux Beginner Tutorial.

config is a class object, so you need to create an instance of this class as follows:

This thing is a lightweight class, so there's no need to place it on the heap; just create it directly on the stack.

SerialPortConfig(uint32_t baud_rate, drivers::serial_driver::FlowControl flow_control , drivers::serial_driver::Parity parity, drivers::serial_driver::StopBits stop_bits)

From this overloaded function, you can see (ask the control group if you don't understand the parameters).

The first parameter baud_rate is the baud rate.

The second parameter flow_control

The third parameter, parity, is used for parity checking.

The fourth parameter, stop_bits, is the stop bit.

The specific parameters are in serial_port.hpp.

The serial port has been successfully initialized.

Detailed explanation of the code

  1. Send main logic

Next, we will write the main sending logic. First, we need to create a delay. Instead of using a blocking loop like while(true), ROS2 provides a timer.

First, create a timer (no need to go into detail about creating a timer; if you don't understand, review Teacher Zhao's video above).

One thing to note is that we are using milliseconds, not microseconds.

The core function is this send function. As you can see, the input parameter is a vector of type 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;
}

Detailed explanation of the receiving code

#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;
}

Asynchronous method (efficient)
#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;
}

Total code (both transmit and receive)

#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;
}

Precautions

  1. Do not reference boost/asio.hpp: Since the library's principle is based on the boost library, and it is the boost library that comes with ROS2, using the general version of boost/asio.hpp will cause errors with many duplicate flag issues.
音乐页