#include <Matcher_Points_DistanceThreshold.h>
Public Member Functions | |
void | initialize (const mrpt::containers::yaml ¶ms) override |
Matcher_Points_DistanceThreshold () | |
Matcher_Points_DistanceThreshold (double distThreshold) | |
Public Member Functions inherited from mp2p_icp::Matcher_Points_Base | |
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 | |
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 | |
uint32_t | pairingsPerPoint = 1 |
double | threshold = 0.50 |
double | thresholdAngularDeg = 0.50 |
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... | |
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 |
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) |
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... | |
Pointcloud matcher: fixed distance thresholds.
Finds point-to-point 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 especified otherwise in the base class member weight_pt2pt_layers
. Refer to example configuration YAML files for example configurations.
Definition at line 30 of file Matcher_Points_DistanceThreshold.h.
Matcher_Points_DistanceThreshold::Matcher_Points_DistanceThreshold | ( | ) |
Definition at line 27 of file Matcher_Points_DistanceThreshold.cpp.
|
inline |
Definition at line 37 of file Matcher_Points_DistanceThreshold.h.
|
overrideprivatevirtual |
Implements mp2p_icp::Matcher_Points_Base.
Definition at line 43 of file Matcher_Points_DistanceThreshold.cpp.
|
overridevirtual |
threshold
: Inliers distance threshold [meters][mandatory]pairingsPerPoint
: Number of pairings in "global" for each "local" points. Default=1. If more than one, they will be picked in ascending order of distance, up to threshold
. [optional].Plus: the parameters of Matcher_Points_Base::initialize()
Reimplemented from mp2p_icp::Matcher_Points_Base.
Definition at line 33 of file Matcher_Points_DistanceThreshold.cpp.
uint32_t mp2p_icp::Matcher_Points_DistanceThreshold::pairingsPerPoint = 1 |
Definition at line 55 of file Matcher_Points_DistanceThreshold.h.
double mp2p_icp::Matcher_Points_DistanceThreshold::threshold = 0.50 |
Definition at line 53 of file Matcher_Points_DistanceThreshold.h.
double mp2p_icp::Matcher_Points_DistanceThreshold::thresholdAngularDeg = 0.50 |
Definition at line 54 of file Matcher_Points_DistanceThreshold.h.