Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include "compressed_depth_image_transport/compressed_depth_publisher.h"
00036 #include <cv_bridge/cv_bridge.h>
00037 #include <sensor_msgs/image_encodings.h>
00038 #include <opencv2/highgui/highgui.hpp>
00039 #include <boost/make_shared.hpp>
00040
00041 #include "compressed_depth_image_transport/codec.h"
00042 #include "compressed_depth_image_transport/compression_common.h"
00043
00044 #include <vector>
00045 #include <sstream>
00046
00047 using namespace cv;
00048 using namespace std;
00049
00050 namespace enc = sensor_msgs::image_encodings;
00051
00052 namespace compressed_depth_image_transport
00053 {
00054
00055 void CompressedDepthPublisher::advertiseImpl(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size,
00056 const image_transport::SubscriberStatusCallback &user_connect_cb,
00057 const image_transport::SubscriberStatusCallback &user_disconnect_cb,
00058 const ros::VoidPtr &tracked_object, bool latch)
00059 {
00060 typedef image_transport::SimplePublisherPlugin<sensor_msgs::CompressedImage> Base;
00061 Base::advertiseImpl(nh, base_topic, queue_size, user_connect_cb, user_disconnect_cb, tracked_object, latch);
00062
00063
00064 reconfigure_server_ = boost::make_shared<ReconfigureServer>(this->nh());
00065 ReconfigureServer::CallbackType f = boost::bind(&CompressedDepthPublisher::configCb, this, _1, _2);
00066 reconfigure_server_->setCallback(f);
00067 }
00068
00069 void CompressedDepthPublisher::configCb(Config& config, uint32_t level)
00070 {
00071 config_ = config;
00072 }
00073
00074 void CompressedDepthPublisher::publish(const sensor_msgs::Image& message, const PublishFn& publish_fn) const
00075 {
00076 sensor_msgs::CompressedImage::Ptr compressed_image =
00077 encodeCompressedDepthImage(message, config_.depth_max, config_.depth_quantization, config_.png_level);
00078
00079 if (compressed_image)
00080 {
00081 publish_fn(*compressed_image);
00082 }
00083 }
00084
00085 }