38 #ifndef NAV2_COSTMAP_2D__INFLATION_LAYER_HPP_
39 #define NAV2_COSTMAP_2D__INFLATION_LAYER_HPP_
47 #include "rclcpp/rclcpp.hpp"
48 #include "nav2_costmap_2d/layer.hpp"
49 #include "nav2_costmap_2d/layered_costmap.hpp"
50 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
69 CellData(
unsigned int x,
unsigned int y,
unsigned int sx,
unsigned int sy)
70 : x_(x), y_(y), src_x_(sx), src_y_(sy)
74 unsigned int src_x_, src_y_;
111 double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
114 double * max_y)
override;
125 int min_i,
int min_j,
int max_i,
int max_j)
override;
151 unsigned char cost = 0;
153 cost = LETHAL_OBSTACLE;
154 }
else if (distance * resolution_ <= inscribed_radius_) {
155 cost = INSCRIBED_INFLATED_OBSTACLE;
159 exp(-1.0 * cost_scaling_factor_ * (distance * resolution_ - inscribed_radius_));
160 cost =
static_cast<unsigned char>((INSCRIBED_INFLATED_OBSTACLE - 1) * factor);
165 static std::shared_ptr<nav2_costmap_2d::InflationLayer> getInflationLayer(
166 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> & costmap_ros,
167 const std::string layer_name =
"")
169 const auto layered_costmap = costmap_ros->getLayeredCostmap();
170 for (
auto layer = layered_costmap->getPlugins()->begin();
171 layer != layered_costmap->getPlugins()->end();
174 auto inflation_layer = std::dynamic_pointer_cast<nav2_costmap_2d::InflationLayer>(*layer);
175 if (inflation_layer) {
176 if (layer_name.empty() || inflation_layer->getName() == layer_name) {
177 return inflation_layer;
185 typedef std::recursive_mutex mutex_t;
195 double getCostScalingFactor()
197 return cost_scaling_factor_;
200 double getInflationRadius()
202 return inflation_radius_;
220 unsigned int mx,
unsigned int my,
unsigned int src_x,
223 unsigned int dx = (mx > src_x) ? mx - src_x : src_x - mx;
224 unsigned int dy = (my > src_y) ? my - src_y : src_y - my;
225 return cached_distances_[dx * cache_length_ + dy];
237 unsigned int mx,
unsigned int my,
unsigned int src_x,
240 unsigned int dx = (mx > src_x) ? mx - src_x : src_x - mx;
241 unsigned int dy = (my > src_y) ? my - src_y : src_y - my;
242 return cached_costs_[dx * cache_length_ + dy];
267 unsigned int index,
unsigned int mx,
unsigned int my,
268 unsigned int src_x,
unsigned int src_y);
274 rcl_interfaces::msg::SetParametersResult
277 double inflation_radius_, inscribed_radius_, cost_scaling_factor_;
278 bool inflate_unknown_, inflate_around_unknown_;
279 unsigned int cell_inflation_radius_;
280 unsigned int cached_cell_inflation_radius_;
281 std::vector<std::vector<CellData>> inflation_cells_;
285 std::vector<bool> seen_;
287 std::vector<unsigned char> cached_costs_;
288 std::vector<double> cached_distances_;
289 std::vector<std::vector<int>> distance_matrix_;
290 unsigned int cache_length_;
291 double last_min_x_, last_min_y_, last_max_x_, last_max_y_;
294 bool need_reinflation_;
297 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
Storage for cell information used during obstacle inflation.
CellData(unsigned int x, unsigned int y, unsigned int sx, unsigned int sy)
Constructor for a CellData objects.
A 2D costmap provides a mapping between points in the world and their associated "costs".
unsigned int cellDistance(double world_dist)
Given distance in the world... convert it to 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 reset() override
Reset this costmap.
void matchSize() override
Match the size of the master costmap.
void onFootprintChanged() override
Process updates on footprint changes to the inflation layer.
bool isClearable() override
If clearing operations should be processed on this layer or not.
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.
Costmap2D * getCostmap()
Get the costmap pointer to the master costmap.