[ros-users] Generic transport plugins and shared memory

Cedric Pradalier cedric.pradalier at mavt.ethz.ch
Mon May 10 21:09:06 UTC 2010


Hi all,

I'm not quite sure who will be interested by this message, but since we 
don't have (yet) our official ros repository, I'll send the info here. 
Please feel free to contact me or discuss on the list if you want more 
information.

Given the long travel time coming back from ICRA, and my experience with 
the image_transport plugin architecture, I found that being only able to 
make transport_plugin and shared memory only for sensor_msgs::Image was 
a bit limiting.

So I've adapted the image_transport framework using templates to make it 
generic, and integrated a generic shared memory transport into the 
framework. I've also ported the compressed and theora transport, but 
still keeping them specialised to Image.

The resulting framework allow to create a starting set of plugins (raw 
and sharedmem) for (e.g) PointCloud using the following code:

manifest.cpp:
#include <pluginlib/class_list_macros.h>
#include <message_transport/raw_publisher.h>
#include <message_transport/raw_subscriber.h>
#include <sharedmem_transport/sharedmem_publisher.h>
#include <sharedmem_transport/sharedmem_subscriber.h>
#include <sensor_msgs/PointCloud.h>

// Raw class
PLUGINLIB_REGISTER_CLASS(raw_pub,
    message_transport::RawPublisher<sensor_msgs::PointCloud>,   
    message_transport::PublisherPlugin<sensor_msgs::PointCloud>)
PLUGINLIB_REGISTER_CLASS(raw_sub,
    message_transport::RawSubscriber<sensor_msgs::PointCloud>,
    message_transport::SubscriberPlugin<sensor_msgs::PointCloud>)

// Sharedmem class (the PointCloud message contains a header, which the 
publisher uses)
PLUGINLIB_REGISTER_CLASS(sharedmem_pub,
    
sharedmem_transport::SharedmemPublisherWithHeader<sensor_msgs::PointCloud>, 
  
    message_transport::PublisherPlugin<sensor_msgs::PointCloud>)
PLUGINLIB_REGISTER_CLASS(sharedmem_sub,
    sharedmem_transport::SharedmemSubscriber<sensor_msgs::PointCloud>,
    message_transport::SubscriberPlugin<sensor_msgs::PointCloud>)

Note that a specialised list_transport must be compiled for each message 
classes where plugins are developed:
list_transport.cpp:
#include <message_transport/list_transport.h>
#include <sensor_msgs/PointCloud.h>

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:

class CompressedPublisher : public    
    message_transport::SimplePublisherPlugin<sensor_msgs::Image,
        sensor_msgs::CompressedImage>
{ ...

protected:
  virtual void publish(const sensor_msgs::Image& message,
          const message_transport::SimplePublisherPlugin<sensor_msgs::Image,
                sensor_msgs::CompressedImage>::PublishFn& publish_fn) 
const ;
};


For the moment, my message_transport stack contains -- i.e. written and 
tested -- (indentation means dependency):
message_transport_common
->sharedmem_transport
  ->pointcloud_transport
  ->imagem_transport
    ->compressed_imagem_transport
    ->theora_imagem_transport

Other plugins are obviously possible and easy to write, to extend the 
library for image and pointcloud or for other types of message.

HTH

-- 
Dr. Cedric Pradalier
http://www.asl.ethz.ch/people/cedricp




More information about the ros-users mailing list