Go to the documentation of this file.
27 if (p.has(
"pairingsWeightParameters"))
45 const Pairings* effectivePairings = &pairings;
46 std::optional<Pairings> altPairings;
51 effectivePairings = &altPairings.value();
Pairings pt2ln_pl_to_pt2pt(const Pairings &in, const SolverContext &sc)
OLAE algorithm to find the SE(3) optimal transformation.
bool impl_optimal_pose(const Pairings &pairings, OptimalTF_Result &out, const SolverContext &sc) const override
void load_from(const mrpt::containers::yaml &p)
void initialize(const mrpt::containers::yaml ¶ms) override
bool optimal_tf_olae(const Pairings &in, const WeightParameters &wp, OptimalTF_Result &result)
ICP registration for points and planes.
IMPLEMENTS_MRPT_OBJECT(QualityEvaluator_RangeImageSimilarity, QualityEvaluator, mp2p_icp) using namespace mp2p_icp
WeightParameters pairingsWeightParameters
MatchedPointLineList paired_pt2ln
virtual void initialize(const mrpt::containers::yaml ¶ms)
MatchedPointPlaneList paired_pt2pl
mp2p_icp
Author(s):
autogenerated on Wed Oct 23 2024 02:45:41