Class SpatioTemporalVoxelGrid
- Defined in File spatio_temporal_voxel_grid.hpp 
Class Documentation
- 
class SpatioTemporalVoxelGrid
- Public Types - 
typedef openvdb::math::Ray<openvdb::Real> GridRay
 - 
typedef openvdb::math::Ray<openvdb::Real>::Vec3T Vec3Type
 - Public Functions - 
~SpatioTemporalVoxelGrid(void)
 - 
void Mark(const std::vector<observation::MeasurementReading> &marking_observations)
 - 
void operator()(const observation::MeasurementReading &obs) const
 - 
void ClearFrustums(const std::vector<observation::MeasurementReading> &clearing_observations, std::unordered_set<occupany_cell> &cleared_cells)
 - 
void GetOccupancyPointCloud(std::unique_ptr<sensor_msgs::msg::PointCloud2> &pc2)
 - 
std::unordered_map<occupany_cell, uint> *GetFlattenedCostmap()
 - 
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)
 - Protected Functions - 
void InitializeGrid(void)
 - 
bool MarkGridPoint(const openvdb::Coord &pt, const double &value) const
 - 
bool ClearGridPoint(const openvdb::Coord &pt) const
 - 
bool IsGridEmpty(void) const
 - 
double GetTemporalClearingDuration(const double &time_delta)
 - 
double GetFrustumAcceleration(const double &time_delta, const double &acceleration_factor)
 - 
void TemporalClearAndGenerateCostmap(std::vector<frustum_model> &frustums, std::unordered_set<occupany_cell> &cleared_cells)
 - 
void PopulateCostmapAndPointcloud(const openvdb::Coord &pt)
 - 
openvdb::Vec3d WorldToIndex(const openvdb::Vec3d &coord) const
 - 
openvdb::Vec3d IndexToWorld(const openvdb::Coord &coord) const
 - Protected Attributes - 
rclcpp::Clock::SharedPtr _clock
 - 
mutable openvdb::DoubleGrid::Ptr _grid
 - 
int _decay_model
 - 
double _background_value
 - 
double _voxel_size
 - 
double _voxel_decay
 - 
bool _pub_voxels
 - 
std::unique_ptr<std::vector<geometry_msgs::msg::Point32>> _grid_points
 - 
std::unordered_map<occupany_cell, uint> *_cost_map
 - 
boost::mutex _grid_lock
 
- 
typedef openvdb::math::Ray<openvdb::Real> GridRay