Solver_GaussNewton.h
Go to the documentation of this file.
1 /* -------------------------------------------------------------------------
2  * A repertory of multi primitive-to-primitive (MP2P) ICP algorithms in C++
3  * Copyright (C) 2018-2021 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
12 #pragma once
13 
14 #include <mp2p_icp/PairWeights.h>
15 #include <mp2p_icp/Solver.h>
16 
17 namespace mp2p_icp
18 {
24 class Solver_GaussNewton : public Solver
25 {
26  DEFINE_MRPT_OBJECT(Solver_GaussNewton, mp2p_icp)
27 
28  public:
29  uint32_t maxIterations = 5;
31  bool innerLoopVerbose = false;
32 
33  void initialize(const mrpt::containers::yaml& params) override;
34 
35  protected:
36  // See base class docs
37  bool impl_optimal_pose(
38  const Pairings& pairings, OptimalTF_Result& out,
39  const SolverContext& sc) const override;
40 };
41 
42 } // namespace mp2p_icp
PairWeights.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp
Definition: covariance.h:17
mp2p_icp::Solver_GaussNewton
Definition: Solver_GaussNewton.h:24
mp2p_icp::Pairings
Definition: Pairings.h:94
mp2p_icp::Solver_GaussNewton::pairWeights
PairWeights pairWeights
Definition: Solver_GaussNewton.h:30
mp2p_icp::Solver_GaussNewton::maxIterations
uint32_t maxIterations
Definition: Solver_GaussNewton.h:29
mp2p_icp::SolverContext
Definition: Solver.h:30
mp2p_icp::OptimalTF_Result
Definition: OptimalTF_Result.h:24
Solver.h
Virtual base class for optimal alignment solvers (one step in ICP).
mp2p_icp::Solver_GaussNewton::innerLoopVerbose
bool innerLoopVerbose
Prints GN inner loop details.
Definition: Solver_GaussNewton.h:31
kitti-batch-convert.out
string out
Definition: kitti-batch-convert.py:7
mp2p_icp::Solver
Definition: Solver.h:46
mp2p_icp::PairWeights
Definition: PairWeights.h:26
mp2p_icp::Solver_GaussNewton::impl_optimal_pose
bool impl_optimal_pose(const Pairings &pairings, OptimalTF_Result &out, const SolverContext &sc) const override
Definition: Solver_GaussNewton.cpp:31
mp2p_icp::Solver_GaussNewton::initialize
void initialize(const mrpt::containers::yaml &params) override
Definition: Solver_GaussNewton.cpp:21


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