[Documentation] [TitleIndex] [WordIndex

Realtime Publisher

The realtime_tools::RealtimePublisher allows users that write C++ realtime 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 init() and update() methods of a realtime controller:

   1 #include <realtime_tools/realtime_publisher.h>
   2 
   3 bool MyController::init(pr2_mechanism_model::RobotState *robot,
   4                         ros::NodeHandle &n)
   5 {
   6   ...
   7 
   8   realtime_pub = new 
   9     realtime_tools::RealtimePublisher<mgs_type>(n, "topic", 4);
  10   return true;
  11 }
  12 
  13 
  14 void MyController::update()
  15 {
  16   if (realtime_pub->trylock()){
  17     realtime_pub->msg_.a_field = "hallo";
  18     realtime_pub->msg_.header.stamp = ros::Time::now();
  19     realtime_pub->unlockAndPublish();
  20   }
  21   ...
  22 }


2024-06-15 12:56