LogRecord.cpp
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  * ------------------------------------------------------------------------- */
6 
7 #include <mp2p_icp/LogRecord.h>
8 #include <mrpt/io/CFileGZInputStream.h>
9 #include <mrpt/io/CFileGZOutputStream.h>
10 #include <mrpt/serialization/CArchive.h>
11 #include <mrpt/serialization/optional_serialization.h>
12 #include <mrpt/serialization/stl_serialization.h>
13 
14 IMPLEMENTS_MRPT_OBJECT(LogRecord, mrpt::serialization::CSerializable, mp2p_icp)
15 
16 using namespace mp2p_icp;
17 
18 // Implementation of the CSerializable virtual interface:
19 uint8_t LogRecord::serializeGetVersion() const { return 1; }
20 void LogRecord::serializeTo(mrpt::serialization::CArchive& out) const
21 {
22  if (pcGlobal)
23  {
24  out.WriteAs<bool>(true);
25  out << *pcGlobal;
26  }
27  else
28  {
29  out.WriteAs<bool>(false);
30  }
31  if (pcLocal)
32  {
33  out.WriteAs<bool>(true);
34  out << *pcLocal;
35  }
36  else
37  {
38  out.WriteAs<bool>(false);
39  }
41  out << icpParameters;
42  out << icpResult;
44  out << dynamicVariables; // added in v1
45 }
46 void LogRecord::serializeFrom(mrpt::serialization::CArchive& in, uint8_t version)
47 {
48  *this = LogRecord();
49 
50  switch (version)
51  {
52  case 0:
53  case 1:
54  {
55  if (in.ReadAs<bool>())
56  {
57  pcGlobal = metric_map_t::Create();
58  in >> const_cast<metric_map_t&>(*pcGlobal);
59  }
60  if (in.ReadAs<bool>())
61  {
62  pcLocal = metric_map_t::Create();
63  in >> const_cast<metric_map_t&>(*pcLocal);
64  }
65 
67 
68  if (version >= 1)
69  in >> dynamicVariables;
70  else
71  dynamicVariables.clear();
72  }
73  break;
74  default:
75  MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version);
76  };
77 }
78 
79 bool LogRecord::save_to_file(const std::string& fileName) const
80 {
81  try
82  {
83  auto f = mrpt::io::CFileGZOutputStream(fileName);
84  if (!f.is_open()) return false;
85 
86  auto arch = mrpt::serialization::archiveFrom(f);
87  arch << *this;
88 
89  return true;
90  }
91  catch (const std::exception& e)
92  {
93  std::cerr << "[LogRecord::save_to_file] Error: " << e.what();
94  return false;
95  }
96 }
97 
99 {
100  try
101  {
102  auto f = mrpt::io::CFileGZInputStream(fileName);
103  if (!f.is_open()) return false;
104 
105  auto arch = mrpt::serialization::archiveFrom(f);
106  arch >> *this;
107 
108  return true;
109  }
110  catch (const std::exception& e)
111  {
112  std::cerr << "[LogRecord::save_to_file] Error: " << e.what();
113  return false;
114  }
115 }
116 
117 static const uint8_t DIPI_SERIALIZATION_VERSION = 0;
118 
119 void LogRecord::DebugInfoPerIteration::serializeTo(mrpt::serialization::CArchive& out) const
120 {
121  out.WriteAs<uint8_t>(DIPI_SERIALIZATION_VERSION);
122 
123  out << optimalPose << pairings;
124 }
125 void LogRecord::DebugInfoPerIteration::serializeFrom(mrpt::serialization::CArchive& in)
126 {
127  const auto readVersion = in.ReadAs<uint8_t>();
128  ASSERT_EQUAL_(readVersion, DIPI_SERIALIZATION_VERSION);
129  in >> optimalPose >> pairings;
130 }
131 
132 mrpt::serialization::CArchive& mrpt::serialization::operator<<(
133  mrpt::serialization::CArchive& out, const LogRecord::DebugInfoPerIteration& obj)
134 {
135  obj.serializeTo(out);
136  return out;
137 }
138 
139 mrpt::serialization::CArchive& mrpt::serialization::operator>>(
140  mrpt::serialization::CArchive& in, LogRecord::DebugInfoPerIteration& obj)
141 {
142  obj.serializeFrom(in);
143  return in;
144 }
mp2p_icp::LogRecord::DebugInfoPerIteration::serializeTo
void serializeTo(mrpt::serialization::CArchive &out) const
Definition: LogRecord.cpp:119
mp2p_icp
Definition: covariance.h:17
mp2p_icp::LogRecord::DebugInfoPerIteration::optimalPose
mrpt::poses::CPose3D optimalPose
for this ICP iteration
Definition: LogRecord.h:52
LogRecord.h
A record of the inputs and outputs of an ICP run.
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:139
mrpt::serialization::operator<<
mrpt::serialization::CArchive & operator<<(mrpt::serialization::CArchive &out, const mp2p_icp::LogRecord::DebugInfoPerIteration &obj)
Definition: LogRecord.cpp:132
kitti-run-seq.f
string f
Definition: kitti-run-seq.py:12
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
testing::internal::string
::std::string string
Definition: gtest.h:1979
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(FilterDecimateVoxelsQuadratic, mp2p_icp_filters::FilterBase, mp2p_icp_filters) using namespace mp2p_icp_filters
mp2p_icp::LogRecord::save_to_file
bool save_to_file(const std::string &fileName) const
Definition: LogRecord.cpp:79
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:125
mp2p_icp::LogRecord::load_from_file
bool load_from_file(const std::string &fileName)
Definition: LogRecord.cpp:98
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
DIPI_SERIALIZATION_VERSION
static const uint8_t DIPI_SERIALIZATION_VERSION
Definition: LogRecord.cpp:117
mp2p_icp::LogRecord::DebugInfoPerIteration::pairings
Pairings pairings
Definition: LogRecord.h:53
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:55
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
Author(s):
autogenerated on Mon May 26 2025 02:45:49