From 79f91e7f9dc1213e5329bbfb623248e5c1584499 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Thu, 10 Oct 2024 19:22:41 +0200 Subject: [PATCH 1/9] Use std::shared_ptr instead of boost::shared_ptr --- include/web_video_server/h264_streamer.hpp | 2 +- include/web_video_server/image_streamer.hpp | 2 +- include/web_video_server/jpeg_streamers.hpp | 2 +- include/web_video_server/libav_streamer.hpp | 2 +- include/web_video_server/png_streamers.hpp | 2 +- .../ros_compressed_streamer.hpp | 2 +- include/web_video_server/vp8_streamer.hpp | 2 +- include/web_video_server/vp9_streamer.hpp | 2 +- include/web_video_server/web_video_server.hpp | 6 ++--- src/h264_streamer.cpp | 4 +-- src/jpeg_streamers.cpp | 4 +-- src/libav_streamer.cpp | 6 ++--- src/png_streamers.cpp | 4 +-- src/ros_compressed_streamer.cpp | 4 +-- src/vp8_streamer.cpp | 4 +-- src/vp9_streamer.cpp | 4 +-- src/web_video_server.cpp | 25 +++++++++---------- 17 files changed, 38 insertions(+), 39 deletions(-) diff --git a/include/web_video_server/h264_streamer.hpp b/include/web_video_server/h264_streamer.hpp index 6539ffc..80f62fe 100644 --- a/include/web_video_server/h264_streamer.hpp +++ b/include/web_video_server/h264_streamer.hpp @@ -57,7 +57,7 @@ class H264StreamerType : public LibavStreamerType { public: H264StreamerType(); - virtual boost::shared_ptr create_streamer( + std::shared_ptr create_streamer( const async_web_server_cpp::HttpRequest & request, async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node); diff --git a/include/web_video_server/image_streamer.hpp b/include/web_video_server/image_streamer.hpp index 974b9ee..3c322e9 100644 --- a/include/web_video_server/image_streamer.hpp +++ b/include/web_video_server/image_streamer.hpp @@ -118,7 +118,7 @@ class ImageTransportImageStreamer : public ImageStreamer class ImageStreamerType { public: - virtual boost::shared_ptr create_streamer( + virtual std::shared_ptr create_streamer( const async_web_server_cpp::HttpRequest & request, async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node) = 0; diff --git a/include/web_video_server/jpeg_streamers.hpp b/include/web_video_server/jpeg_streamers.hpp index 47ab944..3af3346 100644 --- a/include/web_video_server/jpeg_streamers.hpp +++ b/include/web_video_server/jpeg_streamers.hpp @@ -61,7 +61,7 @@ class MjpegStreamer : public ImageTransportImageStreamer class MjpegStreamerType : public ImageStreamerType { public: - boost::shared_ptr create_streamer( + std::shared_ptr create_streamer( const async_web_server_cpp::HttpRequest & request, async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node); diff --git a/include/web_video_server/libav_streamer.hpp b/include/web_video_server/libav_streamer.hpp index aeed2b2..a44b3f2 100644 --- a/include/web_video_server/libav_streamer.hpp +++ b/include/web_video_server/libav_streamer.hpp @@ -98,7 +98,7 @@ class LibavStreamerType : public ImageStreamerType const std::string & format_name, const std::string & codec_name, const std::string & content_type); - boost::shared_ptr create_streamer( + std::shared_ptr create_streamer( const async_web_server_cpp::HttpRequest & request, async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node); diff --git a/include/web_video_server/png_streamers.hpp b/include/web_video_server/png_streamers.hpp index f871f4f..2cdb51d 100644 --- a/include/web_video_server/png_streamers.hpp +++ b/include/web_video_server/png_streamers.hpp @@ -61,7 +61,7 @@ class PngStreamer : public ImageTransportImageStreamer class PngStreamerType : public ImageStreamerType { public: - boost::shared_ptr create_streamer( + std::shared_ptr create_streamer( const async_web_server_cpp::HttpRequest & request, async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node); diff --git a/include/web_video_server/ros_compressed_streamer.hpp b/include/web_video_server/ros_compressed_streamer.hpp index 6b3af51..04ac33a 100644 --- a/include/web_video_server/ros_compressed_streamer.hpp +++ b/include/web_video_server/ros_compressed_streamer.hpp @@ -70,7 +70,7 @@ class RosCompressedStreamer : public ImageStreamer class RosCompressedStreamerType : public ImageStreamerType { public: - boost::shared_ptr create_streamer( + std::shared_ptr create_streamer( const async_web_server_cpp::HttpRequest & request, async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node); diff --git a/include/web_video_server/vp8_streamer.hpp b/include/web_video_server/vp8_streamer.hpp index 97b1bdd..5004b89 100644 --- a/include/web_video_server/vp8_streamer.hpp +++ b/include/web_video_server/vp8_streamer.hpp @@ -60,7 +60,7 @@ class Vp8StreamerType : public LibavStreamerType { public: Vp8StreamerType(); - virtual boost::shared_ptr create_streamer( + std::shared_ptr create_streamer( const async_web_server_cpp::HttpRequest & request, async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node); diff --git a/include/web_video_server/vp9_streamer.hpp b/include/web_video_server/vp9_streamer.hpp index ca94df6..b113f0d 100644 --- a/include/web_video_server/vp9_streamer.hpp +++ b/include/web_video_server/vp9_streamer.hpp @@ -54,7 +54,7 @@ class Vp9StreamerType : public LibavStreamerType { public: Vp9StreamerType(); - virtual boost::shared_ptr create_streamer( + std::shared_ptr create_streamer( const async_web_server_cpp::HttpRequest & request, async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node); diff --git a/include/web_video_server/web_video_server.hpp b/include/web_video_server/web_video_server.hpp index e78273d..af78a8f 100644 --- a/include/web_video_server/web_video_server.hpp +++ b/include/web_video_server/web_video_server.hpp @@ -114,11 +114,11 @@ class WebVideoServer bool verbose_; std::string default_stream_type_; - boost::shared_ptr server_; + std::shared_ptr server_; async_web_server_cpp::HttpRequestHandlerGroup handler_group_; - std::vector> image_subscribers_; - std::map> stream_types_; + std::vector> image_subscribers_; + std::map> stream_types_; boost::mutex subscriber_mutex_; }; diff --git a/src/h264_streamer.cpp b/src/h264_streamer.cpp index 6e195de..05e487f 100644 --- a/src/h264_streamer.cpp +++ b/src/h264_streamer.cpp @@ -69,12 +69,12 @@ H264StreamerType::H264StreamerType() { } -boost::shared_ptr H264StreamerType::create_streamer( +std::shared_ptr H264StreamerType::create_streamer( const async_web_server_cpp::HttpRequest & request, async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node) { - return boost::shared_ptr(new H264Streamer(request, connection, node)); + return std::make_shared(request, connection, node); } } // namespace web_video_server diff --git a/src/jpeg_streamers.cpp b/src/jpeg_streamers.cpp index 55c0f17..aaf917d 100644 --- a/src/jpeg_streamers.cpp +++ b/src/jpeg_streamers.cpp @@ -62,12 +62,12 @@ void MjpegStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time) stream_.sendPartAndClear(time, "image/jpeg", encoded_buffer); } -boost::shared_ptr MjpegStreamerType::create_streamer( +std::shared_ptr MjpegStreamerType::create_streamer( const async_web_server_cpp::HttpRequest & request, async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node) { - return boost::shared_ptr(new MjpegStreamer(request, connection, node)); + return std::make_shared(request, connection, node); } std::string MjpegStreamerType::create_viewer(const async_web_server_cpp::HttpRequest & request) diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index 16ea546..d5d51ff 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -303,13 +303,13 @@ LibavStreamerType::LibavStreamerType( { } -boost::shared_ptr LibavStreamerType::create_streamer( +std::shared_ptr LibavStreamerType::create_streamer( const async_web_server_cpp::HttpRequest & request, async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node) { - return boost::shared_ptr( - new LibavStreamer(request, connection, node, format_name_, codec_name_, content_type_)); + return std::make_shared(request, connection, node, format_name_, codec_name_, + content_type_); } std::string LibavStreamerType::create_viewer(const async_web_server_cpp::HttpRequest & request) diff --git a/src/png_streamers.cpp b/src/png_streamers.cpp index 8c29183..7517f42 100644 --- a/src/png_streamers.cpp +++ b/src/png_streamers.cpp @@ -78,12 +78,12 @@ void PngStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time) stream_.sendPartAndClear(time, "image/png", encoded_buffer); } -boost::shared_ptr PngStreamerType::create_streamer( +std::shared_ptr PngStreamerType::create_streamer( const async_web_server_cpp::HttpRequest & request, async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node) { - return boost::shared_ptr(new PngStreamer(request, connection, node)); + return std::make_shared(request, connection, node); } std::string PngStreamerType::create_viewer(const async_web_server_cpp::HttpRequest & request) diff --git a/src/ros_compressed_streamer.cpp b/src/ros_compressed_streamer.cpp index d1f6f3c..4726733 100644 --- a/src/ros_compressed_streamer.cpp +++ b/src/ros_compressed_streamer.cpp @@ -135,12 +135,12 @@ void RosCompressedStreamer::imageCallback( } -boost::shared_ptr RosCompressedStreamerType::create_streamer( +std::shared_ptr RosCompressedStreamerType::create_streamer( const async_web_server_cpp::HttpRequest & request, async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node) { - return boost::shared_ptr(new RosCompressedStreamer(request, connection, node)); + return std::make_shared(request, connection, node); } std::string RosCompressedStreamerType::create_viewer( diff --git a/src/vp8_streamer.cpp b/src/vp8_streamer.cpp index 1ff224c..c743bf1 100644 --- a/src/vp8_streamer.cpp +++ b/src/vp8_streamer.cpp @@ -75,12 +75,12 @@ Vp8StreamerType::Vp8StreamerType() { } -boost::shared_ptr Vp8StreamerType::create_streamer( +std::shared_ptr Vp8StreamerType::create_streamer( const async_web_server_cpp::HttpRequest & request, async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node) { - return boost::shared_ptr(new Vp8Streamer(request, connection, node)); + return std::make_shared(request, connection, node); } } // namespace web_video_server diff --git a/src/vp9_streamer.cpp b/src/vp9_streamer.cpp index 36d5e59..65511a7 100644 --- a/src/vp9_streamer.cpp +++ b/src/vp9_streamer.cpp @@ -57,12 +57,12 @@ Vp9StreamerType::Vp9StreamerType() { } -boost::shared_ptr Vp9StreamerType::create_streamer( +std::shared_ptr Vp9StreamerType::create_streamer( const async_web_server_cpp::HttpRequest & request, async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node) { - return boost::shared_ptr(new Vp9Streamer(request, connection, node)); + return std::make_shared(request, connection, node); } } // namespace web_video_server diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 27d1515..5be2bec 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -74,13 +74,12 @@ WebVideoServer::WebVideoServer(rclcpp::Node::SharedPtr & node) node_->get_parameter("publish_rate", publish_rate_); node_->get_parameter("default_stream_type", default_stream_type_); - 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()); - stream_types_["vp9"] = boost::shared_ptr(new Vp9StreamerType()); + stream_types_["mjpeg"] = std::make_shared(); + stream_types_["png"] = std::make_shared(); + stream_types_["ros_compressed"] = std::make_shared(); + stream_types_["vp8"] = std::make_shared(); + stream_types_["h264"] = std::make_shared(); + stream_types_["vp9"] = std::make_shared(); handler_group_.addHandlerForPath( "/", @@ -138,7 +137,7 @@ void WebVideoServer::restreamFrames(double max_age) { boost::mutex::scoped_lock lock(subscriber_mutex_); - typedef std::vector>::iterator itr_type; + typedef std::vector>::iterator itr_type; for (itr_type itr = image_subscribers_.begin(); itr < image_subscribers_.end(); ++itr) { (*itr)->restreamFrame(max_age); @@ -149,7 +148,7 @@ void WebVideoServer::cleanup_inactive_streams() { boost::mutex::scoped_lock lock(subscriber_mutex_, boost::try_to_lock); if (lock) { - typedef std::vector>::iterator itr_type; + typedef std::vector>::iterator itr_type; itr_type new_end = std::partition( image_subscribers_.begin(), image_subscribers_.end(), !boost::bind(&ImageStreamer::isInactive, _1)); @@ -212,9 +211,8 @@ bool WebVideoServer::handle_stream( type = "mjpeg"; } } - boost::shared_ptr streamer = stream_types_[type]->create_streamer( - request, - connection, node_); + std::shared_ptr streamer = stream_types_[type]->create_streamer(request, + connection, node_); streamer->start(); boost::mutex::scoped_lock lock(subscriber_mutex_); image_subscribers_.push_back(streamer); @@ -230,7 +228,8 @@ bool WebVideoServer::handle_snapshot( async_web_server_cpp::HttpConnectionPtr connection, const char * begin, const char * end) { - boost::shared_ptr streamer(new JpegSnapshotStreamer(request, connection, node_)); + std::shared_ptr streamer = std::make_shared(request, + connection, node_); streamer->start(); boost::mutex::scoped_lock lock(subscriber_mutex_); From aee851c87cbc9f7fe8d8e49f6b8c826dfb585de7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Thu, 10 Oct 2024 19:26:38 +0200 Subject: [PATCH 2/9] Use std::mutex instead of boost::mutex --- include/web_video_server/image_streamer.hpp | 2 +- include/web_video_server/libav_streamer.hpp | 2 +- include/web_video_server/ros_compressed_streamer.hpp | 2 +- include/web_video_server/web_video_server.hpp | 2 +- src/image_streamer.cpp | 4 ++-- src/jpeg_streamers.cpp | 4 ++-- src/libav_streamer.cpp | 2 +- src/png_streamers.cpp | 4 ++-- src/ros_compressed_streamer.cpp | 6 +++--- src/web_video_server.cpp | 8 ++++---- 10 files changed, 18 insertions(+), 18 deletions(-) diff --git a/include/web_video_server/image_streamer.hpp b/include/web_video_server/image_streamer.hpp index 3c322e9..29df5e1 100644 --- a/include/web_video_server/image_streamer.hpp +++ b/include/web_video_server/image_streamer.hpp @@ -106,7 +106,7 @@ class ImageTransportImageStreamer : public ImageStreamer rclcpp::Time last_frame; cv::Mat output_size_image; - boost::mutex send_mutex_; + std::mutex send_mutex_; private: image_transport::ImageTransport it_; diff --git a/include/web_video_server/libav_streamer.hpp b/include/web_video_server/libav_streamer.hpp index a44b3f2..26e8300 100644 --- a/include/web_video_server/libav_streamer.hpp +++ b/include/web_video_server/libav_streamer.hpp @@ -78,7 +78,7 @@ class LibavStreamer : public ImageTransportImageStreamer AVFrame * frame_; struct SwsContext * sws_context_; rclcpp::Time first_image_timestamp_; - boost::mutex encode_mutex_; + std::mutex encode_mutex_; std::string format_name_; std::string codec_name_; diff --git a/include/web_video_server/ros_compressed_streamer.hpp b/include/web_video_server/ros_compressed_streamer.hpp index 04ac33a..10dbbf7 100644 --- a/include/web_video_server/ros_compressed_streamer.hpp +++ b/include/web_video_server/ros_compressed_streamer.hpp @@ -63,7 +63,7 @@ class RosCompressedStreamer : public ImageStreamer rclcpp::Subscription::SharedPtr image_sub_; rclcpp::Time last_frame; sensor_msgs::msg::CompressedImage::ConstSharedPtr last_msg; - boost::mutex send_mutex_; + std::mutex send_mutex_; std::string qos_profile_name_; }; diff --git a/include/web_video_server/web_video_server.hpp b/include/web_video_server/web_video_server.hpp index af78a8f..dd8b363 100644 --- a/include/web_video_server/web_video_server.hpp +++ b/include/web_video_server/web_video_server.hpp @@ -119,7 +119,7 @@ class WebVideoServer std::vector> image_subscribers_; std::map> stream_types_; - boost::mutex subscriber_mutex_; + std::mutex subscriber_mutex_; }; } // namespace web_video_server diff --git a/src/image_streamer.cpp b/src/image_streamer.cpp index a698754..5867db6 100644 --- a/src/image_streamer.cpp +++ b/src/image_streamer.cpp @@ -117,7 +117,7 @@ void ImageTransportImageStreamer::restreamFrame(double max_age) } try { if (last_frame + rclcpp::Duration::from_seconds(max_age) < node_->now() ) { - boost::mutex::scoped_lock lock(send_mutex_); + std::scoped_lock lock(send_mutex_); // don't update last_frame, it may remain an old value. sendImage(output_size_image, node_->now()); } @@ -184,7 +184,7 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::msg::Image::C cv::flip(img, img, true); } - boost::mutex::scoped_lock lock(send_mutex_); // protects output_size_image + std::scoped_lock lock(send_mutex_); // protects output_size_image if (output_width_ != input_width || output_height_ != input_height) { cv::Mat img_resized; cv::Size new_size(output_width_, output_height_); diff --git a/src/jpeg_streamers.cpp b/src/jpeg_streamers.cpp index aaf917d..7a14ee5 100644 --- a/src/jpeg_streamers.cpp +++ b/src/jpeg_streamers.cpp @@ -47,7 +47,7 @@ MjpegStreamer::MjpegStreamer( MjpegStreamer::~MjpegStreamer() { this->inactive_ = true; - boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. + std::scoped_lock lock(send_mutex_); // protects sendImage. } void MjpegStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time) @@ -91,7 +91,7 @@ JpegSnapshotStreamer::JpegSnapshotStreamer( JpegSnapshotStreamer::~JpegSnapshotStreamer() { this->inactive_ = true; - boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. + std::scoped_lock lock(send_mutex_); // protects sendImage. } void JpegSnapshotStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time) diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index d5d51ff..04209f6 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -217,7 +217,7 @@ void LibavStreamer::initializeEncoder() void LibavStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time) { - boost::mutex::scoped_lock lock(encode_mutex_); + std::scoped_lock lock(encode_mutex_); if (0 == first_image_timestamp_.nanoseconds()) { first_image_timestamp_ = time; } diff --git a/src/png_streamers.cpp b/src/png_streamers.cpp index 7517f42..d7e2221 100644 --- a/src/png_streamers.cpp +++ b/src/png_streamers.cpp @@ -52,7 +52,7 @@ PngStreamer::PngStreamer( PngStreamer::~PngStreamer() { this->inactive_ = true; - boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. + std::scoped_lock lock(send_mutex_); // protects sendImage. } cv::Mat PngStreamer::decodeImage(const sensor_msgs::msg::Image::ConstSharedPtr & msg) @@ -107,7 +107,7 @@ PngSnapshotStreamer::PngSnapshotStreamer( PngSnapshotStreamer::~PngSnapshotStreamer() { this->inactive_ = true; - boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. + std::scoped_lock lock(send_mutex_); // protects sendImage. } cv::Mat PngSnapshotStreamer::decodeImage(const sensor_msgs::msg::Image::ConstSharedPtr & msg) diff --git a/src/ros_compressed_streamer.cpp b/src/ros_compressed_streamer.cpp index 4726733..8c906bf 100644 --- a/src/ros_compressed_streamer.cpp +++ b/src/ros_compressed_streamer.cpp @@ -45,7 +45,7 @@ RosCompressedStreamer::RosCompressedStreamer( RosCompressedStreamer::~RosCompressedStreamer() { this->inactive_ = true; - boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. + std::scoped_lock lock(send_mutex_); // protects sendImage. } void RosCompressedStreamer::start() @@ -81,7 +81,7 @@ void RosCompressedStreamer::restreamFrame(double max_age) } if (last_frame + rclcpp::Duration::from_seconds(max_age) < node_->now() ) { - boost::mutex::scoped_lock lock(send_mutex_); + std::scoped_lock lock(send_mutex_); sendImage(last_msg, node_->now() ); // don't update last_frame, it may remain an old value. } } @@ -128,7 +128,7 @@ void RosCompressedStreamer::sendImage( void RosCompressedStreamer::imageCallback( const sensor_msgs::msg::CompressedImage::ConstSharedPtr msg) { - boost::mutex::scoped_lock lock(send_mutex_); // protects last_msg and last_frame + std::scoped_lock lock(send_mutex_); // protects last_msg and last_frame last_msg = msg; last_frame = rclcpp::Time(msg->header.stamp); sendImage(last_msg, last_frame); diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 5be2bec..97a432b 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -135,7 +135,7 @@ void WebVideoServer::spin() void WebVideoServer::restreamFrames(double max_age) { - boost::mutex::scoped_lock lock(subscriber_mutex_); + std::scoped_lock lock(subscriber_mutex_); typedef std::vector>::iterator itr_type; @@ -146,7 +146,7 @@ void WebVideoServer::restreamFrames(double max_age) void WebVideoServer::cleanup_inactive_streams() { - boost::mutex::scoped_lock lock(subscriber_mutex_, boost::try_to_lock); + std::unique_lock lock(subscriber_mutex_, std::try_to_lock); if (lock) { typedef std::vector>::iterator itr_type; itr_type new_end = std::partition( @@ -214,7 +214,7 @@ bool WebVideoServer::handle_stream( std::shared_ptr streamer = stream_types_[type]->create_streamer(request, connection, node_); streamer->start(); - boost::mutex::scoped_lock lock(subscriber_mutex_); + std::scoped_lock lock(subscriber_mutex_); image_subscribers_.push_back(streamer); } else { async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::not_found)( @@ -232,7 +232,7 @@ bool WebVideoServer::handle_snapshot( connection, node_); streamer->start(); - boost::mutex::scoped_lock lock(subscriber_mutex_); + std::scoped_lock lock(subscriber_mutex_); image_subscribers_.push_back(streamer); return true; } From 6bb6281a054f8c4091fc2ecc42fb0eae20e8313d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Thu, 10 Oct 2024 19:29:20 +0200 Subject: [PATCH 3/9] Replace boost::lexical_cast with std::to_string --- src/jpeg_streamers.cpp | 2 +- src/multipart_stream.cpp | 6 ++---- src/png_streamers.cpp | 2 +- src/web_video_server.cpp | 2 +- 4 files changed, 5 insertions(+), 7 deletions(-) diff --git a/src/jpeg_streamers.cpp b/src/jpeg_streamers.cpp index 7a14ee5..9123e36 100644 --- a/src/jpeg_streamers.cpp +++ b/src/jpeg_streamers.cpp @@ -115,7 +115,7 @@ void JpegSnapshotStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & t .header("Pragma", "no-cache") .header("Content-type", "image/jpeg") .header("Access-Control-Allow-Origin", "*") - .header("Content-Length", boost::lexical_cast(encoded_buffer.size())) + .header("Content-Length", std::to_string(encoded_buffer.size())) .write(connection_); connection_->write_and_clear(encoded_buffer); inactive_ = true; diff --git a/src/multipart_stream.cpp b/src/multipart_stream.cpp index 86ccbfc..db3e82d 100644 --- a/src/multipart_stream.cpp +++ b/src/multipart_stream.cpp @@ -67,10 +67,8 @@ void MultipartStream::sendPartHeader( 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))); + headers->push_back(async_web_server_cpp::HttpHeader("Content-Length", + std::to_string(payload_size))); connection_->write(async_web_server_cpp::HttpReply::to_buffers(*headers), headers); } diff --git a/src/png_streamers.cpp b/src/png_streamers.cpp index d7e2221..d801097 100644 --- a/src/png_streamers.cpp +++ b/src/png_streamers.cpp @@ -142,7 +142,7 @@ void PngSnapshotStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & ti .header("Pragma", "no-cache") .header("Content-type", "image/png") .header("Access-Control-Allow-Origin", "*") - .header("Content-Length", boost::lexical_cast(encoded_buffer.size())) + .header("Content-Length", std::to_string(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 97a432b..fbfd793 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -97,7 +97,7 @@ WebVideoServer::WebVideoServer(rclcpp::Node::SharedPtr & node) try { server_.reset( new async_web_server_cpp::HttpServer( - address_, boost::lexical_cast(port_), + address_, std::to_string(port_), boost::bind(&WebVideoServer::handle_request, this, _1, _2, _3, _4), server_threads ) From a5986b87676a39dad2a206d12c0dca80650c785f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Thu, 10 Oct 2024 17:50:25 +0000 Subject: [PATCH 4/9] Use C++11 foreach loop and auto --- src/vp8_streamer.cpp | 4 ++-- src/web_video_server.cpp | 16 +++++----------- 2 files changed, 7 insertions(+), 13 deletions(-) diff --git a/src/vp8_streamer.cpp b/src/vp8_streamer.cpp index c743bf1..c4c1d0c 100644 --- a/src/vp8_streamer.cpp +++ b/src/vp8_streamer.cpp @@ -56,8 +56,8 @@ void Vp8Streamer::initializeEncoder() av_opt_map["drop_frame"] = "1"; av_opt_map["error-resilient"] = "1"; - for (AvOptMap::iterator itr = av_opt_map.begin(); itr != av_opt_map.end(); ++itr) { - av_opt_set(codec_context_->priv_data, itr->first.c_str(), itr->second.c_str(), 0); + for (auto & opt : av_opt_map) { + av_opt_set(codec_context_->priv_data, opt.first.c_str(), opt.second.c_str(), 0); } // Buffering settings diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index fbfd793..c11c763 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -33,8 +33,6 @@ #include #include -#include -#include #include #include @@ -137,10 +135,8 @@ void WebVideoServer::restreamFrames(double max_age) { std::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); + for (auto& subscriber : image_subscribers_) { + subscriber->restreamFrame(max_age); } } @@ -148,12 +144,11 @@ void WebVideoServer::cleanup_inactive_streams() { std::unique_lock lock(subscriber_mutex_, std::try_to_lock); if (lock) { - typedef std::vector>::iterator itr_type; - itr_type new_end = std::partition( + auto 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) { + for (auto itr = new_end; itr < image_subscribers_.end(); ++itr) { RCLCPP_INFO(node_->get_logger(), "Removed Stream: %s", (*itr)->getTopic().c_str()); } } @@ -326,8 +321,7 @@ bool WebVideoServer::handle_list_streams( "ROS Image Topic List" "

Available ROS Image Topics:

"); connection->write("
    "); - BOOST_FOREACH(std::string & camera_info_topic, camera_info_topics) - { + for(std::string & camera_info_topic : camera_info_topics) { if (boost::algorithm::ends_with(camera_info_topic, "/camera_info")) { std::string base_topic = camera_info_topic.substr( 0, From 31bfd5ad0a3f8e5a2a421c387e09f7bded8d3de4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Fri, 20 Sep 2024 06:15:36 +0000 Subject: [PATCH 5/9] Update boost linking --- CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index d72cbc2..21c9717 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -10,7 +10,7 @@ find_package(rclcpp REQUIRED) find_package(sensor_msgs REQUIRED) find_package(OpenCV REQUIRED) -find_package(Boost REQUIRED COMPONENTS thread) +find_package(Boost REQUIRED COMPONENTS system) find_package(PkgConfig REQUIRED) pkg_check_modules(avcodec libavcodec REQUIRED) @@ -36,7 +36,6 @@ endif() ## Specify additional locations of header files include_directories(include - ${Boost_INCLUDE_DIRS} ${avcodec_INCLUDE_DIRS} ${avformat_INCLUDE_DIRS} ${avutil_INCLUDE_DIRS} @@ -68,7 +67,8 @@ target_link_libraries(${PROJECT_NAME} cv_bridge::cv_bridge image_transport::image_transport rclcpp::rclcpp - ${Boost_LIBRARIES} + Boost::boost + Boost::system ${OpenCV_LIBS} ${avcodec_LIBRARIES} ${avformat_LIBRARIES} From a4d2c8eb47414f5b5f628a27232e0a83ced4df8e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Thu, 10 Oct 2024 17:51:55 +0000 Subject: [PATCH 6/9] Reformat --- src/web_video_server.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index c11c763..f3e9dd7 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -135,7 +135,7 @@ void WebVideoServer::restreamFrames(double max_age) { std::scoped_lock lock(subscriber_mutex_); - for (auto& subscriber : image_subscribers_) { + for (auto & subscriber : image_subscribers_) { subscriber->restreamFrame(max_age); } } From 665db3f69f691e6fdbf283271739a37aa3b0fbbe Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Thu, 10 Oct 2024 19:56:04 +0200 Subject: [PATCH 7/9] Fix cpplint errors --- include/web_video_server/h264_streamer.hpp | 1 + include/web_video_server/image_streamer.hpp | 1 + include/web_video_server/jpeg_streamers.hpp | 1 + include/web_video_server/libav_streamer.hpp | 1 + include/web_video_server/png_streamers.hpp | 1 + include/web_video_server/ros_compressed_streamer.hpp | 1 + include/web_video_server/vp8_streamer.hpp | 1 + include/web_video_server/vp9_streamer.hpp | 2 ++ include/web_video_server/web_video_server.hpp | 1 + 9 files changed, 10 insertions(+) diff --git a/include/web_video_server/h264_streamer.hpp b/include/web_video_server/h264_streamer.hpp index 80f62fe..3df01b4 100644 --- a/include/web_video_server/h264_streamer.hpp +++ b/include/web_video_server/h264_streamer.hpp @@ -29,6 +29,7 @@ #pragma once +#include #include #include "image_transport/image_transport.hpp" diff --git a/include/web_video_server/image_streamer.hpp b/include/web_video_server/image_streamer.hpp index 29df5e1..74c75f9 100644 --- a/include/web_video_server/image_streamer.hpp +++ b/include/web_video_server/image_streamer.hpp @@ -30,6 +30,7 @@ #pragma once +#include #include #include diff --git a/include/web_video_server/jpeg_streamers.hpp b/include/web_video_server/jpeg_streamers.hpp index 3af3346..6946215 100644 --- a/include/web_video_server/jpeg_streamers.hpp +++ b/include/web_video_server/jpeg_streamers.hpp @@ -30,6 +30,7 @@ #pragma once +#include #include #include "image_transport/image_transport.hpp" diff --git a/include/web_video_server/libav_streamer.hpp b/include/web_video_server/libav_streamer.hpp index 26e8300..2f4db10 100644 --- a/include/web_video_server/libav_streamer.hpp +++ b/include/web_video_server/libav_streamer.hpp @@ -42,6 +42,7 @@ extern "C" #include } +#include #include #include "image_transport/image_transport.hpp" diff --git a/include/web_video_server/png_streamers.hpp b/include/web_video_server/png_streamers.hpp index 2cdb51d..14f370e 100644 --- a/include/web_video_server/png_streamers.hpp +++ b/include/web_video_server/png_streamers.hpp @@ -29,6 +29,7 @@ #pragma once +#include #include #include "image_transport/image_transport.hpp" diff --git a/include/web_video_server/ros_compressed_streamer.hpp b/include/web_video_server/ros_compressed_streamer.hpp index 10dbbf7..aceb076 100644 --- a/include/web_video_server/ros_compressed_streamer.hpp +++ b/include/web_video_server/ros_compressed_streamer.hpp @@ -30,6 +30,7 @@ #pragma once +#include #include #include "sensor_msgs/msg/compressed_image.hpp" diff --git a/include/web_video_server/vp8_streamer.hpp b/include/web_video_server/vp8_streamer.hpp index 5004b89..ad6fd2f 100644 --- a/include/web_video_server/vp8_streamer.hpp +++ b/include/web_video_server/vp8_streamer.hpp @@ -30,6 +30,7 @@ #pragma once +#include #include #include "image_transport/image_transport.hpp" diff --git a/include/web_video_server/vp9_streamer.hpp b/include/web_video_server/vp9_streamer.hpp index b113f0d..5491db7 100644 --- a/include/web_video_server/vp9_streamer.hpp +++ b/include/web_video_server/vp9_streamer.hpp @@ -29,6 +29,8 @@ #pragma once +#include + #include "image_transport/image_transport.hpp" #include "web_video_server/libav_streamer.hpp" #include "async_web_server_cpp/http_request.hpp" diff --git a/include/web_video_server/web_video_server.hpp b/include/web_video_server/web_video_server.hpp index dd8b363..bbaf33c 100644 --- a/include/web_video_server/web_video_server.hpp +++ b/include/web_video_server/web_video_server.hpp @@ -31,6 +31,7 @@ #pragma once #include +#include #include #include From ba04b4754d53a8096c37c21560adb62f22a5e7fa Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Thu, 10 Oct 2024 20:03:07 +0200 Subject: [PATCH 8/9] Replace boost::bind with lambda in std::partition --- src/web_video_server.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index f3e9dd7..46dfc09 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -146,7 +146,7 @@ void WebVideoServer::cleanup_inactive_streams() if (lock) { auto new_end = std::partition( image_subscribers_.begin(), image_subscribers_.end(), - !boost::bind(&ImageStreamer::isInactive, _1)); + [](const std::shared_ptr & streamer) {return !streamer->isInactive();}); if (verbose_) { for (auto itr = new_end; itr < image_subscribers_.end(); ++itr) { RCLCPP_INFO(node_->get_logger(), "Removed Stream: %s", (*itr)->getTopic().c_str()); From c9f6e1b022a66808b2029b656c1a5b8d2836aca4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Thu, 10 Oct 2024 18:11:22 +0000 Subject: [PATCH 9/9] Reformat --- src/libav_streamer.cpp | 5 +++-- src/multipart_stream.cpp | 5 +++-- src/web_video_server.cpp | 10 +++++----- 3 files changed, 11 insertions(+), 9 deletions(-) diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index 04209f6..126fa6b 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -308,8 +308,9 @@ std::shared_ptr LibavStreamerType::create_streamer( async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node) { - return std::make_shared(request, connection, node, format_name_, codec_name_, - content_type_); + return std::make_shared( + request, connection, node, format_name_, codec_name_, + content_type_); } std::string LibavStreamerType::create_viewer(const async_web_server_cpp::HttpRequest & request) diff --git a/src/multipart_stream.cpp b/src/multipart_stream.cpp index db3e82d..c43de8a 100644 --- a/src/multipart_stream.cpp +++ b/src/multipart_stream.cpp @@ -67,8 +67,9 @@ void MultipartStream::sendPartHeader( 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", - std::to_string(payload_size))); + headers->push_back( + async_web_server_cpp::HttpHeader( + "Content-Length", std::to_string(payload_size))); connection_->write(async_web_server_cpp::HttpReply::to_buffers(*headers), headers); } diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 46dfc09..3bd67b9 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -206,8 +206,8 @@ bool WebVideoServer::handle_stream( type = "mjpeg"; } } - std::shared_ptr streamer = stream_types_[type]->create_streamer(request, - connection, node_); + std::shared_ptr streamer = stream_types_[type]->create_streamer( + request, connection, node_); streamer->start(); std::scoped_lock lock(subscriber_mutex_); image_subscribers_.push_back(streamer); @@ -223,8 +223,8 @@ bool WebVideoServer::handle_snapshot( async_web_server_cpp::HttpConnectionPtr connection, const char * begin, const char * end) { - std::shared_ptr streamer = std::make_shared(request, - connection, node_); + std::shared_ptr streamer = std::make_shared( + request, connection, node_); streamer->start(); std::scoped_lock lock(subscriber_mutex_); @@ -321,7 +321,7 @@ bool WebVideoServer::handle_list_streams( "ROS Image Topic List" "

    Available ROS Image Topics:

    "); connection->write("
      "); - for(std::string & camera_info_topic : camera_info_topics) { + for (std::string & camera_info_topic : camera_info_topics) { if (boost::algorithm::ends_with(camera_info_topic, "/camera_info")) { std::string base_topic = camera_info_topic.substr( 0,