Skip to content

Commit 711817f

Browse files
Show error if inflation radius is smaller than circumscribed radius (#5148)
* Warn if inflation radius is smaller than circumscribed radius Signed-off-by: Tony Najjar <[email protected]> * Update nav2_mppi_controller/src/critics/cost_critic.cpp Co-authored-by: Steve Macenski <[email protected]> Signed-off-by: Tony Najjar <[email protected]> * Update nav2_smac_planner/include/nav2_smac_planner/utils.hpp Co-authored-by: Steve Macenski <[email protected]> Signed-off-by: Tony Najjar <[email protected]> --------- Signed-off-by: Tony Najjar <[email protected]> Signed-off-by: Tony Najjar <[email protected]> Co-authored-by: Steve Macenski <[email protected]>
1 parent d362e74 commit 711817f

File tree

2 files changed

+26
-0
lines changed

2 files changed

+26
-0
lines changed

nav2_mppi_controller/src/critics/cost_critic.cpp

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -96,6 +96,19 @@ float CostCritic::findCircumscribedCost(
9696
inflation_layer_name_);
9797
if (inflation_layer != nullptr) {
9898
const double resolution = costmap->getCostmap()->getResolution();
99+
double inflation_radius = inflation_layer->getInflationRadius();
100+
if (inflation_radius < circum_radius) {
101+
RCLCPP_ERROR(
102+
rclcpp::get_logger("computeCircumscribedCost"),
103+
"The inflation radius (%f) is smaller than the circumscribed radius (%f) "
104+
"If this is an SE2-collision checking plugin, it cannot use costmap potential "
105+
"field to speed up collision checking by only checking the full footprint "
106+
"when robot is within possibly-inscribed radius of an obstacle. This may "
107+
"significantly slow down planning times!",
108+
inflation_radius, circum_radius);
109+
result = 0.0;
110+
return result;
111+
}
99112
result = inflation_layer->computeCost(circum_radius / resolution);
100113
} else {
101114
RCLCPP_WARN(

nav2_smac_planner/include/nav2_smac_planner/utils.hpp

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -82,6 +82,19 @@ inline double findCircumscribedCost(std::shared_ptr<nav2_costmap_2d::Costmap2DRO
8282
if (inflation_layer != nullptr) {
8383
double circum_radius = costmap->getLayeredCostmap()->getCircumscribedRadius();
8484
double resolution = costmap->getCostmap()->getResolution();
85+
double inflation_radius = inflation_layer->getInflationRadius();
86+
if (inflation_radius < circum_radius) {
87+
RCLCPP_ERROR(
88+
rclcpp::get_logger("computeCircumscribedCost"),
89+
"The inflation radius (%f) is smaller than the circumscribed radius (%f) "
90+
"If this is an SE2-collision checking plugin, it cannot use costmap potential "
91+
"field to speed up collision checking by only checking the full footprint "
92+
"when robot is within possibly-inscribed radius of an obstacle. This may "
93+
"significantly slow down planning times!",
94+
inflation_radius, circum_radius);
95+
result = 0.0;
96+
return result;
97+
}
8598
result = static_cast<double>(inflation_layer->computeCost(circum_radius / resolution));
8699
} else {
87100
RCLCPP_WARN(

0 commit comments

Comments
 (0)