compressed_publisher.h
Go to the documentation of this file.
00001 #ifndef IMAGEM_TRANSPORT_COMPRESSED_PUBLISHER_H
00002 #define IMAGEM_TRANSPORT_COMPRESSED_PUBLISHER_H
00003 
00004 #include <message_transport/simple_publisher_plugin.h>
00005 #include <sensor_msgs/Image.h>
00006 #include <sensor_msgs/CompressedImage.h>
00007 #include <dynamic_reconfigure/server.h>
00008 #include <compressed_imagem_transport/CompressedPublisherConfig.h>
00009 
00010 
00011 namespace compressed_imagem_transport {
00012 
00013     class CompressedPublisher : public message_transport::SimplePublisherPlugin<sensor_msgs::Image,sensor_msgs::CompressedImage>
00014     {
00015         public:
00016             virtual ~CompressedPublisher() {}
00017 
00018             virtual std::string getTransportName() const
00019             {
00020                 return "compressed";
00021             }
00022 
00023         protected:
00024             virtual void publish(const sensor_msgs::Image& message,
00025                     const message_transport::SimplePublisherPlugin<sensor_msgs::Image,sensor_msgs::CompressedImage>::PublishFn& publish_fn) const ;
00026 
00027             virtual void postAdvertiseInit() {
00028                 // Set up reconfigure server for this topic
00029                 reconfigure_server_ = boost::make_shared<ReconfigureServer>(this->getParamNode());
00030                 ReconfigureServer::CallbackType f = boost::bind(&CompressedPublisher::configCb, this, _1, _2);
00031                 reconfigure_server_->setCallback(f);
00032             }
00033 
00034 
00035             typedef compressed_imagem_transport::CompressedPublisherConfig Config;
00036             typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00037             boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00038             Config config_;
00039 
00040             void configCb(Config& config, uint32_t level);
00041     };
00042 
00043 } //namespace compressed_imagem_transport
00044 
00045 #endif // IMAGEM_TRANSPORT_COMPRESSED_PUBLISHER_H


compressed_imagem_transport
Author(s): Cedric Pradalier
autogenerated on Sun Oct 5 2014 23:49:37