diff --git a/include/web_video_server/h264_streamer.hpp b/include/web_video_server/h264_streamer.hpp index b5661be..5c564be 100644 --- a/include/web_video_server/h264_streamer.hpp +++ b/include/web_video_server/h264_streamer.hpp @@ -1,7 +1,9 @@ -#ifndef H264_STREAMERS_H_ -#define H264_STREAMERS_H_ +#ifndef WEB_VIDEO_SERVER__H264_STREAMER_HPP_ +#define WEB_VIDEO_SERVER__H264_STREAMER_HPP_ -#include +#include + +#include "image_transport/image_transport.hpp" #include "web_video_server/libav_streamer.hpp" #include "async_web_server_cpp/http_request.hpp" #include "async_web_server_cpp/http_connection.hpp" @@ -33,6 +35,6 @@ class H264StreamerType : public LibavStreamerType rclcpp::Node::SharedPtr node); }; -} +} // namespace web_video_server -#endif +#endif // WEB_VIDEO_SERVER__H264_STREAMER_HPP_ diff --git a/include/web_video_server/image_streamer.hpp b/include/web_video_server/image_streamer.hpp index 81c6029..6d1a0ab 100644 --- a/include/web_video_server/image_streamer.hpp +++ b/include/web_video_server/image_streamer.hpp @@ -1,10 +1,13 @@ -#ifndef IMAGE_STREAMER_H_ -#define IMAGE_STREAMER_H_ +#ifndef WEB_VIDEO_SERVER__IMAGE_STREAMER_HPP_ +#define WEB_VIDEO_SERVER__IMAGE_STREAMER_HPP_ + +#include -#include -#include -#include #include + +#include "rclcpp/rclcpp.hpp" +#include "image_transport/image_transport.hpp" +#include "image_transport/transport_hints.hpp" #include "web_video_server/utils.hpp" #include "async_web_server_cpp/http_server.hpp" #include "async_web_server_cpp/http_request.hpp" @@ -93,6 +96,6 @@ class ImageStreamerType virtual std::string create_viewer(const async_web_server_cpp::HttpRequest & request) = 0; }; -} +} // namespace web_video_server -#endif +#endif // WEB_VIDEO_SERVER__IMAGE_STREAMER_HPP_ diff --git a/include/web_video_server/jpeg_streamers.hpp b/include/web_video_server/jpeg_streamers.hpp index ef1b025..38d829a 100644 --- a/include/web_video_server/jpeg_streamers.hpp +++ b/include/web_video_server/jpeg_streamers.hpp @@ -1,7 +1,9 @@ -#ifndef JPEG_STREAMERS_H_ -#define JPEG_STREAMERS_H_ +#ifndef WEB_VIDEO_SERVER__JPEG_STREAMERS_HPP_ +#define WEB_VIDEO_SERVER__JPEG_STREAMERS_HPP_ -#include +#include + +#include "image_transport/image_transport.hpp" #include "web_video_server/image_streamer.hpp" #include "async_web_server_cpp/http_request.hpp" #include "async_web_server_cpp/http_connection.hpp" @@ -52,6 +54,6 @@ class JpegSnapshotStreamer : public ImageTransportImageStreamer int quality_; }; -} +} // namespace web_video_server -#endif +#endif // WEB_VIDEO_SERVER__JPEG_STREAMERS_HPP_ diff --git a/include/web_video_server/libav_streamer.hpp b/include/web_video_server/libav_streamer.hpp index ca62ea3..2b97bea 100644 --- a/include/web_video_server/libav_streamer.hpp +++ b/include/web_video_server/libav_streamer.hpp @@ -1,10 +1,5 @@ -#ifndef LIBAV_STREAMERS_H_ -#define LIBAV_STREAMERS_H_ - -#include -#include "web_video_server/image_streamer.hpp" -#include "async_web_server_cpp/http_request.hpp" -#include "async_web_server_cpp/http_connection.hpp" +#ifndef WEB_VIDEO_SERVER__LIBAV_STREAMER_HPP_ +#define WEB_VIDEO_SERVER__LIBAV_STREAMER_HPP_ extern "C" { @@ -18,6 +13,13 @@ extern "C" #include } +#include + +#include "image_transport/image_transport.hpp" +#include "web_video_server/image_streamer.hpp" +#include "async_web_server_cpp/http_request.hpp" +#include "async_web_server_cpp/http_connection.hpp" + namespace web_video_server { @@ -80,6 +82,6 @@ class LibavStreamerType : public ImageStreamerType const std::string content_type_; }; -} +} // namespace web_video_server -#endif +#endif // WEB_VIDEO_SERVER__LIBAV_STREAMER_HPP_ diff --git a/include/web_video_server/multipart_stream.hpp b/include/web_video_server/multipart_stream.hpp index 80489b2..4ea248e 100644 --- a/include/web_video_server/multipart_stream.hpp +++ b/include/web_video_server/multipart_stream.hpp @@ -1,10 +1,13 @@ -#ifndef MULTIPART_STREAM_H_ -#define MULTIPART_STREAM_H_ - -#include -#include +#ifndef WEB_VIDEO_SERVER__MULTIPART_STREAM_HPP_ +#define WEB_VIDEO_SERVER__MULTIPART_STREAM_HPP_ #include +#include +#include +#include + +#include "rclcpp/rclcpp.hpp" +#include "async_web_server_cpp/http_connection.hpp" namespace web_video_server { @@ -45,6 +48,6 @@ class MultipartStream std::queue pending_footers_; }; -} +} // namespace web_video_server -#endif +#endif // WEB_VIDEO_SERVER__MULTIPART_STREAM_HPP_ diff --git a/include/web_video_server/png_streamers.hpp b/include/web_video_server/png_streamers.hpp index 20cd569..4df36b4 100644 --- a/include/web_video_server/png_streamers.hpp +++ b/include/web_video_server/png_streamers.hpp @@ -1,7 +1,9 @@ -#ifndef PNG_STREAMERS_H_ -#define PNG_STREAMERS_H_ +#ifndef WEB_VIDEO_SERVER__PNG_STREAMERS_HPP_ +#define WEB_VIDEO_SERVER__PNG_STREAMERS_HPP_ -#include +#include + +#include "image_transport/image_transport.hpp" #include "web_video_server/image_streamer.hpp" #include "async_web_server_cpp/http_request.hpp" #include "async_web_server_cpp/http_connection.hpp" @@ -52,6 +54,6 @@ class PngSnapshotStreamer : public ImageTransportImageStreamer int quality_; }; -} +} // namespace web_video_server -#endif +#endif // WEB_VIDEO_SERVER__PNG_STREAMERS_HPP_ diff --git a/include/web_video_server/ros_compressed_streamer.hpp b/include/web_video_server/ros_compressed_streamer.hpp index db3886a..ac624c3 100644 --- a/include/web_video_server/ros_compressed_streamer.hpp +++ b/include/web_video_server/ros_compressed_streamer.hpp @@ -1,7 +1,9 @@ -#ifndef ROS_COMPRESSED_STREAMERS_H_ -#define ROS_COMPRESSED_STREAMERS_H_ +#ifndef WEB_VIDEO_SERVER__ROS_COMPRESSED_STREAMER_HPP_ +#define WEB_VIDEO_SERVER__ROS_COMPRESSED_STREAMER_HPP_ -#include +#include + +#include "sensor_msgs/msg/compressed_image.hpp" #include "web_video_server/image_streamer.hpp" #include "async_web_server_cpp/http_request.hpp" #include "async_web_server_cpp/http_connection.hpp" @@ -46,6 +48,6 @@ class RosCompressedStreamerType : public ImageStreamerType std::string create_viewer(const async_web_server_cpp::HttpRequest & request); }; -} +} // namespace web_video_server -#endif +#endif // WEB_VIDEO_SERVER__ROS_COMPRESSED_STREAMER_HPP_ diff --git a/include/web_video_server/vp8_streamer.hpp b/include/web_video_server/vp8_streamer.hpp index 215fa75..c988c37 100644 --- a/include/web_video_server/vp8_streamer.hpp +++ b/include/web_video_server/vp8_streamer.hpp @@ -34,10 +34,12 @@ * *********************************************************************/ -#ifndef VP8_STREAMERS_H_ -#define VP8_STREAMERS_H_ +#ifndef WEB_VIDEO_SERVER__VP8_STREAMER_HPP_ +#define WEB_VIDEO_SERVER__VP8_STREAMER_HPP_ -#include +#include + +#include "image_transport/image_transport.hpp" #include "web_video_server/libav_streamer.hpp" #include "async_web_server_cpp/http_request.hpp" #include "async_web_server_cpp/http_connection.hpp" @@ -71,6 +73,6 @@ class Vp8StreamerType : public LibavStreamerType rclcpp::Node::SharedPtr node); }; -} +} // namespace web_video_server -#endif +#endif // WEB_VIDEO_SERVER__VP8_STREAMER_HPP_ diff --git a/include/web_video_server/vp9_streamer.hpp b/include/web_video_server/vp9_streamer.hpp index 19208cc..d3701f9 100644 --- a/include/web_video_server/vp9_streamer.hpp +++ b/include/web_video_server/vp9_streamer.hpp @@ -1,7 +1,7 @@ -#ifndef VP9_STREAMERS_H_ -#define VP9_STREAMERS_H_ +#ifndef WEB_VIDEO_SERVER__VP9_STREAMER_HPP_ +#define WEB_VIDEO_SERVER__VP9_STREAMER_HPP_ -#include +#include "image_transport/image_transport.hpp" #include "web_video_server/libav_streamer.hpp" #include "async_web_server_cpp/http_request.hpp" #include "async_web_server_cpp/http_connection.hpp" @@ -32,6 +32,6 @@ class Vp9StreamerType : public LibavStreamerType rclcpp::Node::SharedPtr node); }; -} +} // namespace web_video_server -#endif +#endif // WEB_VIDEO_SERVER__VP9_STREAMER_HPP_ diff --git a/include/web_video_server/web_video_server.hpp b/include/web_video_server/web_video_server.hpp index a0a5be9..e5bec31 100644 --- a/include/web_video_server/web_video_server.hpp +++ b/include/web_video_server/web_video_server.hpp @@ -1,15 +1,17 @@ -#ifndef WEB_VIDEO_SERVER_H_ -#define WEB_VIDEO_SERVER_H_ +#ifndef WEB_VIDEO_SERVER__WEB_VIDEO_SERVER_HPP_ +#define WEB_VIDEO_SERVER__WEB_VIDEO_SERVER_HPP_ -#include +#include +#include +#include #ifdef CV_BRIDGE_USES_OLD_HEADERS -#include +#include "cv_bridge/cv_bridge.h" #else -#include +#include "cv_bridge/cv_bridge.hpp" #endif -#include +#include "rclcpp/rclcpp.hpp" #include "web_video_server/image_streamer.hpp" #include "async_web_server_cpp/http_server.hpp" #include "async_web_server_cpp/http_request.hpp" @@ -29,7 +31,7 @@ class WebVideoServer * @brief Constructor * @return */ - WebVideoServer(rclcpp::Node::SharedPtr & node); + explicit WebVideoServer(rclcpp::Node::SharedPtr & node); /** * @brief Destructor - Cleans up @@ -91,6 +93,6 @@ class WebVideoServer boost::mutex subscriber_mutex_; }; -} +} // namespace web_video_server -#endif +#endif // WEB_VIDEO_SERVER__WEB_VIDEO_SERVER_HPP_ diff --git a/src/h264_streamer.cpp b/src/h264_streamer.cpp index 7a889ec..bc0cfad 100644 --- a/src/h264_streamer.cpp +++ b/src/h264_streamer.cpp @@ -48,4 +48,4 @@ boost::shared_ptr H264StreamerType::create_streamer( return boost::shared_ptr(new H264Streamer(request, connection, node)); } -} +} // namespace web_video_server diff --git a/src/image_streamer.cpp b/src/image_streamer.cpp index 1347759..f61b6b5 100644 --- a/src/image_streamer.cpp +++ b/src/image_streamer.cpp @@ -88,7 +88,8 @@ 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_); - sendImage(output_size_image, node_->now() ); // don't update last_frame, it may remain an old value. + // don't update last_frame, it may remain an old value. + sendImage(output_size_image, node_->now()); } } catch (boost::system::system_error & e) { // happens when client disconnects @@ -148,7 +149,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 + boost::mutex::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_); @@ -193,4 +194,4 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::msg::Image::C } } -} +} // namespace web_video_server diff --git a/src/jpeg_streamers.cpp b/src/jpeg_streamers.cpp index 0187991..502e346 100644 --- a/src/jpeg_streamers.cpp +++ b/src/jpeg_streamers.cpp @@ -17,7 +17,7 @@ MjpegStreamer::MjpegStreamer( MjpegStreamer::~MjpegStreamer() { this->inactive_ = true; - boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. + boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. } void MjpegStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time) @@ -61,7 +61,7 @@ JpegSnapshotStreamer::JpegSnapshotStreamer( JpegSnapshotStreamer::~JpegSnapshotStreamer() { this->inactive_ = true; - boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. + boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. } void JpegSnapshotStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time) @@ -74,7 +74,7 @@ void JpegSnapshotStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & t cv::imencode(".jpeg", img, encoded_buffer, encode_params); char stamp[20]; - sprintf(stamp, "%.06lf", time.seconds()); + snprintf(stamp, sizeof(stamp), "%.06lf", time.seconds()); async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok) .header("Connection", "close") .header("Server", "web_video_server") @@ -91,4 +91,4 @@ void JpegSnapshotStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & t inactive_ = true; } -} +} // namespace web_video_server diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index 22fc2af..e1d5c93 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -1,7 +1,7 @@ #include "web_video_server/libav_streamer.hpp" #include "async_web_server_cpp/http_reply.hpp" -/*https://stackoverflow.com/questions/46884682/error-in-building-opencv-with-ffmpeg*/ +// 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 @@ -54,7 +54,7 @@ static int dispatch_output_packet(void * opaque, uint8_t * buffer, int buffer_si std::vector encoded_frame; encoded_frame.assign(buffer, buffer + buffer_size); connection->write_and_clear(encoded_frame); - return 0; // TODO: can this fail? + return 0; // TODO: can this fail? } void LibavStreamer::initialize(const cv::Mat & img) @@ -90,7 +90,7 @@ void LibavStreamer::initialize(const cv::Mat & img) format_context_->max_interleave_delta = 0; // Load codec - if (codec_name_.empty()) { // use default codec if none specified + if (codec_name_.empty()) { // use default codec if none specified codec_ = avcodec_find_encoder(format_context_->oformat->video_codec); } else { codec_ = avcodec_find_encoder_by_name(codec_name_.c_str()); @@ -291,4 +291,4 @@ std::string LibavStreamerType::create_viewer(const async_web_server_cpp::HttpReq return ss.str(); } -} +} // namespace web_video_server diff --git a/src/multipart_stream.cpp b/src/multipart_stream.cpp index ea1dc4c..bd77d98 100644 --- a/src/multipart_stream.cpp +++ b/src/multipart_stream.cpp @@ -32,7 +32,7 @@ void MultipartStream::sendPartHeader( size_t payload_size) { char stamp[20]; - sprintf(stamp, "%.06lf", time.seconds()); + snprintf(stamp, sizeof(stamp), "%.06lf", time.seconds()); std::shared_ptr> headers( new std::vector()); headers->push_back(async_web_server_cpp::HttpHeader("Content-type", type)); @@ -95,4 +95,4 @@ bool MultipartStream::isBusy() return !(max_queue_size_ == 0 || pending_footers_.size() < max_queue_size_); } -} +} // namespace web_video_server diff --git a/src/png_streamers.cpp b/src/png_streamers.cpp index 9fb4e56..64cdf7b 100644 --- a/src/png_streamers.cpp +++ b/src/png_streamers.cpp @@ -17,7 +17,7 @@ PngStreamer::PngStreamer( PngStreamer::~PngStreamer() { this->inactive_ = true; - boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. + boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. } void PngStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time) @@ -61,7 +61,7 @@ PngSnapshotStreamer::PngSnapshotStreamer( PngSnapshotStreamer::~PngSnapshotStreamer() { this->inactive_ = true; - boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. + boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. } void PngSnapshotStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time) @@ -74,7 +74,7 @@ void PngSnapshotStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & ti cv::imencode(".png", img, encoded_buffer, encode_params); char stamp[20]; - sprintf(stamp, "%.06lf", time.seconds()); + snprintf(stamp, sizeof(stamp), "%.06lf", time.seconds()); async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok) .header("Connection", "close") .header("Server", "web_video_server") @@ -91,4 +91,4 @@ void PngSnapshotStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & ti inactive_ = true; } -} +} // namespace web_video_server diff --git a/src/ros_compressed_streamer.cpp b/src/ros_compressed_streamer.cpp index 9e6322a..7d7dfc3 100644 --- a/src/ros_compressed_streamer.cpp +++ b/src/ros_compressed_streamer.cpp @@ -15,7 +15,7 @@ RosCompressedStreamer::RosCompressedStreamer( RosCompressedStreamer::~RosCompressedStreamer() { this->inactive_ = true; - boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. + boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. } void RosCompressedStreamer::start() @@ -52,7 +52,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_); - sendImage(last_msg, node_->now() ); // don't update last_frame, it may remain an old value. + sendImage(last_msg, node_->now() ); // don't update last_frame, it may remain an old value. } } @@ -98,7 +98,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 + boost::mutex::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); @@ -123,5 +123,4 @@ std::string RosCompressedStreamerType::create_viewer( return ss.str(); } - -} +} // namespace web_video_server diff --git a/src/vp8_streamer.cpp b/src/vp8_streamer.cpp index 846f983..89fbf51 100644 --- a/src/vp8_streamer.cpp +++ b/src/vp8_streamer.cpp @@ -69,7 +69,7 @@ void Vp8Streamer::initializeEncoder() // Buffering settings int bufsize = 10; codec_context_->rc_buffer_size = bufsize; - codec_context_->rc_initial_buffer_occupancy = bufsize; //bitrate/3; + codec_context_->rc_initial_buffer_occupancy = bufsize; // bitrate/3; 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); @@ -89,4 +89,4 @@ boost::shared_ptr Vp8StreamerType::create_streamer( return boost::shared_ptr(new Vp8Streamer(request, connection, node)); } -} +} // namespace web_video_server diff --git a/src/vp9_streamer.cpp b/src/vp9_streamer.cpp index 4b37067..907a14e 100644 --- a/src/vp9_streamer.cpp +++ b/src/vp9_streamer.cpp @@ -15,7 +15,6 @@ 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); @@ -37,4 +36,4 @@ boost::shared_ptr Vp9StreamerType::create_streamer( return boost::shared_ptr(new Vp9Streamer(request, connection, node)); } -} +} // namespace web_video_server diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 2647746..d7ef162 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -1,12 +1,14 @@ +#include "web_video_server/web_video_server.hpp" + +#include +#include + #include #include #include -#include -#include -#include #include -#include "web_video_server/web_video_server.hpp" +#include "sensor_msgs/image_encodings.hpp" #include "web_video_server/ros_compressed_streamer.hpp" #include "web_video_server/jpeg_streamers.hpp" #include "web_video_server/png_streamers.hpp" @@ -16,7 +18,7 @@ #include "async_web_server_cpp/http_reply.hpp" using namespace std::chrono_literals; -using namespace boost::placeholders; +using namespace boost::placeholders; // NOLINT namespace web_video_server { @@ -216,7 +218,6 @@ bool WebVideoServer::handle_stream_viewer( 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"; auto tnat = node_->get_topic_names_and_types(); bool did_find_compressed_topic = false; @@ -355,7 +356,7 @@ bool WebVideoServer::handle_list_streams( return true; } -} +} // namespace web_video_server int main(int argc, char ** argv) {