Skip to content

Commit fbd6805

Browse files
renan028SteveMacenski
authored andcommitted
Add inflation_layer_name param (#4047)
Signed-off-by: Renan Salles <[email protected]>
1 parent f784826 commit fbd6805

File tree

3 files changed

+9
-2
lines changed

3 files changed

+9
-2
lines changed

nav2_mppi_controller/README.md

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -107,6 +107,7 @@ This process is then repeated a number of times and returns a converged solution
107107
| collision_cost | double | Default 10000.0. Cost to apply to a true collision in a trajectory. |
108108
| collision_margin_distance | double | Default 0.10. Margin distance from collision to apply severe penalty, similar to footprint inflation. Between 0.05-0.2 is reasonable. |
109109
| near_goal_distance | double | Default 0.5. Distance near goal to stop applying preferential obstacle term to allow robot to smoothly converge to goal pose in close proximity to obstacles.
110+
| inflation_layer_name | string | Default "". Name of the inflation layer. If empty, it uses the last inflation layer in the costmap. If you have multiple inflation layers, you may want to specify the name of the layer to use. |
110111

111112
#### Path Align Critic
112113
| Parameter | Type | Definition |

nav2_mppi_controller/include/nav2_mppi_controller/critics/obstacles_critic.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,9 +16,10 @@
1616
#define NAV2_MPPI_CONTROLLER__CRITICS__OBSTACLES_CRITIC_HPP_
1717

1818
#include <memory>
19+
#include <string>
20+
1921
#include "nav2_costmap_2d/footprint_collision_checker.hpp"
2022
#include "nav2_costmap_2d/inflation_layer.hpp"
21-
2223
#include "nav2_mppi_controller/critic_function.hpp"
2324
#include "nav2_mppi_controller/models/state.hpp"
2425
#include "nav2_mppi_controller/tools/utils.hpp"
@@ -96,6 +97,7 @@ class ObstaclesCritic : public CriticFunction
9697

9798
unsigned int power_{0};
9899
float repulsion_weight_, critical_weight_{0};
100+
std::string inflation_layer_name_;
99101
};
100102

101103
} // namespace mppi::critics

nav2_mppi_controller/src/critics/obstacles_critic.cpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@ void ObstaclesCritic::initialize()
2828
getParam(collision_cost_, "collision_cost", 10000.0);
2929
getParam(collision_margin_distance_, "collision_margin_distance", 0.10);
3030
getParam(near_goal_distance_, "near_goal_distance", 0.5);
31+
getParam(inflation_layer_name_, "inflation_layer_name", std::string(""));
3132

3233
collision_checker_.setCostmap(costmap_);
3334
possibly_inscribed_cost_ = findCircumscribedCost(costmap_ros_);
@@ -68,7 +69,10 @@ float ObstaclesCritic::findCircumscribedCost(
6869
++layer)
6970
{
7071
auto inflation_layer = std::dynamic_pointer_cast<nav2_costmap_2d::InflationLayer>(*layer);
71-
if (!inflation_layer) {
72+
if (!inflation_layer ||
73+
(!inflation_layer_name_.empty() &&
74+
inflation_layer->getName() != inflation_layer_name_))
75+
{
7276
continue;
7377
}
7478

0 commit comments

Comments
 (0)