Classes | Public Member Functions | List of all members
mp2p_icp::LogRecord Class Reference

#include <LogRecord.h>

Inheritance diagram for mp2p_icp::LogRecord:
Inheritance graph
[legend]

Classes

struct  DebugInfoPerIteration
 

Public Member Functions

 LogRecord ()=default
 
 ~LogRecord ()=default
 

Data fields

using iteration_idx_t = std::size_t
 
using IterationsDetails = std::map< iteration_idx_t, DebugInfoPerIteration >
 
metric_map_t::ConstPtr pcGlobal
 
metric_map_t::ConstPtr pcLocal
 
mrpt::math::TPose3D initialGuessLocalWrtGlobal
 
mp2p_icp::Parameters icpParameters
 
mp2p_icp::Results icpResult
 
std::optional< IterationsDetailsiterationsDetails
 

Methods

bool save_to_file (const std::string &fileName) const
 
bool load_from_file (const std::string &fileName)
 
static LogRecord LoadFromFile (const std::string &fileName)
 

Detailed Description

Details on an ICP run, loadable from the GUI tool mp2p-icp-log-viewer.

Definition at line 30 of file LogRecord.h.

Member Typedef Documentation

◆ iteration_idx_t

Definition at line 59 of file LogRecord.h.

◆ IterationsDetails

Definition at line 60 of file LogRecord.h.

Constructor & Destructor Documentation

◆ LogRecord()

mp2p_icp::LogRecord::LogRecord ( )
default

◆ ~LogRecord()

mp2p_icp::LogRecord::~LogRecord ( )
default

Member Function Documentation

◆ load_from_file()

bool LogRecord::load_from_file ( const std::string &  fileName)

Loads the record object from a file. See \save_to_file()

Returns
true on success.

Definition at line 85 of file LogRecord.cpp.

◆ LoadFromFile()

static LogRecord mp2p_icp::LogRecord::LoadFromFile ( const std::string &  fileName)
inlinestatic

Static method alternative to load_from_file(). Throws on any error.

Returns
The loaded object.

Definition at line 85 of file LogRecord.h.

◆ save_to_file()

bool LogRecord::save_to_file ( const std::string &  fileName) const

Saves the record object to a file, using MRPT serialization and using on-the-fly GZIP compression.

Returns
true on success.

Definition at line 74 of file LogRecord.cpp.

Member Data Documentation

◆ icpParameters

mp2p_icp::Parameters mp2p_icp::LogRecord::icpParameters

Definition at line 46 of file LogRecord.h.

◆ icpResult

mp2p_icp::Results mp2p_icp::LogRecord::icpResult

Definition at line 47 of file LogRecord.h.

◆ initialGuessLocalWrtGlobal

mrpt::math::TPose3D mp2p_icp::LogRecord::initialGuessLocalWrtGlobal

Definition at line 44 of file LogRecord.h.

◆ iterationsDetails

std::optional<IterationsDetails> mp2p_icp::LogRecord::iterationsDetails

Definition at line 62 of file LogRecord.h.

◆ pcGlobal

metric_map_t::ConstPtr mp2p_icp::LogRecord::pcGlobal

The ICP input global and local point clouds:

Definition at line 42 of file LogRecord.h.

◆ pcLocal

metric_map_t::ConstPtr mp2p_icp::LogRecord::pcLocal

Definition at line 42 of file LogRecord.h.


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


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