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 { out.WriteAs<bool>(false); }
28  if (pcLocal)
29  {
30  out.WriteAs<bool>(true);
31  out << *pcLocal;
32  }
33  else { out.WriteAs<bool>(false); }
35  out << icpParameters;
36  out << icpResult;
38  out << dynamicVariables; // added in v1
39 }
40 void LogRecord::serializeFrom(
41  mrpt::serialization::CArchive& in, uint8_t version)
42 {
43  *this = LogRecord();
44 
45  switch (version)
46  {
47  case 0:
48  case 1:
49  {
50  if (in.ReadAs<bool>())
51  {
52  pcGlobal = metric_map_t::Create();
53  in >> const_cast<metric_map_t&>(*pcGlobal);
54  }
55  if (in.ReadAs<bool>())
56  {
57  pcLocal = metric_map_t::Create();
58  in >> const_cast<metric_map_t&>(*pcLocal);
59  }
60 
63 
64  if (version >= 1)
65  in >> dynamicVariables;
66  else
67  dynamicVariables.clear();
68  }
69  break;
70  default:
71  MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version);
72  };
73 }
74 
75 bool LogRecord::save_to_file(const std::string& fileName) const
76 {
77  try
78  {
79  auto f = mrpt::io::CFileGZOutputStream(fileName);
80  if (!f.is_open()) return false;
81 
82  auto arch = mrpt::serialization::archiveFrom(f);
83  arch << *this;
84 
85  return true;
86  }
87  catch (const std::exception& e)
88  {
89  std::cerr << "[LogRecord::save_to_file] Error: " << e.what();
90  return false;
91  }
92 }
93 
95 {
96  try
97  {
98  auto f = mrpt::io::CFileGZInputStream(fileName);
99  if (!f.is_open()) return false;
100 
101  auto arch = mrpt::serialization::archiveFrom(f);
102  arch >> *this;
103 
104  return true;
105  }
106  catch (const std::exception& e)
107  {
108  std::cerr << "[LogRecord::save_to_file] Error: " << e.what();
109  return false;
110  }
111 }
112 
113 static const uint8_t DIPI_SERIALIZATION_VERSION = 0;
114 
116  mrpt::serialization::CArchive& out) const
117 {
118  out.WriteAs<uint8_t>(DIPI_SERIALIZATION_VERSION);
119 
120  out << optimalPose << pairings;
121 }
123  mrpt::serialization::CArchive& in)
124 {
125  const auto readVersion = in.ReadAs<uint8_t>();
126  ASSERT_EQUAL_(readVersion, DIPI_SERIALIZATION_VERSION);
127  in >> optimalPose >> pairings;
128 }
129 
130 mrpt::serialization::CArchive& mrpt::serialization::operator<<(
131  mrpt::serialization::CArchive& out,
133 {
134  obj.serializeTo(out);
135  return out;
136 }
137 
138 mrpt::serialization::CArchive& mrpt::serialization::operator>>(
139  mrpt::serialization::CArchive& in, LogRecord::DebugInfoPerIteration& obj)
140 {
141  obj.serializeFrom(in);
142  return in;
143 }
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
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:138
mrpt::serialization::operator<<
mrpt::serialization::CArchive & operator<<(mrpt::serialization::CArchive &out, const mp2p_icp::LogRecord::DebugInfoPerIteration &obj)
Definition: LogRecord.cpp:130
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
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
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
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(QualityEvaluator_RangeImageSimilarity, QualityEvaluator, mp2p_icp) using namespace mp2p_icp
mp2p_icp::LogRecord::LogRecord
LogRecord()=default
DIPI_SERIALIZATION_VERSION
static const uint8_t DIPI_SERIALIZATION_VERSION
Definition: LogRecord.cpp:113
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:49
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 Thu Dec 26 2024 03:48:12