From 87ba72365a0f2993a1282c78961775892378b6b0 Mon Sep 17 00:00:00 2001 From: Patrick Roncagliolo Date: Tue, 16 Apr 2024 11:33:34 +0200 Subject: [PATCH] Add compiler flags (#19) Add some explicit casts & remove some variable name shadowing --- CMakeLists.txt | 2 ++ src/NavMsgOccupancyGrid_CvMat.cpp | 6 ++++-- src/SensorMsgPointCloud2_PCLPointCloud.cpp | 8 ++++---- 3 files changed, 10 insertions(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index be52d36..2d9fdc0 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,6 +3,8 @@ project(native_adapters) set(CMAKE_CXX_STANDARD 17) +add_compile_options(-Wall -Wextra -Wpedantic -Wconversion -Wdouble-promotion -Wfloat-equal -Wshadow) + find_package(std_msgs REQUIRED) find_package(sensor_msgs REQUIRED) find_package(nav_msgs REQUIRED) diff --git a/src/NavMsgOccupancyGrid_CvMat.cpp b/src/NavMsgOccupancyGrid_CvMat.cpp index e7ce6ce..0a7105f 100644 --- a/src/NavMsgOccupancyGrid_CvMat.cpp +++ b/src/NavMsgOccupancyGrid_CvMat.cpp @@ -50,7 +50,8 @@ void rclcpp::TypeAdapter(y, x) - 1; + destination.data[y * source.mat.cols + x] = + static_cast(source.mat.at(y, x) - 1); } } destination.header = source.header; @@ -67,7 +68,8 @@ void rclcpp::TypeAdapter: cv::Mat(source.info.height, source.info.width, CV_MAKETYPE(cv::DataType::type, 1)); for (unsigned int y = 0; y < source.info.height; ++y) { for (unsigned int x = 0; x < source.info.width; ++x) { - destination.mat.at(y, x) = source.data[y * source.info.width + x] + 1; + destination.mat.at(y, x) = + static_cast(source.data[y * source.info.width + x] + 1); } } destination.header = source.header; diff --git a/src/SensorMsgPointCloud2_PCLPointCloud.cpp b/src/SensorMsgPointCloud2_PCLPointCloud.cpp index 900239a..3560abf 100644 --- a/src/SensorMsgPointCloud2_PCLPointCloud.cpp +++ b/src/SensorMsgPointCloud2_PCLPointCloud.cpp @@ -35,20 +35,20 @@ StampedPointCloud_PCL & StampedPointCloud_PCL::operator=(const StampedPointCloud uint32_t StampedPointCloud_PCL::width() const { - return std::visit([](auto && cloud) {return cloud.width;}, cloud); + return std::visit([](auto && _cloud) {return _cloud.width;}, cloud); } uint32_t StampedPointCloud_PCL::height() const { - return std::visit([](auto && cloud) {return cloud.height;}, cloud); + return std::visit([](auto && _cloud) {return _cloud.height;}, cloud); } bool StampedPointCloud_PCL::has_colors() const { return std::visit( - [](auto && cloud) { - using T = typename std::decay_t::PointType; + [](auto && _cloud) { + using T = typename std::decay_t::PointType; return pcl::traits::has_color_v; }, cloud); }