Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
volume_grid::SpatioTemporalVoxelGrid Class Reference

#include <spatio_temporal_voxel_grid.hpp>

Public Types

typedef openvdb::math::Ray< openvdb::Real > GridRay
 
typedef openvdb::math::Ray< openvdb::Real >::Vec3T Vec3Type
 

Public Member Functions

void ClearFrustums (const std::vector< observation::MeasurementReading > &clearing_observations, std::unordered_set< occupany_cell > &cleared_cells)
 
std::unordered_map< occupany_cell, uint > * GetFlattenedCostmap ()
 
void GetOccupancyPointCloud (sensor_msgs::PointCloud2::Ptr &pc2)
 
void Mark (const std::vector< observation::MeasurementReading > &marking_observations)
 
void operator() (const observation::MeasurementReading &obs) const
 
bool ResetGrid (void)
 
void ResetGridArea (const occupany_cell &start, const occupany_cell &end, bool invert_area=false)
 
bool SaveGrid (const std::string &file_name, double &map_size_bytes)
 
 SpatioTemporalVoxelGrid (const float &voxel_size, const double &background_value, const int &decay_model, const double &voxel_decay, const bool &pub_voxels)
 
 ~SpatioTemporalVoxelGrid (void)
 

Protected Member Functions

bool ClearGridPoint (const openvdb::Coord &pt) const
 
double GetFrustumAcceleration (const double &time_delta, const double &acceleration_factor)
 
double GetTemporalClearingDuration (const double &time_delta)
 
openvdb::Vec3d IndexToWorld (const openvdb::Coord &coord) const
 
void InitializeGrid (void)
 
bool IsGridEmpty (void) const
 
bool MarkGridPoint (const openvdb::Coord &pt, const double &value) const
 
void PopulateCostmapAndPointcloud (const openvdb::Coord &pt)
 
void TemporalClearAndGenerateCostmap (std::vector< frustum_model > &frustums, std::unordered_set< occupany_cell > &cleared_cells)
 
openvdb::Vec3d WorldToIndex (const openvdb::Vec3d &coord) const
 

Protected Attributes

double _background_value
 
std::unordered_map< occupany_cell, uint > * _cost_map
 
int _decay_model
 
openvdb::DoubleGrid::Ptr _grid
 
boost::mutex _grid_lock
 
std::vector< geometry_msgs::Point32 > * _grid_points
 
bool _pub_voxels
 
double _voxel_decay
 
double _voxel_size
 

Detailed Description

Definition at line 157 of file spatio_temporal_voxel_grid.hpp.

Member Typedef Documentation

◆ GridRay

typedef openvdb::math::Ray<openvdb::Real> volume_grid::SpatioTemporalVoxelGrid::GridRay

Definition at line 161 of file spatio_temporal_voxel_grid.hpp.

◆ Vec3Type

typedef openvdb::math::Ray<openvdb::Real>::Vec3T volume_grid::SpatioTemporalVoxelGrid::Vec3Type

Definition at line 162 of file spatio_temporal_voxel_grid.hpp.

Constructor & Destructor Documentation

◆ SpatioTemporalVoxelGrid()

volume_grid::SpatioTemporalVoxelGrid::SpatioTemporalVoxelGrid ( const float &  voxel_size,
const double &  background_value,
const int &  decay_model,
const double &  voxel_decay,
const bool &  pub_voxels 
)

Definition at line 79 of file spatio_temporal_voxel_grid.cpp.

◆ ~SpatioTemporalVoxelGrid()

volume_grid::SpatioTemporalVoxelGrid::~SpatioTemporalVoxelGrid ( void  )

Definition at line 95 of file spatio_temporal_voxel_grid.cpp.

Member Function Documentation

◆ ClearFrustums()

void volume_grid::SpatioTemporalVoxelGrid::ClearFrustums ( const std::vector< observation::MeasurementReading > &  clearing_observations,
std::unordered_set< occupany_cell > &  cleared_cells 
)

Definition at line 136 of file spatio_temporal_voxel_grid.cpp.

◆ ClearGridPoint()

bool volume_grid::SpatioTemporalVoxelGrid::ClearGridPoint ( const openvdb::Coord &  pt) const
protected

Definition at line 513 of file spatio_temporal_voxel_grid.cpp.

◆ GetFlattenedCostmap()

std::unordered_map< occupany_cell, uint > * volume_grid::SpatioTemporalVoxelGrid::GetFlattenedCostmap ( )

Definition at line 387 of file spatio_temporal_voxel_grid.cpp.

◆ GetFrustumAcceleration()

double volume_grid::SpatioTemporalVoxelGrid::GetFrustumAcceleration ( const double &  time_delta,
const double &  acceleration_factor 
)
protected

Definition at line 410 of file spatio_temporal_voxel_grid.cpp.

◆ GetOccupancyPointCloud()

void volume_grid::SpatioTemporalVoxelGrid::GetOccupancyPointCloud ( sensor_msgs::PointCloud2::Ptr &  pc2)

Definition at line 421 of file spatio_temporal_voxel_grid.cpp.

◆ GetTemporalClearingDuration()

double volume_grid::SpatioTemporalVoxelGrid::GetTemporalClearingDuration ( const double &  time_delta)
protected

Definition at line 394 of file spatio_temporal_voxel_grid.cpp.

◆ IndexToWorld()

openvdb::Vec3d volume_grid::SpatioTemporalVoxelGrid::IndexToWorld ( const openvdb::Coord &  coord) const
protected

Definition at line 527 of file spatio_temporal_voxel_grid.cpp.

◆ InitializeGrid()

void volume_grid::SpatioTemporalVoxelGrid::InitializeGrid ( void  )
protected

Definition at line 111 of file spatio_temporal_voxel_grid.cpp.

◆ IsGridEmpty()

bool volume_grid::SpatioTemporalVoxelGrid::IsGridEmpty ( void  ) const
protected

Definition at line 553 of file spatio_temporal_voxel_grid.cpp.

◆ Mark()

void volume_grid::SpatioTemporalVoxelGrid::Mark ( const std::vector< observation::MeasurementReading > &  marking_observations)

Definition at line 324 of file spatio_temporal_voxel_grid.cpp.

◆ MarkGridPoint()

bool volume_grid::SpatioTemporalVoxelGrid::MarkGridPoint ( const openvdb::Coord &  pt,
const double &  value 
) const
protected

Definition at line 501 of file spatio_temporal_voxel_grid.cpp.

◆ operator()()

void volume_grid::SpatioTemporalVoxelGrid::operator() ( const observation::MeasurementReading obs) const

Definition at line 343 of file spatio_temporal_voxel_grid.cpp.

◆ PopulateCostmapAndPointcloud()

void volume_grid::SpatioTemporalVoxelGrid::PopulateCostmapAndPointcloud ( const openvdb::Coord &  pt)
protected

Definition at line 294 of file spatio_temporal_voxel_grid.cpp.

◆ ResetGrid()

bool volume_grid::SpatioTemporalVoxelGrid::ResetGrid ( void  )

Definition at line 456 of file spatio_temporal_voxel_grid.cpp.

◆ ResetGridArea()

void volume_grid::SpatioTemporalVoxelGrid::ResetGridArea ( const occupany_cell start,
const occupany_cell end,
bool  invert_area = false 
)

Definition at line 478 of file spatio_temporal_voxel_grid.cpp.

◆ SaveGrid()

bool volume_grid::SpatioTemporalVoxelGrid::SaveGrid ( const std::string &  file_name,
double &  map_size_bytes 
)

Definition at line 561 of file spatio_temporal_voxel_grid.cpp.

◆ TemporalClearAndGenerateCostmap()

void volume_grid::SpatioTemporalVoxelGrid::TemporalClearAndGenerateCostmap ( std::vector< frustum_model > &  frustums,
std::unordered_set< occupany_cell > &  cleared_cells 
)
protected

Definition at line 202 of file spatio_temporal_voxel_grid.cpp.

◆ WorldToIndex()

openvdb::Vec3d volume_grid::SpatioTemporalVoxelGrid::WorldToIndex ( const openvdb::Vec3d &  coord) const
protected

Definition at line 544 of file spatio_temporal_voxel_grid.cpp.

Member Data Documentation

◆ _background_value

double volume_grid::SpatioTemporalVoxelGrid::_background_value
protected

Definition at line 213 of file spatio_temporal_voxel_grid.hpp.

◆ _cost_map

std::unordered_map<occupany_cell, uint>* volume_grid::SpatioTemporalVoxelGrid::_cost_map
protected

Definition at line 216 of file spatio_temporal_voxel_grid.hpp.

◆ _decay_model

int volume_grid::SpatioTemporalVoxelGrid::_decay_model
protected

Definition at line 212 of file spatio_temporal_voxel_grid.hpp.

◆ _grid

openvdb::DoubleGrid::Ptr volume_grid::SpatioTemporalVoxelGrid::_grid
mutableprotected

Definition at line 211 of file spatio_temporal_voxel_grid.hpp.

◆ _grid_lock

boost::mutex volume_grid::SpatioTemporalVoxelGrid::_grid_lock
protected

Definition at line 217 of file spatio_temporal_voxel_grid.hpp.

◆ _grid_points

std::vector<geometry_msgs::Point32>* volume_grid::SpatioTemporalVoxelGrid::_grid_points
protected

Definition at line 215 of file spatio_temporal_voxel_grid.hpp.

◆ _pub_voxels

bool volume_grid::SpatioTemporalVoxelGrid::_pub_voxels
protected

Definition at line 214 of file spatio_temporal_voxel_grid.hpp.

◆ _voxel_decay

double volume_grid::SpatioTemporalVoxelGrid::_voxel_decay
protected

Definition at line 213 of file spatio_temporal_voxel_grid.hpp.

◆ _voxel_size

double volume_grid::SpatioTemporalVoxelGrid::_voxel_size
protected

Definition at line 213 of file spatio_temporal_voxel_grid.hpp.


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


spatio_temporal_voxel_layer
Author(s):
autogenerated on Wed Aug 16 2023 02:10:02