optimal_tf_gauss_newton.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 
15 #include <mp2p_icp/PairWeights.h>
16 #include <mp2p_icp/Pairings.h>
17 
18 namespace mp2p_icp
19 {
24 {
25  bool verbose = false;
26 
28  uint32_t maxInnerLoopIterations = 6;
29 
31  double minDelta = 1e-7;
32 
34  double maxCost = 0;
35 
37  std::optional<mrpt::poses::CPose3D> linearizationPoint;
38 
40 };
41 
51 [[nodiscard]] bool optimal_tf_gauss_newton(
52  const Pairings& in, OptimalTF_Result& result,
54 
57 } // namespace mp2p_icp
Common types for all SE(3) optimal transformation methods.
Common types for all SE(3) optimal transformation methods.
std::optional< mrpt::poses::CPose3D > linearizationPoint
bool optimal_tf_gauss_newton(const Pairings &in, OptimalTF_Result &result, const OptimalTF_GN_Parameters &gnParams=OptimalTF_GN_Parameters())
Common types for all SE(3) optimal transformation methods.


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Thu Jun 1 2023 03:06:43