@@ -54,6 +54,16 @@ void GridCollisionChecker::setFootprint(
5454 const double & possible_collision_cost)
5555{
5656 possible_collision_cost_ = static_cast <float >(possible_collision_cost);
57+ if (possible_collision_cost_ <= 0 .0f ) {
58+ RCLCPP_ERROR_THROTTLE (
59+ logger_, *clock_, 1000 ,
60+ " Inflation layer either not found or inflation is not set sufficiently for "
61+ " optimized non-circular collision checking capabilities. It is HIGHLY recommended to set"
62+ " the inflation radius to be at MINIMUM half of the robot's largest cross-section. See "
63+ " github.com/ros-planning/navigation2/tree/main/nav2_smac_planner#potential-fields"
64+ " for full instructions. This will substantially impact run-time performance." );
65+ }
66+
5767 footprint_is_radius_ = radius;
5868
5969 // Use radius, no caching required
@@ -114,18 +124,8 @@ bool GridCollisionChecker::inCollision(
114124 footprint_cost_ = static_cast <float >(costmap_->getCost (
115125 static_cast <unsigned int >(x + 0 .5f ), static_cast <unsigned int >(y + 0 .5f )));
116126
117- if (footprint_cost_ < possible_collision_cost_) {
118- if (possible_collision_cost_ > 0 .0f ) {
119- return false ;
120- } else {
121- RCLCPP_ERROR_THROTTLE (
122- logger_, *clock_, 1000 ,
123- " Inflation layer either not found or inflation is not set sufficiently for "
124- " optimized non-circular collision checking capabilities. It is HIGHLY recommended to set"
125- " the inflation radius to be at MINIMUM half of the robot's largest cross-section. See "
126- " github.com/ros-planning/navigation2/tree/main/nav2_smac_planner#potential-fields"
127- " for full instructions. This will substantially impact run-time performance." );
128- }
127+ if (footprint_cost_ < possible_collision_cost_ && possible_collision_cost_ > 0 .0f ) {
128+ return false ;
129129 }
130130
131131 // If its inscribed, in collision, or unknown in the middle,
0 commit comments