Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
mp2p_icp::Matcher_Adaptive Class Reference

#include <Matcher_Adaptive.h>

Inheritance diagram for mp2p_icp::Matcher_Adaptive:
Inheritance graph
[legend]

Public Member Functions

void initialize (const mrpt::containers::yaml &params) override
 
 Matcher_Adaptive ()=default
 
 Matcher_Adaptive (double ConfidenceInterval, double FirstToSecondDistanceMax, double AbsoluteMaxSearchDistance)
 
- Public Member Functions inherited from mp2p_icp::Matcher_Points_Base
void initialize (const mrpt::containers::yaml &params) override
 
 Matcher_Points_Base ()=default
 
- Public Member Functions inherited from mp2p_icp::Matcher
virtual bool match (const metric_map_t &pcGlobal, const metric_map_t &pcLocal, const mrpt::poses::CPose3D &localPose, const MatchContext &mc, MatchState &ms, Pairings &out) const
 
- Public Member Functions inherited from mp2p_icp::Parameterizable
ParameterSourceattachedSource ()
 
const ParameterSourceattachedSource () 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...
 

Private Member Functions

void implMatchOneLayer (const mrpt::maps::CMetricMap &pcGlobal, const mrpt::maps::CPointsMap &pcLocal, const mrpt::poses::CPose3D &localPose, MatchState &ms, const layer_name_t &globalName, const layer_name_t &localName, Pairings &out) const override
 

Private Attributes

double absoluteMaxSearchDistance = 5.0
 
double confidenceInterval = 0.80
 
bool enableDetectPlanes = false
 
double firstToSecondDistanceMax = 1.2
 
std::vector< double > histValues_
 
std::vector< double > histXs_
 
std::vector< float > kddXs
 
std::vector< float > kddYs
 
std::vector< float > kddZs
 
std::vector< mrpt::containers::vector_with_small_size_optimization< mrpt::tfest::TMatchingPair, MAX_CORRS_PER_LOCAL > > matchesPerLocal_
 
uint32_t maxPt2PtCorrespondences = 1
 
double minimumCorrDist = 0.1
 
std::vector< size_t > neighborIndices_
 
std::vector< mrpt::math::TPoint3Df > neighborPts_
 
std::vector< float > neighborSqrDists_
 
double planeEigenThreshold = 0.01
 
double planeMinimumDistance = 0.10
 
uint32_t planeMinimumFoundPoints = 4
 
uint32_t planeSearchPoints = 8
 

Static Private Attributes

constexpr static size_t MAX_CORRS_PER_LOCAL = 10
 

Additional Inherited Members

- Static Public Member Functions inherited from mp2p_icp::Matcher_Points_Base
static TransformedLocalPointCloud transform_local_to_global (const mrpt::maps::CPointsMap &pcLocal, const mrpt::poses::CPose3D &localPose, const std::size_t maxLocalPoints=0, const uint64_t localPointsSampleSeed=0)
 
- Public Attributes inherited from mp2p_icp::Matcher_Points_Base
bool allowMatchAlreadyMatchedGlobalPoints_ = false
 
bool allowMatchAlreadyMatchedPoints_ = false
 
double bounding_box_intersection_check_epsilon_ = 0.20
 
std::optional< std::size_t > kdtree_leaf_max_points_
 
uint64_t localPointsSampleSeed_ = 0
 
uint64_t maxLocalPointsPerLayer_ = 0
 
std::map< std::string, std::map< std::string, double > > weight_pt2pt_layers
 
- Public Attributes inherited from mp2p_icp::Matcher
bool enabled = true
 
uint32_t runFromIteration = 0
 
uint32_t runUpToIteration = 0
 0: no limit More...
 
- Protected Member Functions inherited from mp2p_icp::Matcher_Points_Base
bool impl_match (const metric_map_t &pcGlobal, const metric_map_t &pcLocal, const mrpt::poses::CPose3D &localPose, const MatchContext &mc, MatchState &ms, Pairings &out) const override final
 
- 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...
 

Detailed Description

Pointcloud matcher: adaptive algorithm automatically discarding outliers, and creating point-to-plane, point-to-line, or point-to-point pairings.

Finds pairings between the local and global input metric maps.

By default, each local point layer is matched against the layer with the same name in the global map, unless specified otherwise in the base class member weight_pt2pt_layers. Refer to example configuration YAML files for example configurations.

Definition at line 31 of file Matcher_Adaptive.h.

Constructor & Destructor Documentation

◆ Matcher_Adaptive() [1/2]

mp2p_icp::Matcher_Adaptive::Matcher_Adaptive ( )
default

◆ Matcher_Adaptive() [2/2]

mp2p_icp::Matcher_Adaptive::Matcher_Adaptive ( double  ConfidenceInterval,
double  FirstToSecondDistanceMax,
double  AbsoluteMaxSearchDistance 
)
inline

Definition at line 38 of file Matcher_Adaptive.h.

Member Function Documentation

◆ implMatchOneLayer()

void Matcher_Adaptive::implMatchOneLayer ( const mrpt::maps::CMetricMap &  pcGlobal,
const mrpt::maps::CPointsMap &  pcLocal,
const mrpt::poses::CPose3D &  localPose,
MatchState ms,
const layer_name_t globalName,
const layer_name_t localName,
Pairings out 
) const
overrideprivatevirtual

Implements mp2p_icp::Matcher_Points_Base.

Definition at line 52 of file Matcher_Adaptive.cpp.

◆ initialize()

void Matcher_Adaptive::initialize ( const mrpt::containers::yaml &  params)
overridevirtual

Parameters:

  • confidenceInterval: Inliers top-confidence interval. (0-1)
  • firstToSecondDistanceMax:
  • absoluteMaxSearchDistance:

Plus: the parameters of Matcher_Points_Base::initialize()

Reimplemented from mp2p_icp::Matcher.

Definition at line 25 of file Matcher_Adaptive.cpp.

Member Data Documentation

◆ absoluteMaxSearchDistance

double mp2p_icp::Matcher_Adaptive::absoluteMaxSearchDistance = 5.0
mutableprivate

Definition at line 60 of file Matcher_Adaptive.h.

◆ confidenceInterval

double mp2p_icp::Matcher_Adaptive::confidenceInterval = 0.80
private

Definition at line 58 of file Matcher_Adaptive.h.

◆ enableDetectPlanes

bool mp2p_icp::Matcher_Adaptive::enableDetectPlanes = false
private

Definition at line 61 of file Matcher_Adaptive.h.

◆ firstToSecondDistanceMax

double mp2p_icp::Matcher_Adaptive::firstToSecondDistanceMax = 1.2
private

Definition at line 59 of file Matcher_Adaptive.h.

◆ histValues_

std::vector<double> mp2p_icp::Matcher_Adaptive::histValues_
private

Definition at line 74 of file Matcher_Adaptive.h.

◆ histXs_

std::vector<double> mp2p_icp::Matcher_Adaptive::histXs_
mutableprivate

Definition at line 74 of file Matcher_Adaptive.h.

◆ kddXs

std::vector<float> mp2p_icp::Matcher_Adaptive::kddXs
mutableprivate

Definition at line 73 of file Matcher_Adaptive.h.

◆ kddYs

std::vector<float> mp2p_icp::Matcher_Adaptive::kddYs
private

Definition at line 73 of file Matcher_Adaptive.h.

◆ kddZs

std::vector<float> mp2p_icp::Matcher_Adaptive::kddZs
private

Definition at line 73 of file Matcher_Adaptive.h.

◆ matchesPerLocal_

std::vector<mrpt::containers::vector_with_small_size_optimization< mrpt::tfest::TMatchingPair, MAX_CORRS_PER_LOCAL> > mp2p_icp::Matcher_Adaptive::matchesPerLocal_
mutableprivate

Definition at line 80 of file Matcher_Adaptive.h.

◆ MAX_CORRS_PER_LOCAL

constexpr static size_t mp2p_icp::Matcher_Adaptive::MAX_CORRS_PER_LOCAL = 10
staticconstexprprivate

Definition at line 76 of file Matcher_Adaptive.h.

◆ maxPt2PtCorrespondences

uint32_t mp2p_icp::Matcher_Adaptive::maxPt2PtCorrespondences = 1
private

Definition at line 62 of file Matcher_Adaptive.h.

◆ minimumCorrDist

double mp2p_icp::Matcher_Adaptive::minimumCorrDist = 0.1
private

Definition at line 67 of file Matcher_Adaptive.h.

◆ neighborIndices_

std::vector<size_t> mp2p_icp::Matcher_Adaptive::neighborIndices_
mutableprivate

Definition at line 70 of file Matcher_Adaptive.h.

◆ neighborPts_

std::vector<mrpt::math::TPoint3Df> mp2p_icp::Matcher_Adaptive::neighborPts_
mutableprivate

Definition at line 72 of file Matcher_Adaptive.h.

◆ neighborSqrDists_

std::vector<float> mp2p_icp::Matcher_Adaptive::neighborSqrDists_
mutableprivate

Definition at line 71 of file Matcher_Adaptive.h.

◆ planeEigenThreshold

double mp2p_icp::Matcher_Adaptive::planeEigenThreshold = 0.01
private

Definition at line 66 of file Matcher_Adaptive.h.

◆ planeMinimumDistance

double mp2p_icp::Matcher_Adaptive::planeMinimumDistance = 0.10
private

Definition at line 65 of file Matcher_Adaptive.h.

◆ planeMinimumFoundPoints

uint32_t mp2p_icp::Matcher_Adaptive::planeMinimumFoundPoints = 4
private

Definition at line 64 of file Matcher_Adaptive.h.

◆ planeSearchPoints

uint32_t mp2p_icp::Matcher_Adaptive::planeSearchPoints = 8
private

Definition at line 63 of file Matcher_Adaptive.h.


The documentation for this class was generated from the following files:


mp2p_icp
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Wed Jun 26 2024 02:47:10