#include <Matcher_Points_Base.h>
Classes | |
struct | TransformedLocalPointCloud |
Public Member Functions | |
void | initialize (const mrpt::containers::yaml ¶ms) 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 | |
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... | |
Static Public Member Functions | |
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 | |
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 | |
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... | |
Private Member Functions | |
virtual 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 =0 |
Pointcloud matcher auxiliary class for iterating over point layers.
The common to all matchers working on points in the local
input metric map. See derived classes for possible generated pairings.
Definition at line 31 of file Matcher_Points_Base.h.
|
default |
|
finaloverrideprotectedvirtual |
Implements mp2p_icp::Matcher.
Definition at line 22 of file Matcher_Points_Base.cpp.
|
privatepure virtual |
|
overridevirtual |
Common parameters to all derived classes:
maxLocalPointsPerLayer
: Maximum number of local points to consider for the "local" point cloud, per point layer. "0" means "all" (no decimation) [Default=0].localPointsSampleSeed
: Only if maxLocalPointsPerLayer
!=0, and the number of points in the local map is larger than that number, a seed for the RNG used to pick random point indices. 0
(default) means to use a time-based seed.pointLayerMatches
: Optional map of layer names to relative weights. Refer to example YAML files.allowMatchAlreadyMatchedPoints
: Optional (Default=false). Whether to find matches for local points which were already paired by other matcher in an earlier stage in the matchers pipeline.bounding_box_intersection_check_epsilon
: Optional (Default=0.20). The additional "margin" in all axes (x,y,z) that bounding box is enlarged for checking the feasibility of pairings to exist. Reimplemented from mp2p_icp::Matcher.
Reimplemented in mp2p_icp::Matcher_Points_DistanceThreshold, and mp2p_icp::Matcher_Points_InlierRatio.
Definition at line 120 of file Matcher_Points_Base.cpp.
|
static |
Definition at line 174 of file Matcher_Points_Base.cpp.
bool mp2p_icp::Matcher_Points_Base::allowMatchAlreadyMatchedGlobalPoints_ = false |
If false, global map points can be paired exclusively against one local point.
Definition at line 56 of file Matcher_Points_Base.h.
bool mp2p_icp::Matcher_Points_Base::allowMatchAlreadyMatchedPoints_ = false |
Whether to allow matching local points that have been already matched by a former Matcher instance in the pipeline.
Definition at line 52 of file Matcher_Points_Base.h.
double mp2p_icp::Matcher_Points_Base::bounding_box_intersection_check_epsilon_ = 0.20 |
The additional "margin" in all axes (x,y,z) that bounding box is enlarged for checking the feasibility of pairings to exist.
Definition at line 63 of file Matcher_Points_Base.h.
std::optional<std::size_t> mp2p_icp::Matcher_Points_Base::kdtree_leaf_max_points_ |
Maximum number of points per tree node. Not set: nanoflann default.
Definition at line 59 of file Matcher_Points_Base.h.
uint64_t mp2p_icp::Matcher_Points_Base::localPointsSampleSeed_ = 0 |
Definition at line 48 of file Matcher_Points_Base.h.
uint64_t mp2p_icp::Matcher_Points_Base::maxLocalPointsPerLayer_ = 0 |
Definition at line 47 of file Matcher_Points_Base.h.
std::map<std::string, std::map<std::string, double> > mp2p_icp::Matcher_Points_Base::weight_pt2pt_layers |
Weights for each potential Local->Global point layer matching. If empty, the output Pairings::point_weights will left empty (=all points have equal weight).
Definition at line 45 of file Matcher_Points_Base.h.