Skip to content

Commit

Permalink
Fix Wshadow errors and enforce it (#3617)
Browse files Browse the repository at this point in the history
* Fix Wshadow errors and enforce it

Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>

* Remove workaround for pluginlib

* This was only needed because it was included transitively
* By finding and linking properly, the compiler flags get propogated as SYSTEM
  correctly

Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>

---------

Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
  • Loading branch information
Ryanf55 authored and SteveMacenski committed Aug 4, 2023
1 parent cd5246d commit 5468d2a
Show file tree
Hide file tree
Showing 11 changed files with 46 additions and 47 deletions.
4 changes: 2 additions & 2 deletions nav2_amcl/src/pf/eig3.c
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ static void tred2(double V[n][n], double d[n], double e[n])
// Fortran subroutine in EISPACK.

int i, j, k;
double f, g, h, hh;
double f, g, hh;
for (j = 0; j < n; j++) {
d[j] = V[n - 1][j];
}
Expand Down Expand Up @@ -122,7 +122,7 @@ static void tred2(double V[n][n], double d[n], double e[n])
for (i = 0; i < n - 1; i++) {
V[n - 1][i] = V[i][i];
V[i][i] = 1.0;
h = d[i + 1];
const double h = d[i + 1];
if (h != 0.0) {
for (k = 0; k <= i; k++) {
d[k] = V[k][i + 1] / h;
Expand Down
2 changes: 1 addition & 1 deletion nav2_common/cmake/nav2_package.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ macro(nav2_package)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic -Werror -Wdeprecated -fPIC )
add_compile_options(-Wall -Wextra -Wpedantic -Werror -Wdeprecated -fPIC -Wshadow)
add_compile_options("$<$<COMPILE_LANGUAGE:CXX>:-Wnon-virtual-dtor>")
endif()

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -194,8 +194,8 @@ class Smoother
// update cusp zone costmap weights
if (is_cusp) {
double len_to_cusp = current_segment_len;
for (int i = potential_cusp_funcs.size() - 1; i >= 0; i--) {
auto & f = potential_cusp_funcs[i];
for (int i_cusp = potential_cusp_funcs.size() - 1; i_cusp >= 0; i_cusp--) {
auto & f = potential_cusp_funcs[i_cusp];
double new_weight =
params.cusp_costmap_weight * (1.0 - len_to_cusp / cusp_half_length) +
params.costmap_weight * len_to_cusp / cusp_half_length;
Expand Down
4 changes: 2 additions & 2 deletions nav2_costmap_2d/plugins/denoise_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -171,12 +171,12 @@ DenoiseLayer::removeSinglePixels(Image<uint8_t> & image) const
return v == NO_INFORMATION ? FREE_SPACE : v;
};
auto max = [&](const std::initializer_list<uint8_t> lst) {
std::array<uint8_t, 3> buf = {
std::array<uint8_t, 3> rbuf = {
replace_to_free(*lst.begin()),
replace_to_free(*(lst.begin() + 1)),
replace_to_free(*(lst.begin() + 2))
};
return *std::max_element(buf.begin(), buf.end());
return *std::max_element(rbuf.begin(), rbuf.end());
};
dilate(image, max_neighbors_image, group_connectivity_type_, max);
} else {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -73,8 +73,8 @@ class DummyFootprintSubscriber : public nav2_costmap_2d::FootprintSubscriber
DummyFootprintSubscriber(
nav2_util::LifecycleNode::SharedPtr node,
std::string & topic_name,
tf2_ros::Buffer & tf_)
: FootprintSubscriber(node, topic_name, tf_)
tf2_ros::Buffer & tf)
: FootprintSubscriber(node, topic_name, tf)
{}

void setFootprint(geometry_msgs::msg::PolygonStamped::SharedPtr msg)
Expand Down
4 changes: 2 additions & 2 deletions nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -526,8 +526,8 @@ DWBLocalPlanner::transformGlobalPlan(
// from the robot using integrated distance
auto transformation_end = std::find_if(
transformation_begin, global_plan_.poses.end(),
[&](const auto & pose) {
return euclidean_distance(pose, robot_pose.pose) > transform_end_threshold;
[&](const auto & global_plan_pose) {
return euclidean_distance(global_plan_pose, robot_pose.pose) > transform_end_threshold;
});

// Transform the near part of the global plan into the robot's frame of reference.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -105,8 +105,7 @@ TEST(ObstacleFootprint, GetOrientedFootprint)
pose.theta = theta;
footprint_after = dwb_critics::getOrientedFootprint(pose, footprint_before);

uint i;
for (i = 0; i < footprint_before.size(); i++) {
for (uint i = 0; i < footprint_before.size(); i++) {
ASSERT_EQ(rotate_origin(footprint_before[i], theta), footprint_after[i]);
}

Expand Down
58 changes: 28 additions & 30 deletions nav2_navfn_planner/src/navfn.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -421,11 +421,10 @@ inline void
NavFn::updateCell(int n)
{
// get neighbors
float u, d, l, r;
l = potarr[n - 1];
r = potarr[n + 1];
u = potarr[n - nx];
d = potarr[n + nx];
const float l = potarr[n - 1];
const float r = potarr[n + 1];
const float u = potarr[n - nx];
const float d = potarr[n + nx];
// ROS_INFO("[Update] c: %0.1f l: %0.1f r: %0.1f u: %0.1f d: %0.1f\n",
// potarr[n], l, r, u, d);
// ROS_INFO("[Update] cost: %d\n", costarr[n]);
Expand All @@ -452,8 +451,8 @@ NavFn::updateCell(int n)
// use quadratic approximation
// might speed this up through table lookup, but still have to
// do the divide
float d = dc / hf;
float v = -0.2301 * d * d + 0.5307 * d + 0.7040;
const float div = dc / hf;
const float v = -0.2301 * div * div + 0.5307 * div + 0.7040;
pot = ta + hf * v;
}

Expand Down Expand Up @@ -496,11 +495,10 @@ inline void
NavFn::updateCellAstar(int n)
{
// get neighbors
float u, d, l, r;
l = potarr[n - 1];
r = potarr[n + 1];
u = potarr[n - nx];
d = potarr[n + nx];
float l = potarr[n - 1];
float r = potarr[n + 1];
float u = potarr[n - nx];
float d = potarr[n + nx];
// ROS_INFO("[Update] c: %0.1f l: %0.1f r: %0.1f u: %0.1f d: %0.1f\n",
// potarr[n], l, r, u, d);
// ROS_INFO("[Update] cost of %d: %d\n", n, costarr[n]);
Expand All @@ -527,8 +525,8 @@ NavFn::updateCellAstar(int n)
// use quadratic approximation
// might speed this up through table lookup, but still have to
// do the divide
float d = dc / hf;
float v = -0.2301 * d * d + 0.5307 * d + 0.7040;
const float div = dc / hf;
const float v = -0.2301 * div * div + 0.5307 * div + 0.7040;
pot = ta + hf * v;
}

Expand Down Expand Up @@ -834,22 +832,22 @@ NavFn::calcPath(int n, int * st)
// check eight neighbors to find the lowest
int minc = stc;
int minp = potarr[stc];
int st = stcpx - 1;
if (potarr[st] < minp) {minp = potarr[st]; minc = st;}
st++;
if (potarr[st] < minp) {minp = potarr[st]; minc = st;}
st++;
if (potarr[st] < minp) {minp = potarr[st]; minc = st;}
st = stc - 1;
if (potarr[st] < minp) {minp = potarr[st]; minc = st;}
st = stc + 1;
if (potarr[st] < minp) {minp = potarr[st]; minc = st;}
st = stcnx - 1;
if (potarr[st] < minp) {minp = potarr[st]; minc = st;}
st++;
if (potarr[st] < minp) {minp = potarr[st]; minc = st;}
st++;
if (potarr[st] < minp) {minp = potarr[st]; minc = st;}
int sti = stcpx - 1;
if (potarr[sti] < minp) {minp = potarr[sti]; minc = sti;}
sti++;
if (potarr[sti] < minp) {minp = potarr[sti]; minc = sti;}
sti++;
if (potarr[sti] < minp) {minp = potarr[sti]; minc = sti;}
sti = stc - 1;
if (potarr[sti] < minp) {minp = potarr[sti]; minc = sti;}
sti = stc + 1;
if (potarr[sti] < minp) {minp = potarr[sti]; minc = sti;}
sti = stcnx - 1;
if (potarr[sti] < minp) {minp = potarr[sti]; minc = sti;}
sti++;
if (potarr[sti] < minp) {minp = potarr[sti]; minc = sti;}
sti++;
if (potarr[sti] < minp) {minp = potarr[sti]; minc = sti;}
stc = minc;
dx = 0;
dy = 0;
Expand Down
4 changes: 2 additions & 2 deletions nav2_regulated_pure_pursuit_controller/src/path_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,8 +77,8 @@ nav_msgs::msg::Path PathHandler::transformGlobalPlan(
const double max_costmap_extent = getCostmapMaxExtent();
auto transformation_end = std::find_if(
transformation_begin, global_plan_.poses.end(),
[&](const auto & pose) {
return euclidean_distance(pose, robot_pose) > max_costmap_extent;
[&](const auto & global_plan_pose) {
return euclidean_distance(global_plan_pose, robot_pose) > max_costmap_extent;
});

// Lambda to transform a PoseStamped from global frame to local
Expand Down
4 changes: 2 additions & 2 deletions nav2_smoother/test/test_smoother_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -158,8 +158,8 @@ class DummyFootprintSubscriber : public nav2_costmap_2d::FootprintSubscriber
DummyFootprintSubscriber(
nav2_util::LifecycleNode::SharedPtr node,
const std::string & topic_name,
tf2_ros::Buffer & tf_)
: FootprintSubscriber(node, topic_name, tf_)
tf2_ros::Buffer & tf)
: FootprintSubscriber(node, topic_name, tf)
{
auto footprint = std::make_shared<geometry_msgs::msg::PolygonStamped>();
footprint->header.frame_id = "base_link"; // global frame = robot frame to avoid tf lookup
Expand Down
2 changes: 2 additions & 0 deletions nav2_system_tests/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ find_package(nav2_planner REQUIRED)
find_package(navigation2)
find_package(angles REQUIRED)
find_package(behaviortree_cpp_v3 REQUIRED)
find_package(pluginlib REQUIRED)

nav2_package()

Expand All @@ -45,6 +46,7 @@ set(dependencies
nav2_navfn_planner
angles
behaviortree_cpp_v3
pluginlib
)

set(local_controller_plugin_lib local_controller)
Expand Down

0 comments on commit 5468d2a

Please sign in to comment.