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 dyn_params_handler_.reset();
95 auto node = node_.lock();
97 throw std::runtime_error{
"Failed to lock node"};
99 node->get_parameter(name_ +
"." +
"enabled", enabled_);
100 node->get_parameter(name_ +
"." +
"inflation_radius", inflation_radius_);
101 node->get_parameter(name_ +
"." +
"cost_scaling_factor", cost_scaling_factor_);
102 node->get_parameter(name_ +
"." +
"inflate_unknown", inflate_unknown_);
103 node->get_parameter(name_ +
"." +
"inflate_around_unknown", inflate_around_unknown_);
105 dyn_params_handler_ = node->add_on_set_parameters_callback(
108 this, std::placeholders::_1));
113 cached_distances_.clear();
114 cached_costs_.clear();
115 need_reinflation_ =
false;
116 cell_inflation_radius_ =
cellDistance(inflation_radius_);
123 std::lock_guard<Costmap2D::mutex_t> guard(*
getMutex());
126 cell_inflation_radius_ =
cellDistance(inflation_radius_);
133 double ,
double ,
double ,
double * min_x,
134 double * min_y,
double * max_x,
double * max_y)
136 std::lock_guard<Costmap2D::mutex_t> guard(*
getMutex());
137 if (need_reinflation_) {
138 last_min_x_ = *min_x;
139 last_min_y_ = *min_y;
140 last_max_x_ = *max_x;
141 last_max_y_ = *max_y;
143 *min_x = std::numeric_limits<double>::lowest();
144 *min_y = std::numeric_limits<double>::lowest();
145 *max_x = std::numeric_limits<double>::max();
146 *max_y = std::numeric_limits<double>::max();
147 need_reinflation_ =
false;
149 double tmp_min_x = last_min_x_;
150 double tmp_min_y = last_min_y_;
151 double tmp_max_x = last_max_x_;
152 double tmp_max_y = last_max_y_;
153 last_min_x_ = *min_x;
154 last_min_y_ = *min_y;
155 last_max_x_ = *max_x;
156 last_max_y_ = *max_y;
157 *min_x = std::min(tmp_min_x, *min_x) - inflation_radius_;
158 *min_y = std::min(tmp_min_y, *min_y) - inflation_radius_;
159 *max_x = std::max(tmp_max_x, *max_x) + inflation_radius_;
160 *max_y = std::max(tmp_max_y, *max_y) + inflation_radius_;
167 std::lock_guard<Costmap2D::mutex_t> guard(*
getMutex());
169 cell_inflation_radius_ =
cellDistance(inflation_radius_);
171 need_reinflation_ =
true;
173 if (inflation_radius_ < inscribed_radius_) {
176 "The configured inflation radius (%.3f) is smaller than "
177 "the computed inscribed radius (%.3f) of your footprint, "
178 "it is highly recommended to set inflation radius to be at "
179 "least as big as the inscribed radius to avoid collisions",
180 inflation_radius_, inscribed_radius_);
184 logger_,
"InflationLayer::onFootprintChanged(): num footprint points: %zu,"
185 " inscribed_radius_ = %.3f, inflation_radius_ = %.3f",
186 layered_costmap_->
getFootprint().size(), inscribed_radius_, inflation_radius_);
195 std::lock_guard<Costmap2D::mutex_t> guard(*
getMutex());
196 if (!enabled_ || (cell_inflation_radius_ == 0)) {
201 for (
auto & dist : inflation_cells_) {
202 RCLCPP_FATAL_EXPRESSION(
204 !dist.empty(),
"The inflation list must be empty at the beginning of inflation");
207 unsigned char * master_array = master_grid.
getCharMap();
210 if (seen_.size() != size_x * size_y) {
212 logger_,
"InflationLayer::updateCosts(): seen_ vector size is wrong");
213 seen_ = std::vector<bool>(size_x * size_y,
false);
216 std::fill(begin(seen_), end(seen_),
false);
222 const int base_min_i = min_i;
223 const int base_min_j = min_j;
224 const int base_max_i = max_i;
225 const int base_max_j = max_j;
226 min_i -=
static_cast<int>(cell_inflation_radius_);
227 min_j -=
static_cast<int>(cell_inflation_radius_);
228 max_i +=
static_cast<int>(cell_inflation_radius_);
229 max_j +=
static_cast<int>(cell_inflation_radius_);
231 min_i = std::max(0, min_i);
232 min_j = std::max(0, min_j);
233 max_i = std::min(
static_cast<int>(size_x), max_i);
234 max_j = std::min(
static_cast<int>(size_y), max_j);
242 auto & obs_bin = inflation_cells_[0];
243 for (
int j = min_j; j < max_j; j++) {
244 for (
int i = min_i; i < max_i; i++) {
245 int index =
static_cast<int>(master_grid.
getIndex(i, j));
246 unsigned char cost = master_array[index];
247 if (cost == LETHAL_OBSTACLE || (inflate_around_unknown_ && cost == NO_INFORMATION)) {
248 obs_bin.emplace_back(index, i, j, i, j);
256 for (
const auto & dist_bin : inflation_cells_) {
257 for (std::size_t i = 0; i < dist_bin.size(); ++i) {
261 unsigned int index = dist_bin[i].index_;
270 unsigned int mx = dist_bin[i].x_;
271 unsigned int my = dist_bin[i].y_;
272 unsigned int sx = dist_bin[i].src_x_;
273 unsigned int sy = dist_bin[i].src_y_;
276 unsigned char cost =
costLookup(mx, my, sx, sy);
277 unsigned char old_cost = master_array[index];
281 if (
static_cast<int>(mx) >= base_min_i &&
282 static_cast<int>(my) >= base_min_j &&
283 static_cast<int>(mx) < base_max_i &&
284 static_cast<int>(my) < base_max_j)
286 if (old_cost == NO_INFORMATION &&
287 (inflate_unknown_ ? (cost > FREE_SPACE) : (cost >= INSCRIBED_INFLATED_OBSTACLE)))
289 master_array[index] = cost;
291 master_array[index] = std::max(old_cost, cost);
297 enqueue(index - 1, mx - 1, my, sx, sy);
300 enqueue(index - size_x, mx, my - 1, sx, sy);
302 if (mx < size_x - 1) {
303 enqueue(index + 1, mx + 1, my, sx, sy);
305 if (my < size_y - 1) {
306 enqueue(index + size_x, mx, my + 1, sx, sy);
311 for (
auto & dist : inflation_cells_) {
330 unsigned int index,
unsigned int mx,
unsigned int my,
331 unsigned int src_x,
unsigned int src_y)
340 if (distance > cell_inflation_radius_) {
344 const unsigned int r = cell_inflation_radius_ + 2;
347 inflation_cells_[distance_matrix_[mx - src_x + r][my - src_y + r]].emplace_back(
348 index, mx, my, src_x, src_y);
355 std::lock_guard<Costmap2D::mutex_t> guard(*
getMutex());
356 if (cell_inflation_radius_ == 0) {
360 cache_length_ = cell_inflation_radius_ + 2;
363 if (cell_inflation_radius_ != cached_cell_inflation_radius_) {
364 cached_costs_.resize(cache_length_ * cache_length_);
365 cached_distances_.resize(cache_length_ * cache_length_);
367 for (
unsigned int i = 0; i < cache_length_; ++i) {
368 for (
unsigned int j = 0; j < cache_length_; ++j) {
369 cached_distances_[i * cache_length_ + j] = hypot(i, j);
373 cached_cell_inflation_radius_ = cell_inflation_radius_;
376 for (
unsigned int i = 0; i < cache_length_; ++i) {
377 for (
unsigned int j = 0; j < cache_length_; ++j) {
378 cached_costs_[i * cache_length_ + j] =
computeCost(cached_distances_[i * cache_length_ + j]);
383 inflation_cells_.clear();
384 inflation_cells_.resize(max_dist + 1);
385 for (
auto & dist : inflation_cells_) {
393 const int r = cell_inflation_radius_ + 2;
394 const int size = r * 2 + 1;
396 std::vector<std::pair<int, int>> points;
398 for (
int y = -r; y <= r; y++) {
399 for (
int x = -r; x <= r; x++) {
400 if (x * x + y * y <= r * r) {
401 points.emplace_back(x, y);
407 points.begin(), points.end(),
408 [](
const std::pair<int, int> & a,
const std::pair<int, int> & b) ->
bool {
409 return a.first * a.first + a.second * a.second < b.first * b.first + b.second * b.second;
413 std::vector<std::vector<int>> distance_matrix(size, std::vector<int>(size, 0));
414 std::pair<int, int> last = {0, 0};
416 for (
auto const & p : points) {
417 if (p.first * p.first + p.second * p.second !=
418 last.first * last.first + last.second * last.second)
422 distance_matrix[p.first + r][p.second + r] = level;
426 distance_matrix_ = distance_matrix;
434 rcl_interfaces::msg::SetParametersResult
436 std::vector<rclcpp::Parameter> parameters)
438 std::lock_guard<Costmap2D::mutex_t> guard(*
getMutex());
439 rcl_interfaces::msg::SetParametersResult result;
441 bool need_cache_recompute =
false;
443 for (
auto parameter : parameters) {
444 const auto & param_type = parameter.get_type();
445 const auto & param_name = parameter.get_name();
447 if (param_type == ParameterType::PARAMETER_DOUBLE) {
448 if (param_name == name_ +
"." +
"inflation_radius" &&
449 inflation_radius_ != parameter.as_double())
451 inflation_radius_ = parameter.as_double();
452 need_reinflation_ =
true;
453 need_cache_recompute =
true;
454 }
else if (param_name == name_ +
"." +
"cost_scaling_factor" &&
455 cost_scaling_factor_ != parameter.as_double())
457 cost_scaling_factor_ = parameter.as_double();
458 need_reinflation_ =
true;
459 need_cache_recompute =
true;
461 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
462 if (param_name == name_ +
"." +
"enabled" && enabled_ != parameter.as_bool()) {
463 enabled_ = parameter.as_bool();
464 need_reinflation_ =
true;
466 }
else if (param_name == name_ +
"." +
"inflate_unknown" &&
467 inflate_unknown_ != parameter.as_bool())
469 inflate_unknown_ = parameter.as_bool();
470 need_reinflation_ =
true;
471 }
else if (param_name == name_ +
"." +
"inflate_around_unknown" &&
472 inflate_around_unknown_ != parameter.as_bool())
474 inflate_around_unknown_ = parameter.as_bool();
475 need_reinflation_ =
true;
480 if (need_cache_recompute) {
484 result.successful =
true;
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 inforamtion.
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().