16 #include "nav2_mppi_controller/critics/obstacles_critic.hpp"
17 #include "nav2_core/exceptions.hpp"
19 namespace mppi::critics
25 getParam(consider_footprint_,
"consider_footprint",
false);
26 getParam(power_,
"cost_power", 1);
27 getParam(repulsion_weight_,
"repulsion_weight", 1.5);
28 getParam(critical_weight_,
"critical_weight", 20.0);
29 getParam(collision_cost_,
"collision_cost", 10000.0);
30 getParam(collision_margin_distance_,
"collision_margin_distance", 0.10);
31 getParam(near_goal_distance_,
"near_goal_distance", 0.5);
36 if (possibly_inscribed_cost_ < 1.0f) {
39 "Inflation layer either not found or inflation is not set sufficiently for "
40 "optimized non-circular collision checking capabilities. It is HIGHLY recommended to set"
41 " the inflation radius to be at MINIMUM half of the robot's largest cross-section. See "
42 "github.com/ros-planning/navigation2/tree/main/nav2_smac_planner#potential-fields"
43 " for full instructions. This will substantially impact run-time performance.");
46 if (costmap_ros_->getUseRadius() == consider_footprint_) {
49 "Inconsistent configuration in collision checking. Please verify the robot's shape settings "
50 "in both the costmap and the obstacle critic.");
51 if (costmap_ros_->getUseRadius()) {
53 "Considering footprint in collision checking but no robot footprint provided in the "
60 "ObstaclesCritic instantiated with %d power and %f / %f weights. "
61 "Critic will collision check based on %s cost.",
62 power_, critical_weight_, repulsion_weight_, consider_footprint_ ?
63 "footprint" :
"circular");
67 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap)
70 bool inflation_layer_found =
false;
72 const double circum_radius = costmap->getLayeredCostmap()->getCircumscribedRadius();
73 if (
static_cast<float>(circum_radius) == circumscribed_radius_) {
75 return circumscribed_cost_;
79 for (
auto layer = costmap->getLayeredCostmap()->getPlugins()->begin();
80 layer != costmap->getLayeredCostmap()->getPlugins()->end();
83 auto inflation_layer = std::dynamic_pointer_cast<nav2_costmap_2d::InflationLayer>(*layer);
84 if (!inflation_layer) {
88 inflation_layer_found =
true;
89 const double resolution = costmap->getCostmap()->getResolution();
90 result = inflation_layer->computeCost(circum_radius / resolution);
92 getParam(inflation_scale_factor_,
"cost_scaling_factor", 10.0);
93 getParam(inflation_radius_,
"inflation_radius", 0.55);
96 if (!inflation_layer_found) {
99 "No inflation layer found in costmap configuration. "
100 "If this is an SE2-collision checking plugin, it cannot use costmap potential "
101 "field to speed up collision checking by only checking the full footprint "
102 "when robot is within possibly-inscribed radius of an obstacle. This may "
103 "significantly slow down planning times and not avoid anything but absolute collisions!");
106 circumscribed_radius_ =
static_cast<float>(circum_radius);
107 circumscribed_cost_ =
static_cast<float>(result);
109 return circumscribed_cost_;
114 const float scale_factor = inflation_scale_factor_;
115 const float min_radius = costmap_ros_->getLayeredCostmap()->getInscribedRadius();
116 float dist_to_obj = (scale_factor * min_radius - log(cost.cost) + log(253.0f)) / scale_factor;
120 if (!cost.using_footprint) {
121 dist_to_obj -= min_radius;
129 using xt::evaluation_strategy::immediate;
134 if (consider_footprint_) {
140 bool near_goal =
false;
141 if (utils::withinPositionGoalTolerance(near_goal_distance_, data.state.pose.pose, data.goal)) {
145 auto && raw_cost = xt::xtensor<float, 1>::from_shape({data.costs.shape(0)});
147 auto && repulsive_cost = xt::xtensor<float, 1>::from_shape({data.costs.shape(0)});
148 repulsive_cost.fill(0.0f);
150 const size_t traj_len = data.trajectories.x.shape(1);
151 bool all_trajectories_collide =
true;
152 for (
size_t i = 0; i < data.trajectories.x.shape(0); ++i) {
153 bool trajectory_collide =
false;
154 float traj_cost = 0.0f;
155 const auto & traj = data.trajectories;
158 for (
size_t j = 0; j < traj_len; j++) {
159 pose_cost =
costAtPose(traj.x(i, j), traj.y(i, j), traj.yaws(i, j));
160 if (pose_cost.cost < 1.0f) {
continue;}
163 trajectory_collide =
true;
168 if (inflation_radius_ == 0.0f || inflation_scale_factor_ == 0.0f) {
175 if (dist_to_obj < collision_margin_distance_) {
176 traj_cost += (collision_margin_distance_ - dist_to_obj);
177 }
else if (!near_goal) {
178 repulsive_cost[i] += (inflation_radius_ - dist_to_obj);
182 if (!trajectory_collide) {all_trajectories_collide =
false;}
183 raw_cost[i] = trajectory_collide ? collision_cost_ : traj_cost;
186 data.costs += xt::pow(
187 (critical_weight_ * raw_cost) +
188 (repulsion_weight_ * repulsive_cost / traj_len),
190 data.fail_flag = all_trajectories_collide;
200 bool is_tracking_unknown =
201 costmap_ros_->getLayeredCostmap()->isTrackingUnknown();
203 switch (
static_cast<unsigned char>(cost)) {
205 case (LETHAL_OBSTACLE):
207 case (INSCRIBED_INFLATED_OBSTACLE):
208 return consider_footprint_ ? false :
true;
209 case (NO_INFORMATION):
210 return is_tracking_unknown ? false :
true;
219 float & cost = collision_cost.cost;
220 collision_cost.using_footprint =
false;
221 unsigned int x_i, y_i;
222 if (!collision_checker_.
worldToMap(x, y, x_i, y_i)) {
223 cost = nav2_costmap_2d::NO_INFORMATION;
224 return collision_cost;
226 cost = collision_checker_.
pointCost(x_i, y_i);
228 if (consider_footprint_ &&
229 (cost >= possibly_inscribed_cost_ || possibly_inscribed_cost_ < 1.0f))
232 x, y, theta, costmap_ros_->getRobotFootprint()));
233 collision_cost.using_footprint =
true;
236 return collision_cost;
241 #include <pluginlib/class_list_macros.hpp>
243 PLUGINLIB_EXPORT_CLASS(
auto getParamGetter(const std::string &ns)
Get an object to retreive parameters.
Abstract critic objective function to score trajectories.
bool inCollision(float cost) const
Checks if cost represents a collision.
float findCircumscribedCost(std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap)
Find the min cost of the inflation decay function for which the robot MAY be in collision in any orie...
CollisionCost costAtPose(float x, float y, float theta)
cost at a robot pose
float distanceToObstacle(const CollisionCost &cost)
Distance to obstacle from cost.
void initialize() override
Initialize critic.
void score(CriticData &data) override
Evaluate cost related to obstacle avoidance.
Data to pass to critics for scoring, including state, trajectories, pruned path, global goal,...
Utility for storing cost information.