#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 Member Functions inherited from mp2p_icp::Parameterizable | |
ParameterSource * | attachedSource () |
const ParameterSource * | attachedSource () const |
virtual void | attachToParameterSource (ParameterSource &source) |
void | checkAllParametersAreRealized () const |
auto & | declaredParameters () |
const auto & | declaredParameters () const |
void | unrealizeParameters () |
Mark all non-constant parameters as non-evaluated again. More... | |
Public Attributes | |
Parameters | params_ |
Private Member Functions | |
bool | useSingleGrid () const |
Private Attributes | |
std::optional< PointCloudToVoxelGrid > | filter_grid_ |
std::optional< PointCloudToVoxelGridSingle > | filter_grid_single_ |
Additional Inherited Members | |
Protected Member Functions inherited from mp2p_icp::Parameterizable | |
void | parseAndDeclareParameter (const std::string &value, double &target) |
void | parseAndDeclareParameter (const std::string &value, float &target) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
void | parseAndDeclareParameter (const std::string &value, uint32_t &target) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
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.
Definition at line 66 of file FilterDecimateVoxels.h.
FilterDecimateVoxels::FilterDecimateVoxels | ( | ) |
Definition at line 67 of file FilterDecimateVoxels.cpp.
|
overridevirtual |
See docs above for FilterBase.
Implements mp2p_icp_filters::FilterBase.
Definition at line 94 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 72 of file FilterDecimateVoxels.cpp.
|
inlineprivate |
Definition at line 119 of file FilterDecimateVoxels.h.
|
mutableprivate |
Definition at line 116 of file FilterDecimateVoxels.h.
|
mutableprivate |
Definition at line 117 of file FilterDecimateVoxels.h.
Parameters mp2p_icp_filters::FilterDecimateVoxels::params_ |
Algorithm parameters
Definition at line 113 of file FilterDecimateVoxels.h.