16 #include <mrpt/poses/Lie/SE.h>
18 #include <Eigen/Dense>
21 #if defined(MP2P_HAS_TBB)
22 #include <tbb/blocked_range.h>
23 #include <tbb/parallel_reduce.h>
38 gnParams.
linearizationPoint.has_value(),
"This method requires a linearization point");
53 Eigen::Matrix<double, 6, 1> g = Eigen::Matrix<double, 6, 1>::Zero();
54 Eigen::Matrix<double, 6, 6> H = Eigen::Matrix<double, 6, 6>::Zero();
60 std::size_t cur_point_block_start = 0;
65 const auto dDexpe_de = mrpt::poses::Lie::SE<3>::jacob_dDexpe_de(result.
optimalPose);
67 double errNormSqr = 0;
69 #if defined(MP2P_HAS_TBB)
87 Eigen::Matrix<double, 6, 6> H;
88 Eigen::Matrix<double, 6, 1> g;
91 const auto& [H_tbb_pt2pt, g_tbb_pt2pt] = tbb::parallel_reduce(
93 tbb::blocked_range<size_t>{0, nPt2Pt},
97 [&](
const tbb::blocked_range<size_t>& r, Result
res) -> Result
99 auto& [H_local, g_local] =
res;
100 for (
size_t idx_pt = r.begin(); idx_pt < r.end(); idx_pt++)
104 mrpt::math::CMatrixFixed<double, 3, 12> J1;
105 mrpt::math::CVectorFixedDouble<3> ret =
109 if (has_per_pt_weight)
111 if (idx_pt >= cur_point_block_start + cur_point_block_weights->first)
114 ++cur_point_block_weights;
115 cur_point_block_start = idx_pt;
117 w.pt2pt = cur_point_block_weights->second;
121 double weight = w.pt2pt, retSqrNorm = ret.asEigen().squaredNorm();
122 if (robustSqrtWeightFunc) weight *= robustSqrtWeightFunc(retSqrNorm);
125 const Eigen::Vector3d err_i = ret.asEigen();
126 errNormSqr += weight * retSqrNorm;
128 const Eigen::Matrix<double, 3, 6> Ji = J1.asEigen() * dDexpe_de.asEigen();
129 g_local.noalias() += weight * Ji.transpose() * err_i;
130 H_local.noalias() += weight * Ji.transpose() * Ji;
135 [](Result a,
const Result& b) -> Result {
return a + b; });
137 H = std::move(H_tbb_pt2pt);
138 g = std::move(g_tbb_pt2pt);
141 for (
size_t idx_pt = 0; idx_pt < nPt2Pt; idx_pt++)
145 mrpt::math::CMatrixFixed<double, 3, 12> J1;
146 mrpt::math::CVectorFixedDouble<3> ret =
150 if (has_per_pt_weight)
152 if (idx_pt >= cur_point_block_start + cur_point_block_weights->first)
155 ++cur_point_block_weights;
156 cur_point_block_start = idx_pt;
158 w.pt2pt = cur_point_block_weights->second;
162 double weight = w.pt2pt, retSqrNorm = ret.asEigen().squaredNorm();
163 if (robustSqrtWeightFunc) weight *= robustSqrtWeightFunc(retSqrNorm);
166 const Eigen::Vector3d err_i = ret.asEigen();
167 errNormSqr += weight * retSqrNorm;
169 const Eigen::Matrix<double, 3, 6> Ji = J1.asEigen() * dDexpe_de.asEigen();
170 g.noalias() += weight * Ji.transpose() * err_i;
171 H.noalias() += weight * Ji.transpose() * Ji;
176 for (
size_t idx_pt = 0; idx_pt < nPt2Ln; idx_pt++)
180 mrpt::math::CMatrixFixed<double, 3, 12> J1;
181 mrpt::math::CVectorFixedDouble<3> ret =
185 double weight = w.pt2ln, retSqrNorm = ret.asEigen().squaredNorm();
186 if (robustSqrtWeightFunc) weight *= robustSqrtWeightFunc(retSqrNorm);
189 const Eigen::Vector3d err_i = ret.asEigen();
190 errNormSqr += weight * weight * retSqrNorm;
192 const Eigen::Matrix<double, 3, 6> Ji = J1.asEigen() * dDexpe_de.asEigen();
193 g.noalias() += weight * Ji.transpose() * err_i;
194 H.noalias() += weight * Ji.transpose() * Ji;
199 for (
size_t idx_ln = 0; idx_ln < nLn2Ln; idx_ln++)
202 mrpt::math::CMatrixFixed<double, 4, 12> J1;
203 mrpt::math::CVectorFixedDouble<4> ret =
207 double weight = w.ln2ln, retSqrNorm = ret.asEigen().squaredNorm();
208 if (robustSqrtWeightFunc) weight *= robustSqrtWeightFunc(retSqrNorm);
211 const Eigen::Vector4d err_i = ret.asEigen();
212 errNormSqr += weight * weight * retSqrNorm;
214 const Eigen::Matrix<double, 4, 6> Ji = J1.asEigen() * dDexpe_de.asEigen();
215 g.noalias() += weight * Ji.transpose() * err_i;
216 H.noalias() += weight * Ji.transpose() * Ji;
219 #if defined(MP2P_HAS_TBB)
221 const auto& [H_tbb_pt2pl, g_tbb_pt2pl] = tbb::parallel_reduce(
223 tbb::blocked_range<size_t>{0, nPt2Pl},
227 [&](
const tbb::blocked_range<size_t>& r, Result
res) -> Result
229 auto& [H_local, g_local] =
res;
230 for (
size_t idx_pl = r.begin(); idx_pl < r.end(); idx_pl++)
234 mrpt::math::CMatrixFixed<double, 3, 12> J1;
235 mrpt::math::CVectorFixedDouble<3> ret =
239 double weight = w.pt2pl, retSqrNorm = ret.asEigen().squaredNorm();
240 if (robustSqrtWeightFunc) weight *= robustSqrtWeightFunc(retSqrNorm);
243 const Eigen::Vector3d err_i = ret.asEigen();
244 errNormSqr += weight * retSqrNorm;
246 const Eigen::Matrix<double, 3, 6> Ji = J1.asEigen() * dDexpe_de.asEigen();
247 g_local.noalias() += weight * Ji.transpose() * err_i;
248 H_local.noalias() += weight * Ji.transpose() * Ji;
253 [](Result a,
const Result& b) -> Result {
return a + b; });
259 for (
size_t idx_pl = 0; idx_pl < nPt2Pl; idx_pl++)
263 mrpt::math::CMatrixFixed<double, 3, 12> J1;
264 mrpt::math::CVectorFixedDouble<3> ret =
268 double weight = w.pt2pl, retSqrNorm = ret.asEigen().squaredNorm();
269 if (robustSqrtWeightFunc) weight *= robustSqrtWeightFunc(retSqrNorm);
272 const Eigen::Vector3d err_i = ret.asEigen();
273 errNormSqr += weight * weight * retSqrNorm;
275 const Eigen::Matrix<double, 3, 6> Ji = J1.asEigen() * dDexpe_de.asEigen();
276 g.noalias() += weight * Ji.transpose() * err_i;
277 H.noalias() += weight * Ji.transpose() * Ji;
282 for (
size_t idx_pl = 0; idx_pl < nPl2Pl; idx_pl++)
286 mrpt::math::CMatrixFixed<double, 3, 12> J1;
287 mrpt::math::CVectorFixedDouble<3> ret =
291 double weight = w.pl2pl, retSqrNorm = ret.asEigen().squaredNorm();
292 if (robustSqrtWeightFunc) weight *= robustSqrtWeightFunc(retSqrNorm);
294 const Eigen::Vector3d err_i = ret.asEigen();
295 errNormSqr += weight * weight * retSqrNorm;
297 const Eigen::Matrix<double, 3, 6> Ji = J1.asEigen() * dDexpe_de.asEigen();
298 g.noalias() += weight * Ji.transpose() * err_i;
299 H.noalias() += weight * Ji.transpose() * Ji;
303 if (gnParams.
prior.has_value())
305 const auto& priorMean = gnParams.
prior->mean;
306 const auto& priorInf = gnParams.
prior->cov_inv;
313 const mrpt::poses::CPose3D P1invP2 = result.
optimalPose - priorMean;
314 const auto err_i = mrpt::poses::Lie::SE<3>::log(P1invP2);
316 mrpt::math::CMatrixDouble66 df_de2;
318 mrpt::poses::Lie::SE<3>::jacob_dDinvP1invP2_de1e2(
320 mrpt::poses::CPose3D::Identity(),
330 g.noalias() += (df_de2.transpose() * priorInf.asEigen()) * err_i.asEigen();
332 H.noalias() += (df_de2.transpose() * priorInf.asEigen()) * df_de2.asEigen();
336 const double errNorm = std::sqrt(errNormSqr);
338 if (errNorm <= gnParams.
maxCost)
break;
343 const Eigen::Matrix<double, 6, 1> delta = -H.ldlt().solve(g);
346 const auto dE = mrpt::poses::Lie::SE<3>::exp(mrpt::math::CVectorFixed<double, 6>(delta));
352 std::cout <<
"[P2P GN] iter:" << iter <<
" err:" << errNorm
353 <<
" delta:" << delta.transpose() <<
"\n";
357 if (delta.norm() < gnParams.
minDelta)
break;