Parameters.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  * ------------------------------------------------------------------------- */
6 
7 #pragma once
8 
10 #include <mrpt/containers/yaml.h>
11 #include <mrpt/core/bits_math.h> // DEG2RAD()
12 #include <mrpt/serialization/CSerializable.h>
13 
14 #include <cstddef>
15 #include <cstdint>
16 #include <map>
17 #include <string>
18 
19 namespace mp2p_icp
20 {
25 struct Parameters : public mrpt::serialization::CSerializable
26 {
27  DEFINE_SERIALIZABLE(Parameters, mp2p_icp)
28 
29  public:
33  uint32_t maxIterations{40};
34 
38  double minAbsStep_trans{5e-4};
39 
43  double minAbsStep_rot{1e-4};
57  bool generateDebugFiles = false;
58 
61  "icp-run-$UNIQUE_ID-local-$LOCAL_ID$LOCAL_LABEL-"
62  "global-$GLOBAL_ID$GLOBAL_LABEL.icplog";
63 
65 
68  void load_from(const mrpt::containers::yaml& p);
69  void save_to(mrpt::containers::yaml& p) const;
70 };
71 
72 } // namespace mp2p_icp
mp2p_icp
Definition: covariance.h:17
mp2p_icp::Parameters::save_to
void save_to(mrpt::containers::yaml &p) const
Definition: Parameters.cpp:51
mp2p_icp::Parameters::minAbsStep_trans
double minAbsStep_trans
Definition: Parameters.h:38
mp2p_icp::Parameters::generateDebugFiles
bool generateDebugFiles
Definition: Parameters.h:57
mp2p_icp::Parameters::debugFileNameFormat
std::string debugFileNameFormat
Definition: Parameters.h:60
testing::internal::string
::std::string string
Definition: gtest.h:1979
mp2p_icp::Parameters::maxIterations
uint32_t maxIterations
Definition: Parameters.h:33
WeightParameters.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp::Parameters::minAbsStep_rot
double minAbsStep_rot
Definition: Parameters.h:43
mp2p_icp::Parameters::load_from
void load_from(const mrpt::containers::yaml &p)
Definition: Parameters.cpp:42
mp2p_icp::Parameters::debugPrintIterationProgress
bool debugPrintIterationProgress
Definition: Parameters.h:64
mp2p_icp::Parameters
Definition: Parameters.h:25


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