#include <Solver_Horn.h>
Public Member Functions | |
void | initialize (const mrpt::containers::yaml ¶ms) override |
Public Member Functions inherited from mp2p_icp::Solver | |
virtual bool | optimal_pose (const Pairings &pairings, OptimalTF_Result &out, const SolverContext &sc) const |
Public Attributes | |
WeightParameters | pairingsWeightParameters |
Public Attributes inherited from mp2p_icp::Solver | |
uint32_t | runFromIteration = 0 |
uint32_t | runUpToIteration = 0 |
0: no limit More... | |
Protected Member Functions | |
bool | impl_optimal_pose (const Pairings &pairings, OptimalTF_Result &out, const SolverContext &sc) const override |
ICP registration for pointclouds split in different "layers"
Definition at line 22 of file Solver_Horn.h.
|
overrideprotectedvirtual |
Implements mp2p_icp::Solver.
Definition at line 33 of file Solver_Horn.cpp.
|
overridevirtual |
Check each derived class to see required and optional parameters.
Reimplemented from mp2p_icp::Solver.
Definition at line 25 of file Solver_Horn.cpp.
WeightParameters mp2p_icp::Solver_Horn::pairingsWeightParameters |
Weight and robust kernel parameters associated with the low-level optimal pose estimation algorithms
Definition at line 28 of file Solver_Horn.h.