Skip to content

Commit fe2cb91

Browse files
jncfaBriceRenaudeau
authored andcommitted
Updated code to use getInflationLayer() method (ros-navigation#4076)
* updated code to use getInflationLayer method Signed-off-by: Jose Faria <[email protected]> * Fix linting Signed-off-by: Jose Faria <[email protected]> --------- Signed-off-by: Jose Faria <[email protected]> Signed-off-by: Brice <[email protected]>
1 parent f3e8c2c commit fe2cb91

File tree

2 files changed

+9
-34
lines changed

2 files changed

+9
-34
lines changed

nav2_mppi_controller/src/critics/obstacles_critic.cpp

Lines changed: 6 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@
1515

1616
#include <cmath>
1717
#include "nav2_mppi_controller/critics/obstacles_critic.hpp"
18-
18+
#include "nav2_costmap_2d/inflation_layer.hpp"
1919
namespace mppi::critics
2020
{
2121

@@ -56,35 +56,22 @@ float ObstaclesCritic::findCircumscribedCost(
5656
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap)
5757
{
5858
double result = -1.0;
59-
bool inflation_layer_found = false;
60-
6159
const double circum_radius = costmap->getLayeredCostmap()->getCircumscribedRadius();
6260
if (static_cast<float>(circum_radius) == circumscribed_radius_) {
6361
// early return if footprint size is unchanged
6462
return circumscribed_cost_;
6563
}
6664

6765
// check if the costmap has an inflation layer
68-
for (auto layer = costmap->getLayeredCostmap()->getPlugins()->begin();
69-
layer != costmap->getLayeredCostmap()->getPlugins()->end();
70-
++layer)
71-
{
72-
auto inflation_layer = std::dynamic_pointer_cast<nav2_costmap_2d::InflationLayer>(*layer);
73-
if (!inflation_layer ||
74-
(!inflation_layer_name_.empty() &&
75-
inflation_layer->getName() != inflation_layer_name_))
76-
{
77-
continue;
78-
}
79-
80-
inflation_layer_found = true;
66+
const auto inflation_layer = nav2_costmap_2d::InflationLayer::getInflationLayer(
67+
costmap,
68+
inflation_layer_name_);
69+
if (inflation_layer != nullptr) {
8170
const double resolution = costmap->getCostmap()->getResolution();
8271
result = inflation_layer->computeCost(circum_radius / resolution);
8372
inflation_scale_factor_ = static_cast<float>(inflation_layer->getCostScalingFactor());
8473
inflation_radius_ = static_cast<float>(inflation_layer->getInflationRadius());
85-
}
86-
87-
if (!inflation_layer_found) {
74+
} else {
8875
RCLCPP_WARN(
8976
logger_,
9077
"No inflation layer found in costmap configuration. "

nav2_smac_planner/include/nav2_smac_planner/utils.hpp

Lines changed: 3 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -76,27 +76,15 @@ inline geometry_msgs::msg::Quaternion getWorldOrientation(
7676
inline double findCircumscribedCost(std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap)
7777
{
7878
double result = -1.0;
79-
bool inflation_layer_found = false;
8079
std::vector<std::shared_ptr<nav2_costmap_2d::Layer>>::iterator layer;
8180

8281
// check if the costmap has an inflation layer
83-
for (layer = costmap->getLayeredCostmap()->getPlugins()->begin();
84-
layer != costmap->getLayeredCostmap()->getPlugins()->end();
85-
++layer)
86-
{
87-
std::shared_ptr<nav2_costmap_2d::InflationLayer> inflation_layer =
88-
std::dynamic_pointer_cast<nav2_costmap_2d::InflationLayer>(*layer);
89-
if (!inflation_layer) {
90-
continue;
91-
}
92-
93-
inflation_layer_found = true;
82+
const auto inflation_layer = nav2_costmap_2d::InflationLayer::getInflationLayer(costmap);
83+
if (inflation_layer != nullptr) {
9484
double circum_radius = costmap->getLayeredCostmap()->getCircumscribedRadius();
9585
double resolution = costmap->getCostmap()->getResolution();
9686
result = static_cast<double>(inflation_layer->computeCost(circum_radius / resolution));
97-
}
98-
99-
if (!inflation_layer_found) {
87+
} else {
10088
RCLCPP_WARN(
10189
rclcpp::get_logger("computeCircumscribedCost"),
10290
"No inflation layer found in costmap configuration. "

0 commit comments

Comments
 (0)