1 #ifndef LIBAV_STREAMERS_H_ 2 #define LIBAV_STREAMERS_H_ 11 #include <libavcodec/avcodec.h> 12 #include <libavformat/avformat.h> 13 #include <libavutil/intreadwrite.h> 14 #include <libavformat/avio.h> 15 #include <libswscale/swscale.h> 16 #include <libavutil/opt.h> 17 #include <libavutil/mathematics.h> 18 #include <libavutil/imgutils.h> 28 ros::NodeHandle& nh,
const std::string &format_name,
const std::string &codec_name,
29 const std::string &content_type);
65 LibavStreamerType(
const std::string &format_name,
const std::string &codec_name,
const std::string &content_type);
AVFormatContext * format_context_
std::string content_type_
const std::string content_type_
virtual void sendImage(const cv::Mat &, const ros::Time &time)
LibavStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle &nh, const std::string &format_name, const std::string &codec_name, const std::string &content_type)
virtual void initialize(const cv::Mat &)
boost::mutex encode_mutex_
struct SwsContext * sws_context_
virtual void initializeEncoder()
ros::Time first_image_timestamp_
const std::string format_name_
AVOutputFormat * output_format_
const std::string codec_name_
AVCodecContext * codec_context_