#include <theora_subscriber.h>
Public Member Functions | |
virtual std::string | getTransportName () const |
TheoraSubscriber () | |
virtual | ~TheoraSubscriber () |
Protected Types | |
typedef theora_image_transport::TheoraSubscriberConfig | Config |
typedef dynamic_reconfigure::Server < Config > | ReconfigureServer |
Protected Member Functions | |
void | configCb (Config &config, uint32_t level) |
virtual void | internalCallback (const theora_image_transport::PacketConstPtr &msg, const Callback &user_cb) |
void | msgToOggPacket (const theora_image_transport::Packet &msg, ogg_packet &ogg) |
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) |
int | updatePostProcessingLevel (int level) |
Protected Attributes | |
th_dec_ctx * | decoding_context_ |
th_comment | header_comment_ |
th_info | header_info_ |
sensor_msgs::ImagePtr | latest_image_ |
int | pplevel_ |
bool | received_header_ |
bool | received_keyframe_ |
boost::shared_ptr < ReconfigureServer > | reconfigure_server_ |
th_setup_info * | setup_info_ |
Definition at line 46 of file theora_subscriber.h.
typedef theora_image_transport::TheoraSubscriberConfig theora_image_transport::TheoraSubscriber::Config [protected] |
Definition at line 65 of file theora_subscriber.h.
typedef dynamic_reconfigure::Server<Config> theora_image_transport::TheoraSubscriber::ReconfigureServer [protected] |
Definition at line 66 of file theora_subscriber.h.
Definition at line 46 of file theora_subscriber.cpp.
Definition at line 57 of file theora_subscriber.cpp.
void theora_image_transport::TheoraSubscriber::configCb | ( | Config & | config, |
uint32_t | level | ||
) | [protected] |
Definition at line 80 of file theora_subscriber.cpp.
virtual std::string theora_image_transport::TheoraSubscriber::getTransportName | ( | ) | const [inline, virtual] |
Implements image_transport::SubscriberPlugin.
Definition at line 52 of file theora_subscriber.h.
void theora_image_transport::TheoraSubscriber::internalCallback | ( | const theora_image_transport::PacketConstPtr & | msg, |
const Callback & | user_cb | ||
) | [protected, virtual] |
Definition at line 121 of file theora_subscriber.cpp.
void theora_image_transport::TheoraSubscriber::msgToOggPacket | ( | const theora_image_transport::Packet & | msg, |
ogg_packet & | ogg | ||
) | [protected] |
Definition at line 110 of file theora_subscriber.cpp.
void theora_image_transport::TheoraSubscriber::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 | ||
) | [protected, virtual] |
Reimplemented from image_transport::SimpleSubscriberPlugin< theora_image_transport::Packet >.
Definition at line 65 of file theora_subscriber.cpp.
int theora_image_transport::TheoraSubscriber::updatePostProcessingLevel | ( | int | level | ) | [protected] |
Definition at line 90 of file theora_subscriber.cpp.
th_dec_ctx* theora_image_transport::TheoraSubscriber::decoding_context_ [protected] |
Definition at line 78 of file theora_subscriber.h.
th_comment theora_image_transport::TheoraSubscriber::header_comment_ [protected] |
Definition at line 80 of file theora_subscriber.h.
th_info theora_image_transport::TheoraSubscriber::header_info_ [protected] |
Definition at line 79 of file theora_subscriber.h.
sensor_msgs::ImagePtr theora_image_transport::TheoraSubscriber::latest_image_ [protected] |
Definition at line 82 of file theora_subscriber.h.
int theora_image_transport::TheoraSubscriber::pplevel_ [protected] |
Definition at line 68 of file theora_subscriber.h.
bool theora_image_transport::TheoraSubscriber::received_header_ [protected] |
Definition at line 76 of file theora_subscriber.h.
bool theora_image_transport::TheoraSubscriber::received_keyframe_ [protected] |
Definition at line 77 of file theora_subscriber.h.
boost::shared_ptr<ReconfigureServer> theora_image_transport::TheoraSubscriber::reconfigure_server_ [protected] |
Definition at line 67 of file theora_subscriber.h.
th_setup_info* theora_image_transport::TheoraSubscriber::setup_info_ [protected] |
Definition at line 81 of file theora_subscriber.h.