38 #ifndef NAV2_COSTMAP_2D__INFLATION_LAYER_HPP_
39 #define NAV2_COSTMAP_2D__INFLATION_LAYER_HPP_
45 #include "rclcpp/rclcpp.hpp"
46 #include "nav2_costmap_2d/layer.hpp"
47 #include "nav2_costmap_2d/layered_costmap.hpp"
67 CellData(
double i,
unsigned int x,
unsigned int y,
unsigned int sx,
unsigned int sy)
68 : index_(static_cast<unsigned int>(i)), x_(x), y_(y), src_x_(sx), src_y_(sy)
73 unsigned int src_x_, src_y_;
110 double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
113 double * max_y)
override;
124 int min_i,
int min_j,
int max_i,
int max_j)
override;
150 unsigned char cost = 0;
152 cost = LETHAL_OBSTACLE;
153 }
else if (distance * resolution_ <= inscribed_radius_) {
154 cost = INSCRIBED_INFLATED_OBSTACLE;
158 exp(-1.0 * cost_scaling_factor_ * (distance * resolution_ - inscribed_radius_));
159 cost =
static_cast<unsigned char>((INSCRIBED_INFLATED_OBSTACLE - 1) * factor);
165 typedef std::recursive_mutex mutex_t;
190 unsigned int mx,
unsigned int my,
unsigned int src_x,
193 unsigned int dx = (mx > src_x) ? mx - src_x : src_x - mx;
194 unsigned int dy = (my > src_y) ? my - src_y : src_y - my;
195 return cached_distances_[dx * cache_length_ + dy];
207 unsigned int mx,
unsigned int my,
unsigned int src_x,
210 unsigned int dx = (mx > src_x) ? mx - src_x : src_x - mx;
211 unsigned int dy = (my > src_y) ? my - src_y : src_y - my;
212 return cached_costs_[dx * cache_length_ + dy];
237 unsigned int index,
unsigned int mx,
unsigned int my,
238 unsigned int src_x,
unsigned int src_y);
244 rcl_interfaces::msg::SetParametersResult
247 double inflation_radius_, inscribed_radius_, cost_scaling_factor_;
248 bool inflate_unknown_, inflate_around_unknown_;
249 unsigned int cell_inflation_radius_;
250 unsigned int cached_cell_inflation_radius_;
251 std::vector<std::vector<CellData>> inflation_cells_;
255 std::vector<bool> seen_;
257 std::vector<unsigned char> cached_costs_;
258 std::vector<double> cached_distances_;
259 std::vector<std::vector<int>> distance_matrix_;
260 unsigned int cache_length_;
261 double last_min_x_, last_min_y_, last_max_x_, last_max_y_;
264 bool need_reinflation_;
267 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
Storage for cell information used during obstacle inflation.
CellData(double i, 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.
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.
virtual bool isClearable() override
If clearing operations should be processed on this layer or not.
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.