class mp2p_icp::ICP_LibPointmatcher
Overview
ICP wrapper on libpointmatcher
#include <ICP_LibPointmatcher.h> class ICP_LibPointmatcher: public mp2p_icp::ICP { public: // typedefs typedef std::vector<mp2p_icp::Solver::Ptr> solver_list_t; typedef std::vector<QualityEvaluatorEntry> quality_eval_list_t; typedef std::function<IterationHook_Output(const IterationHook_Input&)> iteration_hook_t; // structs struct ParametersLibpointmatcher; // fields ParametersLibpointmatcher parametersLibpointmatcher; // methods const solver_list_t& solvers() const; solver_list_t& solvers(); static void initialize_solvers( const mrpt::containers::yaml& params, ICP::solver_list_t& lst ); const matcher_list_t& matchers() const; matcher_list_t& matchers(); static void initialize_matchers( const mrpt::containers::yaml& params, matcher_list_t& lst ); const quality_eval_list_t& quality_evaluators() const; quality_eval_list_t& quality_evaluators(); static void initialize_quality_evaluators( const mrpt::containers::yaml& params, quality_eval_list_t& lst ); 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 ); void initialize_derived(const mrpt::containers::yaml& params); virtual void align( const metric_map_t& pcLocal, const metric_map_t& pcGlobal, const mrpt::math::TPose3D& initialGuessLocalWrtGlobal, const Parameters& p, Results& result, const std::optional<mrpt::poses::CPose3DPDFGaussianInf>& prior = std::nullopt, const mrpt::optional_ref<LogRecord>& outputDebugInfo = std::nullopt ); void attachToParameterSource(ParameterSource& source); void setIterationHook(const iteration_hook_t& ih); const mrpt::system::CTimeLogger& profiler() const; mrpt::system::CTimeLogger& profiler(); static bool methodAvailable(); };
Inherited Members
public: // structs struct ICP_State; struct IterationHook_Input; struct IterationHook_Output; struct QualityEvaluatorEntry; // methods void initialize_solvers(const mrpt::containers::yaml& params); static bool run_solvers(const solver_list_t& solvers, const Pairings& pairings, OptimalTF_Result& out, const SolverContext& sc = {}); void initialize_quality_evaluators(const mrpt::containers::yaml& params); void initialize_matchers(const mrpt::containers::yaml& params); virtual void align( const metric_map_t& pcLocal, const metric_map_t& pcGlobal, const mrpt::math::TPose3D& initialGuessLocalWrtGlobal, const Parameters& p, Results& result, const std::optional<mrpt::poses::CPose3DPDFGaussianInf>& prior = std::nullopt, const mrpt::optional_ref<LogRecord>& outputDebugInfo = std::nullopt ); virtual void initialize_derived(] const mrpt::containers::yaml& p);
Methods
virtual void align( const metric_map_t& pcLocal, const metric_map_t& pcGlobal, const mrpt::math::TPose3D& initialGuessLocalWrtGlobal, const Parameters& p, Results& result, const std::optional<mrpt::poses::CPose3DPDFGaussianInf>& prior = std::nullopt, const mrpt::optional_ref<LogRecord>& outputDebugInfo = std::nullopt )
Register (align) two point clouds (possibly after having been preprocessed to extract features, etc.) and returns the relative pose of pcLocal with respect to pcGlobal.
static bool methodAvailable()
Returns true if mp2p_icp was built with libpointmatcher support.