#include <FilterDecimateVoxels.h>
Classes | |
struct | Parameters |
Public Member Functions | |
void | filter (mp2p_icp::metric_map_t &inOut) const override |
FilterDecimateVoxels () | |
void | initialize (const mrpt::containers::yaml &c) override |
Public Member Functions inherited from mp2p_icp_filters::FilterBase | |
FilterBase () | |
virtual | ~FilterBase () |
Public Attributes | |
Parameters | params_ |
Private Attributes | |
PointCloudToVoxelGrid | filter_grid_ |
Builds a new layer with a decimated version of an input layer.
This builds a voxel grid from the input point cloud, and then takes either, the mean of the points in the voxel, or one of the points picked at random, depending on the parameter use_voxel_average
.
If the given output pointcloud layer already exists, new points will be appended, without clearing the former contents.
Not compatible with calling from different threads simultaneously for different input point clouds. Use independent instances for each thread if needed.
Definition at line 37 of file FilterDecimateVoxels.h.
|
default |
|
overridevirtual |
See docs above for FilterBase.
Implements mp2p_icp_filters::FilterBase.
Definition at line 69 of file FilterDecimateVoxels.cpp.
|
overridevirtual |
Loads, from a YAML configuration block, all the common, and implementation-specific parameters.
Implements mp2p_icp_filters::FilterBase.
Definition at line 55 of file FilterDecimateVoxels.cpp.
|
mutableprivate |
Definition at line 86 of file FilterDecimateVoxels.h.
Parameters mp2p_icp_filters::FilterDecimateVoxels::params_ |
Algorithm parameters
Definition at line 83 of file FilterDecimateVoxels.h.