Skip to content

Commit 29e684c

Browse files
Mat198mth_sousabjsowa
authored
Fix compile warnings (#176)
* [CHG] Enabling compile warnings Warnings enabled as errors * [CHG] Removing unused variables in functions * [CHG] Correcting initialization order * [CHG] Removing unused variables * [CHG] Removing -Werror flag * Update src/libav_streamer.cpp Co-authored-by: Błażej Sowa <[email protected]> --------- Co-authored-by: mth_sousa <[email protected]> Co-authored-by: Błażej Sowa <[email protected]>
1 parent 965ed73 commit 29e684c

File tree

5 files changed

+14
-13
lines changed

5 files changed

+14
-13
lines changed

CMakeLists.txt

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,10 @@
11
cmake_minimum_required(VERSION 3.5)
22
project(web_video_server)
33

4+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
5+
add_compile_options(-Wall -Wextra -Wpedantic)
6+
endif()
7+
48
find_package(ament_cmake_ros REQUIRED)
59

610
find_package(async_web_server_cpp REQUIRED)

src/image_streamer.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@ namespace web_video_server
4444
ImageStreamer::ImageStreamer(
4545
const async_web_server_cpp::HttpRequest & request,
4646
async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node)
47-
: request_(request), connection_(connection), node_(node), inactive_(false)
47+
: connection_(connection), request_(request), node_(node), inactive_(false)
4848
{
4949
topic_ = request.get_query_param_value_or_default("topic", "");
5050
}

src/libav_streamer.cpp

Lines changed: 3 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -44,9 +44,9 @@ LibavStreamer::LibavStreamer(
4444
const std::string & format_name, const std::string & codec_name,
4545
const std::string & content_type)
4646
: ImageTransportImageStreamer(request, connection, node), format_context_(0), codec_(0),
47-
codec_context_(0), video_stream_(0), frame_(0), sws_context_(0),
47+
codec_context_(0), video_stream_(0), opt_(0), frame_(0), sws_context_(0),
4848
first_image_received_(false), first_image_time_(), format_name_(format_name),
49-
codec_name_(codec_name), content_type_(content_type), opt_(0), io_buffer_(0)
49+
codec_name_(codec_name), content_type_(content_type), io_buffer_(0)
5050
{
5151
bitrate_ = request.get_query_param_value_or_default<int>("bitrate", 100000);
5252
qmin_ = request.get_query_param_value_or_default<int>("qmin", 10);
@@ -87,7 +87,7 @@ static int dispatch_output_packet(void * opaque, uint8_t * buffer, int buffer_si
8787
return 0;
8888
}
8989

90-
void LibavStreamer::initialize(const cv::Mat & img)
90+
void LibavStreamer::initialize(const cv::Mat & /* img */)
9191
{
9292
// Load format
9393
format_context_ = avformat_alloc_context();
@@ -274,9 +274,6 @@ void LibavStreamer::sendImage(
274274
}
275275

276276
if (got_packet) {
277-
std::size_t size;
278-
uint8_t * output_buf;
279-
280277
double seconds = std::chrono::duration_cast<std::chrono::duration<double>>(
281278
time - first_image_time_).count();
282279
// Encode video at 1/0.95 to minimize delay

src/multipart_stream.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@ MultipartStream::MultipartStream(
3838
async_web_server_cpp::HttpConnectionPtr & connection,
3939
const std::string & boundry,
4040
std::size_t max_queue_size)
41-
: connection_(connection), boundry_(boundry), max_queue_size_(max_queue_size)
41+
: max_queue_size_(max_queue_size), connection_(connection), boundry_(boundry)
4242
{}
4343

4444
void MultipartStream::sendInitialHeader()

src/web_video_server.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -212,8 +212,8 @@ bool WebVideoServer::handle_stream(
212212

213213
bool WebVideoServer::handle_snapshot(
214214
const async_web_server_cpp::HttpRequest & request,
215-
async_web_server_cpp::HttpConnectionPtr connection, const char * begin,
216-
const char * end)
215+
async_web_server_cpp::HttpConnectionPtr connection, const char * /* begin */,
216+
const char * /* end */)
217217
{
218218
std::shared_ptr<ImageStreamer> streamer = std::make_shared<JpegSnapshotStreamer>(
219219
request, connection, shared_from_this());
@@ -278,9 +278,9 @@ bool WebVideoServer::handle_stream_viewer(
278278
}
279279

280280
bool WebVideoServer::handle_list_streams(
281-
const async_web_server_cpp::HttpRequest & request,
282-
async_web_server_cpp::HttpConnectionPtr connection, const char * begin,
283-
const char * end)
281+
const async_web_server_cpp::HttpRequest & /* request */,
282+
async_web_server_cpp::HttpConnectionPtr connection, const char * /* begin */,
283+
const char * /* end */)
284284
{
285285
std::vector<std::string> image_topics;
286286
std::vector<std::string> camera_info_topics;

0 commit comments

Comments
 (0)