Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix MPPI obstacle critic InflationLayer check #4047

Merged
merged 1 commit into from
Jan 12, 2024
Merged
Show file tree
Hide file tree
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
1 change: 1 addition & 0 deletions nav2_mppi_controller/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,7 @@ This process is then repeated a number of times and returns a converged solution
| collision_cost | double | Default 100000.0. Cost to apply to a true collision in a trajectory. |
| 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. |
| 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.
| 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. |

#### Path Align Critic
| Parameter | Type | Definition |
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,10 @@
#define NAV2_MPPI_CONTROLLER__CRITICS__OBSTACLES_CRITIC_HPP_

#include <memory>
#include <string>

#include "nav2_costmap_2d/footprint_collision_checker.hpp"
#include "nav2_costmap_2d/inflation_layer.hpp"

#include "nav2_mppi_controller/critic_function.hpp"
#include "nav2_mppi_controller/models/state.hpp"
#include "nav2_mppi_controller/tools/utils.hpp"
Expand Down Expand Up @@ -96,6 +97,7 @@ class ObstaclesCritic : public CriticFunction

unsigned int power_{0};
float repulsion_weight_, critical_weight_{0};
std::string inflation_layer_name_;
};

} // namespace mppi::critics
Expand Down
6 changes: 5 additions & 1 deletion nav2_mppi_controller/src/critics/obstacles_critic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@ void ObstaclesCritic::initialize()
getParam(collision_cost_, "collision_cost", 100000.0);
getParam(collision_margin_distance_, "collision_margin_distance", 0.10);
getParam(near_goal_distance_, "near_goal_distance", 0.5);
getParam(inflation_layer_name_, "inflation_layer_name", std::string(""));

collision_checker_.setCostmap(costmap_);
possibly_inscribed_cost_ = findCircumscribedCost(costmap_ros_);
Expand Down Expand Up @@ -69,7 +70,10 @@ float ObstaclesCritic::findCircumscribedCost(
++layer)
{
auto inflation_layer = std::dynamic_pointer_cast<nav2_costmap_2d::InflationLayer>(*layer);
if (!inflation_layer) {
if (!inflation_layer ||
(!inflation_layer_name_.empty() &&
inflation_layer->getName() != inflation_layer_name_))
{
continue;
}

Expand Down