37 #include <std_msgs/Header.h> 38 #include <dynamic_reconfigure/server.h> 39 #include <theora_image_transport/TheoraPublisherConfig.h> 40 #include <theora_image_transport/Packet.h> 42 #include <theora/codec.h> 43 #include <theora/theoraenc.h> 44 #include <theora/theoradec.h> 69 virtual void publish(
const sensor_msgs::Image& message,
73 typedef theora_image_transport::TheoraPublisherConfig
Config;
77 void configCb(Config& config, uint32_t level);
81 void oggPacketToMsg(
const std_msgs::Header& header,
const ogg_packet &oggpacket,
82 theora_image_transport::Packet &msg)
const;
cv_bridge::CvImage img_image_
bool ensureEncodingContext(const sensor_msgs::Image &image, const PublishFn &publish_fn) const
void updateKeyframeFrequency() const
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
virtual void publish(const sensor_msgs::Image &message, const PublishFn &publish_fn) const
virtual void connectCallback(const ros::SingleSubscriberPublisher &pub)
boost::function< void(const theora_image_transport::Packet &)> PublishFn
virtual std::string getTransportName() const
void oggPacketToMsg(const std_msgs::Header &header, const ogg_packet &oggpacket, theora_image_transport::Packet &msg) const
std::vector< theora_image_transport::Packet > stream_header_
boost::shared_ptr< ReconfigureServer > reconfigure_server_
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)
theora_image_transport::TheoraPublisherConfig Config
dynamic_reconfigure::Server< Config > ReconfigureServer
ogg_uint32_t keyframe_frequency_
boost::shared_ptr< th_enc_ctx > encoding_context_
void configCb(Config &config, uint32_t level)
const ros::NodeHandle & nh() const