Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
cost_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/cost_critic.hpp"
18 #include "nav2_core/controller_exceptions.hpp"
19 
20 namespace mppi::critics
21 {
22 
24 {
25  auto getParam = parameters_handler_->getParamGetter(name_);
26  getParam(consider_footprint_, "consider_footprint", false);
27  getParam(power_, "cost_power", 1);
28  getParam(weight_, "cost_weight", 3.81f);
29  getParam(critical_cost_, "critical_cost", 300.0f);
30  getParam(near_collision_cost_, "near_collision_cost", 253);
31  getParam(collision_cost_, "collision_cost", 1000000.0f);
32  getParam(near_goal_distance_, "near_goal_distance", 0.5f);
33  getParam(inflation_layer_name_, "inflation_layer_name", std::string(""));
34  getParam(trajectory_point_step_, "trajectory_point_step", 2);
35 
36  // Normalized by cost value to put in same regime as other weights
37  weight_ /= 254.0f;
38 
39  // Normalize weight when parameter is changed dynamically as well
40  auto weightDynamicCb = [&](const rclcpp::Parameter & weight) {
41  weight_ = weight.as_double() / 254.0f;
42  };
43  parameters_handler_->addDynamicParamCallback(name_ + ".cost_weight", weightDynamicCb);
44 
45  collision_checker_.setCostmap(costmap_);
46  possible_collision_cost_ = findCircumscribedCost(costmap_ros_);
47 
48  if (possible_collision_cost_ < 1.0f) {
49  RCLCPP_ERROR(
50  logger_,
51  "Inflation layer either not found or inflation is not set sufficiently for "
52  "optimized non-circular collision checking capabilities. It is HIGHLY recommended to set"
53  " the inflation radius to be at MINIMUM half of the robot's largest cross-section. See "
54  "github.com/ros-planning/navigation2/tree/main/nav2_smac_planner#potential-fields"
55  " for full instructions. This will substantially impact run-time performance.");
56  }
57 
58  if (costmap_ros_->getUseRadius() == consider_footprint_) {
59  RCLCPP_WARN(
60  logger_,
61  "Inconsistent configuration in collision checking. Please verify the robot's shape settings "
62  "in both the costmap and the cost critic.");
63  if (costmap_ros_->getUseRadius()) {
65  "Considering footprint in collision checking but no robot footprint provided in the "
66  "costmap.");
67  }
68  }
69 
70  if(near_collision_cost_ > 253) {
71  RCLCPP_WARN(logger_, "Near collision cost is set higher than INSCRIBED_INFLATED_OBSTACLE");
72  }
73 
74  RCLCPP_INFO(
75  logger_,
76  "InflationCostCritic instantiated with %d power and %f / %f weights. "
77  "Critic will collision check based on %s cost.",
78  power_, critical_cost_, weight_, consider_footprint_ ?
79  "footprint" : "circular");
80 }
81 
83  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap)
84 {
85  double result = -1.0;
86  const double circum_radius = costmap->getLayeredCostmap()->getCircumscribedRadius();
87  if (static_cast<float>(circum_radius) == circumscribed_radius_) {
88  // early return if footprint size is unchanged
89  return circumscribed_cost_;
90  }
91 
92  // check if the costmap has an inflation layer
93  const auto inflation_layer = nav2_costmap_2d::InflationLayer::getInflationLayer(
94  costmap,
95  inflation_layer_name_);
96  if (inflation_layer != nullptr) {
97  const double resolution = costmap->getCostmap()->getResolution();
98  double inflation_radius = inflation_layer->getInflationRadius();
99  if (inflation_radius < circum_radius) {
100  RCLCPP_ERROR(
101  rclcpp::get_logger("computeCircumscribedCost"),
102  "The inflation radius (%f) is smaller than the circumscribed radius (%f) "
103  "If this is an SE2-collision checking plugin, it cannot use costmap potential "
104  "field to speed up collision checking by only checking the full footprint "
105  "when robot is within possibly-inscribed radius of an obstacle. This may "
106  "significantly slow down planning times!",
107  inflation_radius, circum_radius);
108  result = 0.0;
109  return result;
110  }
111  result = inflation_layer->computeCost(circum_radius / resolution);
112  } else {
113  RCLCPP_WARN(
114  logger_,
115  "No inflation layer found in costmap configuration. "
116  "If this is an SE2-collision checking plugin, it cannot use costmap potential "
117  "field to speed up collision checking by only checking the full footprint "
118  "when robot is within possibly-inscribed radius of an obstacle. This may "
119  "significantly slow down planning times and not avoid anything but absolute collisions!");
120  }
121 
122  circumscribed_radius_ = static_cast<float>(circum_radius);
123  circumscribed_cost_ = static_cast<float>(result);
124 
125  return circumscribed_cost_;
126 }
127 
129 {
130  using xt::evaluation_strategy::immediate;
131  using xt::placeholders::_;
132  if (!enabled_) {
133  return;
134  }
135 
136  // Setup cost information for various parts of the critic
137  is_tracking_unknown_ = costmap_ros_->getLayeredCostmap()->isTrackingUnknown();
138  auto * costmap = collision_checker_.getCostmap();
139  origin_x_ = static_cast<float>(costmap->getOriginX());
140  origin_y_ = static_cast<float>(costmap->getOriginY());
141  resolution_ = static_cast<float>(costmap->getResolution());
142  size_x_ = costmap->getSizeInCellsX();
143  size_y_ = costmap->getSizeInCellsY();
144 
145  if (consider_footprint_) {
146  // footprint may have changed since initialization if user has dynamic footprints
147  possible_collision_cost_ = findCircumscribedCost(costmap_ros_);
148  }
149 
150  // If near the goal, don't apply the preferential term since the goal is near obstacles
151  bool near_goal = false;
152  if (utils::withinPositionGoalTolerance(near_goal_distance_, data.state.pose.pose, data.goal)) {
153  near_goal = true;
154  }
155 
156  auto && repulsive_cost = xt::xtensor<float, 1>::from_shape({data.costs.shape(0)});
157  bool all_trajectories_collide = true;
158 
159  const size_t traj_len = floor(data.trajectories.x.shape(1) / trajectory_point_step_);
160  const auto traj_x =
161  xt::view(data.trajectories.x, xt::all(), xt::range(0, _, trajectory_point_step_));
162  const auto traj_y =
163  xt::view(data.trajectories.y, xt::all(), xt::range(0, _, trajectory_point_step_));
164  const auto traj_yaw = xt::view(
165  data.trajectories.yaws, xt::all(), xt::range(0, _, trajectory_point_step_));
166 
167  for (size_t i = 0; i < data.trajectories.x.shape(0); ++i) {
168  bool trajectory_collide = false;
169  float pose_cost = 0.0f;
170  float & traj_cost = repulsive_cost[i];
171  traj_cost = 0.0f;
172 
173  for (size_t j = 0; j < traj_len; j++) {
174  float Tx = traj_x(i, j);
175  float Ty = traj_y(i, j);
176  unsigned int x_i = 0u, y_i = 0u;
177 
178  // The getCost doesn't use orientation
179  // The footprintCostAtPose will always return "INSCRIBED" if footprint is over it
180  // So the center point has more information than the footprint
181  if (!worldToMapFloat(Tx, Ty, x_i, y_i)) {
182  pose_cost = 255.0f; // NO_INFORMATION in float
183  } else {
184  pose_cost = static_cast<float>(costmap->getCost(getIndex(x_i, y_i)));
185  if (pose_cost < 1.0f) {
186  continue; // In free space
187  }
188  }
189 
190  if (inCollision(pose_cost, Tx, Ty, traj_yaw(i, j))) {
191  traj_cost = collision_cost_;
192  trajectory_collide = true;
193  break;
194  }
195 
196  // Let near-collision trajectory points be punished severely
197  // Note that we collision check based on the footprint actual,
198  // but score based on the center-point cost regardless
199  if (pose_cost >= static_cast<float>(near_collision_cost_)) {
200  traj_cost += critical_cost_;
201  } else if (!near_goal) { // Generally prefer trajectories further from obstacles
202  traj_cost += pose_cost;
203  }
204  }
205 
206  if (!trajectory_collide) {
207  all_trajectories_collide = false;
208  }
209  }
210 
211  if (power_ > 1u) {
212  data.costs += xt::pow(
213  (std::move(repulsive_cost) * (weight_ / static_cast<float>(traj_len))), power_);
214  } else {
215  data.costs += std::move(repulsive_cost) * (weight_ / static_cast<float>(traj_len));
216  }
217 
218  data.fail_flag = all_trajectories_collide;
219 }
220 
221 } // namespace mppi::critics
222 
223 #include <pluginlib/class_list_macros.hpp>
224 
225 PLUGINLIB_EXPORT_CLASS(
void addDynamicParamCallback(const std::string &name, T &&callback)
Set a parameter to a dynamic parameter callback.
auto getParamGetter(const std::string &ns)
Get an object to retreive parameters.
Critic objective function for avoiding obstacles using costmap's inflated cost.
Definition: cost_critic.hpp:36
bool worldToMapFloat(float wx, float wy, unsigned int &mx, unsigned int &my) const
An implementation of worldToMap fully using floats.
unsigned int getIndex(unsigned int mx, unsigned int my) const
A local implementation of getIndex.
bool inCollision(float cost, float x, float y, float theta)
Checks if cost represents a collision.
Definition: cost_critic.hpp:59
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...
Definition: cost_critic.cpp:82
void initialize() override
Initialize critic.
Definition: cost_critic.cpp:23
void score(CriticData &data) override
Evaluate cost related to obstacle avoidance.
Abstract critic objective function to score trajectories.
CostmapT getCostmap()
Get the current costmap object.
void setCostmap(CostmapT costmap)
Set the current costmap object to use for collision detection.
Data to pass to critics for scoring, including state, trajectories, pruned path, global goal,...
Definition: critic_data.hpp:45