Nav2 Navigation Stack - jazzy
jazzy
ROS 2 Navigation Stack
|
Layer to convolve costmap by robot's radius or footprint to prevent collisions and largely simply collision checking. More...
#include <nav2_costmap_2d/include/nav2_costmap_2d/inflation_layer.hpp>
Public Types | |
typedef std::recursive_mutex | mutex_t |
Public Member Functions | |
InflationLayer () | |
A constructor. | |
~InflationLayer () | |
A destructor. | |
void | onInitialize () override |
Initialization process of layer on startup. | |
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. More... | |
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. More... | |
void | matchSize () override |
Match the size of the master costmap. | |
bool | isClearable () override |
If clearing operations should be processed on this layer or not. | |
void | reset () override |
Reset this costmap. | |
unsigned char | computeCost (double distance) const |
Given a distance, compute a cost. More... | |
mutex_t * | getMutex () |
Get the mutex of the inflation inforamtion. | |
double | getCostScalingFactor () |
double | getInflationRadius () |
![]() | |
Layer () | |
A constructor. | |
virtual | ~Layer () |
A destructor. | |
void | initialize (LayeredCostmap *parent, std::string name, tf2_ros::Buffer *tf, const nav2_util::LifecycleNode::WeakPtr &node, rclcpp::CallbackGroup::SharedPtr callback_group) |
Initialization process of layer on startup. | |
virtual void | deactivate () |
Stop publishers. | |
virtual void | activate () |
Restart publishers if they've been stopped. | |
std::string | getName () const |
Get the name of the costmap layer. | |
bool | isCurrent () const |
Check to make sure all the data in the layer is up to date. If the layer is not up to date, then it may be unsafe to plan using the data from this layer, and the planner may need to know. More... | |
bool | isEnabled () const |
Gets whether the layer is enabled. | |
const std::vector< geometry_msgs::msg::Point > & | getFootprint () const |
Convenience function for layered_costmap_->getFootprint(). | |
void | declareParameter (const std::string ¶m_name, const rclcpp::ParameterValue &value) |
Convenience functions for declaring ROS parameters. | |
void | declareParameter (const std::string ¶m_name, const rclcpp::ParameterType ¶m_type) |
Convenience functions for declaring ROS parameters. | |
bool | hasParameter (const std::string ¶m_name) |
Convenience functions for declaring ROS parameters. | |
std::string | getFullName (const std::string ¶m_name) |
Convenience functions for declaring ROS parameters. | |
Static Public Member Functions | |
static std::shared_ptr< nav2_costmap_2d::InflationLayer > | getInflationLayer (std::shared_ptr< nav2_costmap_2d::Costmap2DROS > &costmap_ros, const std::string layer_name="") |
Protected Member Functions | |
void | onFootprintChanged () override |
Process updates on footprint changes to the inflation layer. | |
double | distanceLookup (unsigned int mx, unsigned int my, unsigned int src_x, unsigned int src_y) |
Lookup pre-computed distances. More... | |
unsigned char | costLookup (unsigned int mx, unsigned int my, unsigned int src_x, unsigned int src_y) |
Lookup pre-computed costs. More... | |
void | computeCaches () |
Compute cached dsitances. | |
int | generateIntegerDistances () |
Compute cached dsitances. | |
unsigned int | cellDistance (double world_dist) |
Compute cached dsitances. | |
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. More... | |
rcl_interfaces::msg::SetParametersResult | dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters) |
Callback executed when a parameter change is detected. More... | |
Protected Attributes | |
double | inflation_radius_ |
double | inscribed_radius_ |
double | cost_scaling_factor_ |
bool | inflate_unknown_ |
bool | inflate_around_unknown_ |
unsigned int | cell_inflation_radius_ |
unsigned int | cached_cell_inflation_radius_ |
std::vector< std::vector< CellData > > | inflation_cells_ |
double | resolution_ |
std::vector< bool > | seen_ |
std::vector< unsigned char > | cached_costs_ |
std::vector< double > | cached_distances_ |
std::vector< std::vector< int > > | distance_matrix_ |
unsigned int | cache_length_ |
double | last_min_x_ |
double | last_min_y_ |
double | last_max_x_ |
double | last_max_y_ |
bool | need_reinflation_ |
mutex_t * | access_ |
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr | dyn_params_handler_ |
![]() | |
LayeredCostmap * | layered_costmap_ |
std::string | name_ |
tf2_ros::Buffer * | tf_ |
rclcpp::CallbackGroup::SharedPtr | callback_group_ |
rclcpp_lifecycle::LifecycleNode::WeakPtr | node_ |
rclcpp::Clock::SharedPtr | clock_ |
rclcpp::Logger | logger_ {rclcpp::get_logger("nav2_costmap_2d")} |
bool | current_ |
bool | enabled_ |
std::unordered_set< std::string > | local_params_ |
Layer to convolve costmap by robot's radius or footprint to prevent collisions and largely simply collision checking.
Definition at line 82 of file inflation_layer.hpp.
|
inline |
Given a distance, compute a cost.
distance | The distance from an obstacle in cells |
Definition at line 149 of file inflation_layer.hpp.
Referenced by computeCaches().
|
inlineprotected |
Lookup pre-computed costs.
mx | The x coordinate of the current cell |
my | The y coordinate of the current cell |
src_x | The x coordinate of the source cell |
src_y | The y coordinate of the source cell |
Definition at line 236 of file inflation_layer.hpp.
Referenced by updateCosts().
|
inlineprotected |
Lookup pre-computed distances.
mx | The x coordinate of the current cell |
my | The y coordinate of the current cell |
src_x | The x coordinate of the source cell |
src_y | The y coordinate of the source cell |
Definition at line 219 of file inflation_layer.hpp.
Referenced by enqueue().
|
protected |
Callback executed when a parameter change is detected.
event | ParameterEvent message |
Definition at line 436 of file inflation_layer.cpp.
References getMutex(), and matchSize().
Referenced by onInitialize().
|
inlineprotected |
Enqueue new cells in cache distance update search.
Given an index of a cell in the costmap, place it into a list pending for obstacle inflation.
grid | The costmap |
index | The index of the cell |
mx | The x coordinate of the cell (can be computed from the index, but saves time to store it) |
my | The y coordinate of the cell (can be computed from the index, but saves time to store it) |
src_x | The x index of the obstacle point inflation started at |
src_y | The y index of the obstacle point inflation started at |
Definition at line 333 of file inflation_layer.cpp.
References distanceLookup().
Referenced by updateCosts().
|
overridevirtual |
Update the bounds of the master costmap by this layer's update dimensions.
robot_x | X pose of robot |
robot_y | Y pose of robot |
robot_yaw | Robot orientation |
min_x | X min map coord of the window to update |
min_y | Y min map coord of the window to update |
max_x | X max map coord of the window to update |
max_y | Y max map coord of the window to update |
Implements nav2_costmap_2d::Layer.
Definition at line 136 of file inflation_layer.cpp.
References getMutex().
|
overridevirtual |
Update the costs in the master costmap in the window.
master_grid | The master costmap grid to update |
min_x | X min map coord of the window to update |
min_y | Y min map coord of the window to update |
max_x | X max map coord of the window to update |
max_y | Y max map coord of the window to update |
Implements nav2_costmap_2d::Layer.
Definition at line 194 of file inflation_layer.cpp.
References costLookup(), enqueue(), nav2_costmap_2d::Costmap2D::getCharMap(), nav2_costmap_2d::Costmap2D::getIndex(), getMutex(), nav2_costmap_2d::Costmap2D::getSizeInCellsX(), and nav2_costmap_2d::Costmap2D::getSizeInCellsY().