LogRecord.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/Pairings.h>
15 #include <mp2p_icp/Parameters.h>
16 #include <mp2p_icp/Results.h>
17 #include <mp2p_icp/metricmap.h>
18 #include <mrpt/serialization/CSerializable.h>
19 
20 #include <optional>
21 
22 namespace mp2p_icp
23 {
30 class LogRecord : public mrpt::serialization::CSerializable
31 {
32  DEFINE_SERIALIZABLE(LogRecord, mp2p_icp)
33 
34  public:
35  LogRecord() = default;
36  ~LogRecord() = default;
37 
42  metric_map_t::ConstPtr pcGlobal, pcLocal;
43 
44  mrpt::math::TPose3D initialGuessLocalWrtGlobal;
45 
48  std::map<std::string, double> dynamicVariables;
49 
51  {
52  mrpt::poses::CPose3D optimalPose;
54 
55  void serializeTo(mrpt::serialization::CArchive& out) const;
56  void serializeFrom(mrpt::serialization::CArchive& in);
57 
58  DECLARE_TTYPENAME_CLASSNAME(mp2p_icp::LogRecord::DebugInfoPerIteration)
59  };
60  using iteration_idx_t = std::size_t;
61  using IterationsDetails = std::map<iteration_idx_t, DebugInfoPerIteration>;
62 
63  std::optional<IterationsDetails> iterationsDetails;
64 
74  bool save_to_file(const std::string& fileName) const;
75 
79  bool load_from_file(const std::string& fileName);
80 
86  static LogRecord LoadFromFile(const std::string& fileName)
87  {
88  LogRecord lr;
89  lr.load_from_file(fileName);
90  return lr;
91  }
92 
94 };
95 
98 } // namespace mp2p_icp
99 
101 {
102 mrpt::serialization::CArchive& operator<<(
103  mrpt::serialization::CArchive& out,
105 
106 mrpt::serialization::CArchive& operator>>(
107  mrpt::serialization::CArchive& in,
109 
110 } // namespace mrpt::serialization
mp2p_icp::LogRecord::DebugInfoPerIteration::serializeTo
void serializeTo(mrpt::serialization::CArchive &out) const
Definition: LogRecord.cpp:115
mp2p_icp
Definition: covariance.h:17
mp2p_icp::LogRecord::DebugInfoPerIteration::optimalPose
mrpt::poses::CPose3D optimalPose
for this ICP iteration
Definition: LogRecord.h:52
mp2p_icp::LogRecord::DebugInfoPerIteration
Definition: LogRecord.h:50
mrpt::serialization::operator>>
mrpt::serialization::CArchive & operator>>(mrpt::serialization::CArchive &in, mp2p_icp::LogRecord::DebugInfoPerIteration &obj)
Definition: LogRecord.cpp:138
mrpt::serialization::operator<<
mrpt::serialization::CArchive & operator<<(mrpt::serialization::CArchive &out, const mp2p_icp::LogRecord::DebugInfoPerIteration &obj)
Definition: LogRecord.cpp:130
mp2p_icp::Pairings
Definition: Pairings.h:94
mp2p_icp::LogRecord::LoadFromFile
static LogRecord LoadFromFile(const std::string &fileName)
Definition: LogRecord.h:86
mp2p_icp::LogRecord::dynamicVariables
std::map< std::string, double > dynamicVariables
Definition: LogRecord.h:48
mp2p_icp::LogRecord
Definition: LogRecord.h:30
mp2p_icp::LogRecord::iterationsDetails
std::optional< IterationsDetails > iterationsDetails
Definition: LogRecord.h:63
Parameters.h
testing::internal::string
::std::string string
Definition: gtest.h:1979
mp2p_icp::LogRecord::save_to_file
bool save_to_file(const std::string &fileName) const
Definition: LogRecord.cpp:75
kitti-batch-convert.out
string out
Definition: kitti-batch-convert.py:7
mp2p_icp::LogRecord::DebugInfoPerIteration::serializeFrom
void serializeFrom(mrpt::serialization::CArchive &in)
Definition: LogRecord.cpp:122
mp2p_icp::LogRecord::load_from_file
bool load_from_file(const std::string &fileName)
Definition: LogRecord.cpp:94
Pairings.h
Common types for all SE(3) optimal transformation methods.
mrpt::serialization
Definition: LogRecord.h:100
mp2p_icp::LogRecord::iteration_idx_t
std::size_t iteration_idx_t
Definition: LogRecord.h:60
mp2p_icp::LogRecord::pcGlobal
metric_map_t::ConstPtr pcGlobal
Definition: LogRecord.h:42
mp2p_icp::LogRecord::icpParameters
mp2p_icp::Parameters icpParameters
Definition: LogRecord.h:46
mp2p_icp::LogRecord::icpResult
mp2p_icp::Results icpResult
Definition: LogRecord.h:47
mp2p_icp::LogRecord::LogRecord
LogRecord()=default
mp2p_icp::LogRecord::DebugInfoPerIteration::pairings
Pairings pairings
Definition: LogRecord.h:53
mp2p_icp::LogRecord::~LogRecord
~LogRecord()=default
metricmap.h
Generic representation of pointcloud(s) and/or extracted features.
mp2p_icp::LogRecord::initialGuessLocalWrtGlobal
mrpt::math::TPose3D initialGuessLocalWrtGlobal
Definition: LogRecord.h:44
mp2p_icp::LogRecord::pcLocal
metric_map_t::ConstPtr pcLocal
Definition: LogRecord.h:42
mp2p_icp::Results
Definition: Results.h:21
mp2p_icp::Parameters
Definition: Parameters.h:26
mp2p_icp::LogRecord::IterationsDetails
std::map< iteration_idx_t, DebugInfoPerIteration > IterationsDetails
Definition: LogRecord.h:61
Results.h


mp2p_icp
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Tue Jul 2 2024 02:47:25