Only released in EOL distros:  

Package Summary

The shared memory transport package

  • Maintainer status: maintained
  • Maintainer: Jrdevil-Wang <stu_981523 AT 163 DOT com>
  • Author: Jrdevil-Wang <stu_981523 AT 163 DOT com>, Wende Tan <twd2 AT 163 DOT com>
  • License: BSD
  • Source: git https://github.com/Jrdevil-Wang/shm_transport.git (branch: master)

What does shm_transport do?

ROS 1 use socket as a communication method. If the publisher and subscriber belong to different processes of a same machine, the socket will go through loopback with AF_INET family (either UDP or TCP protocol).

The main purpose of this package is to use shared memory IPC instead of loopback socket to establish publisher/subscriber communication. And we employ boost::interprocess::managed_shared_memory to accomplish it.

But shared memory is lack of synchronization method like poll/epoll for socket. Even inotify does not support generating a notification when the shared memory region is written or updated. Therefore, we use the original transport (udp or tcp) to send the handle (essentially, an offset pointer) from publishers to subscribers.

Experimental results show that the communication latency can be greatly reduced by using shm_transport, especially for large messages and multiple subscribers.

Tutorials

Using shm_transport is much like using the native ROS transport. Here are some examples.

Writing the publisher node

   1 #include "ros/ros.h"
   2 #include "std_msgs/String.h"
   3 #include <sstream>
   4 #include "shm_transport/shm_topic.hpp"
   5 
   6 #define MSGLEN (1920 * 1080 * 3)
   7 #define HZ (30)
   8 
   9 std::string str(MSGLEN, '-');
  10 char tmp[100];
  11 
  12 int main(int argc, char ** argv) {
  13   ros::init(argc, argv, "shm_talker", ros::init_options::AnonymousName);
  14   ros::NodeHandle n;
  15   shm_transport::Topic t(n);
  16   shm_transport::Publisher p =
  17       t.advertise<std_msgs::String>("test_topic", HZ, 3 * MSGLEN);
  18 
  19   ros::Rate loop_rate(HZ);
  20   int count = 0;
  21   while (ros::ok()) {
  22     int len = snprintf(tmp, 100, "message # %d ...", count);
  23     memcpy(&str[0], tmp, len);
  24 
  25     std_msgs::String msg;
  26     msg.data = str;
  27 
  28     ROS_INFO("info: [%s]", tmp);
  29     p.publish(msg);
  30 
  31     ros::spinOnce();
  32     loop_rate.sleep();
  33     count++;
  34   }
  35   return 0;
  36 }

The main difference between using shm_transport and native ROS transport is at line 15 to 17.

  15   shm_transport::Topic t(n);
  16   shm_transport::Publisher p =
  17       t.advertise<std_msgs::String>("test_topic", HZ, 3 * MSGLEN);

A shm_transport::Topic object is an encapsulation of ros::NodeHandle.

By calling shm_transport::Topic::advertise(), we can get a shm_transport::Publisher object, which acts the same with ros::Publisher.

Note that shm_transport::Topic::advertise() has one more parameter comparing to ros::NodeHandle::advertise(). This parameter (3 * MSGLEN in the example) indicates the total size of shared memory segment. The total size of shared memory segment should be larger than two messages plus the space used by memory allocation algorithm.

Writing the subscriber node

   1 #include "ros/ros.h"
   2 #include "std_msgs/String.h"
   3 #include "shm_transport/shm_topic.hpp"
   4 
   5 void chatterCallback(const std_msgs::String::ConstPtr & msg) {
   6   char str[21] = {'\0'};
   7   strncpy(str, msg->data.c_str(), 20);
   8   ROS_INFO("I heard: [%s]", str);
   9 }
  10 
  11 int main(int argc, char ** argv) {
  12   ros::init(argc, argv, "shm_listener", ros::init_options::AnonymousName);
  13   ros::NodeHandle n;
  14   shm_transport::Topic t(n);
  15   shm_transport::Subscriber<std_msgs::String> s =
  16       t.subscribe("test_topic", 60, chatterCallback);
  17   ros::spin();
  18   return 0;
  19 }

Similar with the publisher node, the main difference between using shm_transport and native ROS transport is at line 14 to 16.

  14   shm_transport::Topic t(n);
  15   shm_transport::Subscriber<std_msgs::String> s =
  16       t.subscribe("test_topic", 60, chatterCallback);

By calling shm_transport::Topic::subscribe(), we can get a shm_transport::Subscriber object, which acts the same with ros::Subscriber, and the registered callback function (chatterCallback in the example) will be called whenever a message arrives.

Performance

Latency vs Message Size

Latency vs Number of Listeners

Wiki: shm_transport (last edited 2017-11-01 09:13:04 by Jrdevil-Wang)