38 #include <opencv2/highgui/highgui.hpp> 39 #include <boost/make_shared.hpp> 55 void CompressedDepthPublisher::advertiseImpl(
ros::NodeHandle &nh,
const std::string &base_topic, uint32_t queue_size,
61 Base::advertiseImpl(nh, base_topic, queue_size, user_connect_cb, user_disconnect_cb, tracked_object, latch);
64 reconfigure_server_ = boost::make_shared<ReconfigureServer>(this->nh());
65 ReconfigureServer::CallbackType
f = boost::bind(&CompressedDepthPublisher::configCb,
this, _1, _2);
66 reconfigure_server_->setCallback(f);
69 void CompressedDepthPublisher::configCb(
Config& config, uint32_t level)
74 void CompressedDepthPublisher::publish(
const sensor_msgs::Image& message,
const PublishFn& publish_fn)
const 76 sensor_msgs::CompressedImage::Ptr compressed_image =
81 publish_fn(*compressed_image);
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
compressed_depth_image_transport::CompressedDepthPublisherConfig Config
boost::function< void(const sensor_msgs::CompressedImage &)> PublishFn
sensor_msgs::CompressedImage::Ptr encodeCompressedDepthImage(const sensor_msgs::Image &message, double depth_max, double depth_quantization, int png_level)