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] 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,