Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
Takes laser and pointcloud data to populate a 3D voxel representation of the environment. More...
#include <nav2_costmap_2d/include/nav2_costmap_2d/voxel_layer.hpp>
Public Member Functions | |
VoxelLayer () | |
Voxel Layer constructor. | |
virtual | ~VoxelLayer () |
Voxel Layer destructor. | |
virtual void | onInitialize () |
Initialization process of layer on startup. | |
virtual void | updateBounds (double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y) |
Update the bounds of the master costmap by this layer's update dimensions. More... | |
void | updateOrigin (double new_origin_x, double new_origin_y) |
Update the layer's origin to a new pose, often when in a rolling costmap. | |
bool | isDiscretized () |
If layer is discretely populated. | |
virtual void | matchSize () |
Match the size of the master costmap. | |
virtual void | reset () |
Reset this costmap. | |
virtual bool | isClearable () |
If clearing operations should be processed on this layer or not. | |
![]() | |
ObstacleLayer () | |
A constructor. | |
virtual | ~ObstacleLayer () |
A destructor. | |
virtual void | updateCosts (nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
Update the costs in the master costmap in the window. More... | |
virtual void | deactivate () |
Deactivate the layer. | |
virtual void | activate () |
Activate the layer. | |
rcl_interfaces::msg::SetParametersResult | dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters) |
Callback executed when a parameter change is detected. More... | |
void | resetBuffersLastUpdated () |
triggers the update of observations buffer | |
void | laserScanCallback (sensor_msgs::msg::LaserScan::ConstSharedPtr message, const std::shared_ptr< nav2_costmap_2d::ObservationBuffer > &buffer) |
A callback to handle buffering LaserScan messages. More... | |
void | laserScanValidInfCallback (sensor_msgs::msg::LaserScan::ConstSharedPtr message, const std::shared_ptr< nav2_costmap_2d::ObservationBuffer > &buffer) |
A callback to handle buffering LaserScan messages which need filtering to turn Inf values into range_max. More... | |
void | pointCloud2Callback (sensor_msgs::msg::PointCloud2::ConstSharedPtr message, const std::shared_ptr< nav2_costmap_2d::ObservationBuffer > &buffer) |
A callback to handle buffering PointCloud2 messages. More... | |
void | addStaticObservation (nav2_costmap_2d::Observation &obs, bool marking, bool clearing) |
void | clearStaticObservations (bool marking, bool clearing) |
![]() | |
CostmapLayer () | |
CostmapLayer constructor. | |
bool | isDiscretized () |
If layer is discrete. | |
virtual void | clearArea (int start_x, int start_y, int end_x, int end_y, bool invert) |
Clear an are in the costmap with the given dimension if invert, then clear everything except these dimensions. | |
void | addExtraBounds (double mx0, double my0, double mx1, double my1) |
![]() | |
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 | onFootprintChanged () |
LayeredCostmap calls this whenever the footprint there changes (via LayeredCostmap::setFootprint()). Override to be notified of changes to the robot's footprint. | |
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. | |
![]() | |
Costmap2D (unsigned int cells_size_x, unsigned int cells_size_y, double resolution, double origin_x, double origin_y, unsigned char default_value=0) | |
Constructor for a costmap. More... | |
Costmap2D (const Costmap2D &map) | |
Copy constructor for a costmap, creates a copy efficiently. More... | |
Costmap2D (const nav_msgs::msg::OccupancyGrid &map) | |
Constructor for a costmap from an OccupancyGrid map. More... | |
Costmap2D & | operator= (const Costmap2D &map) |
Overloaded assignment operator. More... | |
bool | copyCostmapWindow (const Costmap2D &map, double win_origin_x, double win_origin_y, double win_size_x, double win_size_y) |
Turn this costmap into a copy of a window of a costmap passed in. More... | |
bool | copyWindow (const Costmap2D &source, unsigned int sx0, unsigned int sy0, unsigned int sxn, unsigned int syn, unsigned int dx0, unsigned int dy0) |
Copies the (x0,y0)..(xn,yn) window from source costmap into a current costmap. More... | |
Costmap2D () | |
Default constructor. | |
virtual | ~Costmap2D () |
Destructor. | |
unsigned char | getCost (unsigned int mx, unsigned int my) const |
Get the cost of a cell in the costmap. More... | |
unsigned char | getCost (unsigned int index) const |
Get the cost of a cell in the costmap. More... | |
void | setCost (unsigned int mx, unsigned int my, unsigned char cost) |
Set the cost of a cell in the costmap. More... | |
void | mapToWorld (unsigned int mx, unsigned int my, double &wx, double &wy) const |
Convert from map coordinates to world coordinates. More... | |
bool | worldToMap (double wx, double wy, unsigned int &mx, unsigned int &my) const |
Convert from world coordinates to map coordinates. More... | |
void | worldToMapNoBounds (double wx, double wy, int &mx, int &my) const |
Convert from world coordinates to map coordinates without checking for legal bounds. More... | |
void | worldToMapEnforceBounds (double wx, double wy, int &mx, int &my) const |
Convert from world coordinates to map coordinates, constraining results to legal bounds. More... | |
unsigned int | getIndex (unsigned int mx, unsigned int my) const |
Given two map coordinates... compute the associated index. More... | |
void | indexToCells (unsigned int index, unsigned int &mx, unsigned int &my) const |
Given an index... compute the associated map coordinates. More... | |
unsigned char * | getCharMap () const |
Will return a pointer to the underlying unsigned char array used as the costmap. More... | |
unsigned int | getSizeInCellsX () const |
Accessor for the x size of the costmap in cells. More... | |
unsigned int | getSizeInCellsY () const |
Accessor for the y size of the costmap in cells. More... | |
double | getSizeInMetersX () const |
Accessor for the x size of the costmap in meters. More... | |
double | getSizeInMetersY () const |
Accessor for the y size of the costmap in meters. More... | |
double | getOriginX () const |
Accessor for the x origin of the costmap. More... | |
double | getOriginY () const |
Accessor for the y origin of the costmap. More... | |
double | getResolution () const |
Accessor for the resolution of the costmap. More... | |
void | setDefaultValue (unsigned char c) |
Set the default background value of the costmap. More... | |
unsigned char | getDefaultValue () |
Get the default background value of the costmap. More... | |
bool | setConvexPolygonCost (const std::vector< geometry_msgs::msg::Point > &polygon, unsigned char cost_value) |
Sets the cost of a convex polygon to a desired value. More... | |
void | polygonOutlineCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells) |
Get the map cells that make up the outline of a polygon. More... | |
void | convexFillCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells) |
Get the map cells that fill a convex polygon. More... | |
bool | saveMap (std::string file_name) |
Save the costmap out to a pgm file. More... | |
void | resizeMap (unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y) |
Resize the costmap. | |
void | resetMap (unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn) |
Reset the costmap in bounds. | |
void | resetMapToValue (unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn, unsigned char value) |
Reset the costmap in bounds to a value. | |
unsigned int | cellDistance (double world_dist) |
Given distance in the world... convert it to cells. More... | |
mutex_t * | getMutex () |
Protected Member Functions | |
virtual void | resetMaps () |
Reset internal maps. | |
virtual void | raytraceFreespace (const nav2_costmap_2d::Observation &clearing_observation, double *min_x, double *min_y, double *max_x, double *max_y) |
Use raycasting between 2 points to clear freespace. | |
bool | worldToMap3DFloat (double wx, double wy, double wz, double &mx, double &my, double &mz) |
Covert world coordinates into map coordinates. | |
bool | worldToMap3D (double wx, double wy, double wz, unsigned int &mx, unsigned int &my, unsigned int &mz) |
Covert world coordinates into map coordinates. | |
void | mapToWorld3D (unsigned int mx, unsigned int my, unsigned int mz, double &wx, double &wy, double &wz) |
Covert map coordinates into world coordinates. | |
double | dist (double x0, double y0, double z0, double x1, double y1, double z1) |
Find L2 norm distance in 3D. | |
double | getSizeInMetersZ () const |
Get the height of the voxel sizes in meters. | |
rcl_interfaces::msg::SetParametersResult | dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters) |
Callback executed when a parameter change is detected. More... | |
![]() | |
bool | getMarkingObservations (std::vector< nav2_costmap_2d::Observation > &marking_observations) const |
Get the observations used to mark space. More... | |
bool | getClearingObservations (std::vector< nav2_costmap_2d::Observation > &clearing_observations) const |
Get the observations used to clear space. More... | |
void | updateRaytraceBounds (double ox, double oy, double wx, double wy, double max_range, double min_range, double *min_x, double *min_y, double *max_x, double *max_y) |
Process update costmap with raytracing the window bounds. | |
void | updateFootprint (double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y) |
Clear costmap layer info below the robot's footprint. | |
![]() | |
void | updateWithTrueOverwrite (nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
void | updateWithOverwrite (nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
void | updateWithMax (nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
void | updateWithAddition (nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
void | touch (double x, double y, double *min_x, double *min_y, double *max_x, double *max_y) |
void | useExtraBounds (double *min_x, double *min_y, double *max_x, double *max_y) |
![]() | |
template<typename data_type > | |
void | copyMapRegion (data_type *source_map, unsigned int sm_lower_left_x, unsigned int sm_lower_left_y, unsigned int sm_size_x, data_type *dest_map, unsigned int dm_lower_left_x, unsigned int dm_lower_left_y, unsigned int dm_size_x, unsigned int region_size_x, unsigned int region_size_y) |
Copy a region of a source map into a destination map. More... | |
virtual void | deleteMaps () |
Deletes the costmap, static_map, and markers data structures. | |
virtual void | initMaps (unsigned int size_x, unsigned int size_y) |
Initializes the costmap, static_map, and markers data structures. More... | |
template<class ActionType > | |
void | raytraceLine (ActionType at, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, unsigned int max_length=UINT_MAX, unsigned int min_length=0) |
Raytrace a line and apply some action at each step. More... | |
Protected Attributes | |
bool | publish_voxel_ |
rclcpp_lifecycle::LifecyclePublisher< nav2_msgs::msg::VoxelGrid >::SharedPtr | voxel_pub_ |
nav2_voxel_grid::VoxelGrid | voxel_grid_ |
double | z_resolution_ |
double | origin_z_ |
int | unknown_threshold_ |
int | mark_threshold_ |
int | size_z_ |
rclcpp_lifecycle::LifecyclePublisher< sensor_msgs::msg::PointCloud2 >::SharedPtr | clearing_endpoints_pub_ |
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr | dyn_params_handler_ |
![]() | |
std::vector< geometry_msgs::msg::Point > | transformed_footprint_ |
bool | footprint_clearing_enabled_ |
std::string | global_frame_ |
The global frame for the costmap. | |
double | min_obstacle_height_ |
Max Obstacle Height. | |
double | max_obstacle_height_ |
Max Obstacle Height. | |
laser_geometry::LaserProjection | projector_ |
Used to project laser scans into point clouds. | |
std::vector< std::shared_ptr< message_filters::SubscriberBase< rclcpp_lifecycle::LifecycleNode > > > | observation_subscribers_ |
Used for the observation message filters. | |
std::vector< std::shared_ptr< tf2_ros::MessageFilterBase > > | observation_notifiers_ |
Used to make sure that transforms are available for each sensor. | |
std::vector< std::shared_ptr< nav2_costmap_2d::ObservationBuffer > > | observation_buffers_ |
Used to store observations from various sensors. | |
std::vector< std::shared_ptr< nav2_costmap_2d::ObservationBuffer > > | marking_buffers_ |
Used to store observation buffers used for marking obstacles. | |
std::vector< std::shared_ptr< nav2_costmap_2d::ObservationBuffer > > | clearing_buffers_ |
Used to store observation buffers used for clearing obstacles. | |
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr | dyn_params_handler_ |
Dynamic parameters handler. | |
std::vector< nav2_costmap_2d::Observation > | static_clearing_observations_ |
std::vector< nav2_costmap_2d::Observation > | static_marking_observations_ |
bool | rolling_window_ |
bool | was_reset_ |
int | combination_method_ |
![]() | |
bool | has_extra_bounds_ |
![]() | |
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_ |
![]() | |
unsigned int | size_x_ |
unsigned int | size_y_ |
double | resolution_ |
double | origin_x_ |
double | origin_y_ |
unsigned char * | costmap_ |
unsigned char | default_value_ |
Additional Inherited Members | |
![]() | |
typedef std::recursive_mutex | mutex_t |
Takes laser and pointcloud data to populate a 3D voxel representation of the environment.
Definition at line 64 of file voxel_layer.hpp.
|
protected |
Callback executed when a parameter change is detected.
event | ParameterEvent message |
Definition at line 482 of file voxel_layer.cpp.
References matchSize(), and nav2_costmap_2d::ObstacleLayer::max_obstacle_height_.
Referenced by onInitialize().
|
virtual |
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 |
Reimplemented from nav2_costmap_2d::ObstacleLayer.
Definition at line 144 of file voxel_layer.cpp.
References nav2_costmap_2d::ObstacleLayer::getClearingObservations(), nav2_costmap_2d::Costmap2D::getIndex(), nav2_costmap_2d::ObstacleLayer::getMarkingObservations(), nav2_costmap_2d::Costmap2D::getSizeInMetersX(), nav2_costmap_2d::Costmap2D::getSizeInMetersY(), nav2_costmap_2d::ObstacleLayer::global_frame_, nav2_costmap_2d::ObstacleLayer::max_obstacle_height_, raytraceFreespace(), nav2_costmap_2d::CostmapLayer::touch(), nav2_costmap_2d::ObstacleLayer::updateFootprint(), updateOrigin(), and worldToMap3D().