#include <vp8_streamer.h>

Protected Member Functions | |
| virtual void | initializeEncoder () |
Protected Member Functions inherited from web_video_server::LibavStreamer | |
| virtual void | initialize (const cv::Mat &) |
| virtual void | sendImage (const cv::Mat &, const ros::Time &time) |
Protected Member Functions inherited from web_video_server::ImageTransportImageStreamer | |
| virtual void | restreamFrame (double max_age) |
Private Attributes | |
| std::string | quality_ |
Additional Inherited Members | |
Protected Attributes inherited from web_video_server::LibavStreamer | |
| AVCodec * | codec_ |
| AVCodecContext * | codec_context_ |
| AVFormatContext * | format_context_ |
| AVDictionary * | opt_ |
| AVOutputFormat * | output_format_ |
| AVStream * | video_stream_ |
Protected Attributes inherited from web_video_server::ImageTransportImageStreamer | |
| std::string | default_transport_ |
| image_transport::Subscriber | image_sub_ |
| bool | invert_ |
| ros::Time | last_frame |
| int | output_height_ |
| cv::Mat | output_size_image |
| int | output_width_ |
| boost::mutex | send_mutex_ |
Protected Attributes inherited from web_video_server::ImageStreamer | |
| async_web_server_cpp::HttpConnectionPtr | connection_ |
| image_transport::Subscriber | image_sub_ |
| bool | inactive_ |
| ros::NodeHandle | nh_ |
| async_web_server_cpp::HttpRequest | request_ |
| std::string | topic_ |
Definition at line 82 of file vp8_streamer.h.
| web_video_server::Vp8Streamer::Vp8Streamer | ( | const async_web_server_cpp::HttpRequest & | request, |
| async_web_server_cpp::HttpConnectionPtr | connection, | ||
| ros::NodeHandle & | nh | ||
| ) |
Definition at line 76 of file vp8_streamer.cpp.
| web_video_server::Vp8Streamer::~Vp8Streamer | ( | ) |
Definition at line 82 of file vp8_streamer.cpp.
|
protectedvirtual |
Reimplemented from web_video_server::LibavStreamer.
Definition at line 86 of file vp8_streamer.cpp.
|
private |
Definition at line 125 of file vp8_streamer.h.