14 #include <mrpt/math/CMatrixFixed.h>
15 #include <mrpt/math/CQuaternion.h>
16 #include <mrpt/math/CVectorFixed.h>
71 const mrpt::math::TPoint3D& ct_global, mrpt::math::CQuaternionDouble& out_attitude,
83 ASSERTMSG_(nPt2Ln == 0,
"This solver cannot handle point-to-line pairings.");
84 ASSERTMSG_(nPt2Pl == 0,
"This solver cannot handle point-to-plane pairings yet.");
85 const auto nAllMatches = nPt2Pt + nLn2Ln + nPl2Pl;
88 if (nAllMatches < 3)
return false;
90 auto S = mrpt::math::CMatrixDouble33::Zero();
93 auto lambda_each_pair =
94 [&](
const mrpt::math::TVector3D& bi,
const mrpt::math::TVector3D& ri,
const double wi)
99 S(0, 0) += wi * ri.x * bi.x;
100 S(0, 1) += wi * ri.x * bi.y;
101 S(0, 2) += wi * ri.x * bi.z;
103 S(1, 0) += wi * ri.y * bi.x;
104 S(1, 1) += wi * ri.y * bi.y;
105 S(1, 2) += wi * ri.y * bi.z;
107 S(2, 0) += wi * ri.z * bi.x;
108 S(2, 1) += wi * ri.z * bi.y;
109 S(2, 2) += wi * ri.z * bi.z;
112 auto lambda_final = [&](
const double w_sum)
115 if (w_sum > .0) S *= (1.0 / w_sum);
119 in, wp, ct_local, ct_global, in_out_outliers ,
121 lambda_each_pair, lambda_final,
false );
124 auto N = mrpt::math::CMatrixDouble44::Zero();
126 N(0, 0) = S(0, 0) + S(1, 1) + S(2, 2);
127 N(0, 1) = S(1, 2) - S(2, 1);
128 N(0, 2) = S(2, 0) - S(0, 2);
129 N(0, 3) = S(0, 1) - S(1, 0);
132 N(1, 1) = S(0, 0) - S(1, 1) - S(2, 2);
133 N(1, 2) = S(0, 1) + S(1, 0);
134 N(1, 3) = S(2, 0) + S(0, 2);
138 N(2, 2) = -S(0, 0) + S(1, 1) - S(2, 2);
139 N(2, 3) = S(1, 2) + S(2, 1);
144 N(3, 3) = -S(0, 0) - S(1, 1) + S(2, 2);
148 auto Z = mrpt::math::CMatrixDouble44::Zero();
149 std::vector<double> eigvals;
150 N.eig_symmetric(
Z, eigvals,
true );
152 auto v =
Z.blockCopy<4, 1>(0, 3);
154 ASSERTDEB_(fabs(sqrt(v[0] * v[0] + v[1] * v[1] + v[2] * v[2] + v[3] * v[3]) - 1.0) < 0.1);
166 for (
unsigned int i = 0; i < 4; i++) out_attitude[i] = v[i];
171 if (forceScaleToUnity)
179 for (
size_t i = 0; i < nMatches; i++)
181 num += ri[i].sqrNorm();
182 den += bi[i].sqrNorm();
185 s = std::sqrt(num / den);
209 mrpt::math::CQuaternionDouble optimal_q;
212 if (!
se3_l2_internal(in, wp, ct_local, ct_global, optimal_q, result.outliers ))
221 ct_local = new_ct_local;
222 ct_global = new_ct_global;
225 if (!
se3_l2_internal(in, wp, ct_local, ct_global, optimal_q, result.outliers ))
230 result.optimalPose = mrpt::poses::CPose3D(optimal_q, 0, 0, 0);
233 mrpt::math::TPoint3D pp;
234 result.optimalPose.composePoint(ct_local.x, ct_local.y, ct_local.z, pp.x, pp.y, pp.z);
237 result.optimalPose.x(ct_global.x - pp.x);
238 result.optimalPose.y(ct_global.y - pp.y);
239 result.optimalPose.z(ct_global.z - pp.z);