36 #include <dynamic_reconfigure/server.h> 37 #include <theora_image_transport/TheoraSubscriberConfig.h> 38 #include <theora_image_transport/Packet.h> 40 #include <theora/codec.h> 41 #include <theora/theoraenc.h> 42 #include <theora/theoradec.h> 65 typedef theora_image_transport::TheoraSubscriberConfig
Config;
70 void configCb(Config& config, uint32_t level);
74 void msgToOggPacket(
const theora_image_transport::Packet &msg, ogg_packet &ogg);
th_dec_ctx * decoding_context_
theora_image_transport::TheoraSubscriberConfig Config
virtual ~TheoraSubscriber()
boost::function< void(const sensor_msgs::ImageConstPtr &)> Callback
void msgToOggPacket(const theora_image_transport::Packet &msg, ogg_packet &ogg)
boost::shared_ptr< ReconfigureServer > reconfigure_server_
sensor_msgs::ImagePtr latest_image_
virtual void internalCallback(const theora_image_transport::PacketConstPtr &msg, const Callback &user_cb)
int updatePostProcessingLevel(int level)
virtual std::string getTransportName() const
th_setup_info * setup_info_
th_comment header_comment_
const ros::NodeHandle & nh() const
dynamic_reconfigure::Server< Config > ReconfigureServer
void configCb(Config &config, uint32_t level)
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)