17 #include "nav2_mppi_controller/critics/cost_critic.hpp"
18 #include "nav2_core/controller_exceptions.hpp"
20 namespace mppi::critics
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);
40 auto weightDynamicCb = [&](
const rclcpp::Parameter & weight) {
41 weight_ = weight.as_double() / 254.0f;
48 if (possible_collision_cost_ < 1.0f) {
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.");
58 if (costmap_ros_->getUseRadius() == consider_footprint_) {
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 "
70 if(near_collision_cost_ > 253) {
71 RCLCPP_WARN(logger_,
"Near collision cost is set higher than INSCRIBED_INFLATED_OBSTACLE");
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");
83 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap)
86 const double circum_radius = costmap->getLayeredCostmap()->getCircumscribedRadius();
87 if (
static_cast<float>(circum_radius) == circumscribed_radius_) {
89 return circumscribed_cost_;
93 const auto inflation_layer = nav2_costmap_2d::InflationLayer::getInflationLayer(
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) {
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);
111 result = inflation_layer->computeCost(circum_radius / resolution);
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!");
122 circumscribed_radius_ =
static_cast<float>(circum_radius);
123 circumscribed_cost_ =
static_cast<float>(result);
125 return circumscribed_cost_;
130 using xt::evaluation_strategy::immediate;
131 using xt::placeholders::_;
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 (utils::withinPositionGoalTolerance(near_goal_distance_, data.state.pose.pose, data.goal)) {
156 auto && repulsive_cost = xt::xtensor<float, 1>::from_shape({data.costs.shape(0)});
157 bool all_trajectories_collide =
true;
159 const size_t traj_len = floor(data.trajectories.x.shape(1) / trajectory_point_step_);
161 xt::view(data.trajectories.x, xt::all(), xt::range(0, _, trajectory_point_step_));
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_));
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];
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;
184 pose_cost =
static_cast<float>(costmap->getCost(
getIndex(x_i, y_i)));
185 if (pose_cost < 1.0f) {
190 if (
inCollision(pose_cost, Tx, Ty, traj_yaw(i, j))) {
191 traj_cost = collision_cost_;
192 trajectory_collide =
true;
199 if (pose_cost >=
static_cast<float>(near_collision_cost_)) {
200 traj_cost += critical_cost_;
201 }
else if (!near_goal) {
202 traj_cost += pose_cost;
206 if (!trajectory_collide) {
207 all_trajectories_collide =
false;
212 data.costs += xt::pow(
213 (std::move(repulsive_cost) * (weight_ /
static_cast<float>(traj_len))), power_);
215 data.costs += std::move(repulsive_cost) * (weight_ /
static_cast<float>(traj_len));
218 data.fail_flag = all_trajectories_collide;
223 #include <pluginlib/class_list_macros.hpp>
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.
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,...