Skip to content

Commit

Permalink
Add compiler flags (#19)
Browse files Browse the repository at this point in the history
Add some explicit casts & remove some variable name shadowing
  • Loading branch information
roncapat authored Apr 16, 2024
1 parent 293a6dc commit 87ba723
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 6 deletions.
2 changes: 2 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
6 changes: 4 additions & 2 deletions src/NavMsgOccupancyGrid_CvMat.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,8 @@ void rclcpp::TypeAdapter<StampedOccupancyGrid_CV,
destination.data.resize(source.mat.rows * source.mat.cols);
for (int y = 0; y < source.mat.rows; ++y) {
for (int x = 0; x < source.mat.cols; ++x) {
destination.data[y * source.mat.cols + x] = source.mat.at<uint8_t>(y, x) - 1;
destination.data[y * source.mat.cols + x] =
static_cast<int8_t>(source.mat.at<uint8_t>(y, x) - 1);
}
}
destination.header = source.header;
Expand All @@ -67,7 +68,8 @@ void rclcpp::TypeAdapter<StampedOccupancyGrid_CV, nav_msgs::msg::OccupancyGrid>:
cv::Mat(source.info.height, source.info.width, CV_MAKETYPE(cv::DataType<uint8_t>::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<uint8_t>(y, x) = source.data[y * source.info.width + x] + 1;
destination.mat.at<uint8_t>(y, x) =
static_cast<uint8_t>(source.data[y * source.info.width + x] + 1);
}
}
destination.header = source.header;
Expand Down
8 changes: 4 additions & 4 deletions src/SensorMsgPointCloud2_PCLPointCloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<decltype(cloud)>::PointType;
[](auto && _cloud) {
using T = typename std::decay_t<decltype(_cloud)>::PointType;
return pcl::traits::has_color_v<T>;
}, cloud);
}
Expand Down

0 comments on commit 87ba723

Please sign in to comment.