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

#include <theora_publisher.h>

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

Public Member Functions

virtual std::string getTransportName () const
 
 TheoraPublisher ()
 
 ~TheoraPublisher ()
 
- Public Member Functions inherited from image_transport::SimplePublisherPlugin< theora_image_transport::Packet >
virtual uint32_t getNumSubscribers () const
 
virtual std::string getTopic () const
 
virtual void publish (const sensor_msgs::Image &message) const
 
virtual void shutdown ()
 
virtual ~SimplePublisherPlugin ()
 
- Public Member Functions inherited from image_transport::PublisherPlugin
void advertise (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, bool latch=true)
 
void advertise (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const SubscriberStatusCallback &connect_cb, const SubscriberStatusCallback &disconnect_cb=SubscriberStatusCallback(), const ros::VoidPtr &tracked_object=ros::VoidPtr(), bool latch=true)
 
virtual void publish (const sensor_msgs::ImageConstPtr &message) const
 
virtual void publish (const sensor_msgs::Image &message, const uint8_t *data) const
 
virtual ~PublisherPlugin ()
 

Protected Types

typedef theora_image_transport::TheoraPublisherConfig Config
 
typedef dynamic_reconfigure::Server< ConfigReconfigureServer
 
- Protected Types inherited from image_transport::SimplePublisherPlugin< theora_image_transport::Packet >
typedef boost::function< void(const theora_image_transport::Packet &)> PublishFn
 

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 std_msgs::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 Member Functions inherited from image_transport::SimplePublisherPlugin< theora_image_transport::Packet >
virtual void disconnectCallback (const ros::SingleSubscriberPublisher &pub)
 
const ros::PublishergetPublisher () const
 
virtual std::string getTopicToAdvertise (const std::string &base_topic) const
 
const ros::NodeHandlenh () const
 

Protected Attributes

th_info encoder_setup_
 
boost::shared_ptr< th_enc_ctx > encoding_context_
 
cv_bridge::CvImage img_image_
 
ogg_uint32_t keyframe_frequency_
 
boost::shared_ptr< ReconfigureServerreconfigure_server_
 
std::vector< theora_image_transport::Packet > stream_header_
 

Additional Inherited Members

- Static Public Member Functions inherited from image_transport::PublisherPlugin
static std::string getLookupName (const std::string &transport_name)
 

Detailed Description

Definition at line 48 of file theora_publisher.h.

Member Typedef Documentation

typedef theora_image_transport::TheoraPublisherConfig theora_image_transport::TheoraPublisher::Config
protected

Definition at line 73 of file theora_publisher.h.

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

Definition at line 74 of file theora_publisher.h.

Constructor & Destructor Documentation

theora_image_transport::TheoraPublisher::TheoraPublisher ( )

Definition at line 48 of file theora_publisher.cpp.

theora_image_transport::TheoraPublisher::~TheoraPublisher ( )

Definition at line 67 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 
)
protectedvirtual
void theora_image_transport::TheoraPublisher::configCb ( Config config,
uint32_t  level 
)
protected

Definition at line 91 of file theora_publisher.cpp.

void theora_image_transport::TheoraPublisher::connectCallback ( const ros::SingleSubscriberPublisher pub)
protectedvirtual
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 246 of file theora_publisher.cpp.

virtual std::string theora_image_transport::TheoraPublisher::getTransportName ( ) const
inlinevirtual

Implements image_transport::PublisherPlugin.

Definition at line 56 of file theora_publisher.h.

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

Definition at line 287 of file theora_publisher.cpp.

void theora_image_transport::TheoraPublisher::publish ( const sensor_msgs::Image &  message,
const PublishFn publish_fn 
) const
protectedvirtual
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 156 of file theora_publisher.cpp.

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

Definition at line 299 of file theora_publisher.cpp.

Member Data Documentation

th_info theora_image_transport::TheoraPublisher::encoder_setup_
mutableprotected

Definition at line 88 of file theora_publisher.h.

boost::shared_ptr<th_enc_ctx> theora_image_transport::TheoraPublisher::encoding_context_
mutableprotected

Definition at line 90 of file theora_publisher.h.

cv_bridge::CvImage theora_image_transport::TheoraPublisher::img_image_
mutableprotected

Definition at line 87 of file theora_publisher.h.

ogg_uint32_t theora_image_transport::TheoraPublisher::keyframe_frequency_
mutableprotected

Definition at line 89 of file theora_publisher.h.

boost::shared_ptr<ReconfigureServer> theora_image_transport::TheoraPublisher::reconfigure_server_
protected

Definition at line 75 of file theora_publisher.h.

std::vector<theora_image_transport::Packet> theora_image_transport::TheoraPublisher::stream_header_
mutableprotected

Definition at line 91 of file theora_publisher.h.


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


theora_image_transport
Author(s): Patrick Mihelich, Ethan Dreyfuss
autogenerated on Tue Jul 2 2019 19:10:14