Class OccupancyIntegrator

Nested Relationships

Class Documentation

class OccupancyIntegrator

Integrates a pointcloud into an occupancy layer by raycasting the points and updating all the voxels the rays pass through.

Public Functions

OccupancyIntegrator(const Config &config, Layer<OccupancyVoxel> *layer)
void updateOccupancyVoxel(bool occupied, OccupancyVoxel *occ_voxel)
void integratePointCloud(const Transformation &T_G_C, const Pointcloud &points_C)

Protected Attributes

Config config_
Layer<OccupancyVoxel> *layer_
FloatingPoint voxel_size_
size_t voxels_per_side_
FloatingPoint block_size_
float prob_hit_log_
float prob_miss_log_
float clamp_min_log_
float clamp_max_log_
float min_occupancy_log_
FloatingPoint voxel_size_inv_
FloatingPoint voxels_per_side_inv_
FloatingPoint block_size_inv_
struct Config

Public Members

float probability_hit = 0.65f
float probability_miss = 0.4f
float threshold_min = 0.12f
float threshold_max = 0.97f
float threshold_occupancy = 0.7f
FloatingPoint min_ray_length_m = 0.1
FloatingPoint max_ray_length_m = 5.0