36 #include <sensor_msgs/CompressedImage.h> 37 #include <dynamic_reconfigure/server.h> 38 #include <compressed_image_transport/CompressedPublisherConfig.h> 59 virtual void publish(
const sensor_msgs::Image& message,
62 typedef compressed_image_transport::CompressedPublisherConfig
Config;
67 void configCb(Config& config, uint32_t level);
virtual void publish(const sensor_msgs::Image &message, const PublishFn &publish_fn) const
virtual ~CompressedPublisher()
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
boost::function< void(const sensor_msgs::CompressedImage &)> PublishFn
compressed_image_transport::CompressedPublisherConfig Config
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)
void configCb(Config &config, uint32_t level)
dynamic_reconfigure::Server< Config > ReconfigureServer
virtual std::string getTransportName() const
boost::shared_ptr< ReconfigureServer > reconfigure_server_
const ros::NodeHandle & nh() const