Autoware.Auto
|
|
The voxel grid filter is a form of point cloud downsampling that maintains the majority of the information stored in the point cloud.
There are two forms:
Both voxel grid filters operate in the following manner:
Rather than the centroids of all points within a voxel, the point returned is the centroid of the voxel itself. While less accurate, this removes an additional scan over the data. Concretely, this is done in pcl
in the following way:
The centroid voxel grid filter requires an additional pass through the data to compute the centroid of each point assigned to a voxel. This results in a more accurate representation of the underlying surface. Concretely, this is done in pcl
by doing the following:
The following modifications are made:
Similarly, for the approximate voxel grid filter, a hashmap (unordered map) is used to store active voxels. However, centroids are not tracked, and the hashmap is only used to track if the voxel is active or not.
The following architecture was used to maximize code re-use and improve performance.
A core Voxel
class was provided, with common functionality. This class has no virtual methods. This class is templated on a point type.
Child instances of the Voxel
class are instantiated with some additional, common methods which differentiate the behavior of individual voxels.
The VoxelGrid
data structure itself is templated on a Voxel type.
Further down the line, runtime dispatching of algorithms can be achieved by using the non-templated AlgorithmBase
, and templated child class paradigm.
Finally, a note on some API and structural decisions:
unordered_map
was used as the underlying datastructure to have improved average lookup time and match the sparseness of the datastd::forward_list
was used because the splice
method allows us to reuse pointsnew_voxels
in order to prevent the state of the voxel grid from unexpectedly being changed in addition to MISRA considerationsInserting into the voxel grid filter is inserting into a hashmap, which is O(n)
in an adversarial case.
For the centroid voxel grid filter, this results in an algorithm that is O(n*n + n)
in complexity, where the first term is for inserting points into the voxel grid and underlying hashmap, as well as updating the centroids, and the second term is for flushing points out of the voxel grid.
This results in an algorithm that is O(n^2)
Similarly for the approximate voxel grid filter, the algorithm is O(n * n)
for inserting into the voxel grid, and sending newly activated points downstream.
This results in an algorithm that is O(n^2)
.
In practice, inserting into a hashmap is O(1)
, which results in O(n)
algorithms for both cases.
The space complexity of each voxel grid is dominated by the underlying hashmap, which is O(n)
in space.
The voxel grid filters are stateful in two ways: the configuration, and the voxel grid itself.
Hashmap<uint32_t, Voxel>
, main data structure for storing a sparse voxel grid, similar to an std::unordered_map
Voxel
, represents an exact voxel by maintaining two state variables: centroid
and num_points
, to allow incremental updates of the centroidThe following defines the configuration state:
min_point
max_point
, combined with the above define an axis-aligned bounding box (AABB) that all points will fall inleaf_size
, defines the length of each side of the voxelFurther configuration state variables are precomputed from these for computational convenience:
inv_leaf_size
, makes it quicker to compute voxel index by switching a division for a multiplyleaf_size_2
, makes it quick to compute approximate voxel centroidx_width
, number of voxels in the x direction, for quick computation of voxel index and approximate centroidxy_width
, number of voxels in each z row, for quick computation of voxel index and approximate centroidThe input to the voxel grid data structure is an arbitrary point type that the voxel is templated on.
This voxel must have the following properties for successful compilation:
CentroidVoxel
, operator+
and operator*(float32_t)
must be definedThe voxel grid data structure supports to output modes:
TBD by a security expert.
The underlying std::unordered_map
is not static memory, and cannot be made so with default STL capabilities. When available, a static memory allocator must be used.