Solver_GaussNewton.cpp
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  * ------------------------------------------------------------------------- */
15 #include <mrpt/core/exceptions.h>
16 
18 
19 using namespace mp2p_icp;
20 
21 void Solver_GaussNewton::initialize(const mrpt::containers::yaml& params)
22 {
23  Solver::initialize(params);
24 
25  MCP_LOAD_REQ(params, maxIterations);
26  MCP_LOAD_OPT(params, innerLoopVerbose);
27  if (params.has("pair_weights"))
28  pairWeights.load_from(params["pair_weights"]);
29 }
30 
32  const Pairings& pairings, OptimalTF_Result& out,
33  [[maybe_unused]] const SolverContext& sc) const
34 {
35  MRPT_START
36 
38 
39  OptimalTF_GN_Parameters gnParams;
41  gnParams.pairWeights = pairWeights;
42 
43  ASSERT_(sc.guessRelativePose.has_value());
44  gnParams.linearizationPoint =
45  mrpt::poses::CPose3D(sc.guessRelativePose.value());
46 
47  gnParams.verbose = innerLoopVerbose;
48 
49  // Compute the optimal pose, and return its validity:
50  return optimal_tf_gauss_newton(pairings, out, gnParams);
51 
52  MRPT_END
53 }
mp2p_icp::OptimalTF_GN_Parameters
Definition: optimal_tf_gauss_newton.h:23
mp2p_icp::optimal_tf_gauss_newton
bool optimal_tf_gauss_newton(const Pairings &in, OptimalTF_Result &result, const OptimalTF_GN_Parameters &gnParams=OptimalTF_GN_Parameters())
Definition: optimal_tf_gauss_newton.cpp:22
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::OptimalTF_GN_Parameters::verbose
bool verbose
Definition: optimal_tf_gauss_newton.h:25
mp2p_icp::SolverContext
Definition: Solver.h:30
mp2p_icp::OptimalTF_Result
Definition: OptimalTF_Result.h:24
optimal_tf_gauss_newton.h
Simple non-linear optimizer to find the SE(3) optimal transformation.
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::load_from
void load_from(const mrpt::containers::yaml &p)
Definition: PairWeights.cpp:18
mp2p_icp::OptimalTF_GN_Parameters::maxInnerLoopIterations
uint32_t maxInnerLoopIterations
Definition: optimal_tf_gauss_newton.h:28
mp2p_icp::OptimalTF_GN_Parameters::pairWeights
PairWeights pairWeights
Definition: optimal_tf_gauss_newton.h:39
mp2p_icp::OptimalTF_GN_Parameters::linearizationPoint
std::optional< mrpt::poses::CPose3D > linearizationPoint
Definition: optimal_tf_gauss_newton.h:37
Solver_GaussNewton.h
ICP registration for points and planes.
mp2p_icp::Solver::initialize
virtual void initialize(const mrpt::containers::yaml &params)
Definition: Solver.cpp:20
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(metric_map_t, mrpt::serialization::CSerializable, mp2p_icp) using namespace mp2p_icp
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