<> <> == Documentation == This stack exists because I found that being only able to make transport_plugin and shared memory for sensor_msgs::Image was a bit limiting. As a result, the image_transport framework has been adapted to use templates, and to make it generic. This has then been extended to a generic shared memory transport and a udp multicasting transport. The compressed and theora transport, have also been ported to this framework while still keeping them specialised to Image. The resulting framework allows to create a starting set of plugins (raw sharedmem and udp multicasting) for (e.g) PointCloud using the following code: manifest.cpp: {{{#!cplusplus #include #include #include #include #include #include #include #include #include #include // Raw class PLUGINLIB_REGISTER_CLASS(raw_pub, message_transport::RawPublisher, message_transport::PublisherPlugin) PLUGINLIB_REGISTER_CLASS(raw_sub, message_transport::RawSubscriber, message_transport::SubscriberPlugin) // Sharedmem class PLUGINLIB_REGISTER_CLASS(sharedmem_pub, sharedmem_transport::SharedmemPublisherWithHeader, message_transport::PublisherPlugin) PLUGINLIB_REGISTER_CLASS(sharedmem_sub, sharedmem_transport::SharedmemSubscriber, message_transport::SubscriberPlugin) // Decimated class PLUGINLIB_REGISTER_CLASS(decimated_pub, decimated_transport::DecimatedPublisher, message_transport::PublisherPlugin) PLUGINLIB_REGISTER_CLASS(decimated_sub, decimated_transport::DecimatedSubscriber, message_transport::SubscriberPlugin) // UDP multi-casting class PLUGINLIB_REGISTER_CLASS(udpmulti_pub, udpmulti_transport::UDPMultiPublisher, message_transport::PublisherPlugin) PLUGINLIB_REGISTER_CLASS(udpmulti_sub, udpmulti_transport::UDPMultiSubscriber, message_transport::SubscriberPlugin) }}} Note that a specialised list_transport must be compiled for each message classes where plugins are developed: list_transport.cpp: {{{#!cplusplus #include #include using namespace message_transport; int main(int argc, char** argv) { LIST_TRANSPORT("pointcloud_transport",sensor_msgs::PointCloud); return 0; } }}} As an instance, the plugin declaration for the compressed images starts with: {{{#!cplusplus class CompressedPublisher : public message_transport::SimplePublisherPlugin { ... protected: virtual void publish(const sensor_msgs::Image& message, const message_transport::SimplePublisherPlugin::PublishFn& publish_fn) const ; }; }}} For the moment, the message_transport stack contains: message_transport_common . ->bz2_transport . ->sharedmem_transport . ->udpmulti_transport . ->pointcloud_transport (includes a decimated publisher) . ->imagem_transport . ->compressed_imagem_transport . ->theora_imagem_transport Other plugins are obviously possible and easy to write. == Writing a publisher == The example code below should be pretty trivial to adapt to any need: {{{#!cplusplus #include #include #include class PointCloudPublisher { protected: ros::NodeHandle n_; message_transport::MessageTransport it_; message_transport::Publisher pcmsg_pub_; sensor_msgs::PointCloud pointcloud; public: PointCloudPublisher(ros::NodeHandle &n) : n_(n), // Register the transport to the pointcloud_transport plugin // set, and define the type of object transported it_(n_,"pointcloud_transport","sensor_msgs::PointCloud") { // Advertise like a normal topic pcmsg_pub_ = it_.advertise("pc_source",1); } ~PointCloudPublisher() {} void mainloop() { ros::Rate loop_rate(30); while (ros::ok()) { pointcloud.header.stamp = ros::Time::now(); // Fill-in other point cloud data, and publish normally pcmsg_pub_.publish(pointcloud); ros::spinOnce(); loop_rate.sleep(); } } }; int main(int argc, char** argv) { ros::init(argc, argv, "test_publisher"); ros::NodeHandle n; PointCloudPublisher ic(n); ic.mainloop(); return 0; } }}} == Writing a subscriber == The example code below should be pretty trivial to adapt to any need: {{{#!cplusplus #include #include #include void callback(const sensor_msgs::PointCloudConstPtr& pointcloud) { // process the pointcloud } int main(int argc, char** argv) { std::string transport = std::string((argc > 1) ? argv[1] : "raw"); ros::init(argc, argv, "test_receiver", ros::init_options::AnonymousName); ros::NodeHandle nh; // Register the transport to the pointcloud_transport plugin set message_transport::MessageTransport it(nh,"pointcloud_transport","sensor_msgs::PointCloud"); // Subscribe to the topic using the plugin specified as an argument, // defaults to raw message_transport::Subscriber sub = it.subscribe("pc_source", 1, callback, transport); ros::spin(); } }}} == BZ2 Compression (bz2_transport) == This package implement a template message compression using libbzip2. When listening on the respective topic, message are compressed into a specific message type (BZ2Packet), sent over the normal ROS transport and decompressed by the subscriber. Performance will depend on the data being sent. Note however, that for small messages (<100bytes), the BZ2 compression is likely to increase the bandwidth, as the compression is done per message. Best performance is expected for large messages with a lot of repetitive structure. == Shared memory and udp multicasting == These two packages implement generic transport that can then be instantiated for specific types. === Shared memory === Shared memory uses a boost shared memory segment to share the data. Each time an item is published, it is copied to the shared memory segment, and shared condition is triggered. When the subscriber wakes up from the condition it copies the shared memory segment. Obviously, this works only for two processes on the same machine. In our experience, shared memory transfer is useful for very big object 1 MB or more. Before that, normal loopback transfer is equivalent. The shared memory block is managed by a the sharedmem_manager binary in the sharedmem_transport package. This must be started before subscribers can start to access the shared memory. This node provides several services to inspect the state of the shared memory block. The graph below shows how the performance of the shared memory transport improves with the message size. {{attachment:delays.png|Delivery delay as a function of message size|width=95%}} === UDP Multicasting === UDP Multicasting is useful when a topic needs to be sent to many subscribers distributed over several machines. The publisher publishes a single message on a latched topic, describing the udp multicast channels used to send the data. Each time a message is received it is serialised and sent on the UDP channel. The subscriber reads the latched message on the topic, and then uses boost to connect to the multicast channel. UDP packets are limited to 8092 bytes. So message that cannot be serialised in this space will be rejected with an error message. Each topic published via the udpmulti transport will be associated to a port number. The port numbers are managed by the udpmulti_manager in the udpmulti_transport package. This binary must be running before a topic can be published on this transport. It also provides a set of services to inspect and control the topic-port association table. == Limitation == Right now, one plugin must be defined for each data-type. This requires creating a specific package and copy pasting the manifest.cpp file from another package (pointcloud transport is a good example). == Report a Bug == Please report bugs and request features using the [[https://github.com/ethz-asl/ros-message-transport/issues|github page]]. == Change log == See [[ethzasl_message_transport/ChangeList|the change list page]].