errorTerms.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 
15 #include <mp2p_icp/Pairings.h>
18 #include <mrpt/core/optional_ref.h>
19 #include <mrpt/math/CVectorFixed.h>
20 
21 #include <Eigen/Dense>
22 
23 namespace mp2p_icp
24 {
28 mrpt::math::CVectorFixedDouble<3> error_point2point(
29  const mrpt::tfest::TMatchingPair& pairing,
30  const mrpt::poses::CPose3D& relativePose,
31  mrpt::optional_ref<mrpt::math::CMatrixFixed<double, 3, 12>> jacobian =
32  std::nullopt);
33 
34 mrpt::math::CVectorFixedDouble<3> error_point2line(
35  const mp2p_icp::point_line_pair_t& pairing,
36  const mrpt::poses::CPose3D& relativePose,
37  mrpt::optional_ref<mrpt::math::CMatrixFixed<double, 3, 12>> jacobian =
38  std::nullopt);
39 
40 mrpt::math::CVectorFixedDouble<3> error_point2plane(
41  const mp2p_icp::point_plane_pair_t& pairing,
42  const mrpt::poses::CPose3D& relativePose,
43  mrpt::optional_ref<mrpt::math::CMatrixFixed<double, 3, 12>> jacobian =
44  std::nullopt);
45 
46 mrpt::math::CVectorFixedDouble<4> error_line2line(
47  const mp2p_icp::matched_line_t& pairing,
48  const mrpt::poses::CPose3D& relativePose,
49  mrpt::optional_ref<mrpt::math::CMatrixFixed<double, 4, 12>> jacobian =
50  std::nullopt);
51 
52 mrpt::math::CVectorFixedDouble<3> error_plane2plane(
53  const mp2p_icp::matched_plane_t& pairing,
54  const mrpt::poses::CPose3D& relativePose,
55  mrpt::optional_ref<mrpt::math::CMatrixFixed<double, 3, 12>> jacobian =
56  std::nullopt);
57 
58 } // namespace mp2p_icp
mp2p_icp
Definition: covariance.h:17
mp2p_icp::point_plane_pair_t
Definition: point_plane_pair_t.h:26
OptimalTF_Result.h
Common types for all SE(3) optimal transformation methods.
optimal_tf_gauss_newton.h
Simple non-linear optimizer to find the SE(3) optimal transformation.
mp2p_icp::error_plane2plane
mrpt::math::CVectorFixedDouble< 3 > error_plane2plane(const mp2p_icp::matched_plane_t &pairing, const mrpt::poses::CPose3D &relativePose, mrpt::optional_ref< mrpt::math::CMatrixFixed< double, 3, 12 >> jacobian=std::nullopt)
Definition: errorTerms.cpp:337
mp2p_icp::matched_line_t
Definition: Pairings.h:44
mp2p_icp::error_point2plane
mrpt::math::CVectorFixedDouble< 3 > error_point2plane(const mp2p_icp::point_plane_pair_t &pairing, const mrpt::poses::CPose3D &relativePose, mrpt::optional_ref< mrpt::math::CMatrixFixed< double, 3, 12 >> jacobian=std::nullopt)
Definition: errorTerms.cpp:109
Pairings.h
Common types for all SE(3) optimal transformation methods.
WeightParameters.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp::error_point2point
mrpt::math::CVectorFixedDouble< 3 > error_point2point(const mrpt::tfest::TMatchingPair &pairing, const mrpt::poses::CPose3D &relativePose, mrpt::optional_ref< mrpt::math::CMatrixFixed< double, 3, 12 >> jacobian=std::nullopt)
Definition: errorTerms.cpp:28
mp2p_icp::point_line_pair_t
Definition: Pairings.h:53
mp2p_icp::matched_plane_t
Definition: Pairings.h:29
mp2p_icp::error_point2line
mrpt::math::CVectorFixedDouble< 3 > error_point2line(const mp2p_icp::point_line_pair_t &pairing, const mrpt::poses::CPose3D &relativePose, mrpt::optional_ref< mrpt::math::CMatrixFixed< double, 3, 12 >> jacobian=std::nullopt)
Definition: errorTerms.cpp:61
mp2p_icp::error_line2line
mrpt::math::CVectorFixedDouble< 4 > error_line2line(const mp2p_icp::matched_line_t &pairing, const mrpt::poses::CPose3D &relativePose, mrpt::optional_ref< mrpt::math::CMatrixFixed< double, 4, 12 >> jacobian=std::nullopt)
Definition: errorTerms.cpp:167


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