14 #include <mrpt/serialization/CArchive.h> 15 #include <mrpt/serialization/optional_serialization.h> 18 WeightParameters, mrpt::serialization::CSerializable,
mp2p_icp)
23 uint8_t WeightParameters::serializeGetVersion()
const {
return 0; }
24 void WeightParameters::serializeTo(mrpt::serialization::CArchive&
out)
const 31 void WeightParameters::serializeFrom(
32 mrpt::serialization::CArchive& in, uint8_t version)
45 MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version);
56 MCP_LOAD_OPT(p, robust_kernel_scale);
67 MCP_SAVE(p, robust_kernel_scale);
69 mrpt::containers::yaml a = mrpt::containers::yaml::Map();
71 p[
"pair_weights"] = a;
PairWeights pair_weights
See docs for PairWeights.
void load_from(const mrpt::containers::yaml &p)
IMPLEMENTS_MRPT_OBJECT(WeightParameters, mrpt::serialization::CSerializable, mp2p_icp) using namespace mp2p_icp
Common types for all SE(3) optimal transformation methods.
bool use_scale_outlier_detector
void save_to(mrpt::containers::yaml &p) const
double robust_kernel_scale
std::optional< mrpt::poses::CPose3D > currentEstimateForRobust
double scale_outlier_threshold
void serializeFrom(mrpt::serialization::CArchive &in)
void load_from(const mrpt::containers::yaml &p)
void serializeTo(mrpt::serialization::CArchive &out) const
double robust_kernel_param
void save_to(mrpt::containers::yaml &p) const