You're reading the documentation for a development version. For the latest released version, please have a look at Jazzy.

realtime_tools

Contains a set of tools that can be used from a hard realtime thread, without breaking the realtime behavior.

Exchange data between different threads

This package contains different concepts for exchanging data between different threads. In the following, a guideline for the usage for ros2_controllers is given.

Provided concepts

RealtimeThreadSafeBox

A Box that ensures thread-safe access to the boxed contents. Access is best effort. If it can not lock it will return.

LockFreeQueue

This class provides a base implementation for lock-free queues on top of Boost.Lockfree for lock-free queues with various functionalities, such as pushing, popping, and checking the state of the queue. It supports both single-producer single-consumer (SPSC) and multiple-producer multiple-consumer (MPMC) queues.

RealtimePublisher

The realtime_tools::RealtimePublisher allows users that write C++ ros2_controllers to publish messages on a ROS topic from a hard realtime loop. The normal ROS publisher is not realtime safe, and should not be used from within the update loop of a realtime controller. The realtime publisher is a wrapper around the ROS publisher; the wrapper creates an extra non-realtime thread that publishes messages on a ROS topic. The example below shows a typical usage of the realtime publisher in the on_configure() (non-realtime method) and update() (realtime method) methods of a realtime controller:

#include <realtime_tools/realtime_publisher.hpp>

class MyController : public controller_interface::ControllerInterface
{
...
private:
  std::unique_ptr<realtime_tools::RealtimePublisher<my_msgs::msg::MyMsg>> state_publisher_;
  std::shared_ptr<rclcpp::Publisher<my_msgs::msg::MyMsg>> s_publisher_;
  my_msgs::msg::MyMsg some_msg_;
}

controller_interface::CallbackReturn MyController::on_configure(
  const rclcpp_lifecycle::State & /*previous_state*/)
{
  ...
  s_publisher_ = get_node()->create_publisher<my_msgs::msg::MyMsg>(
    "~/status", rclcpp::SystemDefaultsQoS());
  state_publisher_ =
    std::make_unique<realtime_tools::RealtimePublisher<my_msgs::msg::MyMsg>>(s_publisher_);
  some_msg_.header.frame_id = params_.frame_id;
  ...
}

controller_interface::return_type MyController::update(
  const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
{
  ...
  // Publish controller state
  some_msg_.header.stamp = get_node()->now();
  // Fill in the rest of the message
  ....
  state_publisher_->try_publish(some_msg_);
}

Guidelines

There exist the following typical use-cases for ros2_controllers:

  • Passing command messages from topic subscribers in a non-realtime thread to the realtime-thread (one-way).

    • If you care only about the latest received message, use the realtime_tools::RealtimeThreadSafeBox.

    • If you care about the intermediate messages, i.e., receiving more than one message before the realtime-thread can process it: Use the realtime_tools::LockFreeQueue and set a suitable queue size for your application, i.e., consider the maximum expected topic rate vs controller update rate.

  • Send data from the realtime thread to the non-realtime thread for publishing data (one-way): Use the realtime_tools::RealtimePublisher.

  • Exchange data (two-way) between a non-realtime thread and a realtime-thread like state information, current goals etc.:

    • For primitive types like bool, you can simply use std::atomic<bool>, see cppreference.

    • For all other types, when missing some data samples from RT loop is not of major importance, then use the realtime_tools::RealtimeThreadSafeBox with try_set method. In the contrary situation, it is recommended to use realtime_tools::LockFreeQueue to avoid missing any samples.

Other classes and helper methods

Tba.