17 #include "nav2_mppi_controller/critics/obstacles_critic.hpp"
18 #include "nav2_costmap_2d/inflation_layer.hpp"
19 #include "nav2_core/controller_exceptions.hpp"
21 namespace mppi::critics
27 getParam(consider_footprint_,
"consider_footprint",
false);
28 getParam(power_,
"cost_power", 1);
29 getParam(repulsion_weight_,
"repulsion_weight", 1.5f);
30 getParam(critical_weight_,
"critical_weight", 20.0f);
31 getParam(collision_cost_,
"collision_cost", 100000.0f);
32 getParam(collision_margin_distance_,
"collision_margin_distance", 0.10f);
33 getParam(near_goal_distance_,
"near_goal_distance", 0.5f);
34 getParam(inflation_layer_name_,
"inflation_layer_name", std::string(
""));
39 if (possible_collision_cost_ < 1.0f) {
42 "Inflation layer either not found or inflation is not set sufficiently for "
43 "optimized non-circular collision checking capabilities. It is HIGHLY recommended to set"
44 " the inflation radius to be at MINIMUM half of the robot's largest cross-section. See "
45 "github.com/ros-planning/navigation2/tree/main/nav2_smac_planner#potential-fields"
46 " for full instructions. This will substantially impact run-time performance.");
49 if (costmap_ros_->getUseRadius() == consider_footprint_) {
52 "Inconsistent configuration in collision checking. Please verify the robot's shape settings "
53 "in both the costmap and the obstacle critic.");
54 if (costmap_ros_->getUseRadius()) {
56 "Considering footprint in collision checking but no robot footprint provided in the "
63 "ObstaclesCritic instantiated with %d power and %f / %f weights. "
64 "Critic will collision check based on %s cost.",
65 power_, critical_weight_, repulsion_weight_, consider_footprint_ ?
66 "footprint" :
"circular");
70 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap)
73 const double circum_radius = costmap->getLayeredCostmap()->getCircumscribedRadius();
74 if (
static_cast<float>(circum_radius) == circumscribed_radius_) {
76 return circumscribed_cost_;
80 const auto inflation_layer = nav2_costmap_2d::InflationLayer::getInflationLayer(
82 inflation_layer_name_);
83 if (inflation_layer !=
nullptr) {
84 const double resolution = costmap->getCostmap()->getResolution();
85 result = inflation_layer->computeCost(circum_radius / resolution);
86 inflation_scale_factor_ =
static_cast<float>(inflation_layer->getCostScalingFactor());
87 inflation_radius_ =
static_cast<float>(inflation_layer->getInflationRadius());
91 "No inflation layer found in costmap configuration. "
92 "If this is an SE2-collision checking plugin, it cannot use costmap potential "
93 "field to speed up collision checking by only checking the full footprint "
94 "when robot is within possibly-inscribed radius of an obstacle. This may "
95 "significantly slow down planning times and not avoid anything but absolute collisions!");
98 circumscribed_radius_ =
static_cast<float>(circum_radius);
99 circumscribed_cost_ =
static_cast<float>(result);
101 return circumscribed_cost_;
106 const float scale_factor = inflation_scale_factor_;
107 const float min_radius = costmap_ros_->getLayeredCostmap()->getInscribedRadius();
108 float dist_to_obj = (scale_factor * min_radius - log(cost.cost) + log(253.0f)) / scale_factor;
112 if (!cost.using_footprint) {
113 dist_to_obj -= min_radius;
121 using xt::evaluation_strategy::immediate;
126 if (consider_footprint_) {
132 bool near_goal =
false;
133 if (utils::withinPositionGoalTolerance(near_goal_distance_, data.state.pose.pose, data.goal)) {
137 auto && raw_cost = xt::xtensor<float, 1>::from_shape({data.costs.shape(0)});
138 auto && repulsive_cost = xt::xtensor<float, 1>::from_shape({data.costs.shape(0)});
140 const size_t traj_len = data.trajectories.x.shape(1);
141 bool all_trajectories_collide =
true;
142 for (
size_t i = 0; i < data.trajectories.x.shape(0); ++i) {
143 bool trajectory_collide =
false;
144 float traj_cost = 0.0f;
145 const auto & traj = data.trajectories;
148 repulsive_cost[i] = 0.0f;
150 for (
size_t j = 0; j < traj_len; j++) {
151 pose_cost =
costAtPose(traj.x(i, j), traj.y(i, j), traj.yaws(i, j));
152 if (pose_cost.cost < 1.0f) {
continue;}
155 trajectory_collide =
true;
160 if (inflation_radius_ == 0.0f || inflation_scale_factor_ == 0.0f) {
167 if (dist_to_obj < collision_margin_distance_) {
168 traj_cost += (collision_margin_distance_ - dist_to_obj);
173 repulsive_cost[i] += inflation_radius_ - dist_to_obj;
177 if (!trajectory_collide) {all_trajectories_collide =
false;}
178 raw_cost[i] = trajectory_collide ? collision_cost_ : traj_cost;
183 auto && repulsive_cost_normalized =
184 (repulsive_cost - xt::amin(repulsive_cost, immediate)) / traj_len;
187 data.costs += xt::pow(
188 (critical_weight_ * raw_cost) +
189 (repulsion_weight_ * repulsive_cost_normalized),
192 data.costs += (critical_weight_ * raw_cost) +
193 (repulsion_weight_ * repulsive_cost_normalized);
196 data.fail_flag = all_trajectories_collide;
206 bool is_tracking_unknown =
207 costmap_ros_->getLayeredCostmap()->isTrackingUnknown();
210 switch (
static_cast<unsigned char>(cost)) {
211 case (LETHAL_OBSTACLE):
213 case (INSCRIBED_INFLATED_OBSTACLE):
214 return consider_footprint_ ? false :
true;
215 case (NO_INFORMATION):
216 return is_tracking_unknown ? false :
true;
225 float & cost = collision_cost.cost;
226 collision_cost.using_footprint =
false;
227 unsigned int x_i, y_i;
228 if (!collision_checker_.
worldToMap(x, y, x_i, y_i)) {
229 cost = nav2_costmap_2d::NO_INFORMATION;
230 return collision_cost;
232 cost = collision_checker_.
pointCost(x_i, y_i);
234 if (consider_footprint_ &&
235 (cost >= possible_collision_cost_ || possible_collision_cost_ < 1.0f))
238 x, y, theta, costmap_ros_->getRobotFootprint()));
239 collision_cost.using_footprint =
true;
242 return collision_cost;
247 #include <pluginlib/class_list_macros.hpp>
249 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.