14 #include <mrpt/core/exceptions.h>
15 #include <mrpt/poses/Lie/SE.h>
16 #include <mrpt/tfest/se3.h>
18 #include <Eigen/Dense>
25 static mrpt::poses::CPose3D
gibbs2pose(
const Eigen::Vector3d& v)
27 auto x = v[0], y = v[1], z = v[2];
28 const auto r = 1.0 / std::sqrt(1.0 +
x *
x + y * y + z * z);
32 auto q = mrpt::math::CQuaternionDouble(r, -
x, -y, -z);
35 return mrpt::poses::CPose3D(
q, .0, .0, .0);
49 Eigen::Matrix3d M, Mx, My,
Mz;
50 Eigen::Vector3d v, vx, vy,
vz;
59 const mrpt::math::TPoint3D& ct_local,
const mrpt::math::TPoint3D& ct_global,
64 using mrpt::math::TPoint3D;
65 using mrpt::math::TVector3D;
70 res.M = Eigen::Matrix3d::Zero();
71 res.v = Eigen::Vector3d::Zero();
74 res.B = Eigen::Matrix3d::Zero();
77 auto lambda_each_pair = [&](
const mrpt::math::TVector3D& bi,
78 const mrpt::math::TVector3D& ri,
87 const double sx = bi.x + ri.x, sy = bi.y + ri.y, sz = bi.z + ri.z;
100 const double c00 = -sy * sy - sz * sz;
101 const double c11 = -sx * sx - sz * sz;
102 const double c22 = -sx * sx - sy * sy;
103 const double c01 = sx * sy;
104 const double c02 = sx * sz;
105 const double c12 = sy * sz;
108 const auto dM = (Eigen::Matrix3d() <<
111 c02, c12, c22 ).finished();
134 const auto dV = (Eigen::Vector3d() <<
135 (bi.y * ri.z - bi.z * ri.y),
136 (-bi.x * ri.z + bi.z * ri.x),
137 (bi.x * ri.y - bi.y * ri.x) ).finished();
143 const auto dB = (Eigen::Matrix3d() <<
144 bi.x * ri.x, bi.x * ri.y, bi.x * ri.z,
145 bi.y * ri.x, bi.y * ri.y, bi.y * ri.z,
146 bi.z * ri.x, bi.z * ri.y, bi.z * ri.z).finished();
152 auto lambda_final = [&](
const double w_sum) {
156 const auto f = (1.0 / w_sum);
169 in, wp, ct_local, ct_global, in_out_outliers, lambda_each_pair,
170 lambda_final,
true );
176 const Eigen::Matrix3d S =
res.B +
res.B.transpose();
177 const double p =
res.B.trace() + 1;
178 const double m =
res.B.trace() - 1;
180 const auto& v =
res.v;
184 res.M = (Eigen::Matrix3d() <<
185 S(0,0)-p, S(0,1), S(0,2),
186 S(0,1), S(1,1)-p, S(1,2),
187 S(0,2), S(1,2), S(2,2)-p ).finished();
190 const auto& M0 =
res.M;
191 const double z1 = v[0], z2 = v[1], z3 = v[2];
195 res.Mx = (Eigen::Matrix3d() <<
197 -z3 , M0(2,2), -S(1,2),
198 z2 , -S(1,2), M0(1,1)).finished();
199 res.vx = (Eigen::Vector3d() <<
206 res.My = (Eigen::Matrix3d() <<
207 M0(2,2), z3 , -S(0,2),
209 -S(0,2) , -z1 , M0(0,0)).finished();
210 res.vy = (Eigen::Vector3d() <<
217 res.Mz = (Eigen::Matrix3d() <<
218 M0(1,1), -S(0,1), -z2,
219 -S(0,1) , M0(0,0), z1,
220 -z2 , z1 , m).finished();
221 res.vz = (Eigen::Vector3d() <<
238 using mrpt::math::TPoint3D;
239 using mrpt::math::TVector3D;
257 auto [ct_local, ct_global] =
262 in, wp, ct_local, ct_global, result.
outliers );
268 const auto [new_ct_local, new_ct_global] =
271 ct_local = new_ct_local;
272 ct_global = new_ct_global;
276 in, wp, ct_local, ct_global, result.
outliers);
282 const double detM_orig = std::abs(linsys.
M.determinant()),
283 detMx = std::abs(linsys.
Mx.determinant()),
284 detMy = std::abs(linsys.
My.determinant()),
285 detMz = std::abs(linsys.
Mz.determinant());
289 std::cout <<
" |M_orig|= " << detM_orig <<
"\n"
290 " |M_x| = " << detMx <<
"\n"
291 " |M_t| = " << detMy <<
"\n"
292 " |M_z| = " << detMz <<
"\n";
296 if (detM_orig > mrpt::max3(detMx, detMy, detMz))
300 gibbs2pose(linsys.
M.colPivHouseholderQr().solve(linsys.
v));
303 std::cout <<
"M : |M|="
304 << mrpt::format(
"%16.07f", linsys.
M.determinant())
305 <<
" sol: " << sol0.asString() <<
"\n";
308 else if (detMx > mrpt::max3(detM_orig, detMy, detMz))
313 sol1 = mrpt::poses::CPose3D(0, 0, 0, 0, 0, M_PI) + sol1;
316 std::cout <<
"M_x : |M|="
317 << mrpt::format(
"%16.07f", linsys.
Mx.determinant())
318 <<
" sol: " << sol1.asString() <<
"\n";
321 else if (detMy > mrpt::max3(detM_orig, detMx, detMz))
326 sol2 = mrpt::poses::CPose3D(0, 0, 0, 0, M_PI, 0) + sol2;
329 std::cout <<
"M_y : |M|="
330 << mrpt::format(
"%16.07f", linsys.
My.determinant())
331 <<
" sol: " << sol2.asString() <<
"\n";
339 sol3 = mrpt::poses::CPose3D(0, 0, 0, M_PI, 0, 0) + sol3;
342 std::cout <<
"M_z : |M|="
343 << mrpt::format(
"%16.07f", linsys.
Mz.determinant())
344 <<
" sol: " << sol3.asString() <<
"\n";
349 mrpt::math::TPoint3D pp;
351 ct_local.x, ct_local.y, ct_local.z, pp.x, pp.y, pp.z);