covariance.h
Go to the documentation of this file.
1 /* -------------------------------------------------------------------------
2  * A repertory of multi primitive-to-primitive (MP2P) ICP algorithms in C++
3  * Copyright (C) 2018-2024 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
12 #pragma once
13 
14 #include <mp2p_icp/Pairings.h>
15 #include <mrpt/math/CMatrixFixed.h>
16 
17 namespace mp2p_icp
18 {
20 {
21  // Finite difference deltas:
22  double finDif_xyz = 1e-7;
23  double finDif_angles = 1e-7;
24 };
25 
30 mrpt::math::CMatrixDouble66 covariance(
31  const Pairings& finalPairings,
32  const mrpt::poses::CPose3D& finalAlignSolution,
33  const CovarianceParameters& p);
34 
35 } // namespace mp2p_icp
mp2p_icp
Definition: covariance.h:17
mp2p_icp::CovarianceParameters::finDif_xyz
double finDif_xyz
Definition: covariance.h:22
mp2p_icp::CovarianceParameters
Definition: covariance.h:19
mp2p_icp::Pairings
Definition: Pairings.h:78
mp2p_icp::CovarianceParameters::finDif_angles
double finDif_angles
Definition: covariance.h:23
mp2p_icp::covariance
mrpt::math::CMatrixDouble66 covariance(const Pairings &finalPairings, const mrpt::poses::CPose3D &finalAlignSolution, const CovarianceParameters &p)
Definition: covariance.cpp:22
Pairings.h
Common types for all SE(3) optimal transformation methods.


mp2p_icp
Author(s):
autogenerated on Thu Dec 26 2024 03:48:10