Go to the documentation of this file.
18 #include <mrpt/serialization/CSerializable.h>
30 class LogRecord :
public mrpt::serialization::CSerializable
103 mrpt::serialization::CArchive&
out,
107 mrpt::serialization::CArchive& in,
void serializeTo(mrpt::serialization::CArchive &out) const
mrpt::poses::CPose3D optimalPose
for this ICP iteration
mrpt::serialization::CArchive & operator>>(mrpt::serialization::CArchive &in, mp2p_icp::LogRecord::DebugInfoPerIteration &obj)
mrpt::serialization::CArchive & operator<<(mrpt::serialization::CArchive &out, const mp2p_icp::LogRecord::DebugInfoPerIteration &obj)
static LogRecord LoadFromFile(const std::string &fileName)
std::map< std::string, double > dynamicVariables
std::optional< IterationsDetails > iterationsDetails
bool save_to_file(const std::string &fileName) const
void serializeFrom(mrpt::serialization::CArchive &in)
bool load_from_file(const std::string &fileName)
Common types for all SE(3) optimal transformation methods.
std::size_t iteration_idx_t
metric_map_t::ConstPtr pcGlobal
mp2p_icp::Parameters icpParameters
mp2p_icp::Results icpResult
Generic representation of pointcloud(s) and/or extracted features.
mrpt::math::TPose3D initialGuessLocalWrtGlobal
metric_map_t::ConstPtr pcLocal
std::map< iteration_idx_t, DebugInfoPerIteration > IterationsDetails
mp2p_icp
Author(s):
autogenerated on Fri Dec 20 2024 03:45:59