WeightParameters.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-2024 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
12 #pragma once
13 
14 #include <mp2p_icp/PairWeights.h>
16 #include <mrpt/containers/yaml.h>
17 #include <mrpt/poses/CPose3D.h>
18 #include <mrpt/serialization/CSerializable.h>
19 
20 namespace mp2p_icp
21 {
26 struct WeightParameters : public mrpt::serialization::CSerializable
27 {
28  DEFINE_SERIALIZABLE(WeightParameters, mp2p_icp)
29 
30  public:
36 
44 
47 
51 
54  std::optional<mrpt::poses::CPose3D> currentEstimateForRobust;
55 
56  double robust_kernel_param = 1.0;
57 
60  void load_from(const mrpt::containers::yaml& p);
61  void save_to(mrpt::containers::yaml& p) const;
62 };
63 
66 } // namespace mp2p_icp
mp2p_icp::RobustKernel
RobustKernel
Definition: robust_kernels.h:25
PairWeights.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp
Definition: covariance.h:17
mp2p_icp::WeightParameters::use_scale_outlier_detector
bool use_scale_outlier_detector
Definition: WeightParameters.h:35
mp2p_icp::WeightParameters::pair_weights
PairWeights pair_weights
See docs for PairWeights.
Definition: WeightParameters.h:46
mp2p_icp::RobustKernel::None
@ None
None: plain least-squares.
mp2p_icp::WeightParameters::robust_kernel_param
double robust_kernel_param
Definition: WeightParameters.h:56
mp2p_icp::WeightParameters::load_from
void load_from(const mrpt::containers::yaml &p)
Definition: WeightParameters.cpp:65
mp2p_icp::WeightParameters::currentEstimateForRobust
std::optional< mrpt::poses::CPose3D > currentEstimateForRobust
Definition: WeightParameters.h:54
mp2p_icp::WeightParameters::save_to
void save_to(mrpt::containers::yaml &p) const
Definition: WeightParameters.cpp:75
robust_kernels.h
Robust kernel types and functions, for common use in all solvers.
mp2p_icp::WeightParameters::scale_outlier_threshold
double scale_outlier_threshold
Definition: WeightParameters.h:43
mp2p_icp::WeightParameters
Definition: WeightParameters.h:26
mp2p_icp::PairWeights
Definition: PairWeights.h:26
mp2p_icp::WeightParameters::robust_kernel
RobustKernel robust_kernel
Definition: WeightParameters.h:50


mp2p_icp
Author(s):
autogenerated on Wed Oct 23 2024 02:45:41