Public Member Functions | Public Attributes | List of all members
mp2p_icp::Results Struct Reference

#include <Results.h>

Public Member Functions

void print (std::ostream &o) const
 
void serializeFrom (mrpt::serialization::CArchive &in)
 
void serializeTo (mrpt::serialization::CArchive &out) const
 

Public Attributes

Pairings finalPairings
 
size_t nIterations = 0
 
mrpt::poses::CPose3DPDFGaussian optimal_tf
 
double optimalScale = 1.0
 
double quality = 0
 
IterTermReason terminationReason {IterTermReason::Undefined}
 

Detailed Description

Definition at line 21 of file Results.h.

Member Function Documentation

◆ print()

void Results::print ( std::ostream &  o) const

Print all results in human-friendly format to the given output, for example, use std::cout.

Definition at line 50 of file Results.cpp.

◆ serializeFrom()

void Results::serializeFrom ( mrpt::serialization::CArchive &  in)

Definition at line 24 of file Results.cpp.

◆ serializeTo()

void Results::serializeTo ( mrpt::serialization::CArchive &  out) const

Definition at line 16 of file Results.cpp.

Member Data Documentation

◆ finalPairings

Pairings mp2p_icp::Results::finalPairings

A copy of the pairings found in the last ICP iteration.

Definition at line 41 of file Results.h.

◆ nIterations

size_t mp2p_icp::Results::nIterations = 0

The number of executed iterations until convergence

Definition at line 31 of file Results.h.

◆ optimal_tf

mrpt::poses::CPose3DPDFGaussian mp2p_icp::Results::optimal_tf

The found value (mean + covariance) of the optimal transformation of "local" wrt "global".

Definition at line 25 of file Results.h.

◆ optimalScale

double mp2p_icp::Results::optimalScale = 1.0

Found scale (if supported by the underlying algorithm) for optimal_tf

Definition at line 28 of file Results.h.

◆ quality

double mp2p_icp::Results::quality = 0

A measure of the 'quality' of the matching. Different modules are available to evaluate the quality in ICP_Base.

Definition at line 38 of file Results.h.

◆ terminationReason

IterTermReason mp2p_icp::Results::terminationReason {IterTermReason::Undefined}

Definition at line 33 of file Results.h.


The documentation for this struct was generated from the following files:


mp2p_icp
Author(s):
autogenerated on Fri Dec 20 2024 03:46:01