class mp2p_icp_filters::FilterDecimateVoxels
Overview
Builds a new layer with a decimated version of one or more input layers, merging their contents.
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 decimate_method
.
If the given output pointcloud layer already exists, new points will be appended, without clearing the former contents.
If the parameter flatten_to
is defined, this filter will also “flatten” or “summarize” the 3D points into a 2D planar (constant height z
) cloud.
Additional input point fields (ring, intensity, timestamp) will be copied into the output target cloud, except when using the flatten_to
option.
If minimum_input_points_to_filter
is defined, input clouds smaller than that size will not be decimated at all.
Not compatible with calling from different threads simultaneously for different input point clouds. Use independent instances for each thread if needed.
#include <FilterDecimateVoxels.h> class FilterDecimateVoxels: public mp2p_icp_filters::FilterBase { public: // structs struct Parameters; // fields Parameters params_; // methods virtual void initialize(const mrpt::containers::yaml& cfg_block); virtual void filter(mp2p_icp::metric_map_t& inOut) const; };
Inherited Members
public: // methods virtual void initialize(const mrpt::containers::yaml& cfg_block) = 0; virtual void filter(mp2p_icp::metric_map_t& inOut) const = 0;
Fields
Parameters params_
Algorithm parameters
Methods
virtual void initialize(const mrpt::containers::yaml& cfg_block)
Loads, from a YAML configuration block, all the common, and implementation-specific parameters.
virtual void filter(mp2p_icp::metric_map_t& inOut) const
See docs above for FilterBase.