Matcher_Adaptive.h
Go to the documentation of this file.
1 /* -------------------------------------------------------------------------
2  * A repertory of multi primitive-to-primitive (MP2P) ICP algorithms in C++
3  * Copyright (C) 2018-2024 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
12 #pragma once
13 
15 #include <mrpt/containers/vector_with_small_size_optimization.h>
16 
17 namespace mp2p_icp
18 {
32 {
33  DEFINE_MRPT_OBJECT(Matcher_Adaptive, mp2p_icp)
34 
35  public:
36  Matcher_Adaptive() = default;
37 
39  double ConfidenceInterval, double FirstToSecondDistanceMax,
40  double AbsoluteMaxSearchDistance)
42  confidenceInterval(ConfidenceInterval),
43  firstToSecondDistanceMax(FirstToSecondDistanceMax),
44  absoluteMaxSearchDistance(AbsoluteMaxSearchDistance)
45  {
46  }
47 
55  void initialize(const mrpt::containers::yaml& params) override;
56 
57  private:
58  double confidenceInterval = 0.80;
60  mutable double absoluteMaxSearchDistance = 5.0; // m
61  bool enableDetectPlanes = false;
63  uint32_t planeSearchPoints = 8;
65  double planeMinimumDistance = 0.10;
66  double planeEigenThreshold = 0.01;
67  double minimumCorrDist = 0.1; // m
68 
69  // Declared here to avoid memory reallocations:
70  mutable std::vector<size_t> neighborIndices_;
71  mutable std::vector<float> neighborSqrDists_;
72  mutable std::vector<mrpt::math::TPoint3Df> neighborPts_;
73  mutable std::vector<float> kddXs, kddYs, kddZs;
74  mutable std::vector<double> histXs_, histValues_;
75 
76  constexpr static size_t MAX_CORRS_PER_LOCAL = 10;
77 
78  mutable std::vector<mrpt::containers::vector_with_small_size_optimization<
79  mrpt::tfest::TMatchingPair, MAX_CORRS_PER_LOCAL>>
81 
82  void implMatchOneLayer(
83  const mrpt::maps::CMetricMap& pcGlobal,
84  const mrpt::maps::CPointsMap& pcLocal,
85  const mrpt::poses::CPose3D& localPose, MatchState& ms,
86  const layer_name_t& globalName, const layer_name_t& localName,
87  Pairings& out) const override;
88 };
89 
90 } // namespace mp2p_icp
mp2p_icp::Matcher_Adaptive::confidenceInterval
double confidenceInterval
Definition: Matcher_Adaptive.h:58
mp2p_icp::Matcher_Adaptive::kddXs
std::vector< float > kddXs
Definition: Matcher_Adaptive.h:73
mp2p_icp::Matcher_Adaptive::planeMinimumDistance
double planeMinimumDistance
Definition: Matcher_Adaptive.h:65
mp2p_icp::Matcher_Adaptive::planeSearchPoints
uint32_t planeSearchPoints
Definition: Matcher_Adaptive.h:63
mp2p_icp::Matcher_Points_Base
Definition: Matcher_Points_Base.h:31
mp2p_icp
Definition: covariance.h:17
mp2p_icp::Matcher_Adaptive::maxPt2PtCorrespondences
uint32_t maxPt2PtCorrespondences
Definition: Matcher_Adaptive.h:62
mp2p_icp::Pairings
Definition: Pairings.h:94
mp2p_icp::layer_name_t
std::string layer_name_t
Definition: layer_name_t.h:22
mp2p_icp::Matcher_Adaptive::minimumCorrDist
double minimumCorrDist
Definition: Matcher_Adaptive.h:67
mp2p_icp::Matcher_Adaptive::planeEigenThreshold
double planeEigenThreshold
Definition: Matcher_Adaptive.h:66
mp2p_icp::Matcher_Adaptive::MAX_CORRS_PER_LOCAL
constexpr static size_t MAX_CORRS_PER_LOCAL
Definition: Matcher_Adaptive.h:76
mp2p_icp::Matcher_Adaptive::Matcher_Adaptive
Matcher_Adaptive()=default
mp2p_icp::Matcher_Adaptive::kddYs
std::vector< float > kddYs
Definition: Matcher_Adaptive.h:73
mp2p_icp::Matcher_Adaptive::planeMinimumFoundPoints
uint32_t planeMinimumFoundPoints
Definition: Matcher_Adaptive.h:64
mp2p_icp::Matcher_Adaptive::histValues_
std::vector< double > histValues_
Definition: Matcher_Adaptive.h:74
mp2p_icp::Matcher_Adaptive::initialize
void initialize(const mrpt::containers::yaml &params) override
Definition: Matcher_Adaptive.cpp:25
mp2p_icp::MatchState
Definition: Matcher.h:36
kitti-batch-convert.out
string out
Definition: kitti-batch-convert.py:7
Matcher_Points_Base.h
Pointcloud matcher auxiliary class for iterating over point layers.
mp2p_icp::Matcher_Adaptive::firstToSecondDistanceMax
double firstToSecondDistanceMax
Definition: Matcher_Adaptive.h:59
mp2p_icp::Matcher_Adaptive::implMatchOneLayer
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
Definition: Matcher_Adaptive.cpp:52
mp2p_icp::Matcher_Adaptive::enableDetectPlanes
bool enableDetectPlanes
Definition: Matcher_Adaptive.h:61
mp2p_icp::Matcher_Adaptive::absoluteMaxSearchDistance
double absoluteMaxSearchDistance
Definition: Matcher_Adaptive.h:60
mp2p_icp::Matcher_Adaptive::histXs_
std::vector< double > histXs_
Definition: Matcher_Adaptive.h:74
mp2p_icp::Matcher_Adaptive::matchesPerLocal_
std::vector< mrpt::containers::vector_with_small_size_optimization< mrpt::tfest::TMatchingPair, MAX_CORRS_PER_LOCAL > > matchesPerLocal_
Definition: Matcher_Adaptive.h:80
mp2p_icp::Matcher_Adaptive::neighborPts_
std::vector< mrpt::math::TPoint3Df > neighborPts_
Definition: Matcher_Adaptive.h:72
mp2p_icp::Matcher_Adaptive
Definition: Matcher_Adaptive.h:31
mp2p_icp::Matcher_Adaptive::neighborIndices_
std::vector< size_t > neighborIndices_
Definition: Matcher_Adaptive.h:70
mp2p_icp::Matcher_Adaptive::neighborSqrDists_
std::vector< float > neighborSqrDists_
Definition: Matcher_Adaptive.h:71
mp2p_icp::Matcher_Adaptive::kddZs
std::vector< float > kddZs
Definition: Matcher_Adaptive.h:73
mp2p_icp::Matcher_Adaptive::Matcher_Adaptive
Matcher_Adaptive(double ConfidenceInterval, double FirstToSecondDistanceMax, double AbsoluteMaxSearchDistance)
Definition: Matcher_Adaptive.h:38


mp2p_icp
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Tue Jul 2 2024 02:47:25