Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
theora_image_transport::TheoraSubscriber Class Reference

#include <theora_subscriber.h>

Inheritance diagram for theora_image_transport::TheoraSubscriber:
Inheritance graph
[legend]

Public Member Functions

virtual std::string getTransportName () const
 
 TheoraSubscriber ()
 
virtual ~TheoraSubscriber ()
 
- Public Member Functions inherited from image_transport::SimpleSubscriberPlugin< theora_image_transport::Packet >
virtual uint32_t getNumPublishers () const
 
virtual std::string getTopic () const
 
virtual void shutdown ()
 
virtual ~SimpleSubscriberPlugin ()
 
- Public Member Functions inherited from image_transport::SubscriberPlugin
void subscribe (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &), T *obj, const TransportHints &transport_hints=TransportHints())
 
void subscribe (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
 
void subscribe (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &), const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
 
void subscribe (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, void(*fp)(const sensor_msgs::ImageConstPtr &), const TransportHints &transport_hints=TransportHints())
 
virtual ~SubscriberPlugin ()
 

Protected Types

typedef theora_image_transport::TheoraSubscriberConfig Config
 
typedef dynamic_reconfigure::Server< ConfigReconfigureServer
 

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 Member Functions inherited from image_transport::SimpleSubscriberPlugin< theora_image_transport::Packet >
virtual std::string getTopicToSubscribe (const std::string &base_topic) const
 
virtual void internalCallback (const typename theora_image_transport::Packet::ConstPtr &message, const Callback &user_cb)=0
 
const ros::NodeHandlenh () const
 

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< ReconfigureServerreconfigure_server_
 
th_setup_info * setup_info_
 

Additional Inherited Members

- Public Types inherited from image_transport::SubscriberPlugin
typedef boost::function< void(const sensor_msgs::ImageConstPtr &)> Callback
 
- Static Public Member Functions inherited from image_transport::SubscriberPlugin
static std::string getLookupName (const std::string &transport_type)
 

Detailed Description

Definition at line 46 of file theora_subscriber.h.

Member Typedef Documentation

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.

Constructor & Destructor Documentation

theora_image_transport::TheoraSubscriber::TheoraSubscriber ( )

Definition at line 46 of file theora_subscriber.cpp.

theora_image_transport::TheoraSubscriber::~TheoraSubscriber ( )
virtual

Definition at line 57 of file theora_subscriber.cpp.

Member Function Documentation

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
inlinevirtual

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 
)
protectedvirtual
Todo:
Break this function into pieces
Todo:
Handle RGB8 or MONO8 efficiently

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 
)
protectedvirtual
int theora_image_transport::TheoraSubscriber::updatePostProcessingLevel ( int  level)
protected

Definition at line 90 of file theora_subscriber.cpp.

Member Data Documentation

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.


The documentation for this class was generated from the following files:


theora_image_transport
Author(s): Patrick Mihelich, Ethan Dreyfuss
autogenerated on Fri Sep 20 2019 03:32:16