00001 #ifndef IMAGE_TRANSPORT_RAW_PUBLISHER_H
00002 #define IMAGE_TRANSPORT_RAW_PUBLISHER_H
00003 
00004 #include "image_transport/simple_publisher_plugin.h"
00005 
00006 namespace image_transport {
00007 
00014 class RawPublisher : public SimplePublisherPlugin<sensor_msgs::Image>
00015 {
00016 public:
00017   virtual ~RawPublisher() {}
00018 
00019   virtual std::string getTransportName() const
00020   {
00021     return "raw";
00022   }
00023 
00024   
00025   
00026   virtual void publish(const sensor_msgs::ImageConstPtr& message) const
00027   {
00028     getPublisher().publish(message);
00029   }
00030 
00031 protected:
00032   virtual void publish(const sensor_msgs::Image& message, const PublishFn& publish_fn) const
00033   {
00034     publish_fn(message);
00035   }
00036 
00037   virtual std::string getTopicToAdvertise(const std::string& base_topic) const
00038   {
00039     return base_topic;
00040   }
00041 };
00042 
00043 } 
00044 
00045 #endif