17 #include "nav2_mppi_controller/critics/cost_critic.hpp"
18 #include "nav2_core/controller_exceptions.hpp"
20 namespace mppi::critics
25 auto getParentParam = parameters_handler_->
getParamGetter(parent_name_);
27 getParam(consider_footprint_,
"consider_footprint",
false);
28 getParam(power_,
"cost_power", 1);
29 getParam(weight_,
"cost_weight", 3.81f);
30 getParam(critical_cost_,
"critical_cost", 300.0f);
31 getParam(near_collision_cost_,
"near_collision_cost", 253);
32 getParam(collision_cost_,
"collision_cost", 1000000.0f);
33 getParam(near_goal_distance_,
"near_goal_distance", 0.5f);
34 getParam(inflation_layer_name_,
"inflation_layer_name", std::string(
""));
35 getParam(trajectory_point_step_,
"trajectory_point_step", 2);
41 auto weightDynamicCb = [&](
42 const rclcpp::Parameter & weight, rcl_interfaces::msg::SetParametersResult & ) {
43 weight_ = weight.as_double() / 254.0f;
45 parameters_handler_->
addParamCallback(name_ +
".cost_weight", weightDynamicCb);
50 if (possible_collision_cost_ < 1.0f) {
53 "Inflation layer either not found or inflation is not set sufficiently for "
54 "optimized non-circular collision checking capabilities. It is HIGHLY recommended to set"
55 " the inflation radius to be at MINIMUM half of the robot's largest cross-section. See "
56 "github.com/ros-planning/navigation2/tree/main/nav2_smac_planner#potential-fields"
57 " for full instructions. This will substantially impact run-time performance.");
60 if (costmap_ros_->getUseRadius() == consider_footprint_) {
63 "Inconsistent configuration in collision checking. Please verify the robot's shape settings "
64 "in both the costmap and the cost critic.");
65 if (costmap_ros_->getUseRadius()) {
67 "Considering footprint in collision checking but no robot footprint provided in the "
72 if(near_collision_cost_ > 253) {
73 RCLCPP_WARN(logger_,
"Near collision cost is set higher than INSCRIBED_INFLATED_OBSTACLE");
78 "InflationCostCritic instantiated with %d power and %f / %f weights. "
79 "Critic will collision check based on %s cost.",
80 power_, critical_cost_, weight_, consider_footprint_ ?
81 "footprint" :
"circular");
85 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap)
88 const double circum_radius = costmap->getLayeredCostmap()->getCircumscribedRadius();
89 if (
static_cast<float>(circum_radius) == circumscribed_radius_) {
91 return circumscribed_cost_;
95 const auto inflation_layer = nav2_costmap_2d::InflationLayer::getInflationLayer(
97 inflation_layer_name_);
98 if (inflation_layer !=
nullptr) {
99 const double resolution = costmap->getCostmap()->getResolution();
100 double inflation_radius = inflation_layer->getInflationRadius();
101 if (inflation_radius < circum_radius) {
103 rclcpp::get_logger(
"computeCircumscribedCost"),
104 "The inflation radius (%f) is smaller than the circumscribed radius (%f) "
105 "If this is an SE2-collision checking plugin, it cannot use costmap potential "
106 "field to speed up collision checking by only checking the full footprint "
107 "when robot is within possibly-inscribed radius of an obstacle. This may "
108 "significantly slow down planning times!",
109 inflation_radius, circum_radius);
113 result = inflation_layer->computeCost(circum_radius / resolution);
117 "No inflation layer found in costmap configuration. "
118 "If this is an SE2-collision checking plugin, it cannot use costmap potential "
119 "field to speed up collision checking by only checking the full footprint "
120 "when robot is within possibly-inscribed radius of an obstacle. This may "
121 "significantly slow down planning times and not avoid anything but absolute collisions!");
124 circumscribed_radius_ =
static_cast<float>(circum_radius);
125 circumscribed_cost_ =
static_cast<float>(result);
127 return circumscribed_cost_;
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();
145 if (consider_footprint_) {
151 bool near_goal =
false;
152 if (data.state.local_path_length < near_goal_distance_) {
156 Eigen::ArrayXf repulsive_cost(data.costs.rows());
157 repulsive_cost.setZero();
158 bool all_trajectories_collide =
true;
160 int strided_traj_cols = floor((data.trajectories.x.cols() - 1) / trajectory_point_step_) + 1;
161 int strided_traj_rows = data.trajectories.x.rows();
162 int outer_stride = strided_traj_rows * trajectory_point_step_;
164 const auto traj_x = Eigen::Map<
const Eigen::ArrayXXf, 0,
165 Eigen::Stride<-1, -1>>(data.trajectories.x.data(), strided_traj_rows, strided_traj_cols,
166 Eigen::Stride<-1, -1>(outer_stride, 1));
167 const auto traj_y = Eigen::Map<
const Eigen::ArrayXXf, 0,
168 Eigen::Stride<-1, -1>>(data.trajectories.y.data(), strided_traj_rows, strided_traj_cols,
169 Eigen::Stride<-1, -1>(outer_stride, 1));
170 const auto traj_yaw = Eigen::Map<
const Eigen::ArrayXXf, 0,
171 Eigen::Stride<-1, -1>>(data.trajectories.yaws.data(), strided_traj_rows, strided_traj_cols,
172 Eigen::Stride<-1, -1>(outer_stride, 1));
174 for (
int i = 0; i < strided_traj_rows; ++i) {
175 bool trajectory_collide =
false;
176 float pose_cost = 0.0f;
177 float & traj_cost = repulsive_cost(i);
179 for (
int j = 0; j < strided_traj_cols; j++) {
180 float Tx = traj_x(i, j);
181 float Ty = traj_y(i, j);
182 unsigned int x_i = 0u, y_i = 0u;
190 pose_cost =
static_cast<float>(costmap->getCost(
getIndex(x_i, y_i)));
191 if (pose_cost < 1.0f) {
196 if (
inCollision(pose_cost, Tx, Ty, traj_yaw(i, j))) {
197 traj_cost = collision_cost_;
198 trajectory_collide =
true;
205 if (pose_cost >=
static_cast<float>(near_collision_cost_)) {
206 traj_cost += critical_cost_;
207 }
else if (!near_goal) {
208 traj_cost += pose_cost;
212 all_trajectories_collide &= trajectory_collide;
216 data.costs += (repulsive_cost *
217 (weight_ /
static_cast<float>(strided_traj_cols))).pow(power_);
219 data.costs += repulsive_cost * (weight_ /
static_cast<float>(strided_traj_cols));
222 data.fail_flag = all_trajectories_collide;
227 #include <pluginlib/class_list_macros.hpp>
229 PLUGINLIB_EXPORT_CLASS(
auto getParamGetter(const std::string &ns)
Get an object to retrieve parameters.
void addParamCallback(const std::string &name, T &&callback)
register a function to be called when setting a parameter
Critic objective function for avoiding obstacles using costmap's inflated cost.
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.
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...
void initialize() override
Initialize critic.
void score(CriticData &data) override
Evaluate cost related to obstacle avoidance.
Abstract critic objective function to score trajectories.
Data to pass to critics for scoring, including state, trajectories, pruned path, global goal,...