Go to the documentation of this file.00001 #ifndef IMAGEM_TRANSPORT_THEORA_SUBSCRIBER_H
00002 #define IMAGEM_TRANSPORT_THEORA_SUBSCRIBER_H
00003 #include <message_transport/simple_subscriber_plugin.h>
00004 #include <dynamic_reconfigure/server.h>
00005 #include <theora_imagem_transport/TheoraSubscriberConfig.h>
00006 #include <theora_image_transport/Packet.h>
00007 #include <cv_bridge/cv_bridge.h>
00008
00009 #include <theora/codec.h>
00010 #include <theora/theoraenc.h>
00011 #include <theora/theoradec.h>
00012
00013 namespace theora_imagem_transport {
00014
00015 class TheoraSubscriber : public message_transport::SimpleSubscriberPlugin<sensor_msgs::Image,theora_image_transport::Packet>
00016 {
00017 public:
00018 TheoraSubscriber();
00019 virtual ~TheoraSubscriber();
00020
00021 virtual std::string getTransportName() const
00022 {
00023 return "theora";
00024 }
00025
00026 protected:
00027
00028 virtual void internalCallback(const theora_image_transport::Packet::ConstPtr &msg,
00029 const message_transport::SimpleSubscriberPlugin<sensor_msgs::Image,theora_image_transport::Packet>::Callback& user_cb);
00030
00031 typedef message_transport::SubscriberPlugin<sensor_msgs::Image>::Callback ImageCallback;
00032
00033
00034
00035 virtual void subscribeImpl(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00036 const ImageCallback& callback, const ros::VoidPtr& tracked_object,
00037 const message_transport::TransportHints& transport_hints);
00038
00039
00040 typedef theora_imagem_transport::TheoraSubscriberConfig Config;
00041 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00042 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00043 int pplevel_;
00044
00045 void configCb(Config& config, uint32_t level);
00046
00047
00048 int updatePostProcessingLevel(int level);
00049 void msgToOggPacket(const theora_image_transport::Packet &msg, ogg_packet &ogg);
00050
00051 bool received_header_;
00052 bool received_keyframe_;
00053 th_dec_ctx* decoding_context_;
00054 th_info header_info_;
00055 th_comment header_comment_;
00056 th_setup_info* setup_info_;
00057 sensor_msgs::ImagePtr latest_image_;
00058 };
00059
00060 }
00061
00062 #endif // IMAGEM_TRANSPORT_THEORA_SUBSCRIBER_H