Results.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/Results.h>
8 #include <mrpt/serialization/CArchive.h>
9 
10 #include <ostream>
11 
12 using namespace mp2p_icp;
13 
14 static const uint8_t SERIALIZATION_VERSION = 0;
15 
16 void Results::serializeTo(mrpt::serialization::CArchive& out) const
17 {
18  out.WriteAs<uint8_t>(SERIALIZATION_VERSION);
20  out << static_cast<uint8_t>(terminationReason);
21  out << quality;
23 }
24 void Results::serializeFrom(mrpt::serialization::CArchive& in)
25 {
26  const auto readVersion = in.ReadAs<uint8_t>();
27 
28  ASSERT_EQUAL_(readVersion, SERIALIZATION_VERSION);
29 
31  terminationReason = static_cast<IterTermReason>(in.ReadAs<uint8_t>());
32  in >> quality;
34 }
35 
36 mrpt::serialization::CArchive& mp2p_icp::operator<<(
37  mrpt::serialization::CArchive& out, const Results& obj)
38 {
39  obj.serializeTo(out);
40  return out;
41 }
42 
43 mrpt::serialization::CArchive& mp2p_icp::operator>>(
44  mrpt::serialization::CArchive& in, Results& obj)
45 {
46  obj.serializeFrom(in);
47  return in;
48 }
49 
50 void Results::print(std::ostream& o) const
51 {
52  o << "- optimalPoseLocalWrtGlobal: " << optimal_tf.mean
53  << "\n"
54  "- quality: "
55  << 100 * quality
56  << " %\n"
57  "- iterations: "
58  << nIterations
59  << "\n"
60  "- terminationReason: "
61  << mrpt::typemeta::TEnumType<mp2p_icp::IterTermReason>::value2name(
63  << "\n"
64  << "- finalPairings: " << finalPairings.contents_summary() << "\n";
65 }
mp2p_icp::Results::terminationReason
IterTermReason terminationReason
Definition: Results.h:33
mp2p_icp::Pairings::contents_summary
virtual std::string contents_summary() const
Definition: Pairings.cpp:158
mp2p_icp
Definition: covariance.h:17
mp2p_icp::operator>>
mrpt::serialization::CArchive & operator>>(mrpt::serialization::CArchive &in, Pairings &obj)
Definition: Pairings.cpp:55
SERIALIZATION_VERSION
static const uint8_t SERIALIZATION_VERSION
Definition: Results.cpp:14
mp2p_icp::Pairings::serializeFrom
virtual void serializeFrom(mrpt::serialization::CArchive &in)
Definition: Pairings.cpp:37
mp2p_icp::Results::optimal_tf
mrpt::poses::CPose3DPDFGaussian optimal_tf
Definition: Results.h:25
mp2p_icp::Results::serializeTo
void serializeTo(mrpt::serialization::CArchive &out) const
Definition: Results.cpp:16
mp2p_icp::Results::print
void print(std::ostream &o) const
Definition: Results.cpp:50
mp2p_icp::Results::finalPairings
Pairings finalPairings
Definition: Results.h:41
mp2p_icp::Results::nIterations
size_t nIterations
Definition: Results.h:31
mp2p_icp::Results::optimalScale
double optimalScale
Definition: Results.h:28
kitti-batch-convert.out
string out
Definition: kitti-batch-convert.py:7
mp2p_icp::Pairings::serializeTo
virtual void serializeTo(mrpt::serialization::CArchive &out) const
Definition: Pairings.cpp:28
mp2p_icp::IterTermReason
IterTermReason
Definition: IterTermReason.h:18
mp2p_icp::operator<<
mrpt::serialization::CArchive & operator<<(mrpt::serialization::CArchive &out, const Pairings &obj)
Definition: Pairings.cpp:48
mp2p_icp::Results::serializeFrom
void serializeFrom(mrpt::serialization::CArchive &in)
Definition: Results.cpp:24
mp2p_icp::Results
Definition: Results.h:21
Results.h
mp2p_icp::Results::quality
double quality
Definition: Results.h:38


mp2p_icp
Author(s):
autogenerated on Thu Dec 26 2024 03:48:12