#include <voxel_layer.h>
Public Member Functions | |
bool | isDiscretized () |
virtual void | matchSize () |
virtual void | onInitialize () |
virtual void | reset () |
virtual void | updateBounds (double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y) |
void | updateOrigin (double new_origin_x, double new_origin_y) |
VoxelLayer () | |
virtual | ~VoxelLayer () |
![]() | |
virtual void | activate () |
void | addStaticObservation (costmap_2d::Observation &obs, bool marking, bool clearing) |
void | clearStaticObservations (bool marking, bool clearing) |
virtual void | deactivate () |
void | laserScanCallback (const sensor_msgs::LaserScanConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer) |
void | laserScanValidInfCallback (const sensor_msgs::LaserScanConstPtr &message, const boost::shared_ptr< ObservationBuffer > &buffer) |
ObstacleLayer () | |
void | pointCloud2Callback (const sensor_msgs::PointCloud2ConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer) |
void | pointCloudCallback (const sensor_msgs::PointCloudConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer) |
virtual void | updateCosts (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
virtual | ~ObstacleLayer () |
![]() | |
void | addExtraBounds (double mx0, double my0, double mx1, double my1) |
virtual void | clearArea (int start_x, int start_y, int end_x, int end_y, bool invert_area=false) |
CostmapLayer () | |
bool | isDiscretized () |
![]() | |
const std::vector< geometry_msgs::Point > & | getFootprint () const |
const std::string & | getName () const noexcept |
void | initialize (LayeredCostmap *parent, std::string name, tf2_ros::Buffer *tf) |
bool | isCurrent () const |
bool | isEnabled () const noexcept |
Layer () | |
virtual void | onFootprintChanged () |
virtual | ~Layer () |
![]() | |
unsigned int | cellDistance (double world_dist) |
void | convexFillCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells) |
bool | copyCostmapWindow (const Costmap2D &map, double win_origin_x, double win_origin_y, double win_size_x, double win_size_y) |
Costmap2D () | |
Costmap2D (const Costmap2D &map) | |
Costmap2D (unsigned int cells_size_x, unsigned int cells_size_y, double resolution, double origin_x, double origin_y, unsigned char default_value=0) | |
unsigned char * | getCharMap () const |
unsigned char | getCost (unsigned int mx, unsigned int my) const |
unsigned char | getDefaultValue () |
unsigned int | getIndex (unsigned int mx, unsigned int my) const |
mutex_t * | getMutex () |
double | getOriginX () const |
double | getOriginY () const |
double | getResolution () const |
unsigned int | getSizeInCellsX () const |
unsigned int | getSizeInCellsY () const |
double | getSizeInMetersX () const |
double | getSizeInMetersY () const |
void | indexToCells (unsigned int index, unsigned int &mx, unsigned int &my) const |
void | mapToWorld (unsigned int mx, unsigned int my, double &wx, double &wy) const |
Costmap2D & | operator= (const Costmap2D &map) |
void | polygonOutlineCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells) |
void | resetMap (unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn) |
void | resizeMap (unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y) |
bool | saveMap (std::string file_name) |
bool | setConvexPolygonCost (const std::vector< geometry_msgs::Point > &polygon, unsigned char cost_value) |
void | setCost (unsigned int mx, unsigned int my, unsigned char cost) |
void | setDefaultValue (unsigned char c) |
bool | worldToMap (double wx, double wy, unsigned int &mx, unsigned int &my) const |
void | worldToMapEnforceBounds (double wx, double wy, int &mx, int &my) const |
void | worldToMapNoBounds (double wx, double wy, int &mx, int &my) const |
virtual | ~Costmap2D () |
Protected Member Functions | |
virtual void | resetMaps () |
virtual void | setupDynamicReconfigure (ros::NodeHandle &nh) |
![]() | |
bool | getClearingObservations (std::vector< costmap_2d::Observation > &clearing_observations) const |
bool | getMarkingObservations (std::vector< costmap_2d::Observation > &marking_observations) const |
void | updateFootprint (double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y) |
void | updateRaytraceBounds (double ox, double oy, double wx, double wy, double range, double *min_x, double *min_y, double *max_x, double *max_y) |
![]() | |
void | touch (double x, double y, double *min_x, double *min_y, double *max_x, double *max_y) |
void | updateWithAddition (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
void | updateWithMax (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
void | updateWithOverwrite (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
void | updateWithTrueOverwrite (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
void | useExtraBounds (double *min_x, double *min_y, double *max_x, double *max_y) |
![]() | |
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) |
virtual void | deleteMaps () |
virtual void | initMaps (unsigned int size_x, unsigned int size_y) |
void | raytraceLine (ActionType at, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, unsigned int max_length=UINT_MAX) |
Private Member Functions | |
void | clearNonLethal (double wx, double wy, double w_size_x, double w_size_y, bool clear_no_info) |
template<typename data_type > | |
void | copyMapRegion3D (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, int z_shift) |
Copy a region of a source map into a destination map. More... | |
double | dist (double x0, double y0, double z0, double x1, double y1, double z1) |
void | mapToWorld3D (unsigned int mx, unsigned int my, unsigned int mz, double &wx, double &wy, double &wz) |
virtual void | raytraceFreespace (const costmap_2d::Observation &clearing_observation, double *min_x, double *min_y, double *max_x, double *max_y) |
void | reconfigureCB (costmap_2d::VoxelPluginConfig &config, uint32_t level) |
bool | worldToMap3D (double wx, double wy, double wz, unsigned int &mx, unsigned int &my, unsigned int &mz) |
bool | worldToMap3DFloat (double wx, double wy, double wz, double &mx, double &my, double &mz) |
Private Attributes | |
sensor_msgs::PointCloud | clearing_endpoints_ |
ros::Publisher | clearing_endpoints_pub_ |
unsigned int | mark_threshold_ |
double | origin_z_ |
bool | publish_voxel_ |
std::string | robot_base_frame_ |
unsigned int | size_z_ |
unsigned int | unknown_threshold_ |
dynamic_reconfigure::Server< costmap_2d::VoxelPluginConfig > * | voxel_dsrv_ |
voxel_grid::VoxelGrid | voxel_grid_ |
ros::Publisher | voxel_pub_ |
double | z_resolution_ |
Definition at line 96 of file voxel_layer.h.
|
inline |
Definition at line 135 of file voxel_layer.h.
|
virtual |
Definition at line 84 of file voxel_layer.cpp.
|
private |
Definition at line 217 of file voxel_layer.cpp.
|
inlineprivate |
Copy a region of a source map into a destination map.
source_map | The source map |
sm_lower_left_x | The lower left x point of the source map to start the copy |
sm_lower_left_y | The lower left y point of the source map to start the copy |
sm_size_x | The x size of the source map |
dest_map | The destination map |
dm_lower_left_x | The lower left x point of the destination map to start the copy |
dm_lower_left_y | The lower left y point of the destination map to start the copy |
dm_size_x | The x size of the destination map |
region_size_x | The x size of the region to copy |
region_size_y | The y size of the region to copy |
Definition at line 234 of file voxel_layer.h.
|
inlineprivate |
Definition at line 214 of file voxel_layer.h.
|
inline |
Definition at line 148 of file voxel_layer.h.
|
inlineprivate |
Definition at line 206 of file voxel_layer.h.
|
virtual |
Reimplemented from costmap_2d::CostmapLayer.
Definition at line 104 of file voxel_layer.cpp.
|
virtual |
Reimplemented from costmap_2d::ObstacleLayer.
Definition at line 58 of file voxel_layer.cpp.
|
privatevirtual |
Reimplemented from costmap_2d::ObstacleLayer.
Definition at line 268 of file voxel_layer.cpp.
|
private |
Definition at line 90 of file voxel_layer.cpp.
|
virtual |
Reimplemented from costmap_2d::ObstacleLayer.
Definition at line 111 of file voxel_layer.cpp.
|
protectedvirtual |
Reimplemented from costmap_2d::Costmap2D.
Definition at line 119 of file voxel_layer.cpp.
|
protectedvirtual |
Reimplemented from costmap_2d::ObstacleLayer.
Definition at line 76 of file voxel_layer.cpp.
|
virtual |
Reimplemented from costmap_2d::ObstacleLayer.
Definition at line 125 of file voxel_layer.cpp.
|
virtual |
Reimplemented from costmap_2d::Costmap2D.
Definition at line 401 of file voxel_layer.cpp.
|
inlineprivate |
Definition at line 191 of file voxel_layer.h.
|
inlineprivate |
Definition at line 178 of file voxel_layer.h.
|
private |
Definition at line 176 of file voxel_layer.h.
|
private |
Definition at line 175 of file voxel_layer.h.
|
private |
Definition at line 174 of file voxel_layer.h.
|
private |
Definition at line 173 of file voxel_layer.h.
|
private |
Definition at line 169 of file voxel_layer.h.
|
private |
Definition at line 170 of file voxel_layer.h.
|
private |
Definition at line 174 of file voxel_layer.h.
|
private |
Definition at line 174 of file voxel_layer.h.
|
private |
Definition at line 167 of file voxel_layer.h.
|
private |
Definition at line 172 of file voxel_layer.h.
|
private |
Definition at line 171 of file voxel_layer.h.
|
private |
Definition at line 173 of file voxel_layer.h.