#include <Solver_GaussNewton.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 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 | |
| bool | innerLoopVerbose = false | 
| Prints GN inner loop details.  More... | |
| uint32_t | maxIterations = 5 | 
| PairWeights | pairWeights | 
| RobustKernel | robustKernel = RobustKernel::None | 
| double | robustKernelParam = 1.0 | 
|  Public Attributes inherited from mp2p_icp::Solver | |
| bool | enabled = true | 
| uint32_t | runFromIteration = 0 | 
| double | runUntilTranslationCorrectionSmallerThan = 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 | 
|  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... | |
ICP registration for points, planes, and lines, using an iterative Gauss-Newton numerical solver.
Definition at line 25 of file Solver_GaussNewton.h.
| 
 | overrideprotectedvirtual | 
Implements mp2p_icp::Solver.
Definition at line 34 of file Solver_GaussNewton.cpp.
| 
 | overridevirtual | 
Check each derived class to see required and optional parameters.
Reimplemented from mp2p_icp::Solver.
Definition at line 21 of file Solver_GaussNewton.cpp.
| bool mp2p_icp::Solver_GaussNewton::innerLoopVerbose = false | 
Prints GN inner loop details.
Definition at line 35 of file Solver_GaussNewton.h.
| uint32_t mp2p_icp::Solver_GaussNewton::maxIterations = 5 | 
Definition at line 30 of file Solver_GaussNewton.h.
| PairWeights mp2p_icp::Solver_GaussNewton::pairWeights | 
Definition at line 31 of file Solver_GaussNewton.h.
| RobustKernel mp2p_icp::Solver_GaussNewton::robustKernel = RobustKernel::None | 
Definition at line 33 of file Solver_GaussNewton.h.
| double mp2p_icp::Solver_GaussNewton::robustKernelParam = 1.0 | 
Definition at line 34 of file Solver_GaussNewton.h.