36 #include <Eigen/SparseCholesky> 
   41 using namespace Eigen;
 
   65         double maxDist = std::pow(
options.closeLoopDistance, 2);
 
   67         for (
size_t other = 0; other < scan - 
options.loopSize; other++)
 
   69             if ((scans[other]->getPosition() - pos).squaredNorm() < maxDist)
 
   71                 output.push_back(other);
 
   78         auto tree = KDTree::create(cur, 
options.maxLeafSize);
 
   81         for (
size_t other = 0; other < scan - 
options.loopSize; other++)
 
   83             maxLen = max(maxLen, scans[other]->numPoints());
 
   87         for (
size_t other = 0; other < scan - 
options.loopSize; other++)
 
   89             size_t count = KDTree::nearestNeighbors(tree, scans[other], neighbors, 
options.slamMaxDistance);
 
   90             if (count >= 
options.closeLoopPairs)
 
   92                 output.push_back(other);
 
   99     return !output.empty();
 
  128     graph.reserve(n * n / 2);
 
  134     for (
size_t iteration = 0;
 
  147         X = SimplicialCholesky<GraphMatrix>().compute(A).solve(B);
 
  149         double sum_position_diff = 0.0;
 
  152         #pragma omp parallel for reduction(+:sum_position_diff) schedule(static) 
  153         for (
size_t i = 1; i <= last; i++)
 
  155             if (new_scans.empty() || new_scans.at(i))
 
  162                 Matrix4d initialPose = scan->pose();
 
  167                     cout << 
"Start of " << i << 
": " << pos.transpose() << 
", " << theta.transpose() << endl;
 
  170                 double ctx, stx, cty, sty;
 
  173                 sincos(theta.x(), &stx, &ctx);
 
  174                 sincos(theta.y(), &sty, &cty);
 
  176                 __sincos(theta.x(), &stx, &ctx);
 
  177                 __sincos(theta.y(), &sty, &cty);
 
  181                 Ha(0, 4) = -pos.z() * ctx + pos.y() * stx;
 
  182                 Ha(0, 5) = pos.y() * cty * ctx + pos.z() * stx * cty;
 
  185                 Ha(1, 4) = -pos.x() * stx;
 
  186                 Ha(1, 5) = -pos.x() * ctx * cty + pos.z() * sty;
 
  190                 Ha(2, 4) = pos.x() * ctx;
 
  191                 Ha(2, 5) = -pos.x() * cty * stx - pos.y() * sty;
 
  196                 Ha(4, 5) = ctx * cty;
 
  199                 Ha(5, 5) = -stx * cty;
 
  202                 Vector6d result = Ha.inverse() * X.block<6, 1>((i - 1) * 6, 0);
 
  205                 pos -= result.block<3, 1>(0, 0);
 
  206                 theta -= result.block<3, 1>(3, 0);
 
  212                     cout << 
"End: pos: " << pos.transpose() << 
"," << endl << 
"theta: " << theta.transpose() << endl;
 
  219                 sum_position_diff += result.block<3, 1>(0, 0).
norm();
 
  227             for (
size_t i = last + 1; i < scans.size(); i++)
 
  233         cout << 
"Sum of Position differences = " << sum_position_diff << endl;
 
  235         double avg = sum_position_diff / n;
 
  236         if (avg < m_options->slamEpsilon)
 
  247     for (
size_t i = 1; i <= last; i++)
 
  249         graph.push_back(make_pair(i - 1, i));
 
  252     vector<size_t> others;
 
  257         for (
size_t other : others)
 
  259             graph.push_back(make_pair(other, i));
 
  269     map<size_t, KDTreePtr> trees;
 
  270     for (
size_t i = 0; i < graph.size(); i++)
 
  272         size_t a = graph[i].first;
 
  273         if (trees.find(a) == trees.end())
 
  276             trees.insert(make_pair(a, tree));
 
  280     vector<pair<Matrix6d, Vector6d>> coeff(graph.size());
 
  282     #pragma omp parallel for schedule(dynamic) 
  283     for (
size_t i = 0; i < graph.size(); i++)
 
  286         std::tie(a, b) = graph[i];
 
  295         coeff[i] = make_pair(coeffMat, coeffVec);
 
  300     map<pair<int, int>, 
Matrix6d> result;
 
  305     for (
size_t i = 0; i < graph.size(); i++)
 
  308         std::tie(a, b) = graph[i];
 
  312         std::tie(coeffMat, coeffVec) = coeff[i];
 
  316         int offsetA = (a - 1) * 6;
 
  317         int offsetB = (b - 1) * 6;
 
  321             vec.block<6, 1>(offsetA, 0) += coeffVec;
 
  322             auto key = make_pair(offsetA, offsetA);
 
  323             auto found = result.find(key);
 
  324             if (found == result.end())
 
  326                 result.insert(make_pair(key, coeffMat));
 
  330                 found->second += coeffMat;
 
  335             vec.block<6, 1>(offsetB, 0) -= coeffVec;
 
  336             auto key = make_pair(offsetB, offsetB);
 
  337             auto found = result.find(key);
 
  338             if (found == result.end())
 
  340                 result.insert(make_pair(key, coeffMat));
 
  344                 found->second += coeffMat;
 
  347         if (offsetA >= 0 && offsetB >= 0)
 
  349             auto key = make_pair(offsetA, offsetB);
 
  350             auto found = result.find(key);
 
  351             if (found == result.end())
 
  353                 result.insert(make_pair(key, -coeffMat));
 
  357                 found->second -= coeffMat;
 
  360             key = make_pair(offsetB, offsetA);
 
  361             found = result.find(key);
 
  362             if (found == result.end())
 
  364                 result.insert(make_pair(key, -coeffMat));
 
  368                 found->second -= coeffMat;
 
  373     vector<Triplet<double>> triplets;
 
  374     triplets.reserve(result.size() * 6 * 6);
 
  377     for (
auto& e : result)
 
  381         for (
int dx = 0; dx < 6; dx++)
 
  383             for (
int dy = 0; dy < 6; dy++)
 
  385                 triplets.push_back(Triplet<double>(x + dx, y + dy, m(dx, dy)));
 
  389     mat.setFromTriplets(triplets.begin(), triplets.end());
 
  394     size_t n = scan->numPoints();
 
  402     double xy, yz, xz, ypz, xpz, xpy;
 
  403     xy = yz = xz = ypz = xpz = xpy = 0.0;
 
  405     for (
size_t i = 0; i < n; i++)
 
  407         if (results[i] == 
nullptr)
 
  412         Vector3d p = scan->point(i).cast<
double>();
 
  413         Vector3d r = results[i]->cast<
double>();
 
  418         double x = mid.x(), y = mid.y(), z = mid.z();
 
  422         xpy += x * x + y * y;
 
  423         xpz += x * x + z * z;
 
  424         ypz += y * y + z * z;
 
  430         mz.block<3, 1>(0, 0) += d;
 
  432         mz(3) += -z * d.y() + y * d.z();
 
  433         mz(4) += -y * d.x() + x * d.y();
 
  434         mz(5) += z * d.x() - x * d.z();
 
  438     mm(0, 0) = mm(1, 1) = mm(2, 2) = pairs;
 
  443     mm(0, 4) = mm(4, 0) = -sum.y();
 
  444     mm(0, 5) = mm(5, 0) = sum.z();
 
  445     mm(1, 3) = mm(3, 1) = -sum.z();
 
  446     mm(1, 4) = mm(4, 1) = sum.x();
 
  447     mm(2, 3) = mm(3, 2) = sum.y();
 
  448     mm(2, 5) = mm(5, 2) = -sum.x();
 
  450     mm(3, 4) = mm(4, 3) = -xz;
 
  451     mm(3, 5) = mm(5, 3) = -xy;
 
  452     mm(4, 5) = mm(5, 4) = -yz;
 
  458     for (
size_t i = 0; i < n; i++)
 
  460         if (results[i] == 
nullptr)
 
  465         Vector3d p = scan->point(i).cast<
double>();
 
  466         Vector3d r = results[i]->cast<
double>();
 
  471         ss += pow(delta.x() + (d(0) - mid.y() * d(4) + mid.z() * d(5)), 2.0)
 
  472               + pow(delta.y() + (d(1) - mid.z() * d(3) + mid.x() * d(4)), 2.0)
 
  473               + pow(delta.z() + (d(2) + mid.y() * d(3) - mid.x() * d(5)), 2.0);
 
  478     ss = ss / (2.0 * pairs - 3.0);
 
  490     double sx = sin(theta[0]);
 
  491     double cx = cos(theta[0]);
 
  492     double sy = sin(theta[1]);
 
  493     double cy = cos(theta[1]);
 
  494     double sz = sin(theta[2]);
 
  495     double cz = cos(theta[2]);
 
  499         -cx* sy* cz + sx* sz,
 
  502         -sx* sy* sz + cx* cz,
 
  516     mat.transposeInPlace();
 
  523     Matrix4d mat = inputMat.transpose();
 
  528     rPosTheta[1] = asin(max(-1.0, min(1.0, mat(2, 0)))); 
 
  529     if (mat(0, 0) <= 0.0)
 
  531         rPosTheta[1] = 
M_PI - rPosTheta[1];
 
  534     double C = cos(rPosTheta[1]);
 
  535     if (fabs( C ) > 0.005)                    
 
  537         _trX      =  mat(2, 2) / C;             
 
  538         _trY      =  -mat(2, 1) / C;
 
  539         rPosTheta[0]  = atan2( _trY, _trX );
 
  540         _trX      =  mat(0, 0) / C;              
 
  541         _trY      = -mat(1, 0) / C;
 
  542         rPosTheta[2]  = atan2( _trY, _trX );
 
  549         rPosTheta[2]  = atan2( _trY, _trX );
 
  552     rPos = inputMat.block<3, 1>(0, 3);