#include <LogRecord.h>
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::map< std::string, double > | dynamicVariables |
std::optional< IterationsDetails > | iterationsDetails |
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) |
Details on an ICP run, loadable from the GUI tool icp-log-viewer.
Definition at line 30 of file LogRecord.h.
using mp2p_icp::LogRecord::iteration_idx_t = std::size_t |
Definition at line 60 of file LogRecord.h.
using mp2p_icp::LogRecord::IterationsDetails = std::map<iteration_idx_t, DebugInfoPerIteration> |
Definition at line 61 of file LogRecord.h.
|
default |
|
default |
bool LogRecord::load_from_file | ( | const std::string & | fileName | ) |
Loads the record object from a file. See \save_to_file()
Definition at line 94 of file LogRecord.cpp.
|
inlinestatic |
Static method alternative to load_from_file(). Throws on any error.
Definition at line 86 of file LogRecord.h.
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.
Definition at line 75 of file LogRecord.cpp.
std::map<std::string, double> mp2p_icp::LogRecord::dynamicVariables |
Definition at line 48 of file LogRecord.h.
mp2p_icp::Parameters mp2p_icp::LogRecord::icpParameters |
Definition at line 46 of file LogRecord.h.
mp2p_icp::Results mp2p_icp::LogRecord::icpResult |
Definition at line 47 of file LogRecord.h.
mrpt::math::TPose3D mp2p_icp::LogRecord::initialGuessLocalWrtGlobal |
Definition at line 44 of file LogRecord.h.
std::optional<IterationsDetails> mp2p_icp::LogRecord::iterationsDetails |
Definition at line 63 of file LogRecord.h.
metric_map_t::ConstPtr mp2p_icp::LogRecord::pcGlobal |
The ICP input global and local point clouds:
Definition at line 42 of file LogRecord.h.
metric_map_t::ConstPtr mp2p_icp::LogRecord::pcLocal |
Definition at line 42 of file LogRecord.h.