#include <QualityEvaluator_Voxels.h>

Public Member Functions | |
| double | evaluate (const metric_map_t &pcGlobal, const metric_map_t &pcLocal, const mrpt::poses::CPose3D &localPose, const Pairings &pairingsFromICP) const override |
| void | initialize (const mrpt::containers::yaml ¶ms) override |
| QualityEvaluator_Voxels () | |
Public Attributes | |
| double | dist2quality_scale = 0.1 |
| double | maxFreenessUpdateCertainty = 0.55 |
| <[0.5,1.0] More... | |
| double | maxOccupancyUpdateCertainty = 0.65 |
| std::set< std::string > | pointLayers = {mp2p_icp::metric_map_t::PT_LAYER_RAW} |
| double | resolution = 0.25 |
| voxel size [meters] More... | |
Matching quality evaluator: comparison via voxel occupancy.
Definition at line 22 of file QualityEvaluator_Voxels.h.
| QualityEvaluator_Voxels::QualityEvaluator_Voxels | ( | ) |
Definition at line 22 of file QualityEvaluator_Voxels.cpp.
|
overridevirtual |
Finds correspondences between the two point clouds.
Implements mp2p_icp::QualityEvaluator.
Definition at line 53 of file QualityEvaluator_Voxels.cpp.
|
overridevirtual |
Check each derived class to see required and optional parameters.
Implements mp2p_icp::QualityEvaluator.
Definition at line 27 of file QualityEvaluator_Voxels.cpp.
| double mp2p_icp::QualityEvaluator_Voxels::dist2quality_scale = 0.1 |
Definition at line 39 of file QualityEvaluator_Voxels.h.
| double mp2p_icp::QualityEvaluator_Voxels::maxFreenessUpdateCertainty = 0.55 |
<[0.5,1.0]
Definition at line 38 of file QualityEvaluator_Voxels.h.
| double mp2p_icp::QualityEvaluator_Voxels::maxOccupancyUpdateCertainty = 0.65 |
Definition at line 37 of file QualityEvaluator_Voxels.h.
| std::set<std::string> mp2p_icp::QualityEvaluator_Voxels::pointLayers = {mp2p_icp::metric_map_t::PT_LAYER_RAW} |
Evaluate points only in these layers
Definition at line 42 of file QualityEvaluator_Voxels.h.
| double mp2p_icp::QualityEvaluator_Voxels::resolution = 0.25 |
voxel size [meters]
Definition at line 36 of file QualityEvaluator_Voxels.h.