#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_map< occupany_cell, uint > * | GetFlattenedCostmap () |
| void | GetOccupancyPointCloud (pcl::PointCloud< pcl::PointXYZ >::Ptr &pc) |
| void | Mark (const std::vector< observation::MeasurementReading > &marking_observations) |
| void | operator() (const observation::MeasurementReading &obs) const |
| bool | ResetGrid (void) |
| bool | SaveGrid (const std::string &file_name, double &map_size_bytes) |
| SpatioTemporalVoxelGrid (const float &voxel_size, const double &background_value, const GlobalDecayModel &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) |
| openvdb::Vec3d | WorldToIndex (const openvdb::Vec3d &coord) const |
Protected Attributes | |
| double | _background_value |
| std::unordered_map< occupany_cell, uint > * | _cost_map |
| GlobalDecayModel | _decay_model |
| openvdb::DoubleGrid::Ptr | _grid |
| boost::mutex | _grid_lock |
| pcl::PointCloud< pcl::PointXYZ >::Ptr | _pc |
| bool | _pub_voxels |
| double | _voxel_decay |
| double | _voxel_size |
Definition at line 116 of file spatio_temporal_voxel_grid.hpp.
| typedef openvdb::math::Ray<openvdb::Real> volume_grid::SpatioTemporalVoxelGrid::GridRay |
Definition at line 120 of file spatio_temporal_voxel_grid.hpp.
| typedef openvdb::math::Ray<openvdb::Real>::Vec3T volume_grid::SpatioTemporalVoxelGrid::Vec3Type |
Definition at line 121 of file spatio_temporal_voxel_grid.hpp.
| volume_grid::SpatioTemporalVoxelGrid::SpatioTemporalVoxelGrid | ( | const float & | voxel_size, |
| const double & | background_value, | ||
| const GlobalDecayModel & | decay_model, | ||
| const double & | voxel_decay, | ||
| const bool & | pub_voxels | ||
| ) |
Definition at line 44 of file spatio_temporal_voxel_grid.cpp.
| volume_grid::SpatioTemporalVoxelGrid::~SpatioTemporalVoxelGrid | ( | void | ) |
Definition at line 61 of file spatio_temporal_voxel_grid.cpp.
| void volume_grid::SpatioTemporalVoxelGrid::ClearFrustums | ( | const std::vector< observation::MeasurementReading > & | clearing_observations | ) |
Definition at line 96 of file spatio_temporal_voxel_grid.cpp.
|
protected |
Definition at line 393 of file spatio_temporal_voxel_grid.cpp.
| std::unordered_map< occupany_cell, uint > * volume_grid::SpatioTemporalVoxelGrid::GetFlattenedCostmap | ( | ) |
Definition at line 315 of file spatio_temporal_voxel_grid.cpp.
|
protected |
Definition at line 338 of file spatio_temporal_voxel_grid.cpp.
| void volume_grid::SpatioTemporalVoxelGrid::GetOccupancyPointCloud | ( | pcl::PointCloud< pcl::PointXYZ >::Ptr & | pc | ) |
Definition at line 349 of file spatio_temporal_voxel_grid.cpp.
|
protected |
Definition at line 322 of file spatio_temporal_voxel_grid.cpp.
|
protected |
Definition at line 407 of file spatio_temporal_voxel_grid.cpp.
|
protected |
Definition at line 72 of file spatio_temporal_voxel_grid.cpp.
|
protected |
Definition at line 425 of file spatio_temporal_voxel_grid.cpp.
| void volume_grid::SpatioTemporalVoxelGrid::Mark | ( | const std::vector< observation::MeasurementReading > & | marking_observations | ) |
Definition at line 262 of file spatio_temporal_voxel_grid.cpp.
|
protected |
Definition at line 381 of file spatio_temporal_voxel_grid.cpp.
| void volume_grid::SpatioTemporalVoxelGrid::operator() | ( | const observation::MeasurementReading & | obs | ) | const |
Definition at line 281 of file spatio_temporal_voxel_grid.cpp.
|
protected |
Definition at line 235 of file spatio_temporal_voxel_grid.cpp.
| bool volume_grid::SpatioTemporalVoxelGrid::ResetGrid | ( | void | ) |
Definition at line 359 of file spatio_temporal_voxel_grid.cpp.
| bool volume_grid::SpatioTemporalVoxelGrid::SaveGrid | ( | const std::string & | file_name, |
| double & | map_size_bytes | ||
| ) |
Definition at line 433 of file spatio_temporal_voxel_grid.cpp.
|
protected |
Definition at line 159 of file spatio_temporal_voxel_grid.cpp.
|
protected |
Definition at line 416 of file spatio_temporal_voxel_grid.cpp.
|
protected |
Definition at line 169 of file spatio_temporal_voxel_grid.hpp.
|
protected |
Definition at line 172 of file spatio_temporal_voxel_grid.hpp.
|
protected |
Definition at line 168 of file spatio_temporal_voxel_grid.hpp.
|
mutableprotected |
Definition at line 167 of file spatio_temporal_voxel_grid.hpp.
|
protected |
Definition at line 173 of file spatio_temporal_voxel_grid.hpp.
|
protected |
Definition at line 171 of file spatio_temporal_voxel_grid.hpp.
|
protected |
Definition at line 170 of file spatio_temporal_voxel_grid.hpp.
|
protected |
Definition at line 169 of file spatio_temporal_voxel_grid.hpp.
|
protected |
Definition at line 169 of file spatio_temporal_voxel_grid.hpp.