-
Notifications
You must be signed in to change notification settings - Fork 1.2k
/
cost_critic.cpp
200 lines (170 loc) · 6.93 KB
/
cost_critic.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
// Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
// Copyright (c) 2023 Open Navigation LLC
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <cmath>
#include "nav2_mppi_controller/critics/cost_critic.hpp"
namespace mppi::critics
{
void CostCritic::initialize()
{
auto getParam = parameters_handler_->getParamGetter(name_);
getParam(consider_footprint_, "consider_footprint", false);
getParam(power_, "cost_power", 1);
getParam(weight_, "cost_weight", 3.81);
getParam(critical_cost_, "critical_cost", 300.0);
getParam(collision_cost_, "collision_cost", 1000000.0);
getParam(near_goal_distance_, "near_goal_distance", 0.5);
getParam(inflation_layer_name_, "inflation_layer_name", std::string(""));
// Normalized by cost value to put in same regime as other weights
weight_ /= 254.0f;
collision_checker_.setCostmap(costmap_);
possibly_inscribed_cost_ = findCircumscribedCost(costmap_ros_);
if (possibly_inscribed_cost_ < 1.0f) {
RCLCPP_ERROR(
logger_,
"Inflation layer either not found or inflation is not set sufficiently for "
"optimized non-circular collision checking capabilities. It is HIGHLY recommended to set"
" the inflation radius to be at MINIMUM half of the robot's largest cross-section. See "
"github.com/ros-planning/navigation2/tree/main/nav2_smac_planner#potential-fields"
" for full instructions. This will substantially impact run-time performance.");
}
RCLCPP_INFO(
logger_,
"InflationCostCritic instantiated with %d power and %f / %f weights. "
"Critic will collision check based on %s cost.",
power_, critical_cost_, weight_, consider_footprint_ ?
"footprint" : "circular");
}
float CostCritic::findCircumscribedCost(
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap)
{
double result = -1.0;
const double circum_radius = costmap->getLayeredCostmap()->getCircumscribedRadius();
if (static_cast<float>(circum_radius) == circumscribed_radius_) {
// early return if footprint size is unchanged
return circumscribed_cost_;
}
// check if the costmap has an inflation layer
const auto inflation_layer = nav2_costmap_2d::InflationLayer::getInflationLayer(
costmap,
inflation_layer_name_);
if (inflation_layer != nullptr) {
const double resolution = costmap->getCostmap()->getResolution();
result = inflation_layer->computeCost(circum_radius / resolution);
} else {
RCLCPP_WARN(
logger_,
"No inflation layer found in costmap configuration. "
"If this is an SE2-collision checking plugin, it cannot use costmap potential "
"field to speed up collision checking by only checking the full footprint "
"when robot is within possibly-inscribed radius of an obstacle. This may "
"significantly slow down planning times and not avoid anything but absolute collisions!");
}
circumscribed_radius_ = static_cast<float>(circum_radius);
circumscribed_cost_ = static_cast<float>(result);
return circumscribed_cost_;
}
void CostCritic::score(CriticData & data)
{
using xt::evaluation_strategy::immediate;
if (!enabled_) {
return;
}
if (consider_footprint_) {
// footprint may have changed since initialization if user has dynamic footprints
possibly_inscribed_cost_ = findCircumscribedCost(costmap_ros_);
}
// If near the goal, don't apply the preferential term since the goal is near obstacles
bool near_goal = false;
if (utils::withinPositionGoalTolerance(near_goal_distance_, data.state.pose.pose, data.path)) {
near_goal = true;
}
auto && repulsive_cost = xt::xtensor<float, 1>::from_shape({data.costs.shape(0)});
repulsive_cost.fill(0.0);
const size_t traj_len = data.trajectories.x.shape(1);
bool all_trajectories_collide = true;
for (size_t i = 0; i < data.trajectories.x.shape(0); ++i) {
bool trajectory_collide = false;
const auto & traj = data.trajectories;
float pose_cost;
for (size_t j = 0; j < traj_len; j++) {
// The costAtPose doesn't use orientation
// The footprintCostAtPose will always return "INSCRIBED" if footprint is over it
// So the center point has more information than the footprint
pose_cost = costAtPose(traj.x(i, j), traj.y(i, j));
if (pose_cost < 1.0f) {continue;} // In free space
if (inCollision(pose_cost, traj.x(i, j), traj.y(i, j), traj.yaws(i, j))) {
trajectory_collide = true;
break;
}
// Let near-collision trajectory points be punished severely
// Note that we collision check based on the footprint actual,
// but score based on the center-point cost regardless
using namespace nav2_costmap_2d; // NOLINT
if (pose_cost >= INSCRIBED_INFLATED_OBSTACLE) {
repulsive_cost[i] += critical_cost_;
} else if (!near_goal) { // Generally prefer trajectories further from obstacles
repulsive_cost[i] += pose_cost;
}
}
if (!trajectory_collide) {
all_trajectories_collide = false;
} else {
repulsive_cost[i] = collision_cost_;
}
}
data.costs += xt::pow((weight_ * repulsive_cost / traj_len), power_);
data.fail_flag = all_trajectories_collide;
}
/**
* @brief Checks if cost represents a collision
* @param cost Costmap cost
* @return bool if in collision
*/
bool CostCritic::inCollision(float cost, float x, float y, float theta)
{
bool is_tracking_unknown =
costmap_ros_->getLayeredCostmap()->isTrackingUnknown();
// If consider_footprint_ check footprint scort for collision
if (consider_footprint_ &&
(cost >= possibly_inscribed_cost_ || possibly_inscribed_cost_ < 1.0f))
{
cost = static_cast<float>(collision_checker_.footprintCostAtPose(
x, y, theta, costmap_ros_->getRobotFootprint()));
}
switch (static_cast<unsigned char>(cost)) {
using namespace nav2_costmap_2d; // NOLINT
case (LETHAL_OBSTACLE):
return true;
case (INSCRIBED_INFLATED_OBSTACLE):
return consider_footprint_ ? false : true;
case (NO_INFORMATION):
return is_tracking_unknown ? false : true;
}
return false;
}
float CostCritic::costAtPose(float x, float y)
{
using namespace nav2_costmap_2d; // NOLINT
unsigned int x_i, y_i;
if (!collision_checker_.worldToMap(x, y, x_i, y_i)) {
return nav2_costmap_2d::NO_INFORMATION;
}
return collision_checker_.pointCost(x_i, y_i);
}
} // namespace mppi::critics
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(
mppi::critics::CostCritic,
mppi::critics::CriticFunction)