theora_subscriber.h
Go to the documentation of this file.
00001 #include <image_transport/simple_subscriber_plugin.h>
00002 #include <dynamic_reconfigure/server.h>
00003 #include <theora_image_transport/TheoraSubscriberConfig.h>
00004 #include <theora_image_transport/Packet.h>
00005 
00006 #include <theora/codec.h>
00007 #include <theora/theoraenc.h>
00008 #include <theora/theoradec.h>
00009 
00010 namespace theora_image_transport {
00011 
00012 class TheoraSubscriber : public image_transport::SimpleSubscriberPlugin<theora_image_transport::Packet>
00013 {
00014 public:
00015   TheoraSubscriber();
00016   virtual ~TheoraSubscriber();
00017 
00018   virtual std::string getTransportName() const { return "theora"; }
00019 
00020 protected:
00021   // Overridden to bump queue_size, otherwise we might lose headers
00022   // Overridden to tweak arguments and set up reconfigure server
00023   virtual void subscribeImpl(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size,
00024                              const Callback &callback, const ros::VoidPtr &tracked_object,
00025                              const image_transport::TransportHints &transport_hints);
00026   
00027   // The function that does the actual decompression and calls a user supplied callback with the resulting image
00028   virtual void internalCallback(const theora_image_transport::PacketConstPtr &msg, const Callback& user_cb);
00029 
00030   // Dynamic reconfigure support
00031   typedef theora_image_transport::TheoraSubscriberConfig Config;
00032   typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00033   boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00034   int pplevel_; // Post-processing level
00035 
00036   void configCb(Config& config, uint32_t level);
00037 
00038   // Utility functions
00039   int updatePostProcessingLevel(int level);
00040   void msgToOggPacket(const theora_image_transport::Packet &msg, ogg_packet &ogg);
00041 
00042   bool received_header_;
00043   bool received_keyframe_;
00044   th_dec_ctx* decoding_context_;
00045   th_info header_info_;
00046   th_comment header_comment_;
00047   th_setup_info* setup_info_;
00048   sensor_msgs::ImagePtr latest_image_;
00049 };
00050 
00051 } //namespace theora_image_transport


theora_image_transport
Author(s): Patrick Mihelich, Ethan Dreyfuss
autogenerated on Sat Dec 28 2013 17:06:15