Skip to content
Merged
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
10 changes: 10 additions & 0 deletions nav2_costmap_2d/plugins/inflation_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -170,6 +170,16 @@ InflationLayer::onFootprintChanged()
computeCaches();
need_reinflation_ = true;

if (inflation_radius_ < inscribed_radius_) {
RCLCPP_ERROR(
logger_,
"The configured inflation radius (%.3f) is smaller than "
"the computed inscribed radius (%.3f) of your footprint, "
"it is highly recommended to set inflation radius to be at "
"least as big as the inscribed radius to avoid collisions",
inflation_radius_, inscribed_radius_);
}

RCLCPP_DEBUG(
logger_, "InflationLayer::onFootprintChanged(): num footprint points: %zu,"
" inscribed_radius_ = %.3f, inflation_radius_ = %.3f",
Expand Down