compressed_depth_publisher.h
Go to the documentation of this file.
00001 #include "image_transport/simple_publisher_plugin.h"
00002 #include <sensor_msgs/CompressedImage.h>
00003 #include <dynamic_reconfigure/server.h>
00004 #include <compressed_depth_image_transport/CompressedDepthPublisherConfig.h>
00005 
00006 namespace compressed_depth_image_transport {
00007 
00008 class CompressedDepthPublisher : public image_transport::SimplePublisherPlugin<sensor_msgs::CompressedImage>
00009 {
00010 public:
00011   virtual ~CompressedDepthPublisher() {}
00012 
00013   virtual std::string getTransportName() const
00014   {
00015     return "compressedDepth";
00016   }
00017 
00018 protected:
00019   // Overridden to set up reconfigure server
00020   virtual void advertiseImpl(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size,
00021                              const image_transport::SubscriberStatusCallback  &user_connect_cb,
00022                              const image_transport::SubscriberStatusCallback  &user_disconnect_cb,
00023                              const ros::VoidPtr &tracked_object, bool latch);
00024   
00025   virtual void publish(const sensor_msgs::Image& message,
00026                        const PublishFn& publish_fn) const;
00027 
00028   typedef compressed_depth_image_transport::CompressedDepthPublisherConfig Config;
00029   typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00030   boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00031   Config config_;
00032 
00033   void configCb(Config& config, uint32_t level);
00034 };
00035 
00036 } //namespace compressed_depth_image_transport


compressed_depth_image_transport
Author(s): Julius Kammerl
autogenerated on Sat Dec 28 2013 17:06:20