Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
rtabmap_ros::VoxelLayer Class Reference

#include <voxel_layer.h>

Inheritance diagram for rtabmap_ros::VoxelLayer:
Inheritance graph
[legend]

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 ()
 
- Public Member Functions inherited from costmap_2d::ObstacleLayer
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 ()
 
- Public Member Functions inherited from costmap_2d::CostmapLayer
void addExtraBounds (double mx0, double my0, double mx1, double my1)
 
 CostmapLayer ()
 
bool isDiscretized ()
 
- Public Member Functions inherited from costmap_2d::Layer
const std::vector< geometry_msgs::Point > & getFootprint () const
 
std::string getName () const
 
void initialize (LayeredCostmap *parent, std::string name, tf::TransformListener *tf)
 
bool isCurrent () const
 
 Layer ()
 
virtual void onFootprintChanged ()
 
virtual ~Layer ()
 
- Public Member Functions inherited from costmap_2d::Costmap2D
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 (unsigned int cells_size_x, unsigned int cells_size_y, double resolution, double origin_x, double origin_y, unsigned char default_value=0)
 
 Costmap2D (const Costmap2D &map)
 
 Costmap2D ()
 
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_tgetMutex ()
 
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
 
Costmap2Doperator= (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)
 
- Protected Member Functions inherited from costmap_2d::ObstacleLayer
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)
 
- Protected Member Functions inherited from costmap_2d::CostmapLayer
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)
 
- Protected Member Functions inherited from costmap_2d::Costmap2D
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_
 

Additional Inherited Members

- Public Types inherited from costmap_2d::Costmap2D
typedef boost::recursive_mutex mutex_t
 
- Protected Attributes inherited from costmap_2d::ObstacleLayer
std::vector< boost::shared_ptr< costmap_2d::ObservationBuffer > > clearing_buffers_
 
int combination_method_
 
dynamic_reconfigure::Server< costmap_2d::ObstaclePluginConfig > * dsrv_
 
bool footprint_clearing_enabled_
 
std::string global_frame_
 
std::vector< boost::shared_ptr< costmap_2d::ObservationBuffer > > marking_buffers_
 
double max_obstacle_height_
 
std::vector< boost::shared_ptr< costmap_2d::ObservationBuffer > > observation_buffers_
 
std::vector< boost::shared_ptr< tf::MessageFilterBase > > observation_notifiers_
 
std::vector< boost::shared_ptr< message_filters::SubscriberBase > > observation_subscribers_
 
laser_geometry::LaserProjection projector_
 
bool rolling_window_
 
std::vector< costmap_2d::Observationstatic_clearing_observations_
 
std::vector< costmap_2d::Observationstatic_marking_observations_
 
std::vector< geometry_msgs::Pointtransformed_footprint_
 
- Protected Attributes inherited from costmap_2d::CostmapLayer
bool has_extra_bounds_
 
- Protected Attributes inherited from costmap_2d::Layer
bool current_
 
bool enabled_
 
LayeredCostmaplayered_costmap_
 
std::string name_
 
tf::TransformListenertf_
 
- Protected Attributes inherited from costmap_2d::Costmap2D
unsigned char * costmap_
 
unsigned char default_value_
 
double origin_x_
 
double origin_y_
 
double resolution_
 
unsigned int size_x_
 
unsigned int size_y_
 

Detailed Description

Definition at line 60 of file voxel_layer.h.

Constructor & Destructor Documentation

rtabmap_ros::VoxelLayer::VoxelLayer ( )
inline

Definition at line 63 of file voxel_layer.h.

rtabmap_ros::VoxelLayer::~VoxelLayer ( )
virtual

Definition at line 84 of file voxel_layer.cpp.

Member Function Documentation

void rtabmap_ros::VoxelLayer::clearNonLethal ( double  wx,
double  wy,
double  w_size_x,
double  w_size_y,
bool  clear_no_info 
)
private

Definition at line 217 of file voxel_layer.cpp.

template<typename data_type >
void rtabmap_ros::VoxelLayer::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 
)
inlineprivate

Copy a region of a source map into a destination map.

Parameters
source_mapThe source map
sm_lower_left_xThe lower left x point of the source map to start the copy
sm_lower_left_yThe lower left y point of the source map to start the copy
sm_size_xThe x size of the source map
dest_mapThe destination map
dm_lower_left_xThe lower left x point of the destination map to start the copy
dm_lower_left_yThe lower left y point of the destination map to start the copy
dm_size_xThe x size of the destination map
region_size_xThe x size of the region to copy
region_size_yThe y size of the region to copy

Definition at line 162 of file voxel_layer.h.

double rtabmap_ros::VoxelLayer::dist ( double  x0,
double  y0,
double  z0,
double  x1,
double  y1,
double  z1 
)
inlineprivate

Definition at line 142 of file voxel_layer.h.

bool rtabmap_ros::VoxelLayer::isDiscretized ( )
inline

Definition at line 76 of file voxel_layer.h.

void rtabmap_ros::VoxelLayer::mapToWorld3D ( unsigned int  mx,
unsigned int  my,
unsigned int  mz,
double &  wx,
double &  wy,
double &  wz 
)
inlineprivate

Definition at line 134 of file voxel_layer.h.

void rtabmap_ros::VoxelLayer::matchSize ( )
virtual

Reimplemented from costmap_2d::CostmapLayer.

Definition at line 104 of file voxel_layer.cpp.

void rtabmap_ros::VoxelLayer::onInitialize ( )
virtual

Reimplemented from costmap_2d::ObstacleLayer.

Definition at line 58 of file voxel_layer.cpp.

void rtabmap_ros::VoxelLayer::raytraceFreespace ( const costmap_2d::Observation clearing_observation,
double *  min_x,
double *  min_y,
double *  max_x,
double *  max_y 
)
privatevirtual

Reimplemented from costmap_2d::ObstacleLayer.

Definition at line 268 of file voxel_layer.cpp.

void rtabmap_ros::VoxelLayer::reconfigureCB ( costmap_2d::VoxelPluginConfig &  config,
uint32_t  level 
)
private

Definition at line 90 of file voxel_layer.cpp.

void rtabmap_ros::VoxelLayer::reset ( )
virtual

Reimplemented from costmap_2d::ObstacleLayer.

Definition at line 111 of file voxel_layer.cpp.

void rtabmap_ros::VoxelLayer::resetMaps ( )
protectedvirtual

Reimplemented from costmap_2d::Costmap2D.

Definition at line 119 of file voxel_layer.cpp.

void rtabmap_ros::VoxelLayer::setupDynamicReconfigure ( ros::NodeHandle nh)
protectedvirtual

Reimplemented from costmap_2d::ObstacleLayer.

Definition at line 76 of file voxel_layer.cpp.

void rtabmap_ros::VoxelLayer::updateBounds ( double  robot_x,
double  robot_y,
double  robot_yaw,
double *  min_x,
double *  min_y,
double *  max_x,
double *  max_y 
)
virtual

Reimplemented from costmap_2d::ObstacleLayer.

Definition at line 125 of file voxel_layer.cpp.

void rtabmap_ros::VoxelLayer::updateOrigin ( double  new_origin_x,
double  new_origin_y 
)
virtual

Reimplemented from costmap_2d::Costmap2D.

Definition at line 401 of file voxel_layer.cpp.

bool rtabmap_ros::VoxelLayer::worldToMap3D ( double  wx,
double  wy,
double  wz,
unsigned int &  mx,
unsigned int &  my,
unsigned int &  mz 
)
inlineprivate

Definition at line 119 of file voxel_layer.h.

bool rtabmap_ros::VoxelLayer::worldToMap3DFloat ( double  wx,
double  wy,
double  wz,
double &  mx,
double &  my,
double &  mz 
)
inlineprivate

Definition at line 106 of file voxel_layer.h.

Member Data Documentation

sensor_msgs::PointCloud rtabmap_ros::VoxelLayer::clearing_endpoints_
private

Definition at line 104 of file voxel_layer.h.

ros::Publisher rtabmap_ros::VoxelLayer::clearing_endpoints_pub_
private

Definition at line 103 of file voxel_layer.h.

unsigned int rtabmap_ros::VoxelLayer::mark_threshold_
private

Definition at line 102 of file voxel_layer.h.

double rtabmap_ros::VoxelLayer::origin_z_
private

Definition at line 101 of file voxel_layer.h.

bool rtabmap_ros::VoxelLayer::publish_voxel_
private

Definition at line 97 of file voxel_layer.h.

std::string rtabmap_ros::VoxelLayer::robot_base_frame_
private

Definition at line 98 of file voxel_layer.h.

unsigned int rtabmap_ros::VoxelLayer::size_z_
private

Definition at line 102 of file voxel_layer.h.

unsigned int rtabmap_ros::VoxelLayer::unknown_threshold_
private

Definition at line 102 of file voxel_layer.h.

dynamic_reconfigure::Server<costmap_2d::VoxelPluginConfig>* rtabmap_ros::VoxelLayer::voxel_dsrv_
private

Definition at line 95 of file voxel_layer.h.

voxel_grid::VoxelGrid rtabmap_ros::VoxelLayer::voxel_grid_
private

Definition at line 100 of file voxel_layer.h.

ros::Publisher rtabmap_ros::VoxelLayer::voxel_pub_
private

Definition at line 99 of file voxel_layer.h.

double rtabmap_ros::VoxelLayer::z_resolution_
private

Definition at line 101 of file voxel_layer.h.


The documentation for this class was generated from the following files:


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:19