36 #include <sensor_msgs/CompressedImage.h> 37 #include <dynamic_reconfigure/server.h> 38 #include <compressed_image_transport/CompressedSubscriberConfig.h> 40 #include <turbojpeg.h> 64 virtual void internalCallback(
const sensor_msgs::CompressedImageConstPtr& message,
67 sensor_msgs::ImagePtr
decompressJPEG(
const std::vector<uint8_t>& data,
const std::string& source_encoding,
const std_msgs::Header&
header);
69 typedef compressed_image_transport::CompressedSubscriberConfig
Config;
76 void configCb(Config& config, uint32_t level);
sensor_msgs::ImagePtr decompressJPEG(const std::vector< uint8_t > &data, const std::string &source_encoding, const std_msgs::Header &header)
compressed_image_transport::CompressedSubscriberConfig Config
boost::function< void(const sensor_msgs::ImageConstPtr &)> Callback
const ros::NodeHandle & nh() const
virtual void subscribeImpl(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const Callback &callback, const ros::VoidPtr &tracked_object, const image_transport::TransportHints &transport_hints)
virtual void internalCallback(const sensor_msgs::CompressedImageConstPtr &message, const Callback &user_cb)
dynamic_reconfigure::Server< Config > ReconfigureServer
virtual ~CompressedSubscriber()
void configCb(Config &config, uint32_t level)
virtual std::string getTransportName() const
boost::shared_ptr< ReconfigureServer > reconfigure_server_