#include <spatio_temporal_voxel_grid.hpp>
|
typedef openvdb::math::Ray< openvdb::Real > | GridRay |
|
typedef openvdb::math::Ray< openvdb::Real >::Vec3T | Vec3Type |
|
◆ GridRay
◆ Vec3Type
◆ 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 |
|
) |
| |
◆ ~SpatioTemporalVoxelGrid()
volume_grid::SpatioTemporalVoxelGrid::~SpatioTemporalVoxelGrid |
( |
void |
| ) |
|
◆ ClearFrustums()
◆ ClearGridPoint()
bool volume_grid::SpatioTemporalVoxelGrid::ClearGridPoint |
( |
const openvdb::Coord & |
pt | ) |
const |
|
protected |
◆ GetFlattenedCostmap()
std::unordered_map< occupany_cell, uint > * volume_grid::SpatioTemporalVoxelGrid::GetFlattenedCostmap |
( |
| ) |
|
◆ GetFrustumAcceleration()
double volume_grid::SpatioTemporalVoxelGrid::GetFrustumAcceleration |
( |
const double & |
time_delta, |
|
|
const double & |
acceleration_factor |
|
) |
| |
|
protected |
◆ GetOccupancyPointCloud()
void volume_grid::SpatioTemporalVoxelGrid::GetOccupancyPointCloud |
( |
sensor_msgs::PointCloud2::Ptr & |
pc2 | ) |
|
◆ GetTemporalClearingDuration()
double volume_grid::SpatioTemporalVoxelGrid::GetTemporalClearingDuration |
( |
const double & |
time_delta | ) |
|
|
protected |
◆ IndexToWorld()
openvdb::Vec3d volume_grid::SpatioTemporalVoxelGrid::IndexToWorld |
( |
const openvdb::Coord & |
coord | ) |
const |
|
protected |
◆ InitializeGrid()
void volume_grid::SpatioTemporalVoxelGrid::InitializeGrid |
( |
void |
| ) |
|
|
protected |
◆ IsGridEmpty()
bool volume_grid::SpatioTemporalVoxelGrid::IsGridEmpty |
( |
void |
| ) |
const |
|
protected |
◆ Mark()
◆ MarkGridPoint()
bool volume_grid::SpatioTemporalVoxelGrid::MarkGridPoint |
( |
const openvdb::Coord & |
pt, |
|
|
const double & |
value |
|
) |
| const |
|
protected |
◆ operator()()
◆ PopulateCostmapAndPointcloud()
void volume_grid::SpatioTemporalVoxelGrid::PopulateCostmapAndPointcloud |
( |
const openvdb::Coord & |
pt | ) |
|
|
protected |
◆ ResetGrid()
bool volume_grid::SpatioTemporalVoxelGrid::ResetGrid |
( |
void |
| ) |
|
◆ ResetGridArea()
void volume_grid::SpatioTemporalVoxelGrid::ResetGridArea |
( |
const occupany_cell & |
start, |
|
|
const occupany_cell & |
end, |
|
|
bool |
invert_area = false |
|
) |
| |
◆ SaveGrid()
bool volume_grid::SpatioTemporalVoxelGrid::SaveGrid |
( |
const std::string & |
file_name, |
|
|
double & |
map_size_bytes |
|
) |
| |
◆ TemporalClearAndGenerateCostmap()
void volume_grid::SpatioTemporalVoxelGrid::TemporalClearAndGenerateCostmap |
( |
std::vector< frustum_model > & |
frustums, |
|
|
std::unordered_set< occupany_cell > & |
cleared_cells |
|
) |
| |
|
protected |
◆ WorldToIndex()
openvdb::Vec3d volume_grid::SpatioTemporalVoxelGrid::WorldToIndex |
( |
const openvdb::Vec3d & |
coord | ) |
const |
|
protected |
◆ _background_value
double volume_grid::SpatioTemporalVoxelGrid::_background_value |
|
protected |
◆ _cost_map
std::unordered_map<occupany_cell, uint>* volume_grid::SpatioTemporalVoxelGrid::_cost_map |
|
protected |
◆ _decay_model
int volume_grid::SpatioTemporalVoxelGrid::_decay_model |
|
protected |
◆ _grid
openvdb::DoubleGrid::Ptr volume_grid::SpatioTemporalVoxelGrid::_grid |
|
mutableprotected |
◆ _grid_lock
boost::mutex volume_grid::SpatioTemporalVoxelGrid::_grid_lock |
|
protected |
◆ _grid_points
std::vector<geometry_msgs::Point32>* volume_grid::SpatioTemporalVoxelGrid::_grid_points |
|
protected |
◆ _pub_voxels
bool volume_grid::SpatioTemporalVoxelGrid::_pub_voxels |
|
protected |
◆ _voxel_decay
double volume_grid::SpatioTemporalVoxelGrid::_voxel_decay |
|
protected |
◆ _voxel_size
double volume_grid::SpatioTemporalVoxelGrid::_voxel_size |
|
protected |
The documentation for this class was generated from the following files: