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-2021 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 
50  {
51  mrpt::poses::CPose3D optimalPose;
53 
54  void serializeTo(mrpt::serialization::CArchive& out) const;
55  void serializeFrom(mrpt::serialization::CArchive& in);
56 
57  DECLARE_TTYPENAME_CLASSNAME(mp2p_icp::LogRecord::DebugInfoPerIteration)
58  };
59  using iteration_idx_t = std::size_t;
60  using IterationsDetails = std::map<iteration_idx_t, DebugInfoPerIteration>;
61 
62  std::optional<IterationsDetails> iterationsDetails;
63 
73  bool save_to_file(const std::string& fileName) const;
74 
78  bool load_from_file(const std::string& fileName);
79 
85  static LogRecord LoadFromFile(const std::string& fileName)
86  {
87  LogRecord lr;
88  lr.load_from_file(fileName);
89  return lr;
90  }
91 
93 };
94 
97 } // namespace mp2p_icp
98 
100 {
101 mrpt::serialization::CArchive& operator<<(
102  mrpt::serialization::CArchive& out,
104 
105 mrpt::serialization::CArchive& operator>>(
106  mrpt::serialization::CArchive& in,
108 
109 } // namespace mrpt::serialization
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
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
mp2p_icp::Pairings
Definition: Pairings.h:94
mp2p_icp::LogRecord::LoadFromFile
static LogRecord LoadFromFile(const std::string &fileName)
Definition: LogRecord.h:85
mp2p_icp::LogRecord
Definition: LogRecord.h:30
mp2p_icp::LogRecord::iterationsDetails
std::optional< IterationsDetails > iterationsDetails
Definition: LogRecord.h:62
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: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
Pairings.h
Common types for all SE(3) optimal transformation methods.
mrpt::serialization
Definition: LogRecord.h:99
mp2p_icp::LogRecord::iteration_idx_t
std::size_t iteration_idx_t
Definition: LogRecord.h:59
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:52
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:25
mp2p_icp::LogRecord::IterationsDetails
std::map< iteration_idx_t, DebugInfoPerIteration > IterationsDetails
Definition: LogRecord.h:60
Results.h


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