$search

theora_image_transport::TheoraPublisher Class Reference

#include <theora_publisher.h>

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

List of all members.

Public Member Functions

virtual std::string getTransportName () const
 TheoraPublisher ()
 ~TheoraPublisher ()

Protected Types

typedef
theora_image_transport::TheoraPublisherConfig 
Config
typedef
dynamic_reconfigure::Server
< Config
ReconfigureServer

Protected Member Functions

virtual void advertiseImpl (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const image_transport::SubscriberStatusCallback &user_connect_cb, const image_transport::SubscriberStatusCallback &user_disconnect_cb, const ros::VoidPtr &tracked_object, bool latch)
void configCb (Config &config, uint32_t level)
virtual void connectCallback (const ros::SingleSubscriberPublisher &pub)
bool ensureEncodingContext (const sensor_msgs::Image &image, const PublishFn &publish_fn) const
void oggPacketToMsg (const roslib::Header &header, const ogg_packet &oggpacket, theora_image_transport::Packet &msg) const
virtual void publish (const sensor_msgs::Image &message, const PublishFn &publish_fn) const
void updateKeyframeFrequency () const

Protected Attributes

th_info encoder_setup_
boost::shared_ptr< th_enc_ctx > encoding_context_
sensor_msgs::CvBridge img_bridge_
ogg_uint32_t keyframe_frequency_
boost::shared_ptr
< ReconfigureServer
reconfigure_server_
std::vector
< theora_image_transport::Packet
stream_header_

Detailed Description

Definition at line 15 of file theora_publisher.h.


Member Typedef Documentation

typedef theora_image_transport::TheoraPublisherConfig theora_image_transport::TheoraPublisher::Config [protected]

Definition at line 40 of file theora_publisher.h.

typedef dynamic_reconfigure::Server<Config> theora_image_transport::TheoraPublisher::ReconfigureServer [protected]

Definition at line 41 of file theora_publisher.h.


Constructor & Destructor Documentation

theora_image_transport::TheoraPublisher::TheoraPublisher (  ) 

Definition at line 11 of file theora_publisher.cpp.

theora_image_transport::TheoraPublisher::~TheoraPublisher (  ) 

Definition at line 30 of file theora_publisher.cpp.


Member Function Documentation

void theora_image_transport::TheoraPublisher::advertiseImpl ( ros::NodeHandle nh,
const std::string &  base_topic,
uint32_t  queue_size,
const image_transport::SubscriberStatusCallback user_connect_cb,
const image_transport::SubscriberStatusCallback user_disconnect_cb,
const ros::VoidPtr &  tracked_object,
bool  latch 
) [protected, virtual]
void theora_image_transport::TheoraPublisher::configCb ( Config config,
uint32_t  level 
) [protected]

Definition at line 54 of file theora_publisher.cpp.

void theora_image_transport::TheoraPublisher::connectCallback ( const ros::SingleSubscriberPublisher pub  )  [protected, virtual]
bool theora_image_transport::TheoraPublisher::ensureEncodingContext ( const sensor_msgs::Image image,
const PublishFn publish_fn 
) const [protected]

Todo:
Check if encoding has changed
Todo:
Store image encoding in comment
Todo:
Try not to send headers twice to some listeners

Definition at line 189 of file theora_publisher.cpp.

virtual std::string theora_image_transport::TheoraPublisher::getTransportName (  )  const [inline, virtual]

Implements image_transport::PublisherPlugin.

Definition at line 23 of file theora_publisher.h.

void theora_image_transport::TheoraPublisher::oggPacketToMsg ( const roslib::Header header,
const ogg_packet &  oggpacket,
theora_image_transport::Packet msg 
) const [protected]

Definition at line 230 of file theora_publisher.cpp.

void theora_image_transport::TheoraPublisher::publish ( const sensor_msgs::Image message,
const PublishFn publish_fn 
) const [protected, virtual]

Todo:
fromImage is deprecated
Todo:
Optimized gray-scale path, rgb8
Todo:
fromImage can throw cv::Exception on bayer encoded images

Implements image_transport::SimplePublisherPlugin< theora_image_transport::Packet >.

Definition at line 119 of file theora_publisher.cpp.

void theora_image_transport::TheoraPublisher::updateKeyframeFrequency (  )  const [protected]

Definition at line 242 of file theora_publisher.cpp.


Member Data Documentation

Definition at line 55 of file theora_publisher.h.

boost::shared_ptr<th_enc_ctx> theora_image_transport::TheoraPublisher::encoding_context_ [mutable, protected]

Definition at line 57 of file theora_publisher.h.

Definition at line 54 of file theora_publisher.h.

Definition at line 56 of file theora_publisher.h.

Definition at line 42 of file theora_publisher.h.

Definition at line 58 of file theora_publisher.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


theora_image_transport
Author(s): Patrick Mihelich, Ethan Dreyfuss
autogenerated on Fri Mar 1 15:47:59 2013