Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix compile warnings #176

Merged
merged 6 commits into from
Dec 26, 2024
Merged
Show file tree
Hide file tree
Changes from 4 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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 -Werror)
endif()

find_package(ament_cmake_ros REQUIRED)

find_package(async_web_server_cpp REQUIRED)
Expand Down
2 changes: 1 addition & 1 deletion src/image_streamer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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", "");
}
Expand Down
8 changes: 3 additions & 5 deletions src/libav_streamer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<int>("bitrate", 100000);
qmin_ = request.get_query_param_value_or_default<int>("qmin", 10);
Expand Down Expand Up @@ -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();
Expand Down Expand Up @@ -274,8 +274,6 @@ void LibavStreamer::sendImage(
}

if (got_packet) {
std::size_t size;
uint8_t * output_buf;

Mat198 marked this conversation as resolved.
Show resolved Hide resolved
double seconds = std::chrono::duration_cast<std::chrono::duration<double>>(
time - first_image_time_).count();
Expand Down
2 changes: 1 addition & 1 deletion src/multipart_stream.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down
10 changes: 5 additions & 5 deletions src/web_video_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<ImageStreamer> streamer = std::make_shared<JpegSnapshotStreamer>(
request, connection, shared_from_this());
Expand Down Expand Up @@ -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<std::string> image_topics;
std::vector<std::string> camera_info_topics;
Expand Down
Loading