Public Member Functions | Public Attributes | Protected Member Functions | List of all members
mp2p_icp::Matcher Class Referenceabstract

#include <Matcher.h>

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

Public Member Functions

virtual void initialize (const mrpt::containers::yaml &params)
 
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 Attributes

uint32_t runFromIteration = 0
 
uint32_t runUpToIteration = 0
 0: no limit More...
 

Protected Member Functions

virtual 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 =0
 

Detailed Description

Pointcloud matching generic base class. Each "matcher" implementation takes a global ("reference") metric_map_t and another local ("mobile") metric_map_t which is assumed to be placed in a hypothetical SE(3) pose in the global frame, and generates pairings between the geometric entities (points, planes, etc.) of both groups.

Definition at line 70 of file Matcher.h.

Member Function Documentation

◆ impl_match()

virtual bool mp2p_icp::Matcher::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
protectedpure virtual
Returns
true if the mather is actually invoked, false if disabled.

Implemented in mp2p_icp::Matcher_Points_Base.

◆ initialize()

void Matcher::initialize ( const mrpt::containers::yaml &  params)
virtual

Check each derived class to see required and optional parameters.

Reimplemented in mp2p_icp::Matcher_Points_Base, mp2p_icp::Matcher_Point2Plane, mp2p_icp::Matcher_Points_DistanceThreshold, mp2p_icp::Matcher_Point2Line, and mp2p_icp::Matcher_Points_InlierRatio.

Definition at line 20 of file mp2p_icp/src/Matcher.cpp.

◆ match()

bool Matcher::match ( const metric_map_t pcGlobal,
const metric_map_t pcLocal,
const mrpt::poses::CPose3D &  localPose,
const MatchContext mc,
MatchState ms,
Pairings out 
) const
virtual

Finds correspondences between the two point clouds. "out" is not cleared, but new pairings added to it.

Returns
false if the matcher is disabled and was not actually run.

Definition at line 26 of file mp2p_icp/src/Matcher.cpp.

Member Data Documentation

◆ runFromIteration

uint32_t mp2p_icp::Matcher::runFromIteration = 0

Definition at line 87 of file Matcher.h.

◆ runUpToIteration

uint32_t mp2p_icp::Matcher::runUpToIteration = 0

0: no limit

Definition at line 88 of file Matcher.h.


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


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Mon Aug 14 2023 02:09:05