compressed_subscriber.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
36 #include <sensor_msgs/CompressedImage.h>
37 #include <dynamic_reconfigure/server.h>
38 #include <compressed_image_transport/CompressedSubscriberConfig.h>
39 
40 #include <turbojpeg.h>
41 
43 
44 class CompressedSubscriber : public image_transport::SimpleSubscriberPlugin<sensor_msgs::CompressedImage>
45 {
46 public:
48  virtual ~CompressedSubscriber();
49 
50  virtual std::string getTransportName() const
51  {
52  return "compressed";
53  }
54 
55  virtual void shutdown();
56 
57 protected:
58  // Overridden to set up reconfigure server
59  virtual void subscribeImpl(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
60  const Callback& callback, const ros::VoidPtr& tracked_object,
61  const image_transport::TransportHints& transport_hints);
62 
63 
64  virtual void internalCallback(const sensor_msgs::CompressedImageConstPtr& message,
65  const Callback& user_cb);
66 
67  sensor_msgs::ImagePtr decompressJPEG(const std::vector<uint8_t>& data, const std::string& source_encoding, const std_msgs::Header& header);
68 
69  typedef compressed_image_transport::CompressedSubscriberConfig Config;
70  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
73  int imdecode_flag_;
74  tjhandle tj_;
75 
76  void configCb(Config& config, uint32_t level);
77 };
78 
79 } //namespace image_transport
compressed_image_transport::CompressedSubscriber::decompressJPEG
sensor_msgs::ImagePtr decompressJPEG(const std::vector< uint8_t > &data, const std::string &source_encoding, const std_msgs::Header &header)
Definition: compressed_subscriber.cpp:97
boost::shared_ptr< void >
compressed_image_transport::CompressedSubscriber::config_
Config config_
Definition: compressed_subscriber.h:136
compressed_image_transport::CompressedSubscriber::ReconfigureServer
dynamic_reconfigure::Server< Config > ReconfigureServer
Definition: compressed_subscriber.h:134
image_transport::SubscriberPlugin::Callback
boost::function< void(const sensor_msgs::ImageConstPtr &)> Callback
compressed_image_transport::CompressedSubscriber::shutdown
virtual void shutdown()
Definition: compressed_subscriber.cpp:91
compressed_image_transport::CompressedSubscriber::reconfigure_server_
boost::shared_ptr< ReconfigureServer > reconfigure_server_
Definition: compressed_subscriber.h:135
simple_subscriber_plugin.h
compressed_image_transport::CompressedSubscriber::tj_
tjhandle tj_
Definition: compressed_subscriber.h:138
compressed_image_transport
Definition: compressed_publisher.h:40
compressed_image_transport::CompressedSubscriber::getTransportName
virtual std::string getTransportName() const
Definition: compressed_subscriber.h:114
compressed_image_transport::CompressedSubscriber::internalCallback
virtual void internalCallback(const sensor_msgs::CompressedImageConstPtr &message, const Callback &user_cb)
Definition: compressed_subscriber.cpp:183
compressed_image_transport::CompressedSubscriber::configCb
void configCb(Config &config, uint32_t level)
Definition: compressed_subscriber.cpp:79
compressed_image_transport::CompressedSubscriber::Config
compressed_image_transport::CompressedSubscriberConfig Config
Definition: compressed_subscriber.h:133
compressed_image_transport::CompressedSubscriber::subscribeImpl
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)
Definition: compressed_subscriber.cpp:65
image_transport::SimpleSubscriberPlugin< sensor_msgs::CompressedImage >::nh
const ros::NodeHandle & nh() const
compressed_image_transport::CompressedSubscriber::CompressedSubscriber
CompressedSubscriber()
Definition: compressed_subscriber.cpp:55
compressed_image_transport::CompressedSubscriber::imdecode_flag_
int imdecode_flag_
Definition: compressed_subscriber.h:137
image_transport::TransportHints
image_transport::SimpleSubscriberPlugin
compressed_image_transport::CompressedSubscriber::~CompressedSubscriber
virtual ~CompressedSubscriber()
Definition: compressed_subscriber.cpp:59
ros::NodeHandle


compressed_image_transport
Author(s): Patrick Mihelich, Julius Kammerl, David Gossow
autogenerated on Sat Jan 27 2024 03:31:06