Public Member Functions | Private Member Functions | Private Attributes | List of all members
spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer Class Reference

#include <spatio_temporal_voxel_layer.hpp>

Inheritance diagram for spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer:
Inheritance graph
[legend]

Public Member Functions

virtual void activate (void)
 
virtual void deactivate (void)
 
bool GetClearingObservations (std::vector< observation::MeasurementReading > &marking_observations) const
 
bool GetMarkingObservations (std::vector< observation::MeasurementReading > &marking_observations) const
 
virtual void matchSize (void)
 
void ObservationsResetAfterReading () const
 
virtual void onInitialize (void)
 
virtual void reset (void)
 
void ResetGrid (void)
 
bool SaveGridCallback (spatio_temporal_voxel_layer::SaveGrid::Request &req, spatio_temporal_voxel_layer::SaveGrid::Response &resp)
 
 SpatioTemporalVoxelLayer (void)
 
virtual void updateBounds (double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
 
virtual void updateCosts (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
bool updateFootprint (double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
 
void UpdateROSCostmap (double *min_x, double *min_y, double *max_x, double *max_y)
 
virtual ~SpatioTemporalVoxelLayer (void)
 
- 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)
 
virtual void updateOrigin (double new_origin_x, double new_origin_y)
 
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 ()
 

Private Member Functions

bool AddStaticObservations (const observation::MeasurementReading &obs)
 
bool BufferEnablerCallback (std_srvs::SetBool::Request &request, std_srvs::SetBool::Response &response, boost::shared_ptr< buffer::MeasurementBuffer > &buffer, boost::shared_ptr< message_filters::SubscriberBase > &subcriber)
 
void DynamicReconfigureCallback (dynamicReconfigureType &config, uint32_t level)
 
void LaserScanCallback (const sensor_msgs::LaserScanConstPtr &message, const boost::shared_ptr< buffer::MeasurementBuffer > &buffer)
 
void LaserScanValidInfCallback (const sensor_msgs::LaserScanConstPtr &raw_message, const boost::shared_ptr< buffer::MeasurementBuffer > &buffer)
 
void PointCloud2Callback (const sensor_msgs::PointCloud2ConstPtr &message, const boost::shared_ptr< buffer::MeasurementBuffer > &buffer)
 
bool RemoveStaticObservations (void)
 

Private Attributes

std::vector< ros::ServiceServer_buffer_enabler_servers
 
std::vector< boost::shared_ptr< buffer::MeasurementBuffer > > _clearing_buffers
 
int _combination_method
 
volume_grid::GlobalDecayModel _decay_model
 
dynamicReconfigureServerType_dynamic_reconfigure_server
 
bool _enabled
 
std::string _global_frame
 
ros::ServiceServer _grid_saver
 
laser_geometry::LaserProjection _laser_projector
 
ros::Time _last_map_save_time
 
ros::Duration _map_save_duration
 
bool _mapping_mode
 
int _mark_threshold
 
std::vector< boost::shared_ptr< buffer::MeasurementBuffer > > _marking_buffers
 
std::vector< boost::shared_ptr< buffer::MeasurementBuffer > > _observation_buffers
 
std::vector< boost::shared_ptr< tf::MessageFilterBase > > _observation_notifiers
 
std::vector< boost::shared_ptr< message_filters::SubscriberBase > > _observation_subscribers
 
bool _publish_voxels
 
std::vector< observation::MeasurementReading_static_observations
 
std::vector< geometry_msgs::Point_transformed_footprint
 
bool _update_footprint_enabled
 
double _voxel_decay
 
volume_grid::SpatioTemporalVoxelGrid_voxel_grid
 
boost::recursive_mutex _voxel_grid_lock
 
ros::Publisher _voxel_pub
 
double _voxel_size
 

Additional Inherited Members

- Public Types inherited from costmap_2d::Costmap2D
typedef boost::recursive_mutex mutex_t
 
- 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)
 
virtual void resetMaps ()
 
- 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 86 of file spatio_temporal_voxel_layer.hpp.

Constructor & Destructor Documentation

spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::SpatioTemporalVoxelLayer ( void  )

Definition at line 43 of file spatio_temporal_voxel_layer.cpp.

spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::~SpatioTemporalVoxelLayer ( void  )
virtual

Definition at line 49 of file spatio_temporal_voxel_layer.cpp.

Member Function Documentation

void spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::activate ( void  )
virtual

Reimplemented from costmap_2d::Layer.

Definition at line 495 of file spatio_temporal_voxel_layer.cpp.

bool spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::AddStaticObservations ( const observation::MeasurementReading obs)
private

Definition at line 548 of file spatio_temporal_voxel_layer.cpp.

bool spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::BufferEnablerCallback ( std_srvs::SetBool::Request &  request,
std_srvs::SetBool::Response &  response,
boost::shared_ptr< buffer::MeasurementBuffer > &  buffer,
boost::shared_ptr< message_filters::SubscriberBase > &  subcriber 
)
private

Definition at line 376 of file spatio_temporal_voxel_layer.cpp.

void spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::deactivate ( void  )
virtual

Reimplemented from costmap_2d::Layer.

Definition at line 515 of file spatio_temporal_voxel_layer.cpp.

void spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::DynamicReconfigureCallback ( dynamicReconfigureType config,
uint32_t  level 
)
private

Definition at line 582 of file spatio_temporal_voxel_layer.cpp.

bool spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::GetClearingObservations ( std::vector< observation::MeasurementReading > &  marking_observations) const

Definition at line 431 of file spatio_temporal_voxel_layer.cpp.

bool spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::GetMarkingObservations ( std::vector< observation::MeasurementReading > &  marking_observations) const

Definition at line 410 of file spatio_temporal_voxel_layer.cpp.

void spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::LaserScanCallback ( const sensor_msgs::LaserScanConstPtr &  message,
const boost::shared_ptr< buffer::MeasurementBuffer > &  buffer 
)
private

Definition at line 307 of file spatio_temporal_voxel_layer.cpp.

void spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::LaserScanValidInfCallback ( const sensor_msgs::LaserScanConstPtr &  raw_message,
const boost::shared_ptr< buffer::MeasurementBuffer > &  buffer 
)
private

Definition at line 331 of file spatio_temporal_voxel_layer.cpp.

void spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::matchSize ( void  )
virtual

Reimplemented from costmap_2d::CostmapLayer.

Definition at line 634 of file spatio_temporal_voxel_layer.cpp.

void spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::ObservationsResetAfterReading ( ) const

Definition at line 448 of file spatio_temporal_voxel_layer.cpp.

void spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::onInitialize ( void  )
virtual

Reimplemented from costmap_2d::Layer.

Definition at line 63 of file spatio_temporal_voxel_layer.cpp.

void spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::PointCloud2Callback ( const sensor_msgs::PointCloud2ConstPtr &  message,
const boost::shared_ptr< buffer::MeasurementBuffer > &  buffer 
)
private

Definition at line 364 of file spatio_temporal_voxel_layer.cpp.

bool spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::RemoveStaticObservations ( void  )
private

Definition at line 565 of file spatio_temporal_voxel_layer.cpp.

void spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::reset ( void  )
virtual

Reimplemented from costmap_2d::Layer.

Definition at line 532 of file spatio_temporal_voxel_layer.cpp.

void spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::ResetGrid ( void  )

Definition at line 624 of file spatio_temporal_voxel_layer.cpp.

bool spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::SaveGridCallback ( spatio_temporal_voxel_layer::SaveGrid::Request &  req,
spatio_temporal_voxel_layer::SaveGrid::Response &  resp 
)

Definition at line 769 of file spatio_temporal_voxel_layer.cpp.

void spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::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::Layer.

Definition at line 693 of file spatio_temporal_voxel_layer.cpp.

void spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::updateCosts ( costmap_2d::Costmap2D master_grid,
int  min_i,
int  min_j,
int  max_i,
int  max_j 
)
virtual

Reimplemented from costmap_2d::Layer.

Definition at line 642 of file spatio_temporal_voxel_layer.cpp.

bool spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::updateFootprint ( double  robot_x,
double  robot_y,
double  robot_yaw,
double *  min_x,
double *  min_y,
double *  max_x,
double *  max_y 
)

Definition at line 474 of file spatio_temporal_voxel_layer.cpp.

void spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::UpdateROSCostmap ( double *  min_x,
double *  min_y,
double *  max_x,
double *  max_y 
)

Definition at line 671 of file spatio_temporal_voxel_layer.cpp.

Member Data Documentation

std::vector<ros::ServiceServer> spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_buffer_enabler_servers
private

Definition at line 152 of file spatio_temporal_voxel_layer.hpp.

std::vector<boost::shared_ptr<buffer::MeasurementBuffer> > spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_clearing_buffers
private

Definition at line 151 of file spatio_temporal_voxel_layer.hpp.

int spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_combination_method
private

Definition at line 162 of file spatio_temporal_voxel_layer.hpp.

volume_grid::GlobalDecayModel spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_decay_model
private

Definition at line 163 of file spatio_temporal_voxel_layer.hpp.

dynamicReconfigureServerType* spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_dynamic_reconfigure_server
private

Definition at line 153 of file spatio_temporal_voxel_layer.hpp.

bool spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_enabled
private

Definition at line 164 of file spatio_temporal_voxel_layer.hpp.

std::string spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_global_frame
private

Definition at line 160 of file spatio_temporal_voxel_layer.hpp.

ros::ServiceServer spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_grid_saver
private

Definition at line 157 of file spatio_temporal_voxel_layer.hpp.

laser_geometry::LaserProjection spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_laser_projector
private

Definition at line 146 of file spatio_temporal_voxel_layer.hpp.

ros::Time spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_last_map_save_time
private

Definition at line 159 of file spatio_temporal_voxel_layer.hpp.

ros::Duration spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_map_save_duration
private

Definition at line 158 of file spatio_temporal_voxel_layer.hpp.

bool spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_mapping_mode
private

Definition at line 155 of file spatio_temporal_voxel_layer.hpp.

int spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_mark_threshold
private

Definition at line 162 of file spatio_temporal_voxel_layer.hpp.

std::vector<boost::shared_ptr<buffer::MeasurementBuffer> > spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_marking_buffers
private

Definition at line 150 of file spatio_temporal_voxel_layer.hpp.

std::vector<boost::shared_ptr<buffer::MeasurementBuffer> > spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_observation_buffers
private

Definition at line 149 of file spatio_temporal_voxel_layer.hpp.

std::vector<boost::shared_ptr<tf::MessageFilterBase> > spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_observation_notifiers
private

Definition at line 148 of file spatio_temporal_voxel_layer.hpp.

std::vector<boost::shared_ptr<message_filters::SubscriberBase> > spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_observation_subscribers
private

Definition at line 147 of file spatio_temporal_voxel_layer.hpp.

bool spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_publish_voxels
private

Definition at line 155 of file spatio_temporal_voxel_layer.hpp.

std::vector<observation::MeasurementReading> spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_static_observations
private

Definition at line 166 of file spatio_temporal_voxel_layer.hpp.

std::vector<geometry_msgs::Point> spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_transformed_footprint
private

Definition at line 165 of file spatio_temporal_voxel_layer.hpp.

bool spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_update_footprint_enabled
private

Definition at line 164 of file spatio_temporal_voxel_layer.hpp.

double spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_voxel_decay
private

Definition at line 161 of file spatio_temporal_voxel_layer.hpp.

volume_grid::SpatioTemporalVoxelGrid* spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_voxel_grid
private

Definition at line 167 of file spatio_temporal_voxel_layer.hpp.

boost::recursive_mutex spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_voxel_grid_lock
private

Definition at line 168 of file spatio_temporal_voxel_layer.hpp.

ros::Publisher spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_voxel_pub
private

Definition at line 156 of file spatio_temporal_voxel_layer.hpp.

double spatio_temporal_voxel_layer::SpatioTemporalVoxelLayer::_voxel_size
private

Definition at line 161 of file spatio_temporal_voxel_layer.hpp.


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


spatio_temporal_voxel_layer
Author(s):
autogenerated on Sat Dec 21 2019 04:06:19