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

Fixes for nav2_smac_planner to build with -Werror. #4635

Merged
Show file tree
Hide file tree
Changes from all 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
2 changes: 2 additions & 0 deletions nav2_smac_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@ find_package(tf2 REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(visualization_msgs REQUIRED)

nav2_package()

if(MSVC)
add_compile_definitions(_USE_MATH_DEFINES)
else()
Expand Down
10 changes: 5 additions & 5 deletions nav2_smac_planner/include/nav2_smac_planner/constants.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,11 +59,11 @@ inline MotionModel fromString(const std::string & n)
}
}

const float UNKNOWN = 255.0;
const float OCCUPIED = 254.0;
const float INSCRIBED = 253.0;
const float MAX_NON_OBSTACLE = 252.0;
const float FREE = 0;
const float UNKNOWN_COST = 255.0;
const float OCCUPIED_COST = 254.0;
const float INSCRIBED_COST = 253.0;
const float MAX_NON_OBSTACLE_COST = 252.0;
const float FREE_COST = 0;

} // namespace nav2_smac_planner

Expand Down
6 changes: 3 additions & 3 deletions nav2_smac_planner/include/nav2_smac_planner/node_basic.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,9 @@ class NodeBasic
* @brief A constructor for nav2_smac_planner::NodeBasic
* @param index The index of this node for self-reference
*/
explicit NodeBasic(const uint64_t index)
: index(index),
graph_node_ptr(nullptr)
explicit NodeBasic(const uint64_t new_index)
: graph_node_ptr(nullptr),
index(new_index)
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ static Counts& counts() {
# pragma intrinsic(ROBIN_HOOD(BITSCANFORWARD))
# define ROBIN_HOOD_COUNT_TRAILING_ZEROES(x) \
[](size_t mask) noexcept -> int { \
unsigned long index; // NOLINT \
unsigned long index; \ // NOLINT
return ROBIN_HOOD(BITSCANFORWARD)(&index, mask) ? static_cast<int>(index) \
: ROBIN_HOOD(BITNESS); \
}(x)
Expand Down
2 changes: 1 addition & 1 deletion nav2_smac_planner/include/nav2_smac_planner/types.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ struct SmootherParams
* @struct nav2_smac_planner::TurnDirection
* @brief A struct with the motion primitive's direction embedded
*/
enum struct TurnDirection
enum class TurnDirection
{
UNKNOWN = 0,
FORWARD = 1,
Expand Down
20 changes: 10 additions & 10 deletions nav2_smac_planner/src/analytic_expansion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -337,28 +337,28 @@ void AnalyticExpansion<NodeT>::cleanNode(const NodePtr & /*expanded_nodes*/)
template<>
typename AnalyticExpansion<Node2D>::AnalyticExpansionNodes AnalyticExpansion<Node2D>::
getAnalyticPath(
const NodePtr & node,
const NodePtr & goal,
const NodeGetter & node_getter,
const ompl::base::StateSpacePtr & state_space)
const NodePtr &,
const NodePtr &,
const NodeGetter &,
const ompl::base::StateSpacePtr &)
{
return AnalyticExpansionNodes();
}

template<>
typename AnalyticExpansion<Node2D>::NodePtr AnalyticExpansion<Node2D>::setAnalyticPath(
const NodePtr & node,
const NodePtr & goal_node,
const AnalyticExpansionNodes & expanded_nodes)
const NodePtr &,
const NodePtr &,
const AnalyticExpansionNodes &)
{
return NodePtr(nullptr);
}

template<>
typename AnalyticExpansion<Node2D>::NodePtr AnalyticExpansion<Node2D>::tryAnalyticExpansion(
const NodePtr & current_node, const NodePtr & goal_node,
const NodeGetter & getter, int & analytic_iterations,
int & closest_distance)
const NodePtr &, const NodePtr &,
const NodeGetter &, int &,
int &)
{
return NodePtr(nullptr);
}
Expand Down
16 changes: 8 additions & 8 deletions nav2_smac_planner/src/collision_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,11 +130,11 @@ bool GridCollisionChecker::inCollision(

// If its inscribed, in collision, or unknown in the middle,
// no need to even check the footprint, its invalid
if (footprint_cost_ == UNKNOWN && !traverse_unknown) {
if (footprint_cost_ == UNKNOWN_COST && !traverse_unknown) {
return true;
}

if (footprint_cost_ == INSCRIBED || footprint_cost_ == OCCUPIED) {
if (footprint_cost_ == INSCRIBED_COST || footprint_cost_ == OCCUPIED_COST) {
return true;
}

Expand All @@ -153,23 +153,23 @@ bool GridCollisionChecker::inCollision(

footprint_cost_ = static_cast<float>(footprintCost(current_footprint));

if (footprint_cost_ == UNKNOWN && traverse_unknown) {
if (footprint_cost_ == UNKNOWN_COST && traverse_unknown) {
return false;
}

// if occupied or unknown and not to traverse unknown space
return footprint_cost_ >= OCCUPIED;
return footprint_cost_ >= OCCUPIED_COST;
} else {
// if radius, then we can check the center of the cost assuming inflation is used
footprint_cost_ = static_cast<float>(costmap_->getCost(
static_cast<unsigned int>(x + 0.5f), static_cast<unsigned int>(y + 0.5f)));

if (footprint_cost_ == UNKNOWN && traverse_unknown) {
if (footprint_cost_ == UNKNOWN_COST && traverse_unknown) {
return false;
}

// if occupied or unknown and not to traverse unknown space
return footprint_cost_ >= INSCRIBED;
return footprint_cost_ >= INSCRIBED_COST;
}
}

Expand All @@ -178,12 +178,12 @@ bool GridCollisionChecker::inCollision(
const bool & traverse_unknown)
{
footprint_cost_ = costmap_->getCost(i);
if (footprint_cost_ == UNKNOWN && traverse_unknown) {
if (footprint_cost_ == UNKNOWN_COST && traverse_unknown) {
return false;
}

// if occupied or unknown and not to traverse unknown space
return footprint_cost_ >= INSCRIBED;
return footprint_cost_ >= INSCRIBED_COST;
}

float GridCollisionChecker::getCost()
Expand Down
2 changes: 1 addition & 1 deletion nav2_smac_planner/src/costmap_downsampler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ void CostmapDownsampler::on_configure(

_downsampled_costmap = std::make_unique<nav2_costmap_2d::Costmap2D>(
_downsampled_size_x, _downsampled_size_y, _downsampled_resolution,
_costmap->getOriginX(), _costmap->getOriginY(), UNKNOWN);
_costmap->getOriginX(), _costmap->getOriginY(), UNKNOWN_COST);

if (!node.expired()) {
_downsampled_costmap_pub = std::make_unique<nav2_costmap_2d::Costmap2DPublisher>(
Expand Down
4 changes: 2 additions & 2 deletions nav2_smac_planner/src/node_2d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,15 +128,15 @@ void Node2D::getNeighbors(
uint64_t index;
NodePtr neighbor;
uint64_t node_i = this->getIndex();
const Coordinates parent = getCoords(this->getIndex());
const Coordinates coord_parent = getCoords(this->getIndex());
Coordinates child;

for (unsigned int i = 0; i != _neighbors_grid_offsets.size(); ++i) {
index = node_i + _neighbors_grid_offsets[i];

// Check for wrap around conditions
child = getCoords(index);
if (fabs(parent.x - child.x) > 1 || fabs(parent.y - child.y) > 1) {
if (fabs(coord_parent.x - child.x) > 1 || fabs(coord_parent.y - child.y) > 1) {
continue;
}

Expand Down
30 changes: 15 additions & 15 deletions nav2_smac_planner/src/node_hybrid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -169,9 +169,9 @@
const TurnDirection turn_dir = projections[i]._turn_dir;
if (turn_dir != TurnDirection::FORWARD && turn_dir != TurnDirection::REVERSE) {
// Turning, so length is the arc length
const float angle = projections[i]._theta * bin_size;
const float turning_rad = delta_dist / (2.0f * sin(angle / 2.0f));
travel_costs[i] = turning_rad * angle;
const float arc_angle = projections[i]._theta * bin_size;
const float turning_rad = delta_dist / (2.0f * sin(arc_angle / 2.0f));
travel_costs[i] = turning_rad * arc_angle;
} else {
travel_costs[i] = delta_dist;
}
Expand Down Expand Up @@ -290,9 +290,9 @@
const TurnDirection turn_dir = projections[i]._turn_dir;
if (turn_dir != TurnDirection::FORWARD && turn_dir != TurnDirection::REVERSE) {
// Turning, so length is the arc length
const float angle = projections[i]._theta * bin_size;
const float turning_rad = delta_dist / (2.0f * sin(angle / 2.0f));
travel_costs[i] = turning_rad * angle;
const float arc_angle = projections[i]._theta * bin_size;
const float turning_rad = delta_dist / (2.0f * sin(arc_angle / 2.0f));
travel_costs[i] = turning_rad * arc_angle;
} else {
travel_costs[i] = delta_dist;
}
Expand All @@ -305,11 +305,11 @@
projection_list.reserve(projections.size());

for (unsigned int i = 0; i != projections.size(); i++) {
const MotionPose & motion_model = projections[i];
const MotionPose & proj_motion_model = projections[i];

// normalize theta, I know its overkill, but I've been burned before...
const float & node_heading = node->pose.theta;
float new_heading = node_heading + motion_model._theta;
float new_heading = node_heading + proj_motion_model._theta;

if (new_heading < 0.0) {
new_heading += num_angle_quantization_float;
Expand All @@ -322,7 +322,7 @@
projection_list.emplace_back(
delta_xs[i][node_heading] + node->pose.x,
delta_ys[i][node_heading] + node->pose.y,
new_heading, motion_model._turn_dir);
new_heading, proj_motion_model._turn_dir);
}

return projection_list;
Expand Down Expand Up @@ -564,7 +564,7 @@

float NodeHybrid::getObstacleHeuristic(
const Coordinates & node_coords,
const Coordinates & goal_coords,
const Coordinates &,
const float & cost_penalty)
{
// If already expanded, return the cost
Expand Down Expand Up @@ -651,8 +651,8 @@
unsigned int y_offset = (new_idx / size_x) * 2;
unsigned int x_offset = (new_idx - ((new_idx / size_x) * size_x)) * 2;
cost = costmap->getCost(x_offset, y_offset);
for (unsigned int i = 0; i < 2u; ++i) {
unsigned int mxd = x_offset + i;
for (unsigned int k = 0; k < 2u; ++k) {
unsigned int mxd = x_offset + k;
if (mxd >= costmap->getSizeInCellsX()) {
continue;
}
Expand All @@ -661,7 +661,7 @@
if (myd >= costmap->getSizeInCellsY()) {
continue;
}
if (i == 0 && j == 0) {
if (k == 0 && j == 0) {
continue;
}
cost = std::min(cost, static_cast<float>(costmap->getCost(mxd, myd)));
Expand All @@ -674,10 +674,10 @@
if (!is_circular) {
// Adjust cost value if using SE2 footprint checks
cost = adjustedFootprintCost(cost);
if (cost >= OCCUPIED) {
if (cost >= OCCUPIED_COST) {

Check warning on line 677 in nav2_smac_planner/src/node_hybrid.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_smac_planner/src/node_hybrid.cpp#L677

Added line #L677 was not covered by tests
continue;
}
} else if (cost >= INSCRIBED) {
} else if (cost >= INSCRIBED_COST) {
continue;
}

Expand Down
1 change: 0 additions & 1 deletion nav2_smac_planner/src/smac_planner_hybrid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -288,7 +288,6 @@ void SmacPlannerHybrid::activate()

// Special case handling to obtain resolution changes in global costmap
auto resolution_remote_cb = [this](const rclcpp::Parameter & p) {
auto node = _node.lock();
dynamicParametersCallback(
{rclcpp::Parameter("resolution", rclcpp::ParameterValue(p.as_double()))});
};
Expand Down
4 changes: 2 additions & 2 deletions nav2_smac_planner/src/smoother.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -170,7 +170,7 @@ bool Smoother::smoothImpl(
cost = static_cast<float>(costmap->getCost(mx, my));
}

if (cost > MAX_NON_OBSTACLE && cost != UNKNOWN) {
if (cost > MAX_NON_OBSTACLE_COST && cost != UNKNOWN_COST) {
RCLCPP_DEBUG(
rclcpp::get_logger("SmacPlannerSmoother"),
"Smoothing process resulted in an infeasible collision. "
Expand Down Expand Up @@ -374,7 +374,7 @@ void Smoother::findBoundaryExpansion(
// Check for collision
unsigned int mx, my;
costmap->worldToMap(x, y, mx, my);
if (static_cast<float>(costmap->getCost(mx, my)) >= INSCRIBED) {
if (static_cast<float>(costmap->getCost(mx, my)) >= INSCRIBED_COST) {
expansion.in_collision = true;
}

Expand Down
4 changes: 2 additions & 2 deletions nav2_smac_planner/test/deprecated/smoother_cost_function.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -398,7 +398,7 @@ class UnconstrainedSmootherCostFunction : public ceres::FirstOrderFunction
double & r,
Eigen::Vector2d & xi) const
{
if (value == FREE) {
if (value == FREE_COST) {
return;
}

Expand Down Expand Up @@ -432,7 +432,7 @@ class UnconstrainedSmootherCostFunction : public ceres::FirstOrderFunction
double & j0,
double & j1) const
{
if (value == FREE) {
if (value == FREE_COST) {
return;
}

Expand Down
1 change: 0 additions & 1 deletion nav2_smac_planner/test/test_a_star.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -301,7 +301,6 @@ TEST(AStarTest, test_a_star_lattice)
nav2_smac_planner::MotionModel::STATE_LATTICE, info);
int max_iterations = 10000;
float tolerance = 10.0;
int it_on_approach = 10;
int terminal_checking_interval = 5000;
double max_planning_time = 120.0;
int num_it = 0;
Expand Down
6 changes: 2 additions & 4 deletions nav2_smac_planner/test/test_node2d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,10 +142,8 @@ TEST(Node2DTest, test_node_2d_neighbors)
unsigned char cost = static_cast<unsigned int>(1);
nav2_smac_planner::Node2D * node = new nav2_smac_planner::Node2D(1);
node->setCost(cost);
std::function<bool(const uint64_t &,
nav2_smac_planner::Node2D * &)> neighborGetter =
[&, this](const uint64_t & index,
nav2_smac_planner::Node2D * & neighbor_rtn) -> bool
std::function<bool(const uint64_t &, nav2_smac_planner::Node2D * &)> neighborGetter =
[](const uint64_t &, nav2_smac_planner::Node2D * &) -> bool
{
return false;
};
Expand Down
6 changes: 2 additions & 4 deletions nav2_smac_planner/test/test_nodehybrid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -362,10 +362,8 @@ TEST(NodeHybridTest, test_node_reeds_neighbors)
std::make_unique<nav2_smac_planner::GridCollisionChecker>(costmap_ros, 72, lnode);
checker->setFootprint(nav2_costmap_2d::Footprint(), true, 0.0);
nav2_smac_planner::NodeHybrid * node = new nav2_smac_planner::NodeHybrid(49);
std::function<bool(const uint64_t &,
nav2_smac_planner::NodeHybrid * &)> neighborGetter =
[&, this](const uint64_t & index,
nav2_smac_planner::NodeHybrid * & neighbor_rtn) -> bool
std::function<bool(const uint64_t &, nav2_smac_planner::NodeHybrid * &)> neighborGetter =
[](const uint64_t &, nav2_smac_planner::NodeHybrid * &) -> bool
{
// because we don't return a real object
return false;
Expand Down
6 changes: 2 additions & 4 deletions nav2_smac_planner/test/test_nodelattice.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -303,10 +303,8 @@ TEST(NodeLatticeTest, test_get_neighbors)
std::make_unique<nav2_smac_planner::GridCollisionChecker>(costmap_ros, 72, lnode);
checker->setFootprint(nav2_costmap_2d::Footprint(), true, 0.0);

std::function<bool(const uint64_t &,
nav2_smac_planner::NodeLattice * &)> neighborGetter =
[&, this](const uint64_t & index,
nav2_smac_planner::NodeLattice * & neighbor_rtn) -> bool
std::function<bool(const uint64_t &, nav2_smac_planner::NodeLattice * &)> neighborGetter =
[](const uint64_t &, nav2_smac_planner::NodeLattice * &) -> bool
{
// because we don't return a real object
return false;
Expand Down
Loading