Go to the documentation of this file.
23 #include <mrpt/containers/yaml.h>
24 #include <mrpt/core/optional_ref.h>
25 #include <mrpt/math/TPose3D.h>
26 #include <mrpt/rtti/CObject.h>
27 #include <mrpt/system/COutputLogger.h>
51 class ICP :
public mrpt::system::COutputLogger,
public mrpt::rtti::CObject
62 const mrpt::math::TPose3D& initialGuessLocalWrtGlobal,
64 const mrpt::optional_ref<LogRecord>& outputDebugInfo = std::nullopt);
143 mp2p_icp::QualityEvaluator::Ptr
obj;
178 const metric_map_t& pcLocal,
const mrpt::poses::CPose3D& localPose,
190 [[maybe_unused]]
const mrpt::containers::yaml& p)
199 {QualityEvaluator_PairedRatio::Create(), 1.0}};
const quality_eval_list_t & quality_evaluators() const
std::vector< QualityEvaluatorEntry > quality_eval_list_t
Matching quality evaluator: simple ratio [0,1] of paired entities.
static double evaluate_quality(const quality_eval_list_t &evaluators, const metric_map_t &pcGlobal, const metric_map_t &pcLocal, const mrpt::poses::CPose3D &localPose, const Pairings &finalPairings)
A record of the inputs and outputs of an ICP run.
std::string layerOfLargestPc
quality_eval_list_t quality_evaluators_
ICP_State(const metric_map_t &pcsGlobal, const metric_map_t &pcsLocal)
OptimalTF_Result currentSolution
void initialize_solvers(const mrpt::containers::yaml ¶ms)
matcher_list_t & matchers()
solver_list_t & solvers()
const metric_map_t & pcGlobal
std::vector< mp2p_icp::Solver::Ptr > solver_list_t
virtual void align(const metric_map_t &pcLocal, const metric_map_t &pcGlobal, const mrpt::math::TPose3D &initialGuessLocalWrtGlobal, const Parameters &p, Results &result, const mrpt::optional_ref< LogRecord > &outputDebugInfo=std::nullopt)
Virtual base class for optimal alignment solvers (one step in ICP).
const solver_list_t & solvers() const
quality_eval_list_t & quality_evaluators()
void initialize_matchers(const mrpt::containers::yaml ¶ms)
const matcher_list_t & matchers() const
Pointcloud matching generic base class.
Matching quality evaluator (virtual base class)
Generic representation of pointcloud(s) and/or extracted features.
Generic container of pointcloud(s), extracted features and other maps.
mp2p_icp::QualityEvaluator::Ptr obj
virtual void initialize_derived([[maybe_unused]] const mrpt::containers::yaml &p)
static bool run_solvers(const solver_list_t &solvers, const Pairings &pairings, OptimalTF_Result &out, const SolverContext &sc={})
const metric_map_t & pcLocal
void initialize_quality_evaluators(const mrpt::containers::yaml ¶ms)
QualityEvaluatorEntry(mp2p_icp::QualityEvaluator::Ptr o, double w)
std::vector< mp2p_icp::Matcher::Ptr > matcher_list_t
uint32_t currentIteration
static void save_log_file(const LogRecord &log, const Parameters &p)