14 #include <mrpt/core/exceptions.h> 
   15 #include <mrpt/core/round.h> 
   16 #include <mrpt/version.h> 
   18 #if defined(MP2P_HAS_TBB) 
   19 #include <tbb/blocked_range.h> 
   20 #include <tbb/parallel_reduce.h> 
   29     mrpt::system::COutputLogger::setLoggerName(
"Matcher_Points_DistanceThreshold");
 
   42     const mrpt::maps::CMetricMap& pcGlobalMap, 
const mrpt::maps::CPointsMap& pcLocal,
 
   54     const mrpt::maps::NearestNeighborsCapable& nnGlobal =
 
   60     if (pcGlobalMap.isEmpty() || pcLocal.empty()) 
return;
 
   66     if (!pcGlobalMap.boundingBox().intersection(
 
   71     out.paired_pt2pt.reserve(
out.paired_pt2pt.size() + pcLocal.size());
 
   75     const float maxDistForCorrespondenceSquared = mrpt::square(
threshold);
 
   76     const float angularThresholdFactorSquared   = mrpt::square(mrpt::DEG2RAD(
thresholdAngularDeg));
 
   78     const auto&  lxs       = pcLocal.getPointsBufferRef_x();
 
   79     const auto&  lys       = pcLocal.getPointsBufferRef_y();
 
   80     const auto&  lzs       = pcLocal.getPointsBufferRef_z();
 
   81     const size_t nLocalPts = lxs.size();
 
   85     nnGlobal.nn_prepare_for_3d_queries();
 
   87     const auto lambdaAddPair = [
this, &ms, &globalName, &localName, &lxs, &lys, &lzs](
 
   88                                    mrpt::tfest::TMatchingPairList& outPairs, 
const size_t localIdx,
 
   89                                    const mrpt::math::TPoint3Df& globalPt,
 
   90                                    const uint64_t globalIdxOrID, 
const float errSqr)
 
   99         auto& p = outPairs.emplace_back();
 
  101         p.globalIdx = globalIdxOrID;
 
  102         p.localIdx  = localIdx;
 
  104         p.local     = {lxs[localIdx], lys[localIdx], lzs[localIdx]};
 
  106         p.errorSquareAfterTransformation = errSqr;
 
  116 #if defined(MP2P_HAS_TBB) 
  119     using Result = mrpt::tfest::TMatchingPairList;
 
  121     auto newPairs = tbb::parallel_reduce(
 
  123         tbb::blocked_range<size_t>{0, nLocalPts},
 
  127         [&](
const tbb::blocked_range<size_t>& r, Result 
res) -> Result
 
  129             res.reserve(r.size());
 
  130             std::vector<uint64_t>              neighborIndices;
 
  131             std::vector<float>                 neighborSqrDists;
 
  132             std::vector<mrpt::math::TPoint3Df> neighborPts;
 
  133             for (
size_t i = r.begin(); i < r.end(); i++)
 
  135                 const size_t localIdx = tl.
idxs.has_value() ? (*tl.
idxs)[i] : i;
 
  144                 const float localNormSqr = mrpt::square(lx) + mrpt::square(ly) + mrpt::square(lz);
 
  150                     neighborIndices.resize(1);
 
  151                     neighborSqrDists.resize(1);
 
  152                     neighborPts.resize(1);
 
  154                     if (!nnGlobal.nn_single_search(
 
  156                             neighborPts[0], neighborSqrDists[0], neighborIndices[0]))
 
  158                         neighborIndices.clear();
 
  159                         neighborSqrDists.clear();
 
  167                     nnGlobal.nn_radius_search(
 
  169                         maxDistForCorrespondenceSquared, neighborPts, neighborSqrDists,
 
  174                 for (
size_t k = 0; k < neighborIndices.size(); k++)
 
  176                     const auto tentativeErrSqr = neighborSqrDists.at(k);
 
  178                     const float finalThresSqr = maxDistForCorrespondenceSquared +
 
  179                                                 angularThresholdFactorSquared * localNormSqr;
 
  181                     if (tentativeErrSqr >= finalThresSqr) 
break;  
 
  184                         res, localIdx, neighborPts.at(k), neighborIndices.at(k), tentativeErrSqr);
 
  190         [](Result a, 
const Result& b) -> Result
 
  192             a.insert(a.end(), std::make_move_iterator(b.begin()), std::make_move_iterator(b.end()));
 
  196     out.paired_pt2pt.insert(
 
  197         out.paired_pt2pt.end(), std::make_move_iterator(newPairs.begin()),
 
  198         std::make_move_iterator(newPairs.end()));
 
  201     out.paired_pt2pt.reserve(nLocalPts);
 
  203     std::vector<uint64_t>              neighborIndices;
 
  204     std::vector<float>                 neighborSqrDists;
 
  205     std::vector<mrpt::math::TPoint3Df> neighborPts;
 
  207     for (
size_t i = 0; i < nLocalPts; i++)
 
  209         const size_t localIdx = tl.
idxs.has_value() ? (*tl.
idxs)[i] : i;
 
  218         const float localNormSqr = mrpt::square(lx) + mrpt::square(ly) + mrpt::square(lz);
 
  224             neighborIndices.resize(1);
 
  225             neighborSqrDists.resize(1);
 
  226             neighborPts.resize(1);
 
  228             if (!nnGlobal.nn_single_search(
 
  230                     neighborPts[0], neighborSqrDists[0], neighborIndices[0]))
 
  232                 neighborIndices.clear();
 
  233                 neighborSqrDists.clear();
 
  239             nnGlobal.nn_multiple_search(
 
  245         for (
size_t k = 0; k < neighborIndices.size(); k++)
 
  247             const auto tentativeErrSqr = neighborSqrDists.at(k);
 
  249             const float finalThresSqr =
 
  250                 maxDistForCorrespondenceSquared + angularThresholdFactorSquared * localNormSqr;
 
  252             if (tentativeErrSqr >= finalThresSqr) 
break;  
 
  255                 out.paired_pt2pt, localIdx, neighborPts.at(k), neighborIndices.at(k),