diff --git a/CMakeLists.txt b/CMakeLists.txt index ccf5a9b..cd0aceb 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,6 +1,10 @@ cmake_minimum_required(VERSION 3.5) project(web_video_server) +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + find_package(ament_cmake_ros REQUIRED) find_package(async_web_server_cpp REQUIRED) diff --git a/src/image_streamer.cpp b/src/image_streamer.cpp index 8a83958..564e1dc 100644 --- a/src/image_streamer.cpp +++ b/src/image_streamer.cpp @@ -44,7 +44,7 @@ namespace web_video_server ImageStreamer::ImageStreamer( const async_web_server_cpp::HttpRequest & request, async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node) -: request_(request), connection_(connection), node_(node), inactive_(false) +: connection_(connection), request_(request), node_(node), inactive_(false) { topic_ = request.get_query_param_value_or_default("topic", ""); } diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index 4814c4e..62f293f 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -44,9 +44,9 @@ LibavStreamer::LibavStreamer( const std::string & format_name, const std::string & codec_name, const std::string & content_type) : ImageTransportImageStreamer(request, connection, node), format_context_(0), codec_(0), - codec_context_(0), video_stream_(0), frame_(0), sws_context_(0), + codec_context_(0), video_stream_(0), opt_(0), frame_(0), sws_context_(0), first_image_received_(false), first_image_time_(), format_name_(format_name), - codec_name_(codec_name), content_type_(content_type), opt_(0), io_buffer_(0) + codec_name_(codec_name), content_type_(content_type), io_buffer_(0) { bitrate_ = request.get_query_param_value_or_default("bitrate", 100000); qmin_ = request.get_query_param_value_or_default("qmin", 10); @@ -87,7 +87,7 @@ static int dispatch_output_packet(void * opaque, uint8_t * buffer, int buffer_si return 0; } -void LibavStreamer::initialize(const cv::Mat & img) +void LibavStreamer::initialize(const cv::Mat & /* img */) { // Load format format_context_ = avformat_alloc_context(); @@ -274,9 +274,6 @@ void LibavStreamer::sendImage( } if (got_packet) { - std::size_t size; - uint8_t * output_buf; - double seconds = std::chrono::duration_cast>( time - first_image_time_).count(); // Encode video at 1/0.95 to minimize delay diff --git a/src/multipart_stream.cpp b/src/multipart_stream.cpp index b26d229..0429272 100644 --- a/src/multipart_stream.cpp +++ b/src/multipart_stream.cpp @@ -38,7 +38,7 @@ 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) +: max_queue_size_(max_queue_size), connection_(connection), boundry_(boundry) {} void MultipartStream::sendInitialHeader() diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 5f548c3..24db2fb 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -212,8 +212,8 @@ bool WebVideoServer::handle_stream( bool WebVideoServer::handle_snapshot( const async_web_server_cpp::HttpRequest & request, - async_web_server_cpp::HttpConnectionPtr connection, const char * begin, - const char * end) + async_web_server_cpp::HttpConnectionPtr connection, const char * /* begin */, + const char * /* end */) { std::shared_ptr streamer = std::make_shared( request, connection, shared_from_this()); @@ -278,9 +278,9 @@ bool WebVideoServer::handle_stream_viewer( } bool WebVideoServer::handle_list_streams( - const async_web_server_cpp::HttpRequest & request, - async_web_server_cpp::HttpConnectionPtr connection, const char * begin, - const char * end) + const async_web_server_cpp::HttpRequest & /* request */, + async_web_server_cpp::HttpConnectionPtr connection, const char * /* begin */, + const char * /* end */) { std::vector image_topics; std::vector camera_info_topics;