36 #include <sensor_msgs/CompressedImage.h> 37 #include <dynamic_reconfigure/server.h> 38 #include <compressed_depth_image_transport/CompressedDepthPublisherConfig.h> 49 return "compressedDepth";
59 virtual void publish(
const sensor_msgs::Image& message,
62 typedef compressed_depth_image_transport::CompressedDepthPublisherConfig
Config;
67 void configCb(Config& config, uint32_t level);
const ros::NodeHandle & nh() const
virtual std::string getTransportName() const
dynamic_reconfigure::Server< Config > ReconfigureServer
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
compressed_depth_image_transport::CompressedDepthPublisherConfig Config
boost::function< void(const sensor_msgs::CompressedImage &)> PublishFn
virtual ~CompressedDepthPublisher()
void configCb(Config &config, uint32_t level)
virtual void publish(const sensor_msgs::Image &message, const PublishFn &publish_fn) const
virtual void advertiseImpl(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const image_transport::SubscriberStatusCallback &user_connect_cb, const image_transport::SubscriberStatusCallback &user_disconnect_cb, const ros::VoidPtr &tracked_object, bool latch)
boost::shared_ptr< ReconfigureServer > reconfigure_server_