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-2021 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 0; }
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 }
45 void LogRecord::serializeFrom(
46  mrpt::serialization::CArchive& in, uint8_t version)
47 {
48  *this = LogRecord();
49 
50  switch (version)
51  {
52  case 0:
53  {
54  if (in.ReadAs<bool>())
55  {
56  pcGlobal = metric_map_t::Create();
57  in >> const_cast<metric_map_t&>(*pcGlobal);
58  }
59  if (in.ReadAs<bool>())
60  {
61  pcLocal = metric_map_t::Create();
62  in >> const_cast<metric_map_t&>(*pcLocal);
63  }
64 
67  }
68  break;
69  default:
70  MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version);
71  };
72 }
73 
74 bool LogRecord::save_to_file(const std::string& fileName) const
75 {
76  auto f = mrpt::io::CFileGZOutputStream(fileName);
77  if (!f.is_open()) return false;
78 
79  auto arch = mrpt::serialization::archiveFrom(f);
80  arch << *this;
81 
82  return true;
83 }
84 
86 {
87  auto f = mrpt::io::CFileGZInputStream(fileName);
88  if (!f.is_open()) return false;
89 
90  auto arch = mrpt::serialization::archiveFrom(f);
91  arch >> *this;
92 
93  return true;
94 }
95 
96 static const uint8_t DIPI_SERIALIZATION_VERSION = 0;
97 
99  mrpt::serialization::CArchive& out) const
100 {
101  out.WriteAs<uint8_t>(DIPI_SERIALIZATION_VERSION);
102 
103  out << optimalPose << pairings;
104 }
106  mrpt::serialization::CArchive& in)
107 {
108  const auto readVersion = in.ReadAs<uint8_t>();
109  ASSERT_EQUAL_(readVersion, DIPI_SERIALIZATION_VERSION);
110 }
111 
112 mrpt::serialization::CArchive& mrpt::serialization::operator<<(
113  mrpt::serialization::CArchive& out,
115 {
116  obj.serializeTo(out);
117  return out;
118 }
119 
120 mrpt::serialization::CArchive& mrpt::serialization::operator>>(
121  mrpt::serialization::CArchive& in, LogRecord::DebugInfoPerIteration& obj)
122 {
123  obj.serializeFrom(in);
124  return in;
125 }
mp2p_icp::LogRecord::DebugInfoPerIteration::serializeTo
void serializeTo(mrpt::serialization::CArchive &out) const
Definition: LogRecord.cpp:98
mp2p_icp
Definition: covariance.h:17
mp2p_icp::LogRecord::DebugInfoPerIteration::optimalPose
mrpt::poses::CPose3D optimalPose
for this ICP iteration
Definition: LogRecord.h:51
LogRecord.h
A record of the inputs and outputs of an ICP run.
mp2p_icp::LogRecord::DebugInfoPerIteration
Definition: LogRecord.h:49
mrpt::serialization::operator>>
mrpt::serialization::CArchive & operator>>(mrpt::serialization::CArchive &in, mp2p_icp::LogRecord::DebugInfoPerIteration &obj)
Definition: LogRecord.cpp:120
mrpt::serialization::operator<<
mrpt::serialization::CArchive & operator<<(mrpt::serialization::CArchive &out, const mp2p_icp::LogRecord::DebugInfoPerIteration &obj)
Definition: LogRecord.cpp:112
kitti-run-seq.f
string f
Definition: kitti-run-seq.py:12
mp2p_icp::LogRecord
Definition: LogRecord.h:30
mp2p_icp::LogRecord::iterationsDetails
std::optional< IterationsDetails > iterationsDetails
Definition: LogRecord.h:62
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:74
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:105
mp2p_icp::LogRecord::load_from_file
bool load_from_file(const std::string &fileName)
Definition: LogRecord.cpp:85
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:96
mp2p_icp::LogRecord::DebugInfoPerIteration::pairings
Pairings pairings
Definition: LogRecord.h:52
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:47
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
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(metric_map_t, mrpt::serialization::CSerializable, mp2p_icp) using namespace mp2p_icp


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Mon Aug 14 2023 02:09:03