38 #include "nav2_costmap_2d/inflation_layer.hpp"
46 #include "nav2_costmap_2d/costmap_math.hpp"
47 #include "nav2_costmap_2d/footprint.hpp"
48 #include "pluginlib/class_list_macros.hpp"
49 #include "rclcpp/parameter_events_filter.hpp"
53 using nav2_costmap_2d::LETHAL_OBSTACLE;
54 using nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE;
55 using nav2_costmap_2d::NO_INFORMATION;
56 using rcl_interfaces::msg::ParameterType;
62 : inflation_radius_(0),
64 cost_scaling_factor_(0),
65 inflate_unknown_(false),
66 inflate_around_unknown_(false),
67 cell_inflation_radius_(0),
68 cached_cell_inflation_radius_(0),
71 last_min_x_(std::numeric_limits<double>::lowest()),
72 last_min_y_(std::numeric_limits<double>::lowest()),
73 last_max_x_(std::numeric_limits<double>::max()),
74 last_max_y_(std::numeric_limits<double>::max())
76 access_ =
new mutex_t();
81 auto node = node_.lock();
82 if (dyn_params_handler_ && node) {
83 node->remove_on_set_parameters_callback(dyn_params_handler_.get());
85 dyn_params_handler_.reset();
99 auto node = node_.lock();
101 throw std::runtime_error{
"Failed to lock node"};
103 node->get_parameter(name_ +
"." +
"enabled", enabled_);
104 node->get_parameter(name_ +
"." +
"inflation_radius", inflation_radius_);
105 node->get_parameter(name_ +
"." +
"cost_scaling_factor", cost_scaling_factor_);
106 node->get_parameter(name_ +
"." +
"inflate_unknown", inflate_unknown_);
107 node->get_parameter(name_ +
"." +
"inflate_around_unknown", inflate_around_unknown_);
109 dyn_params_handler_ = node->add_on_set_parameters_callback(
112 this, std::placeholders::_1));
117 cached_distances_.clear();
118 cached_costs_.clear();
119 need_reinflation_ =
false;
120 cell_inflation_radius_ =
cellDistance(inflation_radius_);
127 std::lock_guard<Costmap2D::mutex_t> guard(*
getMutex());
130 cell_inflation_radius_ =
cellDistance(inflation_radius_);
137 double ,
double ,
double ,
double * min_x,
138 double * min_y,
double * max_x,
double * max_y)
140 std::lock_guard<Costmap2D::mutex_t> guard(*
getMutex());
141 if (need_reinflation_) {
142 last_min_x_ = *min_x;
143 last_min_y_ = *min_y;
144 last_max_x_ = *max_x;
145 last_max_y_ = *max_y;
147 *min_x = std::numeric_limits<double>::lowest();
148 *min_y = std::numeric_limits<double>::lowest();
149 *max_x = std::numeric_limits<double>::max();
150 *max_y = std::numeric_limits<double>::max();
151 need_reinflation_ =
false;
153 double tmp_min_x = last_min_x_;
154 double tmp_min_y = last_min_y_;
155 double tmp_max_x = last_max_x_;
156 double tmp_max_y = last_max_y_;
157 last_min_x_ = *min_x;
158 last_min_y_ = *min_y;
159 last_max_x_ = *max_x;
160 last_max_y_ = *max_y;
161 *min_x = std::min(tmp_min_x, *min_x) - inflation_radius_;
162 *min_y = std::min(tmp_min_y, *min_y) - inflation_radius_;
163 *max_x = std::max(tmp_max_x, *max_x) + inflation_radius_;
164 *max_y = std::max(tmp_max_y, *max_y) + inflation_radius_;
171 std::lock_guard<Costmap2D::mutex_t> guard(*
getMutex());
173 cell_inflation_radius_ =
cellDistance(inflation_radius_);
175 need_reinflation_ =
true;
177 if (inflation_radius_ < inscribed_radius_) {
180 "The configured inflation radius (%.3f) is smaller than "
181 "the computed inscribed radius (%.3f) of your footprint, "
182 "it is highly recommended to set inflation radius to be at "
183 "least as big as the inscribed radius to avoid collisions",
184 inflation_radius_, inscribed_radius_);
188 logger_,
"InflationLayer::onFootprintChanged(): num footprint points: %zu,"
189 " inscribed_radius_ = %.3f, inflation_radius_ = %.3f",
190 layered_costmap_->
getFootprint().size(), inscribed_radius_, inflation_radius_);
199 std::lock_guard<Costmap2D::mutex_t> guard(*
getMutex());
200 if (!enabled_ || (cell_inflation_radius_ == 0)) {
205 for (
auto & dist : inflation_cells_) {
206 RCLCPP_FATAL_EXPRESSION(
208 !dist.empty(),
"The inflation list must be empty at the beginning of inflation");
211 unsigned char * master_array = master_grid.
getCharMap();
214 if (seen_.size() != size_x * size_y) {
216 logger_,
"InflationLayer::updateCosts(): seen_ vector size is wrong");
217 seen_ = std::vector<bool>(size_x * size_y,
false);
220 std::fill(begin(seen_), end(seen_),
false);
226 const int base_min_i = min_i;
227 const int base_min_j = min_j;
228 const int base_max_i = max_i;
229 const int base_max_j = max_j;
230 min_i -=
static_cast<int>(cell_inflation_radius_);
231 min_j -=
static_cast<int>(cell_inflation_radius_);
232 max_i +=
static_cast<int>(cell_inflation_radius_);
233 max_j +=
static_cast<int>(cell_inflation_radius_);
235 min_i = std::max(0, min_i);
236 min_j = std::max(0, min_j);
237 max_i = std::min(
static_cast<int>(size_x), max_i);
238 max_j = std::min(
static_cast<int>(size_y), max_j);
246 auto & obs_bin = inflation_cells_[0];
247 obs_bin.reserve(200);
248 for (
int j = min_j; j < max_j; j++) {
249 for (
int i = min_i; i < max_i; i++) {
250 int index =
static_cast<int>(master_grid.
getIndex(i, j));
251 unsigned char cost = master_array[index];
252 if (cost == LETHAL_OBSTACLE || (inflate_around_unknown_ && cost == NO_INFORMATION)) {
253 obs_bin.emplace_back(i, j, i, j);
261 for (
auto & dist_bin : inflation_cells_) {
262 dist_bin.reserve(200);
263 for (std::size_t i = 0; i < dist_bin.size(); ++i) {
267 const CellData & cell = dist_bin[i];
268 unsigned int mx = cell.x_;
269 unsigned int my = cell.y_;
270 unsigned int sx = cell.src_x_;
271 unsigned int sy = cell.src_y_;
272 unsigned int index = master_grid.
getIndex(mx, my);
282 unsigned char cost =
costLookup(mx, my, sx, sy);
283 unsigned char old_cost = master_array[index];
287 if (
static_cast<int>(mx) >= base_min_i &&
288 static_cast<int>(my) >= base_min_j &&
289 static_cast<int>(mx) < base_max_i &&
290 static_cast<int>(my) < base_max_j)
292 if (old_cost == NO_INFORMATION &&
293 (inflate_unknown_ ? (cost > FREE_SPACE) : (cost >= INSCRIBED_INFLATED_OBSTACLE)))
295 master_array[index] = cost;
297 master_array[index] = std::max(old_cost, cost);
303 enqueue(index - 1, mx - 1, my, sx, sy);
306 enqueue(index - size_x, mx, my - 1, sx, sy);
308 if (mx < size_x - 1) {
309 enqueue(index + 1, mx + 1, my, sx, sy);
311 if (my < size_y - 1) {
312 enqueue(index + size_x, mx, my + 1, sx, sy);
317 dist_bin = std::vector<CellData>();
334 unsigned int index,
unsigned int mx,
unsigned int my,
335 unsigned int src_x,
unsigned int src_y)
344 if (distance > cell_inflation_radius_) {
348 const unsigned int r = cell_inflation_radius_ + 2;
351 const auto dist = distance_matrix_[mx - src_x + r][my - src_y + r];
352 inflation_cells_[dist].emplace_back(mx, my, src_x, src_y);
359 std::lock_guard<Costmap2D::mutex_t> guard(*
getMutex());
360 if (cell_inflation_radius_ == 0) {
364 cache_length_ = cell_inflation_radius_ + 2;
367 if (cell_inflation_radius_ != cached_cell_inflation_radius_) {
368 cached_costs_.resize(cache_length_ * cache_length_);
369 cached_distances_.resize(cache_length_ * cache_length_);
371 for (
unsigned int i = 0; i < cache_length_; ++i) {
372 for (
unsigned int j = 0; j < cache_length_; ++j) {
373 cached_distances_[i * cache_length_ + j] = hypot(i, j);
377 cached_cell_inflation_radius_ = cell_inflation_radius_;
380 for (
unsigned int i = 0; i < cache_length_; ++i) {
381 for (
unsigned int j = 0; j < cache_length_; ++j) {
382 cached_costs_[i * cache_length_ + j] =
computeCost(cached_distances_[i * cache_length_ + j]);
387 inflation_cells_.clear();
388 inflation_cells_.resize(max_dist + 1);
394 const int r = cell_inflation_radius_ + 2;
395 const int size = r * 2 + 1;
397 std::vector<std::pair<int, int>> points;
399 for (
int y = -r; y <= r; y++) {
400 for (
int x = -r; x <= r; x++) {
401 if (x * x + y * y <= r * r) {
402 points.emplace_back(x, y);
408 points.begin(), points.end(),
409 [](
const std::pair<int, int> & a,
const std::pair<int, int> & b) ->
bool {
410 return a.first * a.first + a.second * a.second < b.first * b.first + b.second * b.second;
414 std::vector<std::vector<int>> distance_matrix(size, std::vector<int>(size, 0));
415 std::pair<int, int> last = {0, 0};
417 for (
auto const & p : points) {
418 if (p.first * p.first + p.second * p.second !=
419 last.first * last.first + last.second * last.second)
423 distance_matrix[p.first + r][p.second + r] = level;
427 distance_matrix_ = distance_matrix;
435 rcl_interfaces::msg::SetParametersResult
437 std::vector<rclcpp::Parameter> parameters)
439 std::lock_guard<Costmap2D::mutex_t> guard(*
getMutex());
440 rcl_interfaces::msg::SetParametersResult result;
442 bool need_cache_recompute =
false;
444 for (
auto parameter : parameters) {
445 const auto & param_type = parameter.get_type();
446 const auto & param_name = parameter.get_name();
447 if (param_name.find(name_ +
".") != 0) {
451 if (param_type == ParameterType::PARAMETER_DOUBLE) {
452 if (param_name == name_ +
"." +
"inflation_radius" &&
453 inflation_radius_ != parameter.as_double())
455 inflation_radius_ = parameter.as_double();
456 need_reinflation_ =
true;
457 need_cache_recompute =
true;
458 }
else if (param_name == name_ +
"." +
"cost_scaling_factor" &&
459 getCostScalingFactor() != parameter.as_double())
461 cost_scaling_factor_ = parameter.as_double();
462 need_reinflation_ =
true;
463 need_cache_recompute =
true;
465 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
466 if (param_name == name_ +
"." +
"enabled" && enabled_ != parameter.as_bool()) {
467 enabled_ = parameter.as_bool();
468 need_reinflation_ =
true;
470 }
else if (param_name == name_ +
"." +
"inflate_unknown" &&
471 inflate_unknown_ != parameter.as_bool())
473 inflate_unknown_ = parameter.as_bool();
474 need_reinflation_ =
true;
475 }
else if (param_name == name_ +
"." +
"inflate_around_unknown" &&
476 inflate_around_unknown_ != parameter.as_bool())
478 inflate_around_unknown_ = parameter.as_bool();
479 need_reinflation_ =
true;
484 if (need_cache_recompute) {
488 result.successful =
true;
Storage for cell information used during obstacle inflation.
A 2D costmap provides a mapping between points in the world and their associated "costs".
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
double getResolution() const
Accessor for the resolution of the costmap.
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Layer to convolve costmap by robot's radius or footprint to prevent collisions and largely simply col...
~InflationLayer()
A destructor.
void computeCaches()
Compute cached dsitances.
void updateCosts(nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) override
Update the costs in the master costmap in the window.
unsigned int cellDistance(double world_dist)
Compute cached dsitances.
unsigned char costLookup(unsigned int mx, unsigned int my, unsigned int src_x, unsigned int src_y)
Lookup pre-computed costs.
InflationLayer()
A constructor.
void onInitialize() override
Initialization process of layer on startup.
void matchSize() override
Match the size of the master costmap.
void onFootprintChanged() override
Process updates on footprint changes to the inflation layer.
unsigned char computeCost(double distance) const
Given a distance, compute a cost.
int generateIntegerDistances()
Compute cached dsitances.
mutex_t * getMutex()
Get the mutex of the inflation information.
void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y) override
Update the bounds of the master costmap by this layer's update dimensions.
void enqueue(unsigned int index, unsigned int mx, unsigned int my, unsigned int src_x, unsigned int src_y)
Enqueue new cells in cache distance update search.
double distanceLookup(unsigned int mx, unsigned int my, unsigned int src_x, unsigned int src_y)
Lookup pre-computed distances.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
Abstract class for layered costmap plugin implementations.
void declareParameter(const std::string ¶m_name, const rclcpp::ParameterValue &value)
Convenience functions for declaring ROS parameters.
Costmap2D * getCostmap()
Get the costmap pointer to the master costmap.
double getInscribedRadius()
The radius of a circle centered at the origin of the robot which is just within all points and edges ...
const std::vector< geometry_msgs::msg::Point > & getFootprint()
Returns the latest footprint stored with setFootprint().