From 5e63d0e3adec28f747705ca99d040da330521d14 Mon Sep 17 00:00:00 2001 From: Russell Toris Date: Thu, 7 May 2015 08:10:56 -0400 Subject: [PATCH 01/54] added verbose flag --- src/web_video_server.cpp | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 2b69882..39cfebf 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -13,12 +13,17 @@ namespace web_video_server { +static bool __verbose; + static void ros_connection_logger(async_web_server_cpp::HttpServerRequestHandler forward, const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end) { - ROS_INFO_STREAM("Handling Request: " << request.uri); + if (__verbose) + { + ROS_INFO_STREAM("Handling Request: " << request.uri); + } try { forward(request, connection, begin, end); @@ -36,6 +41,7 @@ WebVideoServer::WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh) cleanup_timer_ = nh.createTimer(ros::Duration(0.5), boost::bind(&WebVideoServer::cleanup_inactive_streams, this)); private_nh.param("port", port_, 8080); + private_nh.param("verbose", __verbose, true); private_nh.param("address", address_, "0.0.0.0"); @@ -80,9 +86,12 @@ void WebVideoServer::cleanup_inactive_streams() typedef std::vector >::iterator itr_type; itr_type new_end = std::remove_if(image_subscribers_.begin(), image_subscribers_.end(), boost::bind(&ImageStreamer::isInactive, _1)); - for (itr_type itr = new_end; itr < image_subscribers_.end(); ++itr) + if (__verbose) { - ROS_INFO_STREAM("Removed Stream: " << (*itr)->getTopic()); + for (itr_type itr = new_end; itr < image_subscribers_.end(); ++itr) + { + ROS_INFO_STREAM("Removed Stream: " << (*itr)->getTopic()); + } } image_subscribers_.erase(new_end, image_subscribers_.end()); } From 9a4d9236ef3ce6890573b534e1be6dd176c4de04 Mon Sep 17 00:00:00 2001 From: Russell Toris Date: Thu, 7 May 2015 08:11:07 -0400 Subject: [PATCH 02/54] changelog updated --- CHANGELOG.rst | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 7e18347..51e57a5 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package web_video_server ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.0.3 (2015-05-07) +------------------ +* added verbose flag +* Contributors: Russell Toris + 0.0.2 (2015-02-20) ------------------ * Merge pull request #10 from mitchellwills/develop From 29b6b70538b31ba1ed806386cf35e08dd4efcd1f Mon Sep 17 00:00:00 2001 From: Russell Toris Date: Thu, 7 May 2015 08:11:11 -0400 Subject: [PATCH 03/54] 0.0.3 --- package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/package.xml b/package.xml index 5c387bf..016f88d 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ web_video_server - 0.0.2 + 0.0.3 HTTP Streaming of ROS Image Topics in Multiple Formats Russell Toris From 42cef64740ff3dbdd3e86b26249c265bbffa57c8 Mon Sep 17 00:00:00 2001 From: Mitchell Wills Date: Tue, 2 Jun 2015 17:55:34 -0400 Subject: [PATCH 04/54] Added default transport parameter for regular image streamers --- include/web_video_server/image_streamer.h | 1 + src/image_streamer.cpp | 4 +++- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/include/web_video_server/image_streamer.h b/include/web_video_server/image_streamer.h index f24c2f3..ac3111f 100644 --- a/include/web_video_server/image_streamer.h +++ b/include/web_video_server/image_streamer.h @@ -38,6 +38,7 @@ class ImageStreamer int output_width_; int output_height_; bool invert_; + std::string default_transport_; private: image_transport::ImageTransport it_; bool initialized_; diff --git a/src/image_streamer.cpp b/src/image_streamer.cpp index 0afe392..95307f2 100644 --- a/src/image_streamer.cpp +++ b/src/image_streamer.cpp @@ -12,11 +12,13 @@ ImageStreamer::ImageStreamer(const async_web_server_cpp::HttpRequest &request, output_width_ = request.get_query_param_value_or_default("width", -1); output_height_ = request.get_query_param_value_or_default("height", -1); invert_ = request.has_query_param("invert"); + default_transport_ = request.get_query_param_value_or_default("default_transport", "raw"); } void ImageStreamer::start() { - image_sub_ = it_.subscribe(topic_, 1, &ImageStreamer::imageCallback, this); + image_transport::TransportHints hints(default_transport_); + image_sub_ = it_.subscribe(topic_, 1, &ImageStreamer::imageCallback, this, hints); } void ImageStreamer::initialize(const cv::Mat &) From 1dee2d1b8646fc8d5670dfde445a457ef9d80174 Mon Sep 17 00:00:00 2001 From: Mitchell Wills Date: Tue, 2 Jun 2015 18:56:27 -0400 Subject: [PATCH 05/54] Switched from passing image transport to passing node handle to streamer constructors --- include/web_video_server/image_streamer.h | 4 ++-- include/web_video_server/jpeg_streamers.h | 6 +++--- include/web_video_server/libav_streamer.h | 4 ++-- include/web_video_server/vp8_streamer.h | 4 ++-- include/web_video_server/web_video_server.h | 2 -- src/image_streamer.cpp | 4 ++-- src/jpeg_streamers.cpp | 12 ++++++------ src/libav_streamer.cpp | 8 ++++---- src/vp8_streamer.cpp | 8 ++++---- src/web_video_server.cpp | 7 +++---- 10 files changed, 28 insertions(+), 31 deletions(-) diff --git a/include/web_video_server/image_streamer.h b/include/web_video_server/image_streamer.h index ac3111f..c997a99 100644 --- a/include/web_video_server/image_streamer.h +++ b/include/web_video_server/image_streamer.h @@ -14,7 +14,7 @@ class ImageStreamer { public: ImageStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, - image_transport::ImageTransport it); + ros::NodeHandle& it); void start(); @@ -51,7 +51,7 @@ class ImageStreamerType public: virtual boost::shared_ptr create_streamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, - image_transport::ImageTransport it) = 0; + ros::NodeHandle& nh) = 0; virtual std::string create_viewer(const async_web_server_cpp::HttpRequest &request) = 0; }; diff --git a/include/web_video_server/jpeg_streamers.h b/include/web_video_server/jpeg_streamers.h index b513fc6..11402c1 100644 --- a/include/web_video_server/jpeg_streamers.h +++ b/include/web_video_server/jpeg_streamers.h @@ -13,7 +13,7 @@ class MjpegStreamer : public ImageStreamer { public: MjpegStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, - image_transport::ImageTransport it); + ros::NodeHandle& nh); protected: virtual void sendImage(const cv::Mat &, const ros::Time &time); @@ -27,7 +27,7 @@ class MjpegStreamerType : public ImageStreamerType public: boost::shared_ptr create_streamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, - image_transport::ImageTransport it); + ros::NodeHandle& nh); std::string create_viewer(const async_web_server_cpp::HttpRequest &request); }; @@ -36,7 +36,7 @@ class JpegSnapshotStreamer : public ImageStreamer { public: JpegSnapshotStreamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, image_transport::ImageTransport it); + async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh); protected: virtual void sendImage(const cv::Mat &, const ros::Time &time); diff --git a/include/web_video_server/libav_streamer.h b/include/web_video_server/libav_streamer.h index 040a9fe..9dedd0c 100644 --- a/include/web_video_server/libav_streamer.h +++ b/include/web_video_server/libav_streamer.h @@ -24,7 +24,7 @@ class LibavStreamer : public ImageStreamer { public: LibavStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, - image_transport::ImageTransport it, const std::string &format_name, const std::string &codec_name, + ros::NodeHandle& nh, const std::string &format_name, const std::string &codec_name, const std::string &content_type); ~LibavStreamer(); @@ -63,7 +63,7 @@ class LibavStreamerType : public ImageStreamerType boost::shared_ptr create_streamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, - image_transport::ImageTransport it); + ros::NodeHandle& nh); std::string create_viewer(const async_web_server_cpp::HttpRequest &request); diff --git a/include/web_video_server/vp8_streamer.h b/include/web_video_server/vp8_streamer.h index 940ebe6..f1632ae 100644 --- a/include/web_video_server/vp8_streamer.h +++ b/include/web_video_server/vp8_streamer.h @@ -49,7 +49,7 @@ class Vp8Streamer : public LibavStreamer { public: Vp8Streamer(const async_web_server_cpp::HttpRequest& request, async_web_server_cpp::HttpConnectionPtr connection, - image_transport::ImageTransport it); + ros::NodeHandle& nh); ~Vp8Streamer(); protected: virtual void initializeEncoder(); @@ -63,7 +63,7 @@ class Vp8StreamerType : public LibavStreamerType Vp8StreamerType(); virtual boost::shared_ptr create_streamer(const async_web_server_cpp::HttpRequest& request, async_web_server_cpp::HttpConnectionPtr connection, - image_transport::ImageTransport it); + ros::NodeHandle& nh); }; } diff --git a/include/web_video_server/web_video_server.h b/include/web_video_server/web_video_server.h index 8dd6ab3..5821727 100644 --- a/include/web_video_server/web_video_server.h +++ b/include/web_video_server/web_video_server.h @@ -2,7 +2,6 @@ #define WEB_VIDEO_SERVER_H_ #include -#include #include #include #include "web_video_server/image_streamer.h" @@ -52,7 +51,6 @@ class WebVideoServer void cleanup_inactive_streams(); ros::NodeHandle nh_; - image_transport::ImageTransport image_transport_; ros::Timer cleanup_timer_; int ros_threads_; int port_; diff --git a/src/image_streamer.cpp b/src/image_streamer.cpp index 95307f2..aa2167b 100644 --- a/src/image_streamer.cpp +++ b/src/image_streamer.cpp @@ -5,8 +5,8 @@ namespace web_video_server { ImageStreamer::ImageStreamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, image_transport::ImageTransport it) : - request_(request), connection_(connection), it_(it), inactive_(false), initialized_(false) + async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh) : + request_(request), connection_(connection), it_(nh), inactive_(false), initialized_(false) { topic_ = request.get_query_param_value_or_default("topic", ""); output_width_ = request.get_query_param_value_or_default("width", -1); diff --git a/src/jpeg_streamers.cpp b/src/jpeg_streamers.cpp index 1c7637e..08a99c3 100644 --- a/src/jpeg_streamers.cpp +++ b/src/jpeg_streamers.cpp @@ -5,8 +5,8 @@ namespace web_video_server { MjpegStreamer::MjpegStreamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, image_transport::ImageTransport it) : - ImageStreamer(request, connection, it) + async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh) : + ImageStreamer(request, connection, nh) { quality_ = request.get_query_param_value_or_default("quality", 95); @@ -42,9 +42,9 @@ void MjpegStreamer::sendImage(const cv::Mat &img, const ros::Time &time) boost::shared_ptr MjpegStreamerType::create_streamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, - image_transport::ImageTransport it) + ros::NodeHandle& nh) { - return boost::shared_ptr(new MjpegStreamer(request, connection, it)); + return boost::shared_ptr(new MjpegStreamer(request, connection, nh)); } std::string MjpegStreamerType::create_viewer(const async_web_server_cpp::HttpRequest &request) @@ -58,8 +58,8 @@ std::string MjpegStreamerType::create_viewer(const async_web_server_cpp::HttpReq JpegSnapshotStreamer::JpegSnapshotStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, - image_transport::ImageTransport it) : - ImageStreamer(request, connection, it) + ros::NodeHandle& nh) : + ImageStreamer(request, connection, nh) { quality_ = request.get_query_param_value_or_default("quality", 95); } diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index babba03..976847c 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -45,10 +45,10 @@ static int ffmpeg_boost_mutex_lock_manager(void **mutex, enum AVLockOp op) } LibavStreamer::LibavStreamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, image_transport::ImageTransport it, + async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh, const std::string &format_name, const std::string &codec_name, const std::string &content_type) : - ImageStreamer(request, connection, it), output_format_(0), format_context_(0), codec_(0), codec_context_(0), video_stream_( + ImageStreamer(request, connection, nh), output_format_(0), format_context_(0), codec_(0), codec_context_(0), video_stream_( 0), frame_(0), picture_(0), tmp_picture_(0), sws_context_(0), first_image_timestamp_(0), format_name_( format_name), codec_name_(codec_name), content_type_(content_type) { @@ -331,10 +331,10 @@ LibavStreamerType::LibavStreamerType(const std::string &format_name, const std:: boost::shared_ptr LibavStreamerType::create_streamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, - image_transport::ImageTransport it) + ros::NodeHandle& nh) { return boost::shared_ptr( - new LibavStreamer(request, connection, it, format_name_, codec_name_, content_type_)); + new LibavStreamer(request, connection, nh, format_name_, codec_name_, content_type_)); } std::string LibavStreamerType::create_viewer(const async_web_server_cpp::HttpRequest &request) diff --git a/src/vp8_streamer.cpp b/src/vp8_streamer.cpp index 4a973fe..4a17e9a 100644 --- a/src/vp8_streamer.cpp +++ b/src/vp8_streamer.cpp @@ -40,8 +40,8 @@ namespace web_video_server { Vp8Streamer::Vp8Streamer(const async_web_server_cpp::HttpRequest& request, - async_web_server_cpp::HttpConnectionPtr connection, image_transport::ImageTransport it) : - LibavStreamer(request, connection, it, "webm", "libvpx", "video/webm") + async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh) : + LibavStreamer(request, connection, nh, "webm", "libvpx", "video/webm") { quality_ = request.get_query_param_value_or_default("quality", "realtime"); } @@ -84,9 +84,9 @@ Vp8StreamerType::Vp8StreamerType() : boost::shared_ptr Vp8StreamerType::create_streamer(const async_web_server_cpp::HttpRequest& request, async_web_server_cpp::HttpConnectionPtr connection, - image_transport::ImageTransport it) + ros::NodeHandle& nh) { - return boost::shared_ptr(new Vp8Streamer(request, connection, it)); + return boost::shared_ptr(new Vp8Streamer(request, connection, nh)); } } diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 39cfebf..5946f92 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -35,7 +35,7 @@ static void ros_connection_logger(async_web_server_cpp::HttpServerRequestHandler } WebVideoServer::WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh) : - nh_(nh), image_transport_(nh), handler_group_( + nh_(nh), handler_group_( async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::not_found)) { cleanup_timer_ = nh.createTimer(ros::Duration(0.5), boost::bind(&WebVideoServer::cleanup_inactive_streams, this)); @@ -104,8 +104,7 @@ void WebVideoServer::handle_stream(const async_web_server_cpp::HttpRequest &requ std::string type = request.get_query_param_value_or_default("type", "mjpeg"); if (stream_types_.find(type) != stream_types_.end()) { - boost::shared_ptr streamer = stream_types_[type]->create_streamer(request, connection, - image_transport_); + boost::shared_ptr streamer = stream_types_[type]->create_streamer(request, connection, nh_); streamer->start(); boost::mutex::scoped_lock lock(subscriber_mutex_); image_subscribers_.push_back(streamer); @@ -121,7 +120,7 @@ void WebVideoServer::handle_snapshot(const async_web_server_cpp::HttpRequest &re async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end) { - boost::shared_ptr streamer(new JpegSnapshotStreamer(request, connection, image_transport_)); + boost::shared_ptr streamer(new JpegSnapshotStreamer(request, connection, nh_)); streamer->start(); boost::mutex::scoped_lock lock(subscriber_mutex_); From df215bfafc268cd97c51e3905e06904f7c376e02 Mon Sep 17 00:00:00 2001 From: Mitchell Wills Date: Thu, 4 Jun 2015 21:49:44 -0400 Subject: [PATCH 06/54] Added ros compressed video streamer type This directly passes the ros compressed frame data to the http socket without reencoding it --- CMakeLists.txt | 2 + include/web_video_server/image_streamer.h | 35 +++++++-- include/web_video_server/jpeg_streamers.h | 7 +- include/web_video_server/libav_streamer.h | 2 +- include/web_video_server/multipart_stream.h | 28 +++++++ .../ros_compressed_streamer.h | 38 ++++++++++ src/image_streamer.cpp | 21 +++--- src/jpeg_streamers.cpp | 24 +----- src/libav_streamer.cpp | 2 +- src/multipart_stream.cpp | 51 +++++++++++++ src/ros_compressed_streamer.cpp | 73 +++++++++++++++++++ src/web_video_server.cpp | 2 + 12 files changed, 242 insertions(+), 43 deletions(-) create mode 100644 include/web_video_server/multipart_stream.h create mode 100644 include/web_video_server/ros_compressed_streamer.h create mode 100644 src/multipart_stream.cpp create mode 100644 src/ros_compressed_streamer.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 85ea8eb..c25f1ac 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -43,6 +43,8 @@ add_executable(${PROJECT_NAME} src/image_streamer.cpp src/libav_streamer.cpp src/vp8_streamer.cpp + src/multipart_stream.cpp + src/ros_compressed_streamer.cpp src/jpeg_streamers.cpp) ## Specify libraries to link a library or executable target against diff --git a/include/web_video_server/image_streamer.h b/include/web_video_server/image_streamer.h index c997a99..80aa980 100644 --- a/include/web_video_server/image_streamer.h +++ b/include/web_video_server/image_streamer.h @@ -13,12 +13,17 @@ namespace web_video_server class ImageStreamer { public: - ImageStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, - ros::NodeHandle& it); + ImageStreamer(const async_web_server_cpp::HttpRequest &request, + async_web_server_cpp::HttpConnectionPtr connection, + ros::NodeHandle& nh); - void start(); + virtual void start() = 0; - bool isInactive(); + bool isInactive() + { + return inactive_; + } + ; std::string getTopic() { @@ -26,15 +31,29 @@ class ImageStreamer } ; protected: - virtual void sendImage(const cv::Mat &, const ros::Time &time) = 0; - - virtual void initialize(const cv::Mat &); - async_web_server_cpp::HttpConnectionPtr connection_; async_web_server_cpp::HttpRequest request_; + ros::NodeHandle nh_; bool inactive_; image_transport::Subscriber image_sub_; std::string topic_; +}; + + +class ImageTransportImageStreamer : public ImageStreamer +{ +public: + ImageTransportImageStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, + ros::NodeHandle& nh); + + virtual void start(); + +protected: + virtual void sendImage(const cv::Mat &, const ros::Time &time) = 0; + + virtual void initialize(const cv::Mat &); + + image_transport::Subscriber image_sub_; int output_width_; int output_height_; bool invert_; diff --git a/include/web_video_server/jpeg_streamers.h b/include/web_video_server/jpeg_streamers.h index 11402c1..6f17e48 100644 --- a/include/web_video_server/jpeg_streamers.h +++ b/include/web_video_server/jpeg_streamers.h @@ -5,11 +5,12 @@ #include "web_video_server/image_streamer.h" #include "async_web_server_cpp/http_request.hpp" #include "async_web_server_cpp/http_connection.hpp" +#include "web_video_server/multipart_stream.h" namespace web_video_server { -class MjpegStreamer : public ImageStreamer +class MjpegStreamer : public ImageTransportImageStreamer { public: MjpegStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, @@ -19,6 +20,7 @@ class MjpegStreamer : public ImageStreamer virtual void sendImage(const cv::Mat &, const ros::Time &time); private: + MultipartStream stream_; int quality_; }; @@ -28,11 +30,10 @@ class MjpegStreamerType : public ImageStreamerType boost::shared_ptr create_streamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh); - std::string create_viewer(const async_web_server_cpp::HttpRequest &request); }; -class JpegSnapshotStreamer : public ImageStreamer +class JpegSnapshotStreamer : public ImageTransportImageStreamer { public: JpegSnapshotStreamer(const async_web_server_cpp::HttpRequest &request, diff --git a/include/web_video_server/libav_streamer.h b/include/web_video_server/libav_streamer.h index 9dedd0c..cdce25d 100644 --- a/include/web_video_server/libav_streamer.h +++ b/include/web_video_server/libav_streamer.h @@ -20,7 +20,7 @@ extern "C" namespace web_video_server { -class LibavStreamer : public ImageStreamer +class LibavStreamer : public ImageTransportImageStreamer { public: LibavStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, diff --git a/include/web_video_server/multipart_stream.h b/include/web_video_server/multipart_stream.h new file mode 100644 index 0000000..0d0838c --- /dev/null +++ b/include/web_video_server/multipart_stream.h @@ -0,0 +1,28 @@ +#ifndef MULTIPART_STREAM_H_ +#define MULTIPART_STREAM_H_ + +#include +#include + +namespace web_video_server +{ + +class MultipartStream { +public: + MultipartStream(async_web_server_cpp::HttpConnectionPtr& connection, const std::string& boundry="boundarydonotcross"); + + void sendInitialHeader(); + void sendPartHeader(const ros::Time &time, const std::string& type, size_t payload_size); + void sendPartFooter(); + void sendPartAndClear(const ros::Time &time, const std::string& type, std::vector &data); + void sendPart(const ros::Time &time, const std::string& type, const boost::asio::const_buffer &buffer, + async_web_server_cpp::HttpConnection::ResourcePtr resource); + +private: + async_web_server_cpp::HttpConnectionPtr connection_; + std::string boundry_; +}; + +} + +#endif diff --git a/include/web_video_server/ros_compressed_streamer.h b/include/web_video_server/ros_compressed_streamer.h new file mode 100644 index 0000000..72165c2 --- /dev/null +++ b/include/web_video_server/ros_compressed_streamer.h @@ -0,0 +1,38 @@ +#ifndef ROS_COMPRESSED_STREAMERS_H_ +#define ROS_COMPRESSED_STREAMERS_H_ + +#include +#include "web_video_server/image_streamer.h" +#include "async_web_server_cpp/http_request.hpp" +#include "async_web_server_cpp/http_connection.hpp" +#include "web_video_server/multipart_stream.h" + +namespace web_video_server +{ + +class RosCompressedStreamer : public ImageStreamer +{ +public: + RosCompressedStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, + ros::NodeHandle& nh); + virtual void start(); + +private: + void imageCallback(const sensor_msgs::CompressedImageConstPtr &msg); + + MultipartStream stream_; + ros::Subscriber image_sub_; +}; + +class RosCompressedStreamerType : public ImageStreamerType +{ +public: + boost::shared_ptr create_streamer(const async_web_server_cpp::HttpRequest &request, + async_web_server_cpp::HttpConnectionPtr connection, + ros::NodeHandle& nh); + std::string create_viewer(const async_web_server_cpp::HttpRequest &request); +}; + +} + +#endif diff --git a/src/image_streamer.cpp b/src/image_streamer.cpp index aa2167b..a9a961b 100644 --- a/src/image_streamer.cpp +++ b/src/image_streamer.cpp @@ -6,26 +6,32 @@ namespace web_video_server ImageStreamer::ImageStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh) : - request_(request), connection_(connection), it_(nh), inactive_(false), initialized_(false) + request_(request), connection_(connection), nh_(nh), inactive_(false) { topic_ = request.get_query_param_value_or_default("topic", ""); +} + +ImageTransportImageStreamer::ImageTransportImageStreamer(const async_web_server_cpp::HttpRequest &request, + async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh) : + ImageStreamer(request, connection, nh), it_(nh), initialized_(false) +{ output_width_ = request.get_query_param_value_or_default("width", -1); output_height_ = request.get_query_param_value_or_default("height", -1); invert_ = request.has_query_param("invert"); default_transport_ = request.get_query_param_value_or_default("default_transport", "raw"); } -void ImageStreamer::start() +void ImageTransportImageStreamer::start() { image_transport::TransportHints hints(default_transport_); - image_sub_ = it_.subscribe(topic_, 1, &ImageStreamer::imageCallback, this, hints); + image_sub_ = it_.subscribe(topic_, 1, &ImageTransportImageStreamer::imageCallback, this, hints); } -void ImageStreamer::initialize(const cv::Mat &) +void ImageTransportImageStreamer::initialize(const cv::Mat &) { } -void ImageStreamer::imageCallback(const sensor_msgs::ImageConstPtr &msg) +void ImageTransportImageStreamer::imageCallback(const sensor_msgs::ImageConstPtr &msg) { if (inactive_) return; @@ -122,9 +128,4 @@ void ImageStreamer::imageCallback(const sensor_msgs::ImageConstPtr &msg) } } -bool ImageStreamer::isInactive() -{ - return inactive_; -} - } diff --git a/src/jpeg_streamers.cpp b/src/jpeg_streamers.cpp index 08a99c3..1f5d6c9 100644 --- a/src/jpeg_streamers.cpp +++ b/src/jpeg_streamers.cpp @@ -6,16 +6,10 @@ namespace web_video_server MjpegStreamer::MjpegStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh) : - ImageStreamer(request, connection, nh) + ImageTransportImageStreamer(request, connection, nh), stream_(connection) { quality_ = request.get_query_param_value_or_default("quality", 95); - - async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok).header("Connection", "close").header( - "Server", "web_video_server").header("Cache-Control", - "no-cache, no-store, must-revalidate, pre-check=0, post-check=0, max-age=0").header( - "Pragma", "no-cache").header("Content-type", "multipart/x-mixed-replace;boundary=--boundarydonotcross ").header( - "Access-Control-Allow-Origin", "*").write(connection); - connection->write("--boundarydonotcross \r\n"); + stream_.sendInitialHeader(); } void MjpegStreamer::sendImage(const cv::Mat &img, const ros::Time &time) @@ -27,17 +21,7 @@ void MjpegStreamer::sendImage(const cv::Mat &img, const ros::Time &time) std::vector encoded_buffer; cv::imencode(".jpeg", img, encoded_buffer, encode_params); - char stamp[20]; - sprintf(stamp, "%.06lf", time.toSec()); - boost::shared_ptr > headers( - new std::vector()); - headers->push_back(async_web_server_cpp::HttpHeader("Content-type", "image/jpeg")); - headers->push_back(async_web_server_cpp::HttpHeader("X-Timestamp", stamp)); - headers->push_back( - async_web_server_cpp::HttpHeader("Content-Length", boost::lexical_cast(encoded_buffer.size()))); - connection_->write(async_web_server_cpp::HttpReply::to_buffers(*headers), headers); - connection_->write_and_clear(encoded_buffer); - connection_->write("\r\n--boundarydonotcross \r\n"); + stream_.sendPartAndClear(time, "image/jpeg", encoded_buffer); } boost::shared_ptr MjpegStreamerType::create_streamer(const async_web_server_cpp::HttpRequest &request, @@ -59,7 +43,7 @@ std::string MjpegStreamerType::create_viewer(const async_web_server_cpp::HttpReq JpegSnapshotStreamer::JpegSnapshotStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh) : - ImageStreamer(request, connection, nh) + ImageTransportImageStreamer(request, connection, nh) { quality_ = request.get_query_param_value_or_default("quality", 95); } diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index 976847c..d722273 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -48,7 +48,7 @@ LibavStreamer::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) : - ImageStreamer(request, connection, nh), output_format_(0), format_context_(0), codec_(0), codec_context_(0), video_stream_( + ImageTransportImageStreamer(request, connection, nh), output_format_(0), format_context_(0), codec_(0), codec_context_(0), video_stream_( 0), frame_(0), picture_(0), tmp_picture_(0), sws_context_(0), first_image_timestamp_(0), format_name_( format_name), codec_name_(codec_name), content_type_(content_type) { diff --git a/src/multipart_stream.cpp b/src/multipart_stream.cpp new file mode 100644 index 0000000..d2dcc85 --- /dev/null +++ b/src/multipart_stream.cpp @@ -0,0 +1,51 @@ +#include "web_video_server/multipart_stream.h" +#include "async_web_server_cpp/http_reply.hpp" + +namespace web_video_server +{ + +MultipartStream::MultipartStream(async_web_server_cpp::HttpConnectionPtr& connection, const std::string& boundry) + : connection_(connection), boundry_(boundry) {} + +void MultipartStream::sendInitialHeader() { + async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok).header("Connection", "close").header( + "Server", "web_video_server").header("Cache-Control", + "no-cache, no-store, must-revalidate, pre-check=0, post-check=0, max-age=0").header( + "Pragma", "no-cache").header("Content-type", "multipart/x-mixed-replace;boundary="+boundry_).header( + "Access-Control-Allow-Origin", "*").write(connection_); + connection_->write("--"+boundry_+"\r\n"); +} + +void MultipartStream::sendPartHeader(const ros::Time &time, const std::string& type, size_t payload_size) { + char stamp[20]; + sprintf(stamp, "%.06lf", time.toSec()); + boost::shared_ptr > headers( + new std::vector()); + headers->push_back(async_web_server_cpp::HttpHeader("Content-type", type)); + headers->push_back(async_web_server_cpp::HttpHeader("X-Timestamp", stamp)); + headers->push_back( + async_web_server_cpp::HttpHeader("Content-Length", boost::lexical_cast(payload_size))); + connection_->write(async_web_server_cpp::HttpReply::to_buffers(*headers), headers); +} + +void MultipartStream::sendPartFooter() { + connection_->write("\r\n--"+boundry_+"\r\n"); +} + +void MultipartStream::sendPartAndClear(const ros::Time &time, const std::string& type, + std::vector &data) { + sendPartHeader(time, type, data.size()); + connection_->write_and_clear(data); + sendPartFooter(); +} + +void MultipartStream::sendPart(const ros::Time &time, const std::string& type, + const boost::asio::const_buffer &buffer, + async_web_server_cpp::HttpConnection::ResourcePtr resource) { + sendPartHeader(time, type, boost::asio::buffer_size(buffer)); + connection_->write(buffer, resource); + sendPartFooter(); +} + + +} diff --git a/src/ros_compressed_streamer.cpp b/src/ros_compressed_streamer.cpp new file mode 100644 index 0000000..4fbcb17 --- /dev/null +++ b/src/ros_compressed_streamer.cpp @@ -0,0 +1,73 @@ +#include "web_video_server/ros_compressed_streamer.h" + +namespace web_video_server +{ + +RosCompressedStreamer::RosCompressedStreamer(const async_web_server_cpp::HttpRequest &request, + async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh) : + ImageStreamer(request, connection, nh), stream_(connection) +{ + stream_.sendInitialHeader(); +} + +void RosCompressedStreamer::start() { + std::string compressed_topic = topic_ + "/compressed"; + image_sub_ = nh_.subscribe(compressed_topic, 1, &RosCompressedStreamer::imageCallback, this); +} + +void RosCompressedStreamer::imageCallback(const sensor_msgs::CompressedImageConstPtr &msg) { + try { + std::string content_type; + if(msg->format.find("jpeg") != std::string::npos) { + content_type = "image/jpeg"; + } + else if(msg->format.find("png") != std::string::npos) { + content_type = "image/png"; + } + else { + ROS_WARN_STREAM("Unknown ROS compressed image format: " << msg->format); + return; + } + + stream_.sendPart(msg->header.stamp, content_type, boost::asio::buffer(msg->data), msg); + } + catch (boost::system::system_error &e) + { + // happens when client disconnects + ROS_DEBUG("system_error exception: %s", e.what()); + inactive_ = true; + return; + } + catch (std::exception &e) + { + ROS_ERROR_THROTTLE(30, "exception: %s", e.what()); + inactive_ = true; + return; + } + catch (...) + { + ROS_ERROR_THROTTLE(30, "exception"); + inactive_ = true; + return; + } +} + + +boost::shared_ptr RosCompressedStreamerType::create_streamer(const async_web_server_cpp::HttpRequest &request, + async_web_server_cpp::HttpConnectionPtr connection, + ros::NodeHandle& nh) +{ + return boost::shared_ptr(new RosCompressedStreamer(request, connection, nh)); +} + +std::string RosCompressedStreamerType::create_viewer(const async_web_server_cpp::HttpRequest &request) +{ + std::stringstream ss; + ss << ""; + return ss.str(); +} + + +} diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 5946f92..e7f2388 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -6,6 +6,7 @@ #include #include "web_video_server/web_video_server.h" +#include "web_video_server/ros_compressed_streamer.h" #include "web_video_server/jpeg_streamers.h" #include "web_video_server/vp8_streamer.h" #include "async_web_server_cpp/http_reply.hpp" @@ -51,6 +52,7 @@ WebVideoServer::WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh) private_nh.param("ros_threads", ros_threads_, 2); stream_types_["mjpeg"] = boost::shared_ptr(new MjpegStreamerType()); + stream_types_["ros_compressed"] = boost::shared_ptr(new RosCompressedStreamerType()); stream_types_["vp8"] = boost::shared_ptr(new Vp8StreamerType()); handler_group_.addHandlerForPath("/", boost::bind(&WebVideoServer::handle_list_streams, this, _1, _2, _3, _4)); From 66c9c93456850032b4d187bda2ceb46be5b5e7b7 Mon Sep 17 00:00:00 2001 From: Mitchell Wills Date: Mon, 15 Jun 2015 21:33:51 -0400 Subject: [PATCH 07/54] Upgrade for change in signature of async_web_server_cpp request handler --- include/web_video_server/web_video_server.h | 8 ++++---- src/web_video_server.cpp | 14 +++++++++----- 2 files changed, 13 insertions(+), 9 deletions(-) diff --git a/include/web_video_server/web_video_server.h b/include/web_video_server/web_video_server.h index 5821727..b2df65f 100644 --- a/include/web_video_server/web_video_server.h +++ b/include/web_video_server/web_video_server.h @@ -35,16 +35,16 @@ class WebVideoServer */ void spin(); - void handle_stream(const async_web_server_cpp::HttpRequest &request, + bool handle_stream(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end); - void handle_stream_viewer(const async_web_server_cpp::HttpRequest &request, + bool handle_stream_viewer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end); - void handle_snapshot(const async_web_server_cpp::HttpRequest &request, + bool handle_snapshot(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end); - void handle_list_streams(const async_web_server_cpp::HttpRequest &request, + bool handle_list_streams(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end); private: diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index e7f2388..94ca4ba 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -16,7 +16,7 @@ namespace web_video_server static bool __verbose; -static void ros_connection_logger(async_web_server_cpp::HttpServerRequestHandler forward, +static bool ros_connection_logger(async_web_server_cpp::HttpServerRequestHandler forward, const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end) @@ -99,7 +99,7 @@ void WebVideoServer::cleanup_inactive_streams() } } -void WebVideoServer::handle_stream(const async_web_server_cpp::HttpRequest &request, +bool WebVideoServer::handle_stream(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end) { @@ -116,9 +116,10 @@ void WebVideoServer::handle_stream(const async_web_server_cpp::HttpRequest &requ async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::not_found)(request, connection, begin, end); } + return true; } -void WebVideoServer::handle_snapshot(const async_web_server_cpp::HttpRequest &request, +bool WebVideoServer::handle_snapshot(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end) { @@ -127,9 +128,10 @@ void WebVideoServer::handle_snapshot(const async_web_server_cpp::HttpRequest &re boost::mutex::scoped_lock lock(subscriber_mutex_); image_subscribers_.push_back(streamer); + return true; } -void WebVideoServer::handle_stream_viewer(const async_web_server_cpp::HttpRequest &request, +bool WebVideoServer::handle_stream_viewer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end) { @@ -153,9 +155,10 @@ void WebVideoServer::handle_stream_viewer(const async_web_server_cpp::HttpReques async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::not_found)(request, connection, begin, end); } + return true; } -void WebVideoServer::handle_list_streams(const async_web_server_cpp::HttpRequest &request, +bool WebVideoServer::handle_list_streams(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end) { @@ -224,6 +227,7 @@ void WebVideoServer::handle_list_streams(const async_web_server_cpp::HttpRequest connection->write(""); } connection->write(""); + return true; } } From b7ee8aa4becea523e5cd3b99320644e800999f43 Mon Sep 17 00:00:00 2001 From: Mitchell Wills Date: Tue, 16 Jun 2015 11:19:41 -0400 Subject: [PATCH 08/54] Switch to checkout async_web_server_cpp from source --- .travis.yml | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index 031dee5..111df9f 100644 --- a/.travis.yml +++ b/.travis.yml @@ -15,11 +15,13 @@ install: - sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu precise main" > /etc/apt/sources.list.d/ros-latest.list' - wget http://packages.ros.org/ros.key -O - | sudo apt-key add - - sudo apt-get update -qq - - sudo apt-get install python-catkin-pkg python-rosdep ros-groovy-catkin ros-hydro-catkin -qq + - sudo apt-get install python-catkin-pkg python-rosdep ros-hydro-catkin ros-hydro-catkin -qq - sudo rosdep init - rosdep update - mkdir -p /tmp/ws/src - ln -s `pwd` /tmp/ws/src/package + - cd /tmp/ws/src + - git clone https://github.com/WPI-RAIL/async_web_server_cpp.git - cd /tmp/ws - rosdep install --from-paths src --ignore-src --rosdistro hydro -y From 2d0257b861f62b3ba51950d7c76ee5801c96e96a Mon Sep 17 00:00:00 2001 From: Russell Toris Date: Tue, 18 Aug 2015 10:19:51 -0400 Subject: [PATCH 09/54] changelog updated --- CHANGELOG.rst | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 51e57a5..f03bca3 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package web_video_server ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.0.4 (2015-08-18) +------------------ +* Merge pull request #16 from mitchellwills/compressed + Adds support for streaming ROS compressed image topics without the need to reencode them +* Switch to checkout async_web_server_cpp from source +* Upgrade for change in signature of async_web_server_cpp request handler +* Added ros compressed video streamer type + This directly passes the ros compressed frame data to the http socket without reencoding it +* Switched from passing image transport to passing node handle to streamer constructors +* Added default transport parameter for regular image streamers +* Contributors: Mitchell Wills, Russell Toris + 0.0.3 (2015-05-07) ------------------ * added verbose flag From 79203146d9e3e5a8de811a9d03aba41d944ff623 Mon Sep 17 00:00:00 2001 From: Russell Toris Date: Tue, 18 Aug 2015 10:19:54 -0400 Subject: [PATCH 10/54] 0.0.4 --- package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/package.xml b/package.xml index 016f88d..45a1bd3 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ web_video_server - 0.0.3 + 0.0.4 HTTP Streaming of ROS Image Topics in Multiple Formats Russell Toris From 6f7240408e7cbf91c6e824b4e9d7bbd06349e448 Mon Sep 17 00:00:00 2001 From: BennyRe Date: Fri, 20 May 2016 14:53:21 +0200 Subject: [PATCH 11/54] More detailed exception message Programm behavior is not changed since the exception is rethrown. --- src/web_video_server.cpp | 17 +++++++++++++---- 1 file changed, 13 insertions(+), 4 deletions(-) diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 94ca4ba..411462e 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -61,10 +61,19 @@ WebVideoServer::WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh) boost::bind(&WebVideoServer::handle_stream_viewer, this, _1, _2, _3, _4)); handler_group_.addHandlerForPath("/snapshot", boost::bind(&WebVideoServer::handle_snapshot, this, _1, _2, _3, _4)); - server_.reset( - new async_web_server_cpp::HttpServer(address_, boost::lexical_cast(port_), - boost::bind(ros_connection_logger, handler_group_, _1, _2, _3, _4), - server_threads)); + try + { + server_.reset( + new async_web_server_cpp::HttpServer(address_, boost::lexical_cast(port_), + boost::bind(ros_connection_logger, handler_group_, _1, _2, _3, _4), + server_threads)); + } + catch(boost::exception& e) + { + ROS_ERROR("Exception when creating the web server! %s:%d", address_.c_str(), port_); + throw; + } + } WebVideoServer::~WebVideoServer() From e114860bc32c6bb34a9d85b4dc18ae05bf4b2689 Mon Sep 17 00:00:00 2001 From: BennyRe Date: Fri, 20 May 2016 14:54:26 +0200 Subject: [PATCH 12/54] Removed empty line --- src/web_video_server.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 411462e..369f4db 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -73,7 +73,6 @@ WebVideoServer::WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh) ROS_ERROR("Exception when creating the web server! %s:%d", address_.c_str(), port_); throw; } - } WebVideoServer::~WebVideoServer() From d4fa5a06e41d548e99cba822fb50cf381f9a368f Mon Sep 17 00:00:00 2001 From: Jihoon Lee Date: Thu, 13 Oct 2016 09:59:06 +0200 Subject: [PATCH 13/54] update changelog --- CHANGELOG.rst | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index f03bca3..8c667f7 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package web_video_server ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Merge pull request `#23 `_ from iki-wgt/develop + More information when server creation is failed +* Removed empty line +* More detailed exception message + Programm behavior is not changed since the exception is rethrown. +* Contributors: BennyRe, Russell Toris + 0.0.4 (2015-08-18) ------------------ * Merge pull request #16 from mitchellwills/compressed From c2c29d21f3c4701e3932f79fff5ad444e3d9c0b7 Mon Sep 17 00:00:00 2001 From: Jihoon Lee Date: Thu, 13 Oct 2016 09:59:17 +0200 Subject: [PATCH 14/54] 0.0.5 --- CHANGELOG.rst | 4 ++-- package.xml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 8c667f7..713c8ce 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package web_video_server ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +0.0.5 (2016-10-13) +------------------ * Merge pull request `#23 `_ from iki-wgt/develop More information when server creation is failed * Removed empty line diff --git a/package.xml b/package.xml index 45a1bd3..b12c60a 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ web_video_server - 0.0.4 + 0.0.5 HTTP Streaming of ROS Image Topics in Multiple Formats Russell Toris From bd0ee3b412abfe7ca6068b7d3dd8a8d49068722e Mon Sep 17 00:00:00 2001 From: Eric Date: Thu, 3 Nov 2016 16:19:59 -0400 Subject: [PATCH 15/54] Fixed topic list to display all image topics, fixing Issue #18. --- src/web_video_server.cpp | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 369f4db..03953fc 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -234,6 +234,23 @@ bool WebVideoServer::handle_list_streams(const async_web_server_cpp::HttpRequest } connection->write(""); } + connection->write(""); + // Add the rest of the image topics that don't have camera_info. + connection->write(""); return true; } From 50b460b148b72c5813aa9704b99cf3668f5b9681 Mon Sep 17 00:00:00 2001 From: Jihoon Lee Date: Tue, 17 Jan 2017 09:02:51 +0100 Subject: [PATCH 16/54] update change log --- CHANGELOG.rst | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 713c8ce..e5ea9ef 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package web_video_server ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Fixed topic list to display all image topics, fixing Issue `#18 `_. +* Contributors: Eric + 0.0.5 (2016-10-13) ------------------ * Merge pull request `#23 `_ from iki-wgt/develop From 6775e5d0d4e0c6664649316f737eb303a2226d10 Mon Sep 17 00:00:00 2001 From: Jihoon Lee Date: Tue, 17 Jan 2017 09:03:01 +0100 Subject: [PATCH 17/54] 0.0.6 --- CHANGELOG.rst | 4 ++-- package.xml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index e5ea9ef..12f8b97 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package web_video_server ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +0.0.6 (2017-01-17) +------------------ * Fixed topic list to display all image topics, fixing Issue `#18 `_. * Contributors: Eric diff --git a/package.xml b/package.xml index b12c60a..512c2e7 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ web_video_server - 0.0.5 + 0.0.6 HTTP Streaming of ROS Image Topics in Multiple Formats Russell Toris From c98007661e3108b92369575441eaa3dcc87b6181 Mon Sep 17 00:00:00 2001 From: Hans-Joachim Krauch Date: Fri, 10 Feb 2017 13:56:50 +0100 Subject: [PATCH 18/54] web_video_server: fix bool function not returning This fix is required when compiling the package with `clang`. Otherwise a SIGILL (Illegal instruction) is triggered. --- src/web_video_server.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 03953fc..350a75c 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -28,11 +28,14 @@ static bool ros_connection_logger(async_web_server_cpp::HttpServerRequestHandler try { forward(request, connection, begin, end); + return true; } catch (std::exception &e) { ROS_WARN_STREAM("Error Handling Request: " << e.what()); + return false; } + return false; } WebVideoServer::WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh) : From 76facbbdb8dc99c9f9e783dc2e1b7877c0b44b26 Mon Sep 17 00:00:00 2001 From: Jan Date: Thu, 27 Jul 2017 10:43:32 +0200 Subject: [PATCH 19/54] fixed misuse of remove_if (#35) --- src/web_video_server.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 350a75c..504bb1f 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -97,8 +97,8 @@ void WebVideoServer::cleanup_inactive_streams() if (lock) { typedef std::vector >::iterator itr_type; - itr_type new_end = std::remove_if(image_subscribers_.begin(), image_subscribers_.end(), - boost::bind(&ImageStreamer::isInactive, _1)); + itr_type new_end = std::partition(image_subscribers_.begin(), image_subscribers_.end(), + !boost::bind(&ImageStreamer::isInactive, _1)); if (__verbose) { for (itr_type itr = new_end; itr < image_subscribers_.end(); ++itr) From 3f7ffeb1cb9d37ba8f9783ba062c8e847aa3fc55 Mon Sep 17 00:00:00 2001 From: Jihoon Lee Date: Tue, 21 Nov 2017 00:39:37 +0900 Subject: [PATCH 20/54] Update travis configuration to test against kinetic (#44) --- .travis.yml | 41 +++++++++++++++++++++++------------------ 1 file changed, 23 insertions(+), 18 deletions(-) diff --git a/.travis.yml b/.travis.yml index 111df9f..c92d5de 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,31 +1,36 @@ -language: - - cpp - - python +# This config file for Travis CI utilizes ros-industrial/industrial_ci package. +# For more info for the package, see https://github.com/ros-industrial/industrial_ci/blob/master/README.rst + +dist: xenial +services: + - docker +language: generic python: - "2.7" compiler: - gcc +notifications: + email: + on_success: always + on_failure: always + +env: + matrix: + - ROS_DISTRO="kinetic" ROS_REPOSITORY_PATH=http://packages.ros.org/ros/ubuntu USE_DEB=true + - ROS_DISTRO="kinetic" PRERELEASE=true PRERELEASE_DOWNSTREAM_DEPTH=0 + +matrix: + allow_failures: + - env: ROS_DISTRO="kinetic" PRERELEASE=true PRERELEASE_DOWNSTREAM_DEPTH=0 + branches: only: - master - develop install: - - sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu precise main" > /etc/apt/sources.list.d/ros-latest.list' - - wget http://packages.ros.org/ros.key -O - | sudo apt-key add - - - sudo apt-get update -qq - - sudo apt-get install python-catkin-pkg python-rosdep ros-hydro-catkin ros-hydro-catkin -qq - - sudo rosdep init - - rosdep update - - mkdir -p /tmp/ws/src - - ln -s `pwd` /tmp/ws/src/package - - cd /tmp/ws/src - - git clone https://github.com/WPI-RAIL/async_web_server_cpp.git - - cd /tmp/ws - - rosdep install --from-paths src --ignore-src --rosdistro hydro -y + - git clone https://github.com/ros-industrial/industrial_ci.git .ci_config script: - - source /opt/ros/hydro/setup.bash - - catkin_make - - catkin_make install + - source .ci_config/travis.sh From a9dff844c1f234064457a3b77cefb59059097b3a Mon Sep 17 00:00:00 2001 From: russelhowe Date: Mon, 20 Nov 2017 08:11:43 -0800 Subject: [PATCH 21/54] Ffmpeg 3 (#43) * Correct use of deprecated parameters codec_context_->rc_buffer_aggressivity marked as "currently useless", so removed codec_context_->frame_skip_threshold access through new priv_data api * New names for pixel formats * AVPicture is deprecated, use AVFrame * Switch to non-deprecated free functions * Use new encoding api for newer versions encode_video2 is deprecated * codec_context is deprecated, use packet flags --- include/web_video_server/libav_streamer.h | 3 +- src/libav_streamer.cpp | 64 +++++++++++------------ src/vp8_streamer.cpp | 3 +- 3 files changed, 33 insertions(+), 37 deletions(-) diff --git a/include/web_video_server/libav_streamer.h b/include/web_video_server/libav_streamer.h index cdce25d..206d7ad 100644 --- a/include/web_video_server/libav_streamer.h +++ b/include/web_video_server/libav_streamer.h @@ -15,6 +15,7 @@ extern "C" #include #include #include +#include } namespace web_video_server @@ -41,8 +42,6 @@ class LibavStreamer : public ImageTransportImageStreamer private: AVFrame* frame_; - AVPicture* picture_; - AVPicture* tmp_picture_; struct SwsContext* sws_context_; ros::Time first_image_timestamp_; boost::mutex encode_mutex_; diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index d722273..58abcac 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -49,7 +49,7 @@ LibavStreamer::LibavStreamer(const async_web_server_cpp::HttpRequest &request, const std::string &format_name, const std::string &codec_name, const std::string &content_type) : ImageTransportImageStreamer(request, connection, nh), output_format_(0), format_context_(0), codec_(0), codec_context_(0), video_stream_( - 0), frame_(0), picture_(0), tmp_picture_(0), sws_context_(0), first_image_timestamp_(0), format_name_( + 0), frame_(0), sws_context_(0), first_image_timestamp_(0), format_name_( format_name), codec_name_(codec_name), content_type_(content_type) { @@ -72,22 +72,11 @@ LibavStreamer::~LibavStreamer() av_free(frame_); frame_ = NULL; #else - avcodec_free_frame(&frame_); + av_frame_free(&frame_); #endif } if (format_context_) avformat_free_context(format_context_); - if (picture_) - { - avpicture_free(picture_); - delete picture_; - picture_ = NULL; - } - if (tmp_picture_) - { - delete tmp_picture_; - tmp_picture_ = NULL; - } if (sws_context_) sws_freeContext(sws_context_); } @@ -151,7 +140,7 @@ void LibavStreamer::initialize(const cv::Mat &img) codec_context_->time_base.num = 1; codec_context_->time_base.den = 1; codec_context_->gop_size = gop_; - codec_context_->pix_fmt = PIX_FMT_YUV420P; + codec_context_->pix_fmt = AV_PIX_FMT_YUV420P; codec_context_->max_b_frames = 0; // Quality settings @@ -174,18 +163,10 @@ void LibavStreamer::initialize(const cv::Mat &img) } // Allocate frame buffers - frame_ = avcodec_alloc_frame(); - tmp_picture_ = new AVPicture; - picture_ = new AVPicture; - int ret = avpicture_alloc(picture_, codec_context_->pix_fmt, output_width_, output_height_); - if (ret < 0) - { - async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_, - connection_, - NULL, NULL); - throw std::runtime_error("Could not allocate picture frame"); - } - *((AVPicture *)frame_) = *picture_; + frame_ = av_frame_alloc(); + av_image_alloc(frame_->data, frame_->linesize, output_width_, output_height_, + codec_context_->pix_fmt, 1); + output_format_->flags |= AVFMT_NOFILE; @@ -241,9 +222,11 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time) #if (LIBAVUTIL_VERSION_MAJOR < 52) PixelFormat input_coding_format = PIX_FMT_BGR24; #else - AVPixelFormat input_coding_format = PIX_FMT_BGR24; + AVPixelFormat input_coding_format = AV_PIX_FMT_BGR24; #endif - avpicture_fill(tmp_picture_, img.data, input_coding_format, output_width_, output_height_); + AVFrame *raw_frame = av_frame_alloc(); + av_image_fill_arrays(raw_frame->data, raw_frame->linesize, + img.data, input_coding_format, output_width_, output_height_, 0); // Convert from opencv to libav if (!sws_context_) @@ -257,8 +240,12 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time) } } - int ret = sws_scale(sws_context_, (const uint8_t * const *)tmp_picture_->data, tmp_picture_->linesize, 0, - output_height_, picture_->data, picture_->linesize); + + int ret = sws_scale(sws_context_, + (const uint8_t * const *)raw_frame->data, raw_frame->linesize, 0, + output_height_, frame_->data, frame_->linesize); + + av_frame_free(&raw_frame); // Encode the frame AVPacket pkt; @@ -270,13 +257,24 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time) pkt.data = (uint8_t*)av_malloc(buf_size); pkt.size = avcodec_encode_video(codec_context_, pkt.data, buf_size, frame_); got_packet = pkt.size > 0; -#else +#elif (LIBAVCODEC_VERSION_MAJOR < 57) pkt.data = NULL; // packet data will be allocated by the encoder pkt.size = 0; if (avcodec_encode_video2(codec_context_, &pkt, frame_, &got_packet) < 0) + { + throw std::runtime_error("Error encoding video frame"); + } +#else + pkt.data = NULL; // packet data will be allocated by the encoder + pkt.size = 0; + if (avcodec_send_frame(codec_context_, frame_) < 0) { throw std::runtime_error("Error encoding video frame"); } + if (avcodec_receive_packet(codec_context_, &pkt) < 0) + { + throw std::runtime_error("Error retrieving encoded packet"); + } #endif if (got_packet) @@ -291,7 +289,7 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time) pkt.pts = 1; pkt.dts = AV_NOPTS_VALUE; - if (codec_context_->coded_frame->key_frame) + if (pkt.flags&AV_PKT_FLAG_KEY) pkt.flags |= AV_PKT_FLAG_KEY; pkt.stream_index = video_stream_->index; @@ -318,7 +316,7 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time) av_free(pkt.data); #endif - av_free_packet(&pkt); + av_packet_unref(&pkt); connection_->write_and_clear(encoded_frame); } diff --git a/src/vp8_streamer.cpp b/src/vp8_streamer.cpp index 4a17e9a..e0c6808 100644 --- a/src/vp8_streamer.cpp +++ b/src/vp8_streamer.cpp @@ -73,8 +73,7 @@ void Vp8Streamer::initializeEncoder() av_opt_set_int(codec_context_->priv_data, "bufsize", bufsize, 0); av_opt_set_int(codec_context_->priv_data, "buf-initial", bufsize, 0); av_opt_set_int(codec_context_->priv_data, "buf-optimal", bufsize, 0); - codec_context_->rc_buffer_aggressivity = 0.5; - codec_context_->frame_skip_threshold = 10; + av_opt_set_int(codec_context_->priv_data, "skip_threshold", 10, 0); } Vp8StreamerType::Vp8StreamerType() : From 9b1e3f63b2be3af42b9a71d7d03a7137f36f266c Mon Sep 17 00:00:00 2001 From: Jihoon Lee Date: Mon, 20 Nov 2017 17:35:07 +0100 Subject: [PATCH 22/54] update changelog --- CHANGELOG.rst | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 12f8b97..32d3f94 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,24 @@ Changelog for package web_video_server ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Ffmpeg 3 (`#43 `_) + * Correct use of deprecated parameters + codec_context\_->rc_buffer_aggressivity marked as "currently useless", so removed + codec_context\_->frame_skip_threshold access through new priv_data api + * New names for pixel formats + * AVPicture is deprecated, use AVFrame + * Switch to non-deprecated free functions + * Use new encoding api for newer versions + * codec_context is deprecated, use packet flags +* Update travis configuration to test against kinetic (`#44 `_) +* fixed misuse of remove_if (`#35 `_) +* Merge pull request `#33 `_ from achim-k/patch-1 + web_video_server: fix bool function not returning + This fix is required when compiling the package with `clang`. Otherwise a SIGILL (Illegal instruction) is triggered. +* Contributors: Hans-Joachim Krauch, Jan, Jihoon Lee, russelhowe + 0.0.6 (2017-01-17) ------------------ * Fixed topic list to display all image topics, fixing Issue `#18 `_. From 7ae8712d65718c1c0f3f2a2d6b7372c243ea7e19 Mon Sep 17 00:00:00 2001 From: Jihoon Lee Date: Mon, 20 Nov 2017 17:35:17 +0100 Subject: [PATCH 23/54] 0.0.7 --- CHANGELOG.rst | 4 ++-- package.xml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 32d3f94..8dbe13d 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package web_video_server ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +0.0.7 (2017-11-20) +------------------ * Ffmpeg 3 (`#43 `_) * Correct use of deprecated parameters codec_context\_->rc_buffer_aggressivity marked as "currently useless", so removed diff --git a/package.xml b/package.xml index 512c2e7..58c7926 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ web_video_server - 0.0.6 + 0.0.7 HTTP Streaming of ROS Image Topics in Multiple Formats Russell Toris From 80c2fc4ed3ace04f72c88a56ce23765267515a2c Mon Sep 17 00:00:00 2001 From: Jihoon Lee Date: Mon, 8 Jan 2018 13:00:15 +0900 Subject: [PATCH 24/54] Use trusty instead of xenial. See travis-ci/travis-ci#7260 (#49) * Also see RobotWebTools/rosbridge_suite#311 --- .travis.yml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index c92d5de..f68bf66 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,7 +1,8 @@ # This config file for Travis CI utilizes ros-industrial/industrial_ci package. # For more info for the package, see https://github.com/ros-industrial/industrial_ci/blob/master/README.rst -dist: xenial +dist: trusty +sudo: required services: - docker language: generic From ae74f19ada22f288a7c7a99ada7a1b9b6037c7ce Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 8 Jan 2018 04:15:31 +0000 Subject: [PATCH 25/54] use SteadyTimer for cleaning up inactive streams (#45) so that cleanup works correctly even if system time changes --- include/web_video_server/web_video_server.h | 2 +- src/web_video_server.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/include/web_video_server/web_video_server.h b/include/web_video_server/web_video_server.h index b2df65f..9671f83 100644 --- a/include/web_video_server/web_video_server.h +++ b/include/web_video_server/web_video_server.h @@ -51,7 +51,7 @@ class WebVideoServer void cleanup_inactive_streams(); ros::NodeHandle nh_; - ros::Timer cleanup_timer_; + ros::SteadyTimer cleanup_timer_; int ros_threads_; int port_; std::string address_; diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 504bb1f..0cc7af1 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -42,7 +42,7 @@ WebVideoServer::WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh) nh_(nh), handler_group_( async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::not_found)) { - cleanup_timer_ = nh.createTimer(ros::Duration(0.5), boost::bind(&WebVideoServer::cleanup_inactive_streams, this)); + cleanup_timer_ = nh.createSteadyTimer(ros::WallDuration(0.5), boost::bind(&WebVideoServer::cleanup_inactive_streams, this)); private_nh.param("port", port_, 8080); private_nh.param("verbose", __verbose, true); From 9a8d43310b17c2e02c2ca2e2eafa4b3563fc9c11 Mon Sep 17 00:00:00 2001 From: Jihoon Lee Date: Mon, 8 Jan 2018 14:51:24 +0900 Subject: [PATCH 26/54] Revert "use SteadyTimer for cleaning up inactive streams (#45)" (#51) This reverts commit ae74f19ada22f288a7c7a99ada7a1b9b6037c7ce. --- include/web_video_server/web_video_server.h | 2 +- src/web_video_server.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/include/web_video_server/web_video_server.h b/include/web_video_server/web_video_server.h index 9671f83..b2df65f 100644 --- a/include/web_video_server/web_video_server.h +++ b/include/web_video_server/web_video_server.h @@ -51,7 +51,7 @@ class WebVideoServer void cleanup_inactive_streams(); ros::NodeHandle nh_; - ros::SteadyTimer cleanup_timer_; + ros::Timer cleanup_timer_; int ros_threads_; int port_; std::string address_; diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 0cc7af1..504bb1f 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -42,7 +42,7 @@ WebVideoServer::WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh) nh_(nh), handler_group_( async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::not_found)) { - cleanup_timer_ = nh.createSteadyTimer(ros::WallDuration(0.5), boost::bind(&WebVideoServer::cleanup_inactive_streams, this)); + cleanup_timer_ = nh.createTimer(ros::Duration(0.5), boost::bind(&WebVideoServer::cleanup_inactive_streams, this)); private_nh.param("port", port_, 8080); private_nh.param("verbose", __verbose, true); From 0933c6e07bf39d3946581da2f4ca580e7b99e37f Mon Sep 17 00:00:00 2001 From: randoms Date: Mon, 8 Jan 2018 14:31:49 +0800 Subject: [PATCH 27/54] Fix Build for ubuntu 14.04 (#48) * fix issue #47 * fix double free --- src/libav_streamer.cpp | 26 +++++++++++++++++++++++--- 1 file changed, 23 insertions(+), 3 deletions(-) diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index 58abcac..fc733b1 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -68,7 +68,7 @@ LibavStreamer::~LibavStreamer() avcodec_close(codec_context_); if (frame_) { -#if (LIBAVCODEC_VERSION_MAJOR < 54) +#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1) av_free(frame_); frame_ = NULL; #else @@ -163,7 +163,11 @@ void LibavStreamer::initialize(const cv::Mat &img) } // Allocate frame buffers +#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1) + frame_ = avcodec_alloc_frame(); +#else frame_ = av_frame_alloc(); +#endif av_image_alloc(frame_->data, frame_->linesize, output_width_, output_height_, codec_context_->pix_fmt, 1); @@ -219,14 +223,22 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time) first_image_timestamp_ = time; } std::vector encoded_frame; -#if (LIBAVUTIL_VERSION_MAJOR < 52) +#if (LIBAVUTIL_VERSION_MAJOR < 53) PixelFormat input_coding_format = PIX_FMT_BGR24; #else AVPixelFormat input_coding_format = AV_PIX_FMT_BGR24; #endif + +#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1) + AVPicture *raw_frame = new AVPicture; + avpicture_fill(raw_frame, img.data, input_coding_format, output_width_, output_height_); +#else AVFrame *raw_frame = av_frame_alloc(); av_image_fill_arrays(raw_frame->data, raw_frame->linesize, img.data, input_coding_format, output_width_, output_height_, 0); +#endif + + // Convert from opencv to libav if (!sws_context_) @@ -245,7 +257,11 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time) (const uint8_t * const *)raw_frame->data, raw_frame->linesize, 0, output_height_, frame_->data, frame_->linesize); +#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1) + delete raw_frame; +#else av_frame_free(&raw_frame); +#endif // Encode the frame AVPacket pkt; @@ -312,11 +328,15 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time) { encoded_frame.clear(); } -#if (LIBAVCODEC_VERSION_MAJOR < 54) +#if LIBAVCODEC_VERSION_INT < 54 av_free(pkt.data); #endif +#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1) + av_free_packet(&pkt); +#else av_packet_unref(&pkt); +#endif connection_->write_and_clear(encoded_frame); } From 1df1f0af2f41b25057d2a042feaba677c20c8a63 Mon Sep 17 00:00:00 2001 From: randoms Date: Fri, 12 Jan 2018 14:55:45 +0800 Subject: [PATCH 28/54] Set image streamer as inactive if topic is not available (#53) * Resolves #38 --- src/image_streamer.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/src/image_streamer.cpp b/src/image_streamer.cpp index a9a961b..bfa6861 100644 --- a/src/image_streamer.cpp +++ b/src/image_streamer.cpp @@ -24,6 +24,14 @@ ImageTransportImageStreamer::ImageTransportImageStreamer(const async_web_server_ void ImageTransportImageStreamer::start() { image_transport::TransportHints hints(default_transport_); + ros::master::V_TopicInfo available_topics; + ros::master::getTopics(available_topics); + inactive_ = true; + for (size_t it = 0; it Date: Sun, 28 Jan 2018 11:53:17 -0800 Subject: [PATCH 29/54] Add Indigo test matrix in travis configuration (#50) --- .travis.yml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.travis.yml b/.travis.yml index f68bf66..f2bff60 100644 --- a/.travis.yml +++ b/.travis.yml @@ -19,11 +19,14 @@ notifications: env: matrix: - ROS_DISTRO="kinetic" ROS_REPOSITORY_PATH=http://packages.ros.org/ros/ubuntu USE_DEB=true + - ROS_DISTRO="indigo" ROS_REPOSITORY_PATH=http://packages.ros.org/ros/ubuntu USE_DEB=true - ROS_DISTRO="kinetic" PRERELEASE=true PRERELEASE_DOWNSTREAM_DEPTH=0 + - ROS_DISTRO="indigo" PRERELEASE=true PRERELEASE_DOWNSTREAM_DEPTH=0 matrix: allow_failures: - env: ROS_DISTRO="kinetic" PRERELEASE=true PRERELEASE_DOWNSTREAM_DEPTH=0 + - env: ROS_DISTRO="indigo" PRERELEASE=true PRERELEASE_DOWNSTREAM_DEPTH=0 branches: only: From c3d27c1929645dacaa5a2dce5c41af15db09a7c6 Mon Sep 17 00:00:00 2001 From: randoms Date: Mon, 29 Jan 2018 04:57:04 +0800 Subject: [PATCH 30/54] Fix vp8 in kinetic add vp9 and h264 support (#52) * fix vp8 in kinetic * add h264 and vp9 support --- CMakeLists.txt | 2 + include/web_video_server/h264_streamer.h | 35 ++++++++++ include/web_video_server/libav_streamer.h | 4 ++ include/web_video_server/vp9_streamer.h | 33 ++++++++++ src/h264_streamer.cpp | 49 ++++++++++++++ src/libav_streamer.cpp | 79 +++++++++++++---------- src/vp9_streamer.cpp | 38 +++++++++++ src/web_video_server.cpp | 4 ++ 8 files changed, 210 insertions(+), 34 deletions(-) create mode 100644 include/web_video_server/h264_streamer.h create mode 100644 include/web_video_server/vp9_streamer.h create mode 100644 src/h264_streamer.cpp create mode 100644 src/vp9_streamer.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index c25f1ac..72f9f2f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -43,6 +43,8 @@ add_executable(${PROJECT_NAME} src/image_streamer.cpp src/libav_streamer.cpp src/vp8_streamer.cpp + src/h264_streamer.cpp + src/vp9_streamer.cpp src/multipart_stream.cpp src/ros_compressed_streamer.cpp src/jpeg_streamers.cpp) diff --git a/include/web_video_server/h264_streamer.h b/include/web_video_server/h264_streamer.h new file mode 100644 index 0000000..28c67f2 --- /dev/null +++ b/include/web_video_server/h264_streamer.h @@ -0,0 +1,35 @@ +#ifndef H264_STREAMERS_H_ +#define H264_STREAMERS_H_ + +#include +#include "web_video_server/libav_streamer.h" +#include "async_web_server_cpp/http_request.hpp" +#include "async_web_server_cpp/http_connection.hpp" + +namespace web_video_server +{ + +class H264Streamer : public LibavStreamer +{ +public: + H264Streamer(const async_web_server_cpp::HttpRequest& request, async_web_server_cpp::HttpConnectionPtr connection, + ros::NodeHandle& nh); + ~H264Streamer(); +protected: + virtual void initializeEncoder(); + std::string preset_; +}; + +class H264StreamerType : public LibavStreamerType +{ +public: + H264StreamerType(); + virtual boost::shared_ptr create_streamer(const async_web_server_cpp::HttpRequest& request, + async_web_server_cpp::HttpConnectionPtr connection, + ros::NodeHandle& nh); +}; + +} + +#endif + diff --git a/include/web_video_server/libav_streamer.h b/include/web_video_server/libav_streamer.h index 206d7ad..e8dc12a 100644 --- a/include/web_video_server/libav_streamer.h +++ b/include/web_video_server/libav_streamer.h @@ -40,6 +40,8 @@ class LibavStreamer : public ImageTransportImageStreamer AVCodecContext* codec_context_; AVStream* video_stream_; + AVDictionary* opt_; // container format options + private: AVFrame* frame_; struct SwsContext* sws_context_; @@ -53,6 +55,8 @@ class LibavStreamer : public ImageTransportImageStreamer int qmin_; int qmax_; int gop_; + + uint8_t* io_buffer_; // custom IO buffer }; class LibavStreamerType : public ImageStreamerType diff --git a/include/web_video_server/vp9_streamer.h b/include/web_video_server/vp9_streamer.h new file mode 100644 index 0000000..041f466 --- /dev/null +++ b/include/web_video_server/vp9_streamer.h @@ -0,0 +1,33 @@ +#ifndef VP9_STREAMERS_H_ +#define VP9_STREAMERS_H_ + +#include +#include "web_video_server/libav_streamer.h" +#include "async_web_server_cpp/http_request.hpp" +#include "async_web_server_cpp/http_connection.hpp" + +namespace web_video_server +{ + +class Vp9Streamer : public LibavStreamer +{ +public: + Vp9Streamer(const async_web_server_cpp::HttpRequest& request, async_web_server_cpp::HttpConnectionPtr connection, + ros::NodeHandle& nh); + ~Vp9Streamer(); +protected: + virtual void initializeEncoder(); +}; + +class Vp9StreamerType : public LibavStreamerType +{ +public: + Vp9StreamerType(); + virtual boost::shared_ptr create_streamer(const async_web_server_cpp::HttpRequest& request, + async_web_server_cpp::HttpConnectionPtr connection, + ros::NodeHandle& nh); +}; + +} + +#endif diff --git a/src/h264_streamer.cpp b/src/h264_streamer.cpp new file mode 100644 index 0000000..5477369 --- /dev/null +++ b/src/h264_streamer.cpp @@ -0,0 +1,49 @@ +#include "web_video_server/h264_streamer.h" + +namespace web_video_server +{ + +H264Streamer::H264Streamer(const async_web_server_cpp::HttpRequest& request, + async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh) : + LibavStreamer(request, connection, nh, "mp4", "libx264", "video/mp4") +{ + /* possible quality presets: + * ultrafast, superfast, veryfast, faster, fast, medium, slow, slower, veryslow, placebo + * no latency improvements observed with ultrafast instead of medium + */ + preset_ = request.get_query_param_value_or_default("preset", "ultrafast"); +} + +H264Streamer::~H264Streamer() +{ +} + +void H264Streamer::initializeEncoder() +{ + av_opt_set(codec_context_->priv_data, "preset", preset_.c_str(), 0); + av_opt_set(codec_context_->priv_data, "tune", "zerolatency", 0); + av_opt_set_int(codec_context_->priv_data, "crf", 20, 0); + av_opt_set_int(codec_context_->priv_data, "bufsize", 100, 0); + av_opt_set_int(codec_context_->priv_data, "keyint", 30, 0); + av_opt_set_int(codec_context_->priv_data, "g", 1, 0); + + // container format options + if (!strcmp(format_context_->oformat->name, "mp4")) { + // set up mp4 for streaming (instead of seekable file output) + av_dict_set(&opt_, "movflags", "+frag_keyframe+empty_moov+faststart", 0); + } +} + +H264StreamerType::H264StreamerType() : + LibavStreamerType("mp4", "libx264", "video/mp4") +{ +} + +boost::shared_ptr H264StreamerType::create_streamer(const async_web_server_cpp::HttpRequest& request, + async_web_server_cpp::HttpConnectionPtr connection, + ros::NodeHandle& nh) +{ + return boost::shared_ptr(new H264Streamer(request, connection, nh)); +} + +} diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index fc733b1..08980e4 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -50,7 +50,7 @@ LibavStreamer::LibavStreamer(const async_web_server_cpp::HttpRequest &request, const std::string &content_type) : ImageTransportImageStreamer(request, connection, nh), output_format_(0), format_context_(0), codec_(0), codec_context_(0), video_stream_( 0), frame_(0), sws_context_(0), first_image_timestamp_(0), format_name_( - format_name), codec_name_(codec_name), content_type_(content_type) + format_name), codec_name_(codec_name), content_type_(content_type), opt_(0), io_buffer_(0) { bitrate_ = request.get_query_param_value_or_default("bitrate", 100000); @@ -75,12 +75,26 @@ LibavStreamer::~LibavStreamer() av_frame_free(&frame_); #endif } + if (io_buffer_) + delete io_buffer_; + if (format_context_->pb) + av_free(format_context_->pb); if (format_context_) avformat_free_context(format_context_); if (sws_context_) sws_freeContext(sws_context_); } +// output callback for ffmpeg IO context +static int dispatch_output_packet(void* opaque, uint8_t* buffer, int buffer_size) +{ + async_web_server_cpp::HttpConnectionPtr connection = *((async_web_server_cpp::HttpConnectionPtr*) opaque); + std::vector encoded_frame; + encoded_frame.assign(buffer, buffer + buffer_size); + connection->write_and_clear(encoded_frame); + return 0; // TODO: can this fail? +} + void LibavStreamer::initialize(const cv::Mat &img) { // Load format @@ -102,6 +116,22 @@ void LibavStreamer::initialize(const cv::Mat &img) } format_context_->oformat = output_format_; + // Set up custom IO callback. + size_t io_buffer_size = 3 * 1024; // 3M seen elsewhere and adjudged good + io_buffer_ = new unsigned char[io_buffer_size]; + AVIOContext* io_ctx = avio_alloc_context(io_buffer_, io_buffer_size, AVIO_FLAG_WRITE, &connection_, NULL, dispatch_output_packet, NULL); + if (!io_ctx) + { + async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_, + connection_, + NULL, NULL); + throw std::runtime_error("Error setting up IO context"); + } + io_ctx->seekable = 0; // no seeking, it's a stream + format_context_->pb = io_ctx; + output_format_->flags |= AVFMT_FLAG_CUSTOM_IO; + output_format_->flags |= AVFMT_NOFILE; + // Load codec if (codec_name_.empty()) // use default codec if none specified codec_ = avcodec_find_encoder(output_format_->video_codec); @@ -127,7 +157,7 @@ void LibavStreamer::initialize(const cv::Mat &img) // Set options avcodec_get_context_defaults3(codec_context_, codec_); - codec_context_->codec_id = output_format_->video_codec; + codec_context_->codec_id = codec_->id; codec_context_->bit_rate = bitrate_; codec_context_->width = output_width_; @@ -171,7 +201,9 @@ void LibavStreamer::initialize(const cv::Mat &img) av_image_alloc(frame_->data, frame_->linesize, output_width_, output_height_, codec_context_->pix_fmt, 1); - + frame_->width = output_width_; + frame_->height = output_height_; + frame_->format = codec_context_->pix_fmt; output_format_->flags |= AVFMT_NOFILE; // Generate header @@ -182,24 +214,6 @@ void LibavStreamer::initialize(const cv::Mat &img) av_dict_set(&format_context_->metadata, "author", "ROS web_video_server", 0); av_dict_set(&format_context_->metadata, "title", topic_.c_str(), 0); - if (avio_open_dyn_buf(&format_context_->pb) >= 0) - { - if (avformat_write_header(format_context_, NULL) < 0) - { - async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_, - connection_, - NULL, NULL); - throw std::runtime_error("Error openning dynamic buffer"); - } - header_size = avio_close_dyn_buf(format_context_->pb, &header_raw_buffer); - - // copy header buffer to vector - header_buffer.resize(header_size); - memcpy(&header_buffer[0], header_raw_buffer, header_size); - - av_free(header_raw_buffer); - } - // Send response headers async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok).header("Connection", "close").header( "Server", "web_video_server").header("Cache-Control", @@ -208,7 +222,13 @@ void LibavStreamer::initialize(const cv::Mat &img) "Content-type", content_type_).header("Access-Control-Allow-Origin", "*").write(connection_); // Send video stream header - connection_->write_and_clear(header_buffer); + if (avformat_write_header(format_context_, &opt_) < 0) + { + async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_, + connection_, + NULL, NULL); + throw std::runtime_error("Error openning dynamic buffer"); + } } void LibavStreamer::initializeEncoder() @@ -235,7 +255,7 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time) #else AVFrame *raw_frame = av_frame_alloc(); av_image_fill_arrays(raw_frame->data, raw_frame->linesize, - img.data, input_coding_format, output_width_, output_height_, 0); + img.data, input_coding_format, output_width_, output_height_, 1); #endif @@ -310,18 +330,9 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time) pkt.stream_index = video_stream_->index; - if (avio_open_dyn_buf(&format_context_->pb) >= 0) + if (av_write_frame(format_context_, &pkt)) { - if (av_write_frame(format_context_, &pkt)) - { - throw std::runtime_error("Error when writing frame"); - } - size = avio_close_dyn_buf(format_context_->pb, &output_buf); - - encoded_frame.resize(size); - memcpy(&encoded_frame[0], output_buf, size); - - av_free(output_buf); + throw std::runtime_error("Error when writing frame"); } } else diff --git a/src/vp9_streamer.cpp b/src/vp9_streamer.cpp new file mode 100644 index 0000000..b487092 --- /dev/null +++ b/src/vp9_streamer.cpp @@ -0,0 +1,38 @@ +#include "web_video_server/vp9_streamer.h" + +namespace web_video_server +{ + +Vp9Streamer::Vp9Streamer(const async_web_server_cpp::HttpRequest& request, + async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh) : + LibavStreamer(request, connection, nh, "webm", "libvpx-vp9", "video/webm") +{ +} +Vp9Streamer::~Vp9Streamer() +{ +} + +void Vp9Streamer::initializeEncoder() +{ + + // codec options set up to provide somehow reasonable performance in cost of poor quality + // should be updated as soon as VP9 encoding matures + av_opt_set_int(codec_context_->priv_data, "pass", 1, 0); + av_opt_set_int(codec_context_->priv_data, "speed", 8, 0); + av_opt_set_int(codec_context_->priv_data, "cpu-used", 4, 0); // 8 is max + av_opt_set_int(codec_context_->priv_data, "crf", 20, 0); // 0..63 (higher is lower quality) +} + +Vp9StreamerType::Vp9StreamerType() : + LibavStreamerType("webm", "libvpx-vp9", "video/webm") +{ +} + +boost::shared_ptr Vp9StreamerType::create_streamer(const async_web_server_cpp::HttpRequest& request, + async_web_server_cpp::HttpConnectionPtr connection, + ros::NodeHandle& nh) +{ + return boost::shared_ptr(new Vp9Streamer(request, connection, nh)); +} + +} diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 504bb1f..75c81bf 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -9,6 +9,8 @@ #include "web_video_server/ros_compressed_streamer.h" #include "web_video_server/jpeg_streamers.h" #include "web_video_server/vp8_streamer.h" +#include "web_video_server/h264_streamer.h" +#include "web_video_server/vp9_streamer.h" #include "async_web_server_cpp/http_reply.hpp" namespace web_video_server @@ -57,6 +59,8 @@ WebVideoServer::WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh) stream_types_["mjpeg"] = boost::shared_ptr(new MjpegStreamerType()); stream_types_["ros_compressed"] = boost::shared_ptr(new RosCompressedStreamerType()); stream_types_["vp8"] = boost::shared_ptr(new Vp8StreamerType()); + stream_types_["h264"] = boost::shared_ptr(new H264StreamerType()); + stream_types_["vp9"] = boost::shared_ptr(new Vp9StreamerType()); handler_group_.addHandlerForPath("/", boost::bind(&WebVideoServer::handle_list_streams, this, _1, _2, _3, _4)); handler_group_.addHandlerForPath("/stream", boost::bind(&WebVideoServer::handle_stream, this, _1, _2, _3, _4)); From 34415273afaddc7f0d0ef5089b31f8da8c8f1646 Mon Sep 17 00:00:00 2001 From: James Bailey Date: Mon, 26 Feb 2018 10:53:22 -0700 Subject: [PATCH 31/54] Fix segfault in libav_streamer destructor (resolves #59) (#60) --- src/libav_streamer.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index 08980e4..8682667 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -77,10 +77,11 @@ LibavStreamer::~LibavStreamer() } if (io_buffer_) delete io_buffer_; - if (format_context_->pb) - av_free(format_context_->pb); - if (format_context_) + if (format_context_) { + if (format_context_->pb) + av_free(format_context_->pb); avformat_free_context(format_context_); + } if (sws_context_) sws_freeContext(sws_context_); } From 2dc73124921d8377599a152ad438b3052575f25d Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 29 Jun 2018 03:27:28 +0200 Subject: [PATCH 32/54] use SteadyTimer (if available) for cleaning up inactive streams (#63) * use SteadyTimer for cleaning up inactive streams so that cleanup works correctly even if system time changes SteadyTimer is available since roscpp 1.13.1 * possibility to use SteadyTimer on older ROS versions when SteadyTimer has been backported to those... --- include/web_video_server/web_video_server.h | 4 ++++ src/web_video_server.cpp | 4 ++++ 2 files changed, 8 insertions(+) diff --git a/include/web_video_server/web_video_server.h b/include/web_video_server/web_video_server.h index b2df65f..d5ed833 100644 --- a/include/web_video_server/web_video_server.h +++ b/include/web_video_server/web_video_server.h @@ -51,7 +51,11 @@ class WebVideoServer void cleanup_inactive_streams(); ros::NodeHandle nh_; +#if ROS_VERSION_MINIMUM(1, 13, 1) || defined USE_STEADY_TIMER + ros::SteadyTimer cleanup_timer_; +#else ros::Timer cleanup_timer_; +#endif int ros_threads_; int port_; std::string address_; diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 75c81bf..416a1a0 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -44,7 +44,11 @@ WebVideoServer::WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh) nh_(nh), handler_group_( async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::not_found)) { +#if ROS_VERSION_MINIMUM(1, 13, 1) || defined USE_STEADY_TIMER + cleanup_timer_ = nh.createSteadyTimer(ros::WallDuration(0.5), boost::bind(&WebVideoServer::cleanup_inactive_streams, this)); +#else cleanup_timer_ = nh.createTimer(ros::Duration(0.5), boost::bind(&WebVideoServer::cleanup_inactive_streams, this)); +#endif private_nh.param("port", port_, 8080); private_nh.param("verbose", __verbose, true); From d2886061b8ce078370023020eac32bee060facb0 Mon Sep 17 00:00:00 2001 From: schallerr <32197750+schallerr@users.noreply.github.com> Date: Sun, 1 Jul 2018 05:04:52 +0200 Subject: [PATCH 33/54] Avoid queuing of images on slow ethernet connection (#64) --- include/web_video_server/multipart_stream.h | 11 +++++- src/multipart_stream.cpp | 37 ++++++++++++++++----- 2 files changed, 38 insertions(+), 10 deletions(-) diff --git a/include/web_video_server/multipart_stream.h b/include/web_video_server/multipart_stream.h index 0d0838c..95826ff 100644 --- a/include/web_video_server/multipart_stream.h +++ b/include/web_video_server/multipart_stream.h @@ -4,12 +4,16 @@ #include #include +#include + namespace web_video_server { class MultipartStream { public: - MultipartStream(async_web_server_cpp::HttpConnectionPtr& connection, const std::string& boundry="boundarydonotcross"); + MultipartStream(async_web_server_cpp::HttpConnectionPtr& connection, + const std::string& boundry="boundarydonotcross", + std::size_t max_queue_size=1); void sendInitialHeader(); void sendPartHeader(const ros::Time &time, const std::string& type, size_t payload_size); @@ -19,8 +23,13 @@ class MultipartStream { async_web_server_cpp::HttpConnection::ResourcePtr resource); private: + bool isBusy(); + +private: + const std::size_t max_queue_size_; async_web_server_cpp::HttpConnectionPtr connection_; std::string boundry_; + std::queue > pending_footers_; }; } diff --git a/src/multipart_stream.cpp b/src/multipart_stream.cpp index d2dcc85..8f999c4 100644 --- a/src/multipart_stream.cpp +++ b/src/multipart_stream.cpp @@ -4,8 +4,12 @@ namespace web_video_server { -MultipartStream::MultipartStream(async_web_server_cpp::HttpConnectionPtr& connection, const std::string& boundry) - : connection_(connection), boundry_(boundry) {} +MultipartStream::MultipartStream( + async_web_server_cpp::HttpConnectionPtr& connection, + const std::string& boundry, + std::size_t max_queue_size) + : connection_(connection), boundry_(boundry), max_queue_size_(max_queue_size) +{} void MultipartStream::sendInitialHeader() { async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok).header("Connection", "close").header( @@ -29,23 +33,38 @@ void MultipartStream::sendPartHeader(const ros::Time &time, const std::string& t } void MultipartStream::sendPartFooter() { - connection_->write("\r\n--"+boundry_+"\r\n"); + boost::shared_ptr str(new std::string("\r\n--"+boundry_+"\r\n")); + connection_->write(boost::asio::buffer(*str), str); + if (max_queue_size_ > 0) pending_footers_.push(str); } void MultipartStream::sendPartAndClear(const ros::Time &time, const std::string& type, std::vector &data) { - sendPartHeader(time, type, data.size()); - connection_->write_and_clear(data); - sendPartFooter(); + if (!isBusy()) + { + sendPartHeader(time, type, data.size()); + connection_->write_and_clear(data); + sendPartFooter(); + } } void MultipartStream::sendPart(const ros::Time &time, const std::string& type, const boost::asio::const_buffer &buffer, async_web_server_cpp::HttpConnection::ResourcePtr resource) { - sendPartHeader(time, type, boost::asio::buffer_size(buffer)); - connection_->write(buffer, resource); - sendPartFooter(); + if (!isBusy()) + { + sendPartHeader(time, type, boost::asio::buffer_size(buffer)); + connection_->write(buffer, resource); + sendPartFooter(); + } } +bool MultipartStream::isBusy() { + while (!pending_footers_.empty() && pending_footers_.front().expired()) + { + pending_footers_.pop(); + } + return !(max_queue_size_ == 0 || pending_footers_.size() < max_queue_size_); +} } From 85230ea75628039f11fe02c97fa8db306eb1cd9b Mon Sep 17 00:00:00 2001 From: Jihoon Lee Date: Sun, 1 Jul 2018 12:06:31 +0900 Subject: [PATCH 34/54] update changelog --- CHANGELOG.rst | 27 +++++++++++++++++++++++++++ 1 file changed, 27 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 8dbe13d..36c411d 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package web_video_server ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Avoid queuing of images on slow ethernet connection (`#64 `_) +* use SteadyTimer (if available) for cleaning up inactive streams (`#63 `_) + * use SteadyTimer for cleaning up inactive streams + so that cleanup works correctly even if system time changes + SteadyTimer is available since roscpp 1.13.1 + * possibility to use SteadyTimer on older ROS versions + when SteadyTimer has been backported to those... +* Fix segfault in libav_streamer destructor (resolves `#59 `_) (`#60 `_) +* Fix vp8 in kinetic add vp9 and h264 support (`#52 `_) + * fix vp8 in kinetic + * add h264 and vp9 support +* Add Indigo test matrix in travis configuration (`#50 `_) +* Set image streamer as inactive if topic is not available (`#53 `_) + * Resolves `#38 `_ +* Fix Build for ubuntu 14.04 (`#48 `_) + * fix issue `#47 `_ + * fix double free +* Revert "use SteadyTimer for cleaning up inactive streams (`#45 `_)" (`#51 `_) + This reverts commit ae74f19ada22f288a7c7a99ada7a1b9b6037c7ce. +* use SteadyTimer for cleaning up inactive streams (`#45 `_) + so that cleanup works correctly even if system time changes +* Use trusty instead of xenial. See `travis-ci/travis-ci#7260 `_ (`#49 `_) + * Also see `RobotWebTools/rosbridge_suite#311 `_ +* Contributors: Felix Ruess, James Bailey, Jihoon Lee, randoms, schallerr + 0.0.7 (2017-11-20) ------------------ * Ffmpeg 3 (`#43 `_) From 0077643461baddd8a11813ec4c248c088dc4bd7c Mon Sep 17 00:00:00 2001 From: Jihoon Lee Date: Sun, 1 Jul 2018 12:07:00 +0900 Subject: [PATCH 35/54] 0.1.0 --- CHANGELOG.rst | 4 ++-- package.xml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 36c411d..c216909 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package web_video_server ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +0.1.0 (2018-07-01) +------------------ * Avoid queuing of images on slow ethernet connection (`#64 `_) * use SteadyTimer (if available) for cleaning up inactive streams (`#63 `_) * use SteadyTimer for cleaning up inactive streams diff --git a/package.xml b/package.xml index 58c7926..550f4c9 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ web_video_server - 0.0.7 + 0.1.0 HTTP Streaming of ROS Image Topics in Multiple Formats Russell Toris From b49f5c775187fca54099844f23bed3da45131709 Mon Sep 17 00:00:00 2001 From: Andreas Klintberg Date: Sun, 15 Jul 2018 18:22:30 -0700 Subject: [PATCH 36/54] fixed undeclared CODEC_FLAG_GLOBAL_HEADER (#65) --- src/libav_streamer.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index 8682667..7a4d67c 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -1,6 +1,10 @@ #include "web_video_server/libav_streamer.h" #include "async_web_server_cpp/http_reply.hpp" +/*https://stackoverflow.com/questions/46884682/error-in-building-opencv-with-ffmpeg*/ +#define AV_CODEC_FLAG_GLOBAL_HEADER (1 << 22) +#define CODEC_FLAG_GLOBAL_HEADER AV_CODEC_FLAG_GLOBAL_HEADER + namespace web_video_server { From 97ac8e4188ca6c8ffb575c83e64132caa2892b25 Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Sun, 19 Aug 2018 18:28:48 -0700 Subject: [PATCH 37/54] Pkg format 2 (#68) * use package format 2 * add missing dependency on sensor_msgs --- CMakeLists.txt | 2 +- package.xml | 16 +++++++++------- 2 files changed, 10 insertions(+), 8 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 72f9f2f..dd1b7d3 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -4,7 +4,7 @@ project(web_video_server) ## Find catkin macros and libraries ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## is used, also find other catkin packages -find_package(catkin REQUIRED COMPONENTS roscpp roslib cv_bridge image_transport async_web_server_cpp) +find_package(catkin REQUIRED COMPONENTS roscpp roslib cv_bridge image_transport async_web_server_cpp sensor_msgs) find_package(OpenCV REQUIRED) find_package(Boost REQUIRED COMPONENTS thread) diff --git a/package.xml b/package.xml index 550f4c9..a538c2e 100644 --- a/package.xml +++ b/package.xml @@ -1,5 +1,5 @@ - + web_video_server 0.1.0 HTTP Streaming of ROS Image Topics in Multiple Formats @@ -21,11 +21,13 @@ image_transport async_web_server_cpp ffmpeg + sensor_msgs - roscpp - roslib - cv_bridge - image_transport - async_web_server_cpp - ffmpeg + roscpp + roslib + cv_bridge + image_transport + async_web_server_cpp + ffmpeg + sensor_msgs From 7a45912535a42626b9fcac1c8119a0b6bae401f8 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 10 Oct 2018 09:13:26 +0200 Subject: [PATCH 38/54] fix SteadyTimer check for backported ROS versions (#71) i.e. on current kinetic --- include/web_video_server/web_video_server.h | 4 +++- src/web_video_server.cpp | 2 +- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/include/web_video_server/web_video_server.h b/include/web_video_server/web_video_server.h index d5ed833..182fe8c 100644 --- a/include/web_video_server/web_video_server.h +++ b/include/web_video_server/web_video_server.h @@ -9,6 +9,8 @@ #include "async_web_server_cpp/http_request.hpp" #include "async_web_server_cpp/http_connection.hpp" +#define ROS_HAS_STEADYTIMER (ROS_VERSION_MINIMUM(1, 13, 1) || ((ROS_VERSION_MINOR == 12) && (ROS_VERSION_PATCH >= 8))) + namespace web_video_server { @@ -51,7 +53,7 @@ class WebVideoServer void cleanup_inactive_streams(); ros::NodeHandle nh_; -#if ROS_VERSION_MINIMUM(1, 13, 1) || defined USE_STEADY_TIMER +#if ROS_HAS_STEADYTIMER || defined USE_STEADY_TIMER ros::SteadyTimer cleanup_timer_; #else ros::Timer cleanup_timer_; diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 416a1a0..75da9ed 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -44,7 +44,7 @@ WebVideoServer::WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh) nh_(nh), handler_group_( async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::not_found)) { -#if ROS_VERSION_MINIMUM(1, 13, 1) || defined USE_STEADY_TIMER +#if ROS_HAS_STEADYTIMER || defined USE_STEADY_TIMER cleanup_timer_ = nh.createSteadyTimer(ros::WallDuration(0.5), boost::bind(&WebVideoServer::cleanup_inactive_streams, this)); #else cleanup_timer_ = nh.createTimer(ros::Duration(0.5), boost::bind(&WebVideoServer::cleanup_inactive_streams, this)); From 4d58229ced2b503ecdf339cd45a3602f655cdb22 Mon Sep 17 00:00:00 2001 From: Viktor Kunovski Date: Fri, 19 Oct 2018 03:27:19 +0200 Subject: [PATCH 39/54] Add PngStreamer (#74) --- CMakeLists.txt | 4 +- include/web_video_server/png_streamers.h | 51 +++++++++++++++++ src/png_streamers.cpp | 73 ++++++++++++++++++++++++ src/web_video_server.cpp | 2 + 4 files changed, 129 insertions(+), 1 deletion(-) create mode 100644 include/web_video_server/png_streamers.h create mode 100644 src/png_streamers.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index dd1b7d3..dcb702f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -47,7 +47,9 @@ add_executable(${PROJECT_NAME} src/vp9_streamer.cpp src/multipart_stream.cpp src/ros_compressed_streamer.cpp - src/jpeg_streamers.cpp) + src/jpeg_streamers.cpp + src/png_streamers.cpp +) ## Specify libraries to link a library or executable target against target_link_libraries(${PROJECT_NAME} diff --git a/include/web_video_server/png_streamers.h b/include/web_video_server/png_streamers.h new file mode 100644 index 0000000..d4deb7c --- /dev/null +++ b/include/web_video_server/png_streamers.h @@ -0,0 +1,51 @@ +#ifndef PNG_STREAMERS_H_ +#define PNG_STREAMERS_H_ + +#include +#include "web_video_server/image_streamer.h" +#include "async_web_server_cpp/http_request.hpp" +#include "async_web_server_cpp/http_connection.hpp" +#include "web_video_server/multipart_stream.h" + +namespace web_video_server +{ + +class PngStreamer : public ImageTransportImageStreamer +{ +public: + PngStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, + ros::NodeHandle& nh); + +protected: + virtual void sendImage(const cv::Mat &, const ros::Time &time); + +private: + MultipartStream stream_; + int quality_; +}; + +class PngStreamerType : public ImageStreamerType +{ +public: + boost::shared_ptr create_streamer(const async_web_server_cpp::HttpRequest &request, + async_web_server_cpp::HttpConnectionPtr connection, + ros::NodeHandle& nh); + std::string create_viewer(const async_web_server_cpp::HttpRequest &request); +}; + +class PngSnapshotStreamer : public ImageTransportImageStreamer +{ +public: + PngSnapshotStreamer(const async_web_server_cpp::HttpRequest &request, + async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh); + +protected: + virtual void sendImage(const cv::Mat &, const ros::Time &time); + +private: + int quality_; +}; + +} + +#endif diff --git a/src/png_streamers.cpp b/src/png_streamers.cpp new file mode 100644 index 0000000..6e47357 --- /dev/null +++ b/src/png_streamers.cpp @@ -0,0 +1,73 @@ +#include "web_video_server/png_streamers.h" +#include "async_web_server_cpp/http_reply.hpp" + +namespace web_video_server +{ + +PngStreamer::PngStreamer(const async_web_server_cpp::HttpRequest &request, + async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh) : + ImageTransportImageStreamer(request, connection, nh), stream_(connection) +{ + quality_ = request.get_query_param_value_or_default("quality", 3); + stream_.sendInitialHeader(); +} + +void PngStreamer::sendImage(const cv::Mat &img, const ros::Time &time) +{ + std::vector encode_params; + encode_params.push_back(CV_IMWRITE_PNG_COMPRESSION); + encode_params.push_back(quality_); + + std::vector encoded_buffer; + cv::imencode(".png", img, encoded_buffer, encode_params); + + stream_.sendPartAndClear(time, "image/png", encoded_buffer); +} + +boost::shared_ptr PngStreamerType::create_streamer(const async_web_server_cpp::HttpRequest &request, + async_web_server_cpp::HttpConnectionPtr connection, + ros::NodeHandle& nh) +{ + return boost::shared_ptr(new PngStreamer(request, connection, nh)); +} + +std::string PngStreamerType::create_viewer(const async_web_server_cpp::HttpRequest &request) +{ + std::stringstream ss; + ss << ""; + return ss.str(); +} + +PngSnapshotStreamer::PngSnapshotStreamer(const async_web_server_cpp::HttpRequest &request, + async_web_server_cpp::HttpConnectionPtr connection, + ros::NodeHandle& nh) : + ImageTransportImageStreamer(request, connection, nh) +{ + quality_ = request.get_query_param_value_or_default("quality", 3); +} + +void PngSnapshotStreamer::sendImage(const cv::Mat &img, const ros::Time &time) +{ + std::vector encode_params; + encode_params.push_back(CV_IMWRITE_PNG_COMPRESSION); + encode_params.push_back(quality_); + + std::vector encoded_buffer; + cv::imencode(".png", img, encoded_buffer, encode_params); + + char stamp[20]; + sprintf(stamp, "%.06lf", time.toSec()); + async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok).header("Connection", "close").header( + "Server", "web_video_server").header("Cache-Control", + "no-cache, no-store, must-revalidate, pre-check=0, post-check=0, max-age=0").header( + "X-Timestamp", stamp).header("Pragma", "no-cache").header("Content-type", "image/png").header( + "Access-Control-Allow-Origin", "*").header("Content-Length", + boost::lexical_cast(encoded_buffer.size())).write( + connection_); + connection_->write_and_clear(encoded_buffer); + inactive_ = true; +} + +} diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 75da9ed..24aa48b 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -8,6 +8,7 @@ #include "web_video_server/web_video_server.h" #include "web_video_server/ros_compressed_streamer.h" #include "web_video_server/jpeg_streamers.h" +#include "web_video_server/png_streamers.h" #include "web_video_server/vp8_streamer.h" #include "web_video_server/h264_streamer.h" #include "web_video_server/vp9_streamer.h" @@ -61,6 +62,7 @@ WebVideoServer::WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh) private_nh.param("ros_threads", ros_threads_, 2); stream_types_["mjpeg"] = boost::shared_ptr(new MjpegStreamerType()); + stream_types_["png"] = boost::shared_ptr(new PngStreamerType()); stream_types_["ros_compressed"] = boost::shared_ptr(new RosCompressedStreamerType()); stream_types_["vp8"] = boost::shared_ptr(new Vp8StreamerType()); stream_types_["h264"] = boost::shared_ptr(new H264StreamerType()); From 243d0fbf77a5498bf1926bea73427acce4e7270d Mon Sep 17 00:00:00 2001 From: Kazuto Murase Date: Thu, 17 Jan 2019 15:29:44 +0900 Subject: [PATCH 40/54] lax rule for topic name (#77) --- src/image_streamer.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/image_streamer.cpp b/src/image_streamer.cpp index bfa6861..877e90d 100644 --- a/src/image_streamer.cpp +++ b/src/image_streamer.cpp @@ -28,7 +28,9 @@ void ImageTransportImageStreamer::start() ros::master::getTopics(available_topics); inactive_ = true; for (size_t it = 0; it Date: Mon, 28 Jan 2019 06:05:12 +0300 Subject: [PATCH 41/54] Add a workaround for MultipartStream constant busy state (#83) * Add a workaround for MultipartStream constant busy state * Remove C++11 features --- include/web_video_server/multipart_stream.h | 9 ++++++-- src/multipart_stream.cpp | 25 ++++++++++++++++----- 2 files changed, 26 insertions(+), 8 deletions(-) diff --git a/include/web_video_server/multipart_stream.h b/include/web_video_server/multipart_stream.h index 95826ff..476ee73 100644 --- a/include/web_video_server/multipart_stream.h +++ b/include/web_video_server/multipart_stream.h @@ -9,6 +9,11 @@ namespace web_video_server { +struct PendingFooter { + ros::Time timestamp; + boost::weak_ptr contents; +}; + class MultipartStream { public: MultipartStream(async_web_server_cpp::HttpConnectionPtr& connection, @@ -17,7 +22,7 @@ class MultipartStream { void sendInitialHeader(); void sendPartHeader(const ros::Time &time, const std::string& type, size_t payload_size); - void sendPartFooter(); + void sendPartFooter(const ros::Time &time); void sendPartAndClear(const ros::Time &time, const std::string& type, std::vector &data); void sendPart(const ros::Time &time, const std::string& type, const boost::asio::const_buffer &buffer, async_web_server_cpp::HttpConnection::ResourcePtr resource); @@ -29,7 +34,7 @@ class MultipartStream { const std::size_t max_queue_size_; async_web_server_cpp::HttpConnectionPtr connection_; std::string boundry_; - std::queue > pending_footers_; + std::queue pending_footers_; }; } diff --git a/src/multipart_stream.cpp b/src/multipart_stream.cpp index 8f999c4..5ce235d 100644 --- a/src/multipart_stream.cpp +++ b/src/multipart_stream.cpp @@ -32,10 +32,13 @@ void MultipartStream::sendPartHeader(const ros::Time &time, const std::string& t connection_->write(async_web_server_cpp::HttpReply::to_buffers(*headers), headers); } -void MultipartStream::sendPartFooter() { +void MultipartStream::sendPartFooter(const ros::Time &time) { boost::shared_ptr str(new std::string("\r\n--"+boundry_+"\r\n")); + PendingFooter pf; + pf.timestamp = time; + pf.contents = str; connection_->write(boost::asio::buffer(*str), str); - if (max_queue_size_ > 0) pending_footers_.push(str); + if (max_queue_size_ > 0) pending_footers_.push(pf); } void MultipartStream::sendPartAndClear(const ros::Time &time, const std::string& type, @@ -44,7 +47,7 @@ void MultipartStream::sendPartAndClear(const ros::Time &time, const std::string& { sendPartHeader(time, type, data.size()); connection_->write_and_clear(data); - sendPartFooter(); + sendPartFooter(time); } } @@ -55,14 +58,24 @@ void MultipartStream::sendPart(const ros::Time &time, const std::string& type, { sendPartHeader(time, type, boost::asio::buffer_size(buffer)); connection_->write(buffer, resource); - sendPartFooter(); + sendPartFooter(time); } } bool MultipartStream::isBusy() { - while (!pending_footers_.empty() && pending_footers_.front().expired()) + ros::Time currentTime = ros::Time::now(); + while (!pending_footers_.empty()) { - pending_footers_.pop(); + if (pending_footers_.front().contents.expired()) { + pending_footers_.pop(); + } else { + ros::Time footerTime = pending_footers_.front().timestamp; + if ((currentTime - footerTime).toSec() > 0.5) { + pending_footers_.pop(); + } else { + break; + } + } } return !(max_queue_size_ == 0 || pending_footers_.size() < max_queue_size_); } From 5a44cddc7c840f21e53bf40fa23bd13751502878 Mon Sep 17 00:00:00 2001 From: sfalexrog Date: Wed, 30 Jan 2019 12:42:56 +0300 Subject: [PATCH 42/54] Add "default_stream_type" parameter (#84) This allows users to specify default stream type in their .launch files. Using a "ros_compressed" stream type sometimes results in a much lower resource consumption, and having it set as a default is much nicer for end users. --- src/web_video_server.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 24aa48b..dc7f640 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -19,6 +19,8 @@ namespace web_video_server static bool __verbose; +static std::string __default_stream_type; + static bool ros_connection_logger(async_web_server_cpp::HttpServerRequestHandler forward, const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, const char* begin, @@ -61,6 +63,8 @@ WebVideoServer::WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh) private_nh.param("ros_threads", ros_threads_, 2); + private_nh.param("default_stream_type", __default_stream_type, "mjpeg"); + stream_types_["mjpeg"] = boost::shared_ptr(new MjpegStreamerType()); stream_types_["png"] = boost::shared_ptr(new PngStreamerType()); stream_types_["ros_compressed"] = boost::shared_ptr(new RosCompressedStreamerType()); @@ -124,7 +128,7 @@ bool WebVideoServer::handle_stream(const async_web_server_cpp::HttpRequest &requ async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end) { - std::string type = request.get_query_param_value_or_default("type", "mjpeg"); + std::string type = request.get_query_param_value_or_default("type", __default_stream_type); if (stream_types_.find(type) != stream_types_.end()) { boost::shared_ptr streamer = stream_types_[type]->create_streamer(request, connection, nh_); From 6a54d8ab64c05dfbe51b9aec64126947d22a59b6 Mon Sep 17 00:00:00 2001 From: Jihoon Lee Date: Wed, 30 Jan 2019 18:44:49 +0900 Subject: [PATCH 43/54] update changelog --- CHANGELOG.rst | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index c216909..131c6f6 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,24 @@ Changelog for package web_video_server ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Add "default_stream_type" parameter (`#84 `_) + This allows users to specify default stream type in their .launch files. Using a "ros_compressed" stream type sometimes + results in a much lower resource consumption, and having it set as a default is much nicer for end users. +* Add a workaround for MultipartStream constant busy state (`#83 `_) + * Add a workaround for MultipartStream constant busy state + * Remove C++11 features +* lax rule for topic name (`#77 `_) +* Add PngStreamer (`#74 `_) +* fix SteadyTimer check for backported ROS versions (`#71 `_) + i.e. on current kinetic +* Pkg format 2 (`#68 `_) + * use package format 2 + * add missing dependency on sensor_msgs +* fixed undeclared CODEC_FLAG_GLOBAL_HEADER (`#65 `_) +* Contributors: Andreas Klintberg, Dirk Thomas, Felix Ruess, Kazuto Murase, Viktor Kunovski, sfalexrog + 0.1.0 (2018-07-01) ------------------ * Avoid queuing of images on slow ethernet connection (`#64 `_) From 224f1abf8b28c3c3a4cc7add2d920e9559b044f9 Mon Sep 17 00:00:00 2001 From: Jihoon Lee Date: Wed, 30 Jan 2019 18:44:59 +0900 Subject: [PATCH 44/54] 0.2.0 --- CHANGELOG.rst | 4 ++-- package.xml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 131c6f6..ab1ac99 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package web_video_server ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +0.2.0 (2019-01-30) +------------------ * Add "default_stream_type" parameter (`#84 `_) This allows users to specify default stream type in their .launch files. Using a "ros_compressed" stream type sometimes results in a much lower resource consumption, and having it set as a default is much nicer for end users. diff --git a/package.xml b/package.xml index a538c2e..882cda8 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ web_video_server - 0.1.0 + 0.2.0 HTTP Streaming of ROS Image Topics in Multiple Formats Russell Toris From fa6cc2537ab280668f87aa15636dd7c63d52af38 Mon Sep 17 00:00:00 2001 From: sfalexrog Date: Wed, 17 Apr 2019 04:47:47 +0300 Subject: [PATCH 45/54] Fall back to mjpeg if ros_compressed is unavailable (#87) --- src/web_video_server.cpp | 46 +++++++++++++++++++++++++++++++++++++++- 1 file changed, 45 insertions(+), 1 deletion(-) diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index dc7f640..8a224a6 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -131,6 +131,28 @@ bool WebVideoServer::handle_stream(const async_web_server_cpp::HttpRequest &requ std::string type = request.get_query_param_value_or_default("type", __default_stream_type); if (stream_types_.find(type) != stream_types_.end()) { + std::string topic = request.get_query_param_value_or_default("topic", ""); + // Fallback for topics without corresponding compressed topics + if (type == std::string("ros_compressed")) + { + std::string compressed_topic_name = topic + "/compressed"; + ros::master::V_TopicInfo topics; + ros::master::getTopics(topics); + bool did_find_compressed_topic = false; + for(ros::master::V_TopicInfo::iterator it = topics.begin(); it != topics.end(); ++it) + { + if (it->name == compressed_topic_name) + { + did_find_compressed_topic = true; + break; + } + } + if (!did_find_compressed_topic) + { + ROS_WARN_STREAM("Could not find compressed image topic for " << topic << ", falling back to mjpeg"); + type = "mjpeg"; + } + } boost::shared_ptr streamer = stream_types_[type]->create_streamer(request, connection, nh_); streamer->start(); boost::mutex::scoped_lock lock(subscriber_mutex_); @@ -160,10 +182,32 @@ bool WebVideoServer::handle_stream_viewer(const async_web_server_cpp::HttpReques async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end) { - std::string type = request.get_query_param_value_or_default("type", "mjpeg"); + std::string type = request.get_query_param_value_or_default("type", __default_stream_type); if (stream_types_.find(type) != stream_types_.end()) { std::string topic = request.get_query_param_value_or_default("topic", ""); + // Fallback for topics without corresponding compressed topics + if (type == std::string("ros_compressed")) + { + + std::string compressed_topic_name = topic + "/compressed"; + ros::master::V_TopicInfo topics; + ros::master::getTopics(topics); + bool did_find_compressed_topic = false; + for(ros::master::V_TopicInfo::iterator it = topics.begin(); it != topics.end(); ++it) + { + if (it->name == compressed_topic_name) + { + did_find_compressed_topic = true; + break; + } + } + if (!did_find_compressed_topic) + { + ROS_WARN_STREAM("Could not find compressed image topic for " << topic << ", falling back to mjpeg"); + type = "mjpeg"; + } + } async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok).header("Connection", "close").header( "Server", "web_video_server").header("Content-type", "text/html;").write(connection); From ef37d0bbb0ff7bc7024065f5e6dd96bb64b6b890 Mon Sep 17 00:00:00 2001 From: Jihoon Lee Date: Tue, 7 May 2019 17:35:29 +0700 Subject: [PATCH 46/54] Update travis config (#89) --- .travis.yml | 19 +++++++++---------- 1 file changed, 9 insertions(+), 10 deletions(-) diff --git a/.travis.yml b/.travis.yml index f2bff60..82adc91 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,8 +1,6 @@ # This config file for Travis CI utilizes ros-industrial/industrial_ci package. # For more info for the package, see https://github.com/ros-industrial/industrial_ci/blob/master/README.rst -dist: trusty -sudo: required services: - docker language: generic @@ -18,15 +16,16 @@ notifications: env: matrix: - - ROS_DISTRO="kinetic" ROS_REPOSITORY_PATH=http://packages.ros.org/ros/ubuntu USE_DEB=true - - ROS_DISTRO="indigo" ROS_REPOSITORY_PATH=http://packages.ros.org/ros/ubuntu USE_DEB=true - - ROS_DISTRO="kinetic" PRERELEASE=true PRERELEASE_DOWNSTREAM_DEPTH=0 - - ROS_DISTRO="indigo" PRERELEASE=true PRERELEASE_DOWNSTREAM_DEPTH=0 + - ROS_DISTRO=kinetic ROS_REPO=ros-shadow-fixed UPSTREAM_WORKSPACE=debian OS_NAME=ubuntu OS_CODE_NAME=xenial + - ROS_DISTRO=melodic ROS_REPO=ros-shadow-fixed UPSTREAM_WORKSPACE=debian OS_NAME=ubuntu OS_CODE_NAME=bionic + - ROS_DISTRO=melodic ROS_REPO=ros-shadow-fixed UPSTREAM_WORKSPACE=debian OS_NAME=debian OS_CODE_NAME=stretch matrix: allow_failures: - - env: ROS_DISTRO="kinetic" PRERELEASE=true PRERELEASE_DOWNSTREAM_DEPTH=0 - - env: ROS_DISTRO="indigo" PRERELEASE=true PRERELEASE_DOWNSTREAM_DEPTH=0 + - env: ROS_DISTRO=melodic ROS_REPO=ros-shadow-fixed UPSTREAM_WORKSPACE=debian OS_NAME=debian OS_CODE_NAME=stretch + + #- env: ROS_DISTRO="kinetic" PRERELEASE=true PRERELEASE_DOWNSTREAM_DEPTH=0 + #- env: ROS_DISTRO="melodic" PRERELEASE=true PRERELEASE_DOWNSTREAM_DEPTH=0 branches: only: @@ -34,7 +33,7 @@ branches: - develop install: - - git clone https://github.com/ros-industrial/industrial_ci.git .ci_config + - git clone --quiet --depth 1 https://github.com/ros-industrial/industrial_ci.git .industrial_ci script: - - source .ci_config/travis.sh + - source .industrial_ci/travis.sh From 8e828bb5011f6f488950b6865effca7f058c4aae Mon Sep 17 00:00:00 2001 From: Viktor Kunovski Date: Fri, 10 May 2019 14:09:59 +0200 Subject: [PATCH 47/54] Restream buffered frames with minimum publish rate (#88) * Restream buffered frames with minimum publish rate * Implement restreaming for ros_compressed_streamer --- include/web_video_server/image_streamer.h | 15 +++++- include/web_video_server/jpeg_streamers.h | 4 +- include/web_video_server/png_streamers.h | 4 +- .../ros_compressed_streamer.h | 10 +++- include/web_video_server/web_video_server.h | 2 + src/image_streamer.cpp | 46 ++++++++++++++++++- src/jpeg_streamers.cpp | 32 ++++++++++--- src/png_streamers.cpp | 32 ++++++++++--- src/ros_compressed_streamer.cpp | 30 +++++++++++- src/web_video_server.cpp | 32 +++++++++++-- 10 files changed, 179 insertions(+), 28 deletions(-) diff --git a/include/web_video_server/image_streamer.h b/include/web_video_server/image_streamer.h index 80aa980..b5caba2 100644 --- a/include/web_video_server/image_streamer.h +++ b/include/web_video_server/image_streamer.h @@ -18,6 +18,7 @@ class ImageStreamer ros::NodeHandle& nh); virtual void start() = 0; + virtual ~ImageStreamer(); bool isInactive() { @@ -25,6 +26,11 @@ class ImageStreamer } ; + /** + * Restreams the last received image frame if older than max_age. + */ + virtual void restreamFrame(double max_age) = 0; + std::string getTopic() { return topic_; @@ -45,12 +51,12 @@ class ImageTransportImageStreamer : public ImageStreamer public: ImageTransportImageStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh); - + virtual ~ImageTransportImageStreamer(); virtual void start(); protected: virtual void sendImage(const cv::Mat &, const ros::Time &time) = 0; - + virtual void restreamFrame(double max_age); virtual void initialize(const cv::Mat &); image_transport::Subscriber image_sub_; @@ -58,6 +64,11 @@ class ImageTransportImageStreamer : public ImageStreamer int output_height_; bool invert_; std::string default_transport_; + + ros::Time last_frame; + cv::Mat output_size_image; + boost::mutex send_mutex_; + private: image_transport::ImageTransport it_; bool initialized_; diff --git a/include/web_video_server/jpeg_streamers.h b/include/web_video_server/jpeg_streamers.h index 6f17e48..3a7f69f 100644 --- a/include/web_video_server/jpeg_streamers.h +++ b/include/web_video_server/jpeg_streamers.h @@ -15,7 +15,7 @@ class MjpegStreamer : public ImageTransportImageStreamer public: MjpegStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh); - + ~MjpegStreamer(); protected: virtual void sendImage(const cv::Mat &, const ros::Time &time); @@ -38,7 +38,7 @@ class JpegSnapshotStreamer : public ImageTransportImageStreamer public: JpegSnapshotStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh); - + ~JpegSnapshotStreamer(); protected: virtual void sendImage(const cv::Mat &, const ros::Time &time); diff --git a/include/web_video_server/png_streamers.h b/include/web_video_server/png_streamers.h index d4deb7c..2207894 100644 --- a/include/web_video_server/png_streamers.h +++ b/include/web_video_server/png_streamers.h @@ -15,7 +15,7 @@ class PngStreamer : public ImageTransportImageStreamer public: PngStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh); - + ~PngStreamer(); protected: virtual void sendImage(const cv::Mat &, const ros::Time &time); @@ -38,7 +38,7 @@ class PngSnapshotStreamer : public ImageTransportImageStreamer public: PngSnapshotStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh); - + ~PngSnapshotStreamer(); protected: virtual void sendImage(const cv::Mat &, const ros::Time &time); diff --git a/include/web_video_server/ros_compressed_streamer.h b/include/web_video_server/ros_compressed_streamer.h index 72165c2..7e8af37 100644 --- a/include/web_video_server/ros_compressed_streamer.h +++ b/include/web_video_server/ros_compressed_streamer.h @@ -15,13 +15,21 @@ class RosCompressedStreamer : public ImageStreamer public: RosCompressedStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh); + ~RosCompressedStreamer(); + virtual void start(); + virtual void restreamFrame(double max_age); + +protected: + virtual void sendImage(const sensor_msgs::CompressedImageConstPtr &msg, const ros::Time &time); private: void imageCallback(const sensor_msgs::CompressedImageConstPtr &msg); - MultipartStream stream_; ros::Subscriber image_sub_; + ros::Time last_frame; + sensor_msgs::CompressedImageConstPtr last_msg; + boost::mutex send_mutex_; }; class RosCompressedStreamerType : public ImageStreamerType diff --git a/include/web_video_server/web_video_server.h b/include/web_video_server/web_video_server.h index 182fe8c..e4e0d73 100644 --- a/include/web_video_server/web_video_server.h +++ b/include/web_video_server/web_video_server.h @@ -50,6 +50,7 @@ class WebVideoServer async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end); private: + void restreamFrames(double max_age); void cleanup_inactive_streams(); ros::NodeHandle nh_; @@ -59,6 +60,7 @@ class WebVideoServer ros::Timer cleanup_timer_; #endif int ros_threads_; + double publish_rate_; int port_; std::string address_; boost::shared_ptr server_; diff --git a/src/image_streamer.cpp b/src/image_streamer.cpp index 877e90d..68736ac 100644 --- a/src/image_streamer.cpp +++ b/src/image_streamer.cpp @@ -1,5 +1,6 @@ #include "web_video_server/image_streamer.h" #include +#include namespace web_video_server { @@ -11,6 +12,10 @@ ImageStreamer::ImageStreamer(const async_web_server_cpp::HttpRequest &request, topic_ = request.get_query_param_value_or_default("topic", ""); } +ImageStreamer::~ImageStreamer() +{ +} + ImageTransportImageStreamer::ImageTransportImageStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh) : ImageStreamer(request, connection, nh), it_(nh), initialized_(false) @@ -21,6 +26,10 @@ ImageTransportImageStreamer::ImageTransportImageStreamer(const async_web_server_ default_transport_ = request.get_query_param_value_or_default("default_transport", "raw"); } +ImageTransportImageStreamer::~ImageTransportImageStreamer() +{ +} + void ImageTransportImageStreamer::start() { image_transport::TransportHints hints(default_transport_); @@ -41,6 +50,37 @@ void ImageTransportImageStreamer::initialize(const cv::Mat &) { } +void ImageTransportImageStreamer::restreamFrame(double max_age) +{ + if (inactive_ || !initialized_ ) + return; + try { + if ( last_frame + ros::Duration(max_age) < ros::Time::now() ) { + boost::mutex::scoped_lock lock(send_mutex_); + sendImage(output_size_image, ros::Time::now() ); // don't update last_frame, it may remain an old value. + } + } + catch (boost::system::system_error &e) + { + // happens when client disconnects + ROS_DEBUG("system_error exception: %s", e.what()); + inactive_ = true; + return; + } + catch (std::exception &e) + { + ROS_ERROR_THROTTLE(30, "exception: %s", e.what()); + inactive_ = true; + return; + } + catch (...) + { + ROS_ERROR_THROTTLE(30, "exception"); + inactive_ = true; + return; + } +} + void ImageTransportImageStreamer::imageCallback(const sensor_msgs::ImageConstPtr &msg) { if (inactive_) @@ -84,7 +124,7 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::ImageConstPtr cv::flip(img, img, true); } - cv::Mat output_size_image; + boost::mutex::scoped_lock lock(send_mutex_); // protects output_size_image if (output_width_ != input_width || output_height_ != input_height) { cv::Mat img_resized; @@ -102,7 +142,9 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::ImageConstPtr initialize(output_size_image); initialized_ = true; } - sendImage(output_size_image, msg->header.stamp); + + last_frame = ros::Time::now(); + sendImage(output_size_image, last_frame ); } catch (cv_bridge::Exception &e) diff --git a/src/jpeg_streamers.cpp b/src/jpeg_streamers.cpp index 1f5d6c9..121730d 100644 --- a/src/jpeg_streamers.cpp +++ b/src/jpeg_streamers.cpp @@ -12,6 +12,12 @@ MjpegStreamer::MjpegStreamer(const async_web_server_cpp::HttpRequest &request, stream_.sendInitialHeader(); } +MjpegStreamer::~MjpegStreamer() +{ + this->inactive_ = true; + boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. +} + void MjpegStreamer::sendImage(const cv::Mat &img, const ros::Time &time) { std::vector encode_params; @@ -48,6 +54,12 @@ JpegSnapshotStreamer::JpegSnapshotStreamer(const async_web_server_cpp::HttpReque quality_ = request.get_query_param_value_or_default("quality", 95); } +JpegSnapshotStreamer::~JpegSnapshotStreamer() +{ + this->inactive_ = true; + boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. +} + void JpegSnapshotStreamer::sendImage(const cv::Mat &img, const ros::Time &time) { std::vector encode_params; @@ -59,13 +71,19 @@ void JpegSnapshotStreamer::sendImage(const cv::Mat &img, const ros::Time &time) char stamp[20]; sprintf(stamp, "%.06lf", time.toSec()); - async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok).header("Connection", "close").header( - "Server", "web_video_server").header("Cache-Control", - "no-cache, no-store, must-revalidate, pre-check=0, post-check=0, max-age=0").header( - "X-Timestamp", stamp).header("Pragma", "no-cache").header("Content-type", "image/jpeg").header( - "Access-Control-Allow-Origin", "*").header("Content-Length", - boost::lexical_cast(encoded_buffer.size())).write( - connection_); + async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok) + .header("Connection", "close") + .header("Server", "web_video_server") + .header("Cache-Control", + "no-cache, no-store, must-revalidate, pre-check=0, post-check=0, " + "max-age=0") + .header("X-Timestamp", stamp) + .header("Pragma", "no-cache") + .header("Content-type", "image/jpeg") + .header("Access-Control-Allow-Origin", "*") + .header("Content-Length", + boost::lexical_cast(encoded_buffer.size())) + .write(connection_); connection_->write_and_clear(encoded_buffer); inactive_ = true; } diff --git a/src/png_streamers.cpp b/src/png_streamers.cpp index 6e47357..629adf0 100644 --- a/src/png_streamers.cpp +++ b/src/png_streamers.cpp @@ -12,6 +12,12 @@ PngStreamer::PngStreamer(const async_web_server_cpp::HttpRequest &request, stream_.sendInitialHeader(); } +PngStreamer::~PngStreamer() +{ + this->inactive_ = true; + boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. +} + void PngStreamer::sendImage(const cv::Mat &img, const ros::Time &time) { std::vector encode_params; @@ -48,6 +54,12 @@ PngSnapshotStreamer::PngSnapshotStreamer(const async_web_server_cpp::HttpRequest quality_ = request.get_query_param_value_or_default("quality", 3); } +PngSnapshotStreamer::~PngSnapshotStreamer() +{ + this->inactive_ = true; + boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. +} + void PngSnapshotStreamer::sendImage(const cv::Mat &img, const ros::Time &time) { std::vector encode_params; @@ -59,13 +71,19 @@ void PngSnapshotStreamer::sendImage(const cv::Mat &img, const ros::Time &time) char stamp[20]; sprintf(stamp, "%.06lf", time.toSec()); - async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok).header("Connection", "close").header( - "Server", "web_video_server").header("Cache-Control", - "no-cache, no-store, must-revalidate, pre-check=0, post-check=0, max-age=0").header( - "X-Timestamp", stamp).header("Pragma", "no-cache").header("Content-type", "image/png").header( - "Access-Control-Allow-Origin", "*").header("Content-Length", - boost::lexical_cast(encoded_buffer.size())).write( - connection_); + async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok) + .header("Connection", "close") + .header("Server", "web_video_server") + .header("Cache-Control", + "no-cache, no-store, must-revalidate, pre-check=0, post-check=0, " + "max-age=0") + .header("X-Timestamp", stamp) + .header("Pragma", "no-cache") + .header("Content-type", "image/png") + .header("Access-Control-Allow-Origin", "*") + .header("Content-Length", + boost::lexical_cast(encoded_buffer.size())) + .write(connection_); connection_->write_and_clear(encoded_buffer); inactive_ = true; } diff --git a/src/ros_compressed_streamer.cpp b/src/ros_compressed_streamer.cpp index 4fbcb17..eedcf0d 100644 --- a/src/ros_compressed_streamer.cpp +++ b/src/ros_compressed_streamer.cpp @@ -10,12 +10,30 @@ RosCompressedStreamer::RosCompressedStreamer(const async_web_server_cpp::HttpReq stream_.sendInitialHeader(); } +RosCompressedStreamer::~RosCompressedStreamer() +{ + this->inactive_ = true; + boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. +} + void RosCompressedStreamer::start() { std::string compressed_topic = topic_ + "/compressed"; image_sub_ = nh_.subscribe(compressed_topic, 1, &RosCompressedStreamer::imageCallback, this); } -void RosCompressedStreamer::imageCallback(const sensor_msgs::CompressedImageConstPtr &msg) { +void RosCompressedStreamer::restreamFrame(double max_age) +{ + if (inactive_ || (last_msg == 0)) + return; + + if ( last_frame + ros::Duration(max_age) < ros::Time::now() ) { + boost::mutex::scoped_lock lock(send_mutex_); + sendImage(last_msg, ros::Time::now() ); // don't update last_frame, it may remain an old value. + } +} + +void RosCompressedStreamer::sendImage(const sensor_msgs::CompressedImageConstPtr &msg, + const ros::Time &time) { try { std::string content_type; if(msg->format.find("jpeg") != std::string::npos) { @@ -29,7 +47,7 @@ void RosCompressedStreamer::imageCallback(const sensor_msgs::CompressedImageCons return; } - stream_.sendPart(msg->header.stamp, content_type, boost::asio::buffer(msg->data), msg); + stream_.sendPart(time, content_type, boost::asio::buffer(msg->data), msg); } catch (boost::system::system_error &e) { @@ -53,6 +71,14 @@ void RosCompressedStreamer::imageCallback(const sensor_msgs::CompressedImageCons } +void RosCompressedStreamer::imageCallback(const sensor_msgs::CompressedImageConstPtr &msg) { + boost::mutex::scoped_lock lock(send_mutex_); // protects last_msg and last_frame + last_msg = msg; + last_frame = ros::Time(msg->header.stamp.sec, msg->header.stamp.nsec); + sendImage(last_msg, last_frame); +} + + boost::shared_ptr RosCompressedStreamerType::create_streamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh) diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 8a224a6..a1e76e3 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -62,6 +62,7 @@ WebVideoServer::WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh) private_nh.param("server_threads", server_threads, 1); private_nh.param("ros_threads", ros_threads_, 2); + private_nh.param("publish_rate", publish_rate_, -1.0); private_nh.param("default_stream_type", __default_stream_type, "mjpeg"); @@ -100,11 +101,36 @@ void WebVideoServer::spin() { server_->run(); ROS_INFO_STREAM("Waiting For connections on " << address_ << ":" << port_); - ros::MultiThreadedSpinner spinner(ros_threads_); - spinner.spin(); + + ros::AsyncSpinner spinner(ros_threads_); + spinner.start(); + + if ( publish_rate_ > 0 ) { + ros::Rate r(publish_rate_); + + while( ros::ok() ) { + this->restreamFrames( 1.0 / publish_rate_ ); + r.sleep(); + } + } else { + ros::waitForShutdown(); + } + server_->stop(); } +void WebVideoServer::restreamFrames( double max_age ) +{ + boost::mutex::scoped_lock lock(subscriber_mutex_); + + typedef std::vector >::iterator itr_type; + + for (itr_type itr = image_subscribers_.begin(); itr < image_subscribers_.end(); ++itr) + { + (*itr)->restreamFrame( max_age ); + } +} + void WebVideoServer::cleanup_inactive_streams() { boost::mutex::scoped_lock lock(subscriber_mutex_, boost::try_to_lock); @@ -189,7 +215,7 @@ bool WebVideoServer::handle_stream_viewer(const async_web_server_cpp::HttpReques // Fallback for topics without corresponding compressed topics if (type == std::string("ros_compressed")) { - + std::string compressed_topic_name = topic + "/compressed"; ros::master::V_TopicInfo topics; ros::master::getTopics(topics); From 0697d269e4662ce368e2e357243422b416773e1b Mon Sep 17 00:00:00 2001 From: Jihoon Lee Date: Wed, 5 Jun 2019 16:42:02 +0900 Subject: [PATCH 48/54] update changelog --- CHANGELOG.rst | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index ab1ac99..3df0535 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package web_video_server ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Restream buffered frames with minimum publish rate (`#88 `_) + * Restream buffered frames with minimum publish rate + * Implement restreaming for ros_compressed_streamer +* Update travis config (`#89 `_) +* Fall back to mjpeg if ros_compressed is unavailable (`#87 `_) +* Contributors: Jihoon Lee, Viktor Kunovski, sfalexrog + 0.2.0 (2019-01-30) ------------------ * Add "default_stream_type" parameter (`#84 `_) From 4ab9568b34a66b9517b58f8161a63fdee8bf1677 Mon Sep 17 00:00:00 2001 From: Jihoon Lee Date: Wed, 5 Jun 2019 16:42:14 +0900 Subject: [PATCH 49/54] 0.2.1 --- CHANGELOG.rst | 4 ++-- package.xml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 3df0535..fdb6121 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package web_video_server ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +0.2.1 (2019-06-05) +------------------ * Restream buffered frames with minimum publish rate (`#88 `_) * Restream buffered frames with minimum publish rate * Implement restreaming for ros_compressed_streamer diff --git a/package.xml b/package.xml index 882cda8..6c2a71c 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ web_video_server - 0.2.0 + 0.2.1 HTTP Streaming of ROS Image Topics in Multiple Formats Russell Toris From b82ea3df4f3ebca36a02cbf427e2fae846d2c6ae Mon Sep 17 00:00:00 2001 From: okapi1125 <37995620+oka1125@users.noreply.github.com> Date: Mon, 30 Sep 2019 15:38:28 +0900 Subject: [PATCH 50/54] fix multipart_stream.cpp HttpHeader values in order to solve DOMException(cross origin) CORS issue (#92) --- src/multipart_stream.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/src/multipart_stream.cpp b/src/multipart_stream.cpp index 5ce235d..c38056d 100644 --- a/src/multipart_stream.cpp +++ b/src/multipart_stream.cpp @@ -16,7 +16,8 @@ void MultipartStream::sendInitialHeader() { "Server", "web_video_server").header("Cache-Control", "no-cache, no-store, must-revalidate, pre-check=0, post-check=0, max-age=0").header( "Pragma", "no-cache").header("Content-type", "multipart/x-mixed-replace;boundary="+boundry_).header( - "Access-Control-Allow-Origin", "*").write(connection_); + "Access-Control-Allow-Origin", "*").header("Access-Control-Allow-Methods", "GET,POST,PUT,DELETE,HEAD,OPTIONS").header( + "Access-Control-Allow-Headers", "Origin, Authorization, Accept, Content-Type").header("Access-Control-Max-Age", "3600").write(connection_); connection_->write("--"+boundry_+"\r\n"); } @@ -27,6 +28,10 @@ void MultipartStream::sendPartHeader(const ros::Time &time, const std::string& t new std::vector()); headers->push_back(async_web_server_cpp::HttpHeader("Content-type", type)); headers->push_back(async_web_server_cpp::HttpHeader("X-Timestamp", stamp)); + headers->push_back(async_web_server_cpp::HttpHeader("Access-Control-Allow-Origin", "*")); + headers->push_back(async_web_server_cpp::HttpHeader("Access-Control-Allow-Methods", "GET,POST,PUT,DELETE,HEAD,OPTIONS")); + headers->push_back(async_web_server_cpp::HttpHeader("Access-Control-Allow-Headers", "Origin, Authorization, Accept, Content-Type")); + headers->push_back(async_web_server_cpp::HttpHeader("Access-Control-Max-Age", "3600")); headers->push_back( async_web_server_cpp::HttpHeader("Content-Length", boost::lexical_cast(payload_size))); connection_->write(async_web_server_cpp::HttpReply::to_buffers(*headers), headers); From b3b367df835908f062191fd5cd4d7b1f5472705b Mon Sep 17 00:00:00 2001 From: Gady Date: Tue, 19 May 2020 04:02:30 +0300 Subject: [PATCH 51/54] add a mention of mjpegcanvasjs in the readme (#100) --- README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/README.md b/README.md index cbe4568..decba1b 100644 --- a/README.md +++ b/README.md @@ -7,6 +7,7 @@ This node combines the capabilities of [ros_web_video](https://github.com/RobotW For full documentation, see [the ROS wiki](http://ros.org/wiki/web_video_server). [Doxygen](http://docs.ros.org/indigo/api/web_video_server/html/) files can be found on the ROS wiki. +[mjpegcanvasjs](https://github.com/rctoris/mjpegcanvasjs) can be used to display a MJPEG stream from the ROS web_video_server This project is released as part of the [Robot Web Tools](http://robotwebtools.org/) effort. From dfc4bf08c7cd0a1623f66fa3be7589e59b82bebc Mon Sep 17 00:00:00 2001 From: randoms Date: Sat, 20 Jun 2020 11:29:37 +0800 Subject: [PATCH 52/54] fix vp9 and h264, support for opencv4 and ffmpeg 4 (#103) --- include/web_video_server/jpeg_streamers.h | 1 + include/web_video_server/png_streamers.h | 1 + src/image_streamer.cpp | 10 ++--- src/jpeg_streamers.cpp | 8 ++++ src/libav_streamer.cpp | 48 ++++++++++++++++++----- src/png_streamers.cpp | 8 ++++ 6 files changed, 61 insertions(+), 15 deletions(-) diff --git a/include/web_video_server/jpeg_streamers.h b/include/web_video_server/jpeg_streamers.h index 3a7f69f..7be2991 100644 --- a/include/web_video_server/jpeg_streamers.h +++ b/include/web_video_server/jpeg_streamers.h @@ -2,6 +2,7 @@ #define JPEG_STREAMERS_H_ #include +#include #include "web_video_server/image_streamer.h" #include "async_web_server_cpp/http_request.hpp" #include "async_web_server_cpp/http_connection.hpp" diff --git a/include/web_video_server/png_streamers.h b/include/web_video_server/png_streamers.h index 2207894..c8f4176 100644 --- a/include/web_video_server/png_streamers.h +++ b/include/web_video_server/png_streamers.h @@ -2,6 +2,7 @@ #define PNG_STREAMERS_H_ #include +#include #include "web_video_server/image_streamer.h" #include "async_web_server_cpp/http_request.hpp" #include "async_web_server_cpp/http_connection.hpp" diff --git a/src/image_streamer.cpp b/src/image_streamer.cpp index 68736ac..bbe45bb 100644 --- a/src/image_streamer.cpp +++ b/src/image_streamer.cpp @@ -112,10 +112,9 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::ImageConstPtr int input_width = img.cols; int input_height = img.rows; - if (output_width_ == -1) - output_width_ = input_width; - if (output_height_ == -1) - output_height_ = input_height; + + output_width_ = input_width; + output_height_ = input_height; if (invert_) { @@ -144,8 +143,7 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::ImageConstPtr } last_frame = ros::Time::now(); - sendImage(output_size_image, last_frame ); - + sendImage(output_size_image, msg->header.stamp); } catch (cv_bridge::Exception &e) { diff --git a/src/jpeg_streamers.cpp b/src/jpeg_streamers.cpp index 121730d..8f8eac9 100644 --- a/src/jpeg_streamers.cpp +++ b/src/jpeg_streamers.cpp @@ -21,7 +21,11 @@ MjpegStreamer::~MjpegStreamer() void MjpegStreamer::sendImage(const cv::Mat &img, const ros::Time &time) { std::vector encode_params; +#if CV_VERSION_MAJOR >= 3 + encode_params.push_back(cv::IMWRITE_JPEG_QUALITY); +#else encode_params.push_back(CV_IMWRITE_JPEG_QUALITY); +#endif encode_params.push_back(quality_); std::vector encoded_buffer; @@ -63,7 +67,11 @@ JpegSnapshotStreamer::~JpegSnapshotStreamer() void JpegSnapshotStreamer::sendImage(const cv::Mat &img, const ros::Time &time) { std::vector encode_params; +#if CV_VERSION_MAJOR >= 3 + encode_params.push_back(cv::IMWRITE_JPEG_QUALITY); +#else encode_params.push_back(CV_IMWRITE_JPEG_QUALITY); +#endif encode_params.push_back(quality_); std::vector encoded_buffer; diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index 7a4d67c..8c65ce8 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -60,16 +60,24 @@ LibavStreamer::LibavStreamer(const async_web_server_cpp::HttpRequest &request, bitrate_ = request.get_query_param_value_or_default("bitrate", 100000); qmin_ = request.get_query_param_value_or_default("qmin", 10); qmax_ = request.get_query_param_value_or_default("qmax", 42); - gop_ = request.get_query_param_value_or_default("gop", 250); + gop_ = request.get_query_param_value_or_default("gop", 25); +#if ( LIBAVCODEC_VERSION_INT < AV_VERSION_INT(58,9,100) ) av_lockmgr_register(&ffmpeg_boost_mutex_lock_manager); av_register_all(); +#endif } LibavStreamer::~LibavStreamer() { if (codec_context_) + { + #if ( LIBAVCODEC_VERSION_INT < AV_VERSION_INT(58,9,100) ) avcodec_close(codec_context_); + #else + avcodec_free_context(&codec_context_); + #endif + } if (frame_) { #if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1) @@ -134,6 +142,7 @@ void LibavStreamer::initialize(const cv::Mat &img) } io_ctx->seekable = 0; // no seeking, it's a stream format_context_->pb = io_ctx; + format_context_->max_interleave_delta = 0; output_format_->flags |= AVFMT_FLAG_CUSTOM_IO; output_format_->flags |= AVFMT_NOFILE; @@ -157,7 +166,11 @@ void LibavStreamer::initialize(const cv::Mat &img) NULL, NULL); throw std::runtime_error("Error creating video stream"); } + #if ( LIBAVCODEC_VERSION_INT < AV_VERSION_INT(58,9,100) ) codec_context_ = video_stream_->codec; + #else + codec_context_ = avcodec_alloc_context3(codec_); + #endif // Set options avcodec_get_context_defaults3(codec_context_, codec_); @@ -182,11 +195,14 @@ void LibavStreamer::initialize(const cv::Mat &img) codec_context_->qmin = qmin_; codec_context_->qmax = qmax_; + #if ( LIBAVCODEC_VERSION_INT >= AV_VERSION_INT(58,9,100) ) + avcodec_parameters_from_context(video_stream_->codecpar, codec_context_); + #endif + initializeEncoder(); - // Some formats want stream headers to be separate - if (format_context_->oformat->flags & AVFMT_GLOBALHEADER) - codec_context_->flags |= CODEC_FLAG_GLOBAL_HEADER; + codec_context_->flags |= AV_CODEC_FLAG_LOW_DELAY; + codec_context_->max_b_frames = 0; // Open Codec if (avcodec_open2(codec_context_, codec_, NULL) < 0) @@ -306,15 +322,29 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time) throw std::runtime_error("Error encoding video frame"); } #else - pkt.data = NULL; // packet data will be allocated by the encoder - pkt.size = 0; - if (avcodec_send_frame(codec_context_, frame_) < 0) + ret = avcodec_send_frame(codec_context_, frame_); + if (ret == AVERROR_EOF) + { + ROS_DEBUG_STREAM("avcodec_send_frame() encoder flushed"); + } + else if (ret == AVERROR(EAGAIN)) + { + ROS_DEBUG_STREAM("avcodec_send_frame() need output read out"); + } + if (ret < 0) { throw std::runtime_error("Error encoding video frame"); } - if (avcodec_receive_packet(codec_context_, &pkt) < 0) + ret = avcodec_receive_packet(codec_context_, &pkt); + got_packet = pkt.size > 0; + if (ret == AVERROR_EOF) + { + ROS_DEBUG_STREAM("avcodec_recieve_packet() encoder flushed"); + } + else if (ret == AVERROR(EAGAIN)) { - throw std::runtime_error("Error retrieving encoded packet"); + ROS_DEBUG_STREAM("avcodec_recieve_packet() need more input"); + got_packet = 0; } #endif diff --git a/src/png_streamers.cpp b/src/png_streamers.cpp index 629adf0..d26f232 100644 --- a/src/png_streamers.cpp +++ b/src/png_streamers.cpp @@ -21,7 +21,11 @@ PngStreamer::~PngStreamer() void PngStreamer::sendImage(const cv::Mat &img, const ros::Time &time) { std::vector encode_params; +#if CV_VERSION_MAJOR >= 3 + encode_params.push_back(cv::IMWRITE_PNG_COMPRESSION); +#else encode_params.push_back(CV_IMWRITE_PNG_COMPRESSION); +#endif encode_params.push_back(quality_); std::vector encoded_buffer; @@ -63,7 +67,11 @@ PngSnapshotStreamer::~PngSnapshotStreamer() void PngSnapshotStreamer::sendImage(const cv::Mat &img, const ros::Time &time) { std::vector encode_params; +#if CV_VERSION_MAJOR >= 3 + encode_params.push_back(cv::IMWRITE_PNG_COMPRESSION); +#else encode_params.push_back(CV_IMWRITE_PNG_COMPRESSION); +#endif encode_params.push_back(quality_); std::vector encoded_buffer; From e8eb661926d98928d19836ca244f82793b7a880e Mon Sep 17 00:00:00 2001 From: Jihoon Lee Date: Fri, 23 Jul 2021 10:49:34 +0900 Subject: [PATCH 53/54] update changelog --- CHANGELOG.rst | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index fdb6121..251dd5d 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package web_video_server ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* fix vp9 and h264, support for opencv4 and ffmpeg 4 (`#103 `_) +* add a mention of mjpegcanvasjs in the readme (`#100 `_) +* fix multipart_stream.cpp HttpHeader values in order to solve DOMException(cross origin) CORS issue (`#92 `_) +* Contributors: Gady, okapi1125, randoms + 0.2.1 (2019-06-05) ------------------ * Restream buffered frames with minimum publish rate (`#88 `_) From c90d142831409ba215553890821db09a1fcaa4b5 Mon Sep 17 00:00:00 2001 From: Jihoon Lee Date: Fri, 23 Jul 2021 10:50:02 +0900 Subject: [PATCH 54/54] 0.2.2 --- CHANGELOG.rst | 4 ++-- package.xml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 251dd5d..5ace9f7 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package web_video_server ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +0.2.2 (2021-07-23) +------------------ * fix vp9 and h264, support for opencv4 and ffmpeg 4 (`#103 `_) * add a mention of mjpegcanvasjs in the readme (`#100 `_) * fix multipart_stream.cpp HttpHeader values in order to solve DOMException(cross origin) CORS issue (`#92 `_) diff --git a/package.xml b/package.xml index 6c2a71c..4b3b7e8 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ web_video_server - 0.2.1 + 0.2.2 HTTP Streaming of ROS Image Topics in Multiple Formats Russell Toris