Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
obstacles_critic.cpp
1 // Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
2 // Copyright (c) 2023 Open Navigation LLC
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #include <cmath>
17 #include "nav2_mppi_controller/critics/obstacles_critic.hpp"
18 #include "nav2_costmap_2d/inflation_layer.hpp"
19 #include "nav2_core/controller_exceptions.hpp"
20 
21 namespace mppi::critics
22 {
23 
25 {
26  auto getParentParam = parameters_handler_->getParamGetter(parent_name_);
27  auto getParam = parameters_handler_->getParamGetter(name_);
28  getParam(consider_footprint_, "consider_footprint", false);
29  getParam(power_, "cost_power", 1);
30  getParam(repulsion_weight_, "repulsion_weight", 1.5f);
31  getParam(critical_weight_, "critical_weight", 20.0f);
32  getParam(collision_cost_, "collision_cost", 100000.0f);
33  getParam(collision_margin_distance_, "collision_margin_distance", 0.10f);
34  getParam(near_goal_distance_, "near_goal_distance", 0.5f);
35  getParam(inflation_layer_name_, "inflation_layer_name", std::string(""));
36 
37  collision_checker_.setCostmap(costmap_);
38  possible_collision_cost_ = findCircumscribedCost(costmap_ros_);
39 
40  if (possible_collision_cost_ < 1.0f) {
41  RCLCPP_ERROR(
42  logger_,
43  "Inflation layer either not found or inflation is not set sufficiently for "
44  "optimized non-circular collision checking capabilities. It is HIGHLY recommended to set"
45  " the inflation radius to be at MINIMUM half of the robot's largest cross-section. See "
46  "github.com/ros-planning/navigation2/tree/main/nav2_smac_planner#potential-fields"
47  " for full instructions. This will substantially impact run-time performance.");
48  }
49 
50  if (costmap_ros_->getUseRadius() == consider_footprint_) {
51  RCLCPP_WARN(
52  logger_,
53  "Inconsistent configuration in collision checking. Please verify the robot's shape settings "
54  "in both the costmap and the obstacle critic.");
55  if (costmap_ros_->getUseRadius()) {
57  "Considering footprint in collision checking but no robot footprint provided in the "
58  "costmap.");
59  }
60  }
61 
62  RCLCPP_INFO(
63  logger_,
64  "ObstaclesCritic instantiated with %d power and %f / %f weights. "
65  "Critic will collision check based on %s cost.",
66  power_, critical_weight_, repulsion_weight_, consider_footprint_ ?
67  "footprint" : "circular");
68 }
69 
71  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap)
72 {
73  double result = -1.0;
74  const double circum_radius = costmap->getLayeredCostmap()->getCircumscribedRadius();
75  if (static_cast<float>(circum_radius) == circumscribed_radius_) {
76  // early return if footprint size is unchanged
77  return circumscribed_cost_;
78  }
79 
80  // check if the costmap has an inflation layer
81  const auto inflation_layer = nav2_costmap_2d::InflationLayer::getInflationLayer(
82  costmap,
83  inflation_layer_name_);
84  if (inflation_layer != nullptr) {
85  const double resolution = costmap->getCostmap()->getResolution();
86  result = inflation_layer->computeCost(circum_radius / resolution);
87  inflation_scale_factor_ = static_cast<float>(inflation_layer->getCostScalingFactor());
88  inflation_radius_ = static_cast<float>(inflation_layer->getInflationRadius());
89  } else {
90  RCLCPP_WARN(
91  logger_,
92  "No inflation layer found in costmap configuration. "
93  "If this is an SE2-collision checking plugin, it cannot use costmap potential "
94  "field to speed up collision checking by only checking the full footprint "
95  "when robot is within possibly-inscribed radius of an obstacle. This may "
96  "significantly slow down planning times and not avoid anything but absolute collisions!");
97  }
98 
99  circumscribed_radius_ = static_cast<float>(circum_radius);
100  circumscribed_cost_ = static_cast<float>(result);
101 
102  return circumscribed_cost_;
103 }
104 
106 {
107  const float scale_factor = inflation_scale_factor_;
108  const float min_radius = costmap_ros_->getLayeredCostmap()->getInscribedRadius();
109  float dist_to_obj = (scale_factor * min_radius - log(cost.cost) + log(253.0f)) / scale_factor;
110 
111  // If not footprint collision checking, the cost is using the center point cost and
112  // needs the radius subtracted to obtain the closest distance to the object
113  if (!cost.using_footprint) {
114  dist_to_obj -= min_radius;
115  }
116 
117  return dist_to_obj;
118 }
119 
121 {
122  if (!enabled_) {
123  return;
124  }
125 
126  if (consider_footprint_) {
127  // footprint may have changed since initialization if user has dynamic footprints
128  possible_collision_cost_ = findCircumscribedCost(costmap_ros_);
129  }
130 
131  // If near the goal, don't apply the preferential term since the goal is near obstacles
132  bool near_goal = false;
133  if (data.state.local_path_length < near_goal_distance_) {
134  near_goal = true;
135  }
136 
137  Eigen::ArrayXf raw_cost = Eigen::ArrayXf::Zero(data.costs.size());
138  Eigen::ArrayXf repulsive_cost = Eigen::ArrayXf::Zero(data.costs.size());
139 
140  const unsigned int traj_len = data.trajectories.x.cols();
141  const unsigned int batch_size = data.trajectories.x.rows();
142  bool all_trajectories_collide = true;
143 
144  for(unsigned int i = 0; i != batch_size; i++) {
145  bool trajectory_collide = false;
146  float traj_cost = 0.0f;
147  const auto & traj = data.trajectories;
148  CollisionCost pose_cost;
149  raw_cost(i) = 0.0f;
150  repulsive_cost(i) = 0.0f;
151 
152  for(unsigned int j = 0; j != traj_len; j++) {
153  pose_cost = costAtPose(traj.x(i, j), traj.y(i, j), traj.yaws(i, j));
154  if (pose_cost.cost < 1.0f) {continue;} // In free space
155 
156  if (inCollision(pose_cost.cost)) {
157  trajectory_collide = true;
158  break;
159  }
160 
161  // Cannot process repulsion if inflation layer does not exist
162  if (inflation_radius_ == 0.0f || inflation_scale_factor_ == 0.0f) {
163  continue;
164  }
165 
166  const float dist_to_obj = distanceToObstacle(pose_cost);
167 
168  // Let near-collision trajectory points be punished severely
169  if (dist_to_obj < collision_margin_distance_) {
170  traj_cost += (collision_margin_distance_ - dist_to_obj);
171  }
172 
173  // Generally prefer trajectories further from obstacles
174  if (!near_goal) {
175  repulsive_cost[i] += inflation_radius_ - dist_to_obj;
176  }
177  }
178 
179  if (!trajectory_collide) {all_trajectories_collide = false;}
180  raw_cost(i) = trajectory_collide ? collision_cost_ : traj_cost;
181  }
182 
183  // Normalize repulsive cost by trajectory length & lowest score to not overweight importance
184  // This is a preferential cost, not collision cost, to be tuned relative to desired behaviors
185  auto repulsive_cost_normalized = (repulsive_cost - repulsive_cost.minCoeff()) / traj_len;
186 
187  if (power_ > 1u) {
188  data.costs +=
189  ((critical_weight_ * raw_cost) + (repulsion_weight_ * repulsive_cost_normalized)).pow(power_);
190  } else {
191  data.costs += (critical_weight_ * raw_cost) + (repulsion_weight_ * repulsive_cost_normalized);
192  }
193 
194  data.fail_flag = all_trajectories_collide;
195 }
196 
202 bool ObstaclesCritic::inCollision(float cost) const
203 {
204  bool is_tracking_unknown =
205  costmap_ros_->getLayeredCostmap()->isTrackingUnknown();
206 
207  using namespace nav2_costmap_2d; // NOLINT
208  switch (static_cast<unsigned char>(cost)) {
209  case (LETHAL_OBSTACLE):
210  return true;
211  case (INSCRIBED_INFLATED_OBSTACLE):
212  return consider_footprint_ ? false : true;
213  case (NO_INFORMATION):
214  return is_tracking_unknown ? false : true;
215  }
216 
217  return false;
218 }
219 
220 CollisionCost ObstaclesCritic::costAtPose(float x, float y, float theta)
221 {
222  CollisionCost collision_cost;
223  float & cost = collision_cost.cost;
224  collision_cost.using_footprint = false;
225  unsigned int x_i, y_i;
226  if (!collision_checker_.worldToMap(x, y, x_i, y_i)) {
227  cost = nav2_costmap_2d::NO_INFORMATION;
228  return collision_cost;
229  }
230  cost = collision_checker_.pointCost(x_i, y_i);
231 
232  if (consider_footprint_ &&
233  (cost >= possible_collision_cost_ || possible_collision_cost_ < 1.0f))
234  {
235  cost = static_cast<float>(collision_checker_.footprintCostAtPose(
236  x, y, theta, costmap_ros_->getRobotFootprint()));
237  collision_cost.using_footprint = true;
238  }
239 
240  return collision_cost;
241 }
242 
243 } // namespace mppi::critics
244 
245 #include <pluginlib/class_list_macros.hpp>
246 
247 PLUGINLIB_EXPORT_CLASS(
auto getParamGetter(const std::string &ns)
Get an object to retrieve 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.
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my)
Get the map coordinates from a world point.
double footprintCostAtPose(double x, double y, double theta, const Footprint &footprint)
Find the footprint cost a a post with an unoriented footprint.
void setCostmap(CostmapT costmap)
Set the current costmap object to use for collision detection.
double pointCost(int x, int y) const
Get the cost of a point.
Data to pass to critics for scoring, including state, trajectories, pruned path, global goal,...
Definition: critic_data.hpp:40
Utility for storing cost information.