MRPT  2.0.3
CPointsMap.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #include "maps-precomp.h" // Precomp header
11 
13 #include <mrpt/maps/CPointsMap.h>
15 #include <mrpt/math/TPose2D.h>
16 #include <mrpt/math/geometry.h>
25 #include <mrpt/system/CTicTac.h>
27 #include <mrpt/system/os.h>
28 #include <fstream>
29 #include <sstream>
30 
31 #include <mrpt/core/SSE_macros.h>
32 #include <mrpt/core/SSE_types.h>
33 
34 #if MRPT_HAS_MATLAB
35 #include <mexplus.h>
36 #endif
37 
38 using namespace mrpt::poses;
39 using namespace mrpt::maps;
40 using namespace mrpt::math;
41 using namespace mrpt::tfest;
42 using namespace mrpt::obs;
43 using namespace mrpt::img;
44 using namespace mrpt::system;
45 using namespace std;
46 
48 
49 /*---------------------------------------------------------------
50  Constructor
51  ---------------------------------------------------------------*/
53  : insertionOptions(), likelihoodOptions(), m_x(), m_y(), m_z()
54 
55 {
56  mark_as_modified();
57 }
58 
59 /*---------------------------------------------------------------
60  Destructor
61  ---------------------------------------------------------------*/
62 CPointsMap::~CPointsMap() = default;
63 
64 bool CPointsMap::save2D_to_text_file(const string& file) const
65 {
66  FILE* f = os::fopen(file.c_str(), "wt");
67  if (!f) return false;
68  for (size_t i = 0; i < m_x.size(); i++)
69  os::fprintf(f, "%f %f\n", m_x[i], m_y[i]);
70  os::fclose(f);
71  return true;
72 }
73 
74 bool CPointsMap::save3D_to_text_file(const string& file) const
75 {
76  FILE* f = os::fopen(file.c_str(), "wt");
77  if (!f) return false;
78 
79  for (size_t i = 0; i < m_x.size(); i++)
80  os::fprintf(f, "%f %f %f\n", m_x[i], m_y[i], m_z[i]);
81 
82  os::fclose(f);
83  return true;
84 }
85 
86 bool CPointsMap::save2D_to_text_stream(std::ostream& out) const
87 {
88  char lin[200];
89  for (size_t i = 0; i < m_x.size(); i++)
90  {
91  os::sprintf(lin, sizeof(lin), "%f %f\n", m_x[i], m_y[i]);
92  out << lin;
93  }
94  return true;
95 }
96 bool CPointsMap::save3D_to_text_stream(std::ostream& out) const
97 {
98  char lin[220];
99  for (size_t i = 0; i < m_x.size(); i++)
100  {
101  os::sprintf(lin, sizeof(lin), "%f %f %f\n", m_x[i], m_y[i], m_z[i]);
102  out << lin;
103  }
104  return true;
105 }
106 
107 bool CPointsMap::load2Dor3D_from_text_stream(
108  std::istream& in, mrpt::optional_ref<std::string> outErrorMsg,
109  const bool is_3D)
110 {
111  MRPT_START
112 
113  // Clear current map:
114  mark_as_modified();
115  this->clear();
116 
117  size_t linIdx = 1;
118  for (std::string line; std::getline(in, line); ++linIdx)
119  {
120  float coords[3];
121  std::stringstream ss(line);
122  for (int idxCoord = 0; idxCoord < (is_3D ? 3 : 2); idxCoord++)
123  {
124  if (!(ss >> coords[idxCoord]))
125  {
126  std::stringstream sErr;
127  sErr << "[CPointsMap::load2Dor3D_from_text_stream] Unexpected "
128  "format on line "
129  << linIdx << " for coordinate #" << (idxCoord + 1) << "\n";
130 
131  if (outErrorMsg)
132  outErrorMsg.value().get() = sErr.str();
133  else
134  std::cerr << sErr.str();
135 
136  return false;
137  }
138  }
139 
140  this->insertPoint(coords[0], coords[1], coords[2]);
141  }
142  return true;
143  MRPT_END
144 }
145 
146 bool CPointsMap::load2Dor3D_from_text_file(
147  const std::string& file, const bool is_3D)
148 {
149  MRPT_START
150 
151  // Clear current map:
152  mark_as_modified();
153  this->clear();
154 
155  std::ifstream fi(file);
156  if (!fi.is_open()) return false;
157 
158  return load2Dor3D_from_text_stream(fi, std::nullopt, is_3D);
159 
160  MRPT_END
161 }
162 
163 /*---------------------------------------------------------------
164  Implements the writing to a mxArray for Matlab
165  ---------------------------------------------------------------*/
166 #if MRPT_HAS_MATLAB
167 // Add to implement mexplus::from template specialization
169 #endif
170 
171 mxArray* CPointsMap::writeToMatlab() const
172 {
173 #if MRPT_HAS_MATLAB
174  MRPT_TODO("Create 3xN array xyz of points coordinates")
175  const char* fields[] = {"x", "y", "z"};
176  mexplus::MxArray map_struct(
177  mexplus::MxArray::Struct(sizeof(fields) / sizeof(fields[0]), fields));
178 
179  map_struct.set("x", m_x);
180  map_struct.set("y", m_y);
181  map_struct.set("z", m_z);
182  return map_struct.release();
183 #else
184  THROW_EXCEPTION("MRPT built without MATLAB/Mex support");
185 #endif
186 }
187 
188 /*---------------------------------------------------------------
189  getPoint
190  Access to stored points coordinates:
191  ---------------------------------------------------------------*/
192 void CPointsMap::getPoint(size_t index, float& x, float& y) const
193 {
194  ASSERT_BELOW_(index, m_x.size());
195  x = m_x[index];
196  y = m_y[index];
197 }
198 void CPointsMap::getPoint(size_t index, float& x, float& y, float& z) const
199 {
200  ASSERT_BELOW_(index, m_x.size());
201  x = m_x[index];
202  y = m_y[index];
203  z = m_z[index];
204 }
205 void CPointsMap::getPoint(size_t index, double& x, double& y) const
206 {
207  ASSERT_BELOW_(index, m_x.size());
208  x = m_x[index];
209  y = m_y[index];
210 }
211 void CPointsMap::getPoint(size_t index, double& x, double& y, double& z) const
212 {
213  ASSERT_BELOW_(index, m_x.size());
214  x = m_x[index];
215  y = m_y[index];
216  z = m_z[index];
217 }
218 
219 /*---------------------------------------------------------------
220  getPointsBuffer
221  ---------------------------------------------------------------*/
222 void CPointsMap::getPointsBuffer(
223  size_t& outPointsCount, const float*& xs, const float*& ys,
224  const float*& zs) const
225 {
226  outPointsCount = size();
227 
228  if (outPointsCount > 0)
229  {
230  xs = &m_x[0];
231  ys = &m_y[0];
232  zs = &m_z[0];
233  }
234  else
235  {
236  xs = ys = zs = nullptr;
237  }
238 }
239 
240 /*---------------------------------------------------------------
241  clipOutOfRangeInZ
242  ---------------------------------------------------------------*/
243 void CPointsMap::clipOutOfRangeInZ(float zMin, float zMax)
244 {
245  const size_t n = size();
246  vector<bool> deletionMask(n);
247 
248  // Compute it:
249  for (size_t i = 0; i < n; i++)
250  deletionMask[i] = (m_z[i] < zMin || m_z[i] > zMax);
251 
252  // Perform deletion:
253  applyDeletionMask(deletionMask);
254 
255  mark_as_modified();
256 }
257 
258 /*---------------------------------------------------------------
259  clipOutOfRange
260  ---------------------------------------------------------------*/
261 void CPointsMap::clipOutOfRange(const TPoint2D& p, float maxRange)
262 {
263  size_t i, n = size();
264  vector<bool> deletionMask;
265 
266  // The deletion mask:
267  deletionMask.resize(n);
268 
269  const auto max_sq = maxRange * maxRange;
270 
271  // Compute it:
272  for (i = 0; i < n; i++)
273  deletionMask[i] = square(p.x - m_x[i]) + square(p.y - m_y[i]) > max_sq;
274 
275  // Perform deletion:
276  applyDeletionMask(deletionMask);
277 
278  mark_as_modified();
279 }
280 
281 void CPointsMap::determineMatching2D(
282  const mrpt::maps::CMetricMap* otherMap2, const CPose2D& otherMapPose_,
283  TMatchingPairList& correspondences, const TMatchingParams& params,
284  TMatchingExtraResults& extraResults) const
285 {
286  MRPT_START
287 
288  extraResults = TMatchingExtraResults(); // Clear output
289 
290  ASSERT_ABOVE_(params.decimation_other_map_points, 0);
292  params.offset_other_map_points, params.decimation_other_map_points);
293  ASSERT_(IS_DERIVED(*otherMap2, CPointsMap));
294  const auto* otherMap = static_cast<const CPointsMap*>(otherMap2);
295 
296  const TPose2D otherMapPose(
297  otherMapPose_.x(), otherMapPose_.y(), otherMapPose_.phi());
298 
299  const size_t nLocalPoints = otherMap->size();
300  const size_t nGlobalPoints = this->size();
301  float _sumSqrDist = 0;
302  size_t _sumSqrCount = 0;
303  size_t nOtherMapPointsWithCorrespondence =
304  0; // Number of points with one corrs. at least
305 
306  float local_x_min = std::numeric_limits<float>::max(),
307  local_x_max = -std::numeric_limits<float>::max();
308  float global_x_min = std::numeric_limits<float>::max(),
309  global_x_max = -std::numeric_limits<float>::max();
310  float local_y_min = std::numeric_limits<float>::max(),
311  local_y_max = -std::numeric_limits<float>::max();
312  float global_y_min = std::numeric_limits<float>::max(),
313  global_y_max = -std::numeric_limits<float>::max();
314 
315  double maxDistForCorrespondenceSquared;
316  float x_local, y_local;
317  unsigned int localIdx;
318 
319  const float *x_other_it, *y_other_it, *z_other_it;
320 
321  // Prepare output: no correspondences initially:
322  correspondences.clear();
323  correspondences.reserve(nLocalPoints);
324  extraResults.correspondencesRatio = 0;
325 
326  TMatchingPairList _correspondences;
327  _correspondences.reserve(nLocalPoints);
328 
329  // Nothing to do if we have an empty map!
330  if (!nGlobalPoints || !nLocalPoints) return;
331 
332  const double sin_phi = sin(otherMapPose.phi);
333  const double cos_phi = cos(otherMapPose.phi);
334 
335 // Do matching only there is any chance of the two maps to overlap:
336 // -----------------------------------------------------------
337 // Translate and rotate all local points, while simultaneously
338 // estimating the bounding box:
339 #if MRPT_HAS_SSE2
340  // Number of 4-floats:
341  size_t nPackets = nLocalPoints / 4;
342 
343  Eigen::ArrayXf x_locals(nLocalPoints), y_locals(nLocalPoints);
344 
345  // load 4 copies of the same value
346  const __m128 cos_4val = _mm_set1_ps(cos_phi);
347  const __m128 sin_4val = _mm_set1_ps(sin_phi);
348  const __m128 x0_4val = _mm_set1_ps(otherMapPose.x);
349  const __m128 y0_4val = _mm_set1_ps(otherMapPose.y);
350 
351  // For the bounding box:
352  __m128 x_mins = _mm_set1_ps(std::numeric_limits<float>::max());
353  __m128 x_maxs = _mm_set1_ps(std::numeric_limits<float>::min());
354  __m128 y_mins = x_mins;
355  __m128 y_maxs = x_maxs;
356 
357  const float* ptr_in_x = &otherMap->m_x[0];
358  const float* ptr_in_y = &otherMap->m_y[0];
359  float* ptr_out_x = &x_locals[0];
360  float* ptr_out_y = &y_locals[0];
361 
362  for (; nPackets; nPackets--, ptr_in_x += 4, ptr_in_y += 4, ptr_out_x += 4,
363  ptr_out_y += 4)
364  {
365  const __m128 xs = _mm_loadu_ps(ptr_in_x); // *Unaligned* load
366  const __m128 ys = _mm_loadu_ps(ptr_in_y);
367 
368  const __m128 lxs = _mm_add_ps(
369  x0_4val,
370  _mm_sub_ps(_mm_mul_ps(xs, cos_4val), _mm_mul_ps(ys, sin_4val)));
371  const __m128 lys = _mm_add_ps(
372  y0_4val,
373  _mm_add_ps(_mm_mul_ps(xs, sin_4val), _mm_mul_ps(ys, cos_4val)));
374  _mm_store_ps(ptr_out_x, lxs);
375  _mm_store_ps(ptr_out_y, lys);
376 
377  x_mins = _mm_min_ps(x_mins, lxs);
378  x_maxs = _mm_max_ps(x_maxs, lxs);
379  y_mins = _mm_min_ps(y_mins, lys);
380  y_maxs = _mm_max_ps(y_maxs, lys);
381  }
382 
383  // Recover the min/max:
384  alignas(MRPT_MAX_STATIC_ALIGN_BYTES) float temp_nums[4];
385 
386  _mm_store_ps(temp_nums, x_mins);
387  local_x_min =
388  min(min(temp_nums[0], temp_nums[1]), min(temp_nums[2], temp_nums[3]));
389  _mm_store_ps(temp_nums, y_mins);
390  local_y_min =
391  min(min(temp_nums[0], temp_nums[1]), min(temp_nums[2], temp_nums[3]));
392  _mm_store_ps(temp_nums, x_maxs);
393  local_x_max =
394  max(max(temp_nums[0], temp_nums[1]), max(temp_nums[2], temp_nums[3]));
395  _mm_store_ps(temp_nums, y_maxs);
396  local_y_max =
397  max(max(temp_nums[0], temp_nums[1]), max(temp_nums[2], temp_nums[3]));
398 
399  // transform extra pts & update BBox
400  for (size_t k = 0; k < nLocalPoints % 4; k++)
401  {
402  float x = ptr_in_x[k];
403  float y = ptr_in_y[k];
404  float out_x = otherMapPose.x + cos_phi * x - sin_phi * y;
405  float out_y = otherMapPose.y + sin_phi * x + cos_phi * y;
406 
407  local_x_min = std::min(local_x_min, out_x);
408  local_x_max = std::max(local_x_max, out_x);
409 
410  local_y_min = std::min(local_y_min, out_y);
411  local_y_max = std::max(local_y_max, out_y);
412 
413  ptr_out_x[k] = out_x;
414  ptr_out_y[k] = out_y;
415  }
416 
417 #else
418  // Non SSE2 version:
420  const_cast<float*>(&otherMap->m_x[0]), otherMap->m_x.size(), 1);
422  const_cast<float*>(&otherMap->m_y[0]), otherMap->m_y.size(), 1);
423 
424  Eigen::Array<float, Eigen::Dynamic, 1> x_locals =
425  otherMapPose.x + cos_phi * x_org.array() - sin_phi * y_org.array();
426  Eigen::Array<float, Eigen::Dynamic, 1> y_locals =
427  otherMapPose.y + sin_phi * x_org.array() + cos_phi * y_org.array();
428 
429  local_x_min = x_locals.minCoeff();
430  local_y_min = y_locals.minCoeff();
431  local_x_max = x_locals.maxCoeff();
432  local_y_max = y_locals.maxCoeff();
433 #endif
434 
435  // Find the bounding box:
436  float global_z_min, global_z_max;
437  this->boundingBox(
438  global_x_min, global_x_max, global_y_min, global_y_max, global_z_min,
439  global_z_max);
440 
441  // Only try doing a matching if there exist any chance of both maps
442  // touching/overlaping:
443  if (local_x_min > global_x_max || local_x_max < global_x_min ||
444  local_y_min > global_y_max || local_y_max < global_y_min)
445  return; // We know for sure there is no matching at all
446 
447  // Loop for each point in local map:
448  // --------------------------------------------------
449  for (localIdx = params.offset_other_map_points,
450  x_other_it = &otherMap->m_x[params.offset_other_map_points],
451  y_other_it = &otherMap->m_y[params.offset_other_map_points],
452  z_other_it = &otherMap->m_z[params.offset_other_map_points];
453  localIdx < nLocalPoints;
454  x_other_it += params.decimation_other_map_points,
455  y_other_it += params.decimation_other_map_points,
456  z_other_it += params.decimation_other_map_points,
457  localIdx += params.decimation_other_map_points)
458  {
459  // For speed-up:
460  x_local = x_locals[localIdx]; // *x_locals_it;
461  y_local = y_locals[localIdx]; // *y_locals_it;
462 
463  // Find all the matchings in the requested distance:
464 
465  // KD-TREE implementation =================================
466  // Use a KD-tree to look for the nearnest neighbor of:
467  // (x_local, y_local, z_local)
468  // In "this" (global/reference) points map.
469 
470  float tentativ_err_sq;
471  unsigned int tentativ_this_idx = kdTreeClosestPoint2D(
472  x_local, y_local, // Look closest to this guy
473  tentativ_err_sq // save here the min. distance squared
474  );
475 
476  // Compute max. allowed distance:
477  maxDistForCorrespondenceSquared = square(
478  params.maxAngularDistForCorrespondence *
479  std::sqrt(
480  square(params.angularDistPivotPoint.x - x_local) +
481  square(params.angularDistPivotPoint.y - y_local)) +
482  params.maxDistForCorrespondence);
483 
484  // Distance below the threshold??
485  if (tentativ_err_sq < maxDistForCorrespondenceSquared)
486  {
487  // Save all the correspondences:
488  _correspondences.resize(_correspondences.size() + 1);
489 
490  TMatchingPair& p = _correspondences.back();
491 
492  p.this_idx = tentativ_this_idx;
493  p.this_x = m_x[tentativ_this_idx];
494  p.this_y = m_y[tentativ_this_idx];
495  p.this_z = m_z[tentativ_this_idx];
496 
497  p.other_idx = localIdx;
498  p.other_x = *x_other_it;
499  p.other_y = *y_other_it;
500  p.other_z = *z_other_it;
501 
502  p.errorSquareAfterTransformation = tentativ_err_sq;
503 
504  // At least one:
505  nOtherMapPointsWithCorrespondence++;
506 
507  // Accumulate the MSE:
508  _sumSqrDist += p.errorSquareAfterTransformation;
509  _sumSqrCount++;
510  }
511 
512  } // For each local point
513 
514  // Additional consistency filter: "onlyKeepTheClosest" up to now
515  // led to just one correspondence for each "local map" point, but
516  // many of them may have as corresponding pair the same "global point"!!
517  // -------------------------------------------------------------------------
518  if (params.onlyUniqueRobust)
519  {
520  ASSERTMSG_(
521  params.onlyKeepTheClosest,
522  "ERROR: onlyKeepTheClosest must be also set to true when "
523  "onlyUniqueRobust=true.");
524  _correspondences.filterUniqueRobustPairs(
525  nGlobalPoints, correspondences);
526  }
527  else
528  {
529  correspondences.swap(_correspondences);
530  }
531 
532  // If requested, copy sum of squared distances to output pointer:
533  // -------------------------------------------------------------------
534  if (_sumSqrCount)
535  extraResults.sumSqrDist =
536  _sumSqrDist / static_cast<double>(_sumSqrCount);
537  else
538  extraResults.sumSqrDist = 0;
539 
540  // The ratio of points in the other map with corrs:
541  extraResults.correspondencesRatio = params.decimation_other_map_points *
542  nOtherMapPointsWithCorrespondence /
543  d2f(nLocalPoints);
544 
545  MRPT_END
546 }
547 
548 /*---------------------------------------------------------------
549  changeCoordinatesReference
550  ---------------------------------------------------------------*/
551 void CPointsMap::changeCoordinatesReference(const CPose2D& newBase)
552 {
553  const size_t N = m_x.size();
554 
555  const CPose3D newBase3D(newBase);
556 
557  for (size_t i = 0; i < N; i++)
558  newBase3D.composePoint(
559  m_x[i], m_y[i], m_z[i], // In
560  m_x[i], m_y[i], m_z[i] // Out
561  );
562 
563  mark_as_modified();
564 }
565 
566 /*---------------------------------------------------------------
567  changeCoordinatesReference
568  ---------------------------------------------------------------*/
569 void CPointsMap::changeCoordinatesReference(const CPose3D& newBase)
570 {
571  const size_t N = m_x.size();
572 
573  for (size_t i = 0; i < N; i++)
574  newBase.composePoint(
575  m_x[i], m_y[i], m_z[i], // In
576  m_x[i], m_y[i], m_z[i] // Out
577  );
578 
579  mark_as_modified();
580 }
581 
582 /*---------------------------------------------------------------
583  changeCoordinatesReference
584  ---------------------------------------------------------------*/
585 void CPointsMap::changeCoordinatesReference(
586  const CPointsMap& other, const CPose3D& newBase)
587 {
588  *this = other;
589  changeCoordinatesReference(newBase);
590 }
591 
592 /*---------------------------------------------------------------
593  isEmpty
594  ---------------------------------------------------------------*/
595 bool CPointsMap::isEmpty() const { return m_x.empty(); }
596 /*---------------------------------------------------------------
597  TInsertionOptions
598  ---------------------------------------------------------------*/
599 CPointsMap::TInsertionOptions::TInsertionOptions()
600  : horizontalTolerance(0.05_deg)
601 
602 {
603 }
604 
605 // Binary dump to/read from stream - for usage in derived classes' serialization
608 {
609  const int8_t version = 0;
610  out << version;
611 
612  out << minDistBetweenLaserPoints << addToExistingPointsMap
613  << also_interpolate << disableDeletion << fuseWithExisting
614  << isPlanarMap << horizontalTolerance << maxDistForInterpolatePoints
615  << insertInvalidPoints; // v0
616 }
617 
620 {
621  int8_t version;
622  in >> version;
623  switch (version)
624  {
625  case 0:
626  {
627  in >> minDistBetweenLaserPoints >> addToExistingPointsMap >>
628  also_interpolate >> disableDeletion >> fuseWithExisting >>
629  isPlanarMap >> horizontalTolerance >>
630  maxDistForInterpolatePoints >> insertInvalidPoints; // v0
631  }
632  break;
633  default:
635  }
636 }
637 
639 
640  = default;
641 
644 {
645  const int8_t version = 0;
646  out << version;
647  out << sigma_dist << max_corr_distance << decimation;
648 }
649 
652 {
653  int8_t version;
654  in >> version;
655  switch (version)
656  {
657  case 0:
658  {
659  in >> sigma_dist >> max_corr_distance >> decimation;
660  }
661  break;
662  default:
664  }
665 }
666 
669 {
670  const int8_t version = 0;
671  out << version;
672  out << point_size << color << int8_t(colormap);
673 }
674 
677 {
678  int8_t version;
679  in >> version;
680  switch (version)
681  {
682  case 0:
683  {
684  in >> point_size >> this->color;
685  in.ReadAsAndCastTo<int8_t>(this->colormap);
686  }
687  break;
688  default:
690  }
691 }
692 
694 {
695  out << "\n----------- [CPointsMap::TInsertionOptions] ------------ \n\n";
696 
697  LOADABLEOPTS_DUMP_VAR(minDistBetweenLaserPoints, double);
698  LOADABLEOPTS_DUMP_VAR(maxDistForInterpolatePoints, double);
699  LOADABLEOPTS_DUMP_VAR_DEG(horizontalTolerance);
700 
701  LOADABLEOPTS_DUMP_VAR(addToExistingPointsMap, bool);
702  LOADABLEOPTS_DUMP_VAR(also_interpolate, bool);
703  LOADABLEOPTS_DUMP_VAR(disableDeletion, bool);
704  LOADABLEOPTS_DUMP_VAR(fuseWithExisting, bool);
705  LOADABLEOPTS_DUMP_VAR(isPlanarMap, bool);
706 
707  LOADABLEOPTS_DUMP_VAR(insertInvalidPoints, bool);
708 
709  out << endl;
710 }
711 
713 {
714  out << "\n----------- [CPointsMap::TLikelihoodOptions] ------------ \n\n";
715 
716  LOADABLEOPTS_DUMP_VAR(sigma_dist, double);
717  LOADABLEOPTS_DUMP_VAR(max_corr_distance, double);
718  LOADABLEOPTS_DUMP_VAR(decimation, int);
719 }
720 
722 {
723  out << "\n----------- [CPointsMap::TRenderOptions] ------------ \n\n";
724 
725  LOADABLEOPTS_DUMP_VAR(point_size, float);
726  LOADABLEOPTS_DUMP_VAR(color.R, float);
727  LOADABLEOPTS_DUMP_VAR(color.G, float);
728  LOADABLEOPTS_DUMP_VAR(color.B, float);
729  // LOADABLEOPTS_DUMP_VAR(colormap, int);
730 }
731 /*---------------------------------------------------------------
732  loadFromConfigFile
733  ---------------------------------------------------------------*/
735  const mrpt::config::CConfigFileBase& iniFile, const string& section)
736 {
737  MRPT_LOAD_CONFIG_VAR(minDistBetweenLaserPoints, float, iniFile, section);
738  MRPT_LOAD_CONFIG_VAR_DEGREES(horizontalTolerance, iniFile, section);
739 
740  MRPT_LOAD_CONFIG_VAR(addToExistingPointsMap, bool, iniFile, section);
741  MRPT_LOAD_CONFIG_VAR(also_interpolate, bool, iniFile, section);
742  MRPT_LOAD_CONFIG_VAR(disableDeletion, bool, iniFile, section);
743  MRPT_LOAD_CONFIG_VAR(fuseWithExisting, bool, iniFile, section);
744  MRPT_LOAD_CONFIG_VAR(isPlanarMap, bool, iniFile, section);
745 
746  MRPT_LOAD_CONFIG_VAR(maxDistForInterpolatePoints, float, iniFile, section);
747 
748  MRPT_LOAD_CONFIG_VAR(insertInvalidPoints, bool, iniFile, section);
749 }
750 
752  const mrpt::config::CConfigFileBase& iniFile, const string& section)
753 {
754  MRPT_LOAD_CONFIG_VAR(sigma_dist, double, iniFile, section);
755  MRPT_LOAD_CONFIG_VAR(max_corr_distance, double, iniFile, section);
756  MRPT_LOAD_CONFIG_VAR(decimation, int, iniFile, section);
757 }
758 
760  const mrpt::config::CConfigFileBase& iniFile, const string& section)
761 {
762  MRPT_LOAD_CONFIG_VAR(point_size, float, iniFile, section);
763  MRPT_LOAD_CONFIG_VAR(color.R, float, iniFile, section);
764  MRPT_LOAD_CONFIG_VAR(color.G, float, iniFile, section);
765  MRPT_LOAD_CONFIG_VAR(color.B, float, iniFile, section);
766  colormap = iniFile.read_enum(section, "colormap", this->colormap);
767 }
768 
769 /*---------------------------------------------------------------
770  getAs3DObject
771 ---------------------------------------------------------------*/
773 {
774  MRPT_START
776 
778  {
779  // Single color:
780  auto obj = opengl::CPointCloud::Create();
781  obj->loadFromPointsMap(this);
782  obj->setColor(renderOptions.color);
783  obj->setPointSize(renderOptions.point_size);
784  obj->enableColorFromZ(false);
785  outObj->insert(obj);
786  }
787  else
788  {
790  obj->loadFromPointsMap(this);
791  obj->setPointSize(renderOptions.point_size);
792  mrpt::math::TPoint3D pMin, pMax;
793  this->boundingBox(pMin, pMax);
794  obj->recolorizeByCoordinate(
795  pMin.z, pMax.z, 2 /*z*/, renderOptions.colormap);
796  outObj->insert(obj);
797  }
798  MRPT_END
799 }
800 
802  const mrpt::maps::CMetricMap* otherMap2,
803  const mrpt::poses::CPose3D& otherMapPose,
804  const TMatchingRatioParams& mrp) const
805 {
806  TMatchingPairList correspondences;
808  TMatchingExtraResults extraResults;
809 
810  params.maxDistForCorrespondence = mrp.maxDistForCorr;
811 
812  this->determineMatching3D(
813  otherMap2->getAsSimplePointsMap(), otherMapPose, correspondences,
814  params, extraResults);
815 
816  return extraResults.correspondencesRatio;
817 }
818 
819 /*---------------------------------------------------------------
820  getLargestDistanceFromOrigin
821 ---------------------------------------------------------------*/
823 {
824  // Updated?
826  {
827  // NO: Update it:
828  float maxDistSq = 0, d;
829  for (auto X = m_x.begin(), Y = m_y.begin(), Z = m_z.begin();
830  X != m_x.end(); ++X, ++Y, ++Z)
831  {
832  d = square(*X) + square(*Y) + square(*Z);
833  maxDistSq = max(d, maxDistSq);
834  }
835 
836  m_largestDistanceFromOrigin = sqrt(maxDistSq);
838  }
840 }
841 
842 /*---------------------------------------------------------------
843  getAllPoints
844 ---------------------------------------------------------------*/
846  vector<float>& xs, vector<float>& ys, size_t decimation) const
847 {
848  MRPT_START
849  ASSERT_(decimation > 0);
850  if (decimation == 1)
851  {
852  xs = vector<float>(m_x.begin(), m_x.end());
853  ys = vector<float>(m_y.begin(), m_y.end());
854  }
855  else
856  {
857  size_t N = m_x.size() / decimation;
858 
859  xs.resize(N);
860  ys.resize(N);
861 
862  auto X = m_x.begin();
863  auto Y = m_y.begin();
864  for (auto oX = xs.begin(), oY = ys.begin(); oX != xs.end();
865  X += decimation, Y += decimation, ++oX, ++oY)
866  {
867  *oX = *X;
868  *oY = *Y;
869  }
870  }
871  MRPT_END
872 }
873 
874 /*---------------------------------------------------------------
875  squareDistanceToClosestCorrespondence
876 ---------------------------------------------------------------*/
878  float x0, float y0) const
879 {
880  // Just the closest point:
881 
882 #if 1
883  return kdTreeClosestPoint2DsqrError(x0, y0);
884 #else
885  // The distance to the line that interpolates the TWO closest points:
886  float x1, y1, x2, y2, d1, d2;
888  x0, y0, // The query
889  x1, y1, // Closest point #1
890  x2, y2, // Closest point #2
891  d1, d2);
892 
893  ASSERT_(d2 >= d1);
894 
895  // If the two points are too far, do not interpolate:
896  float d12 = square(x1 - x2) + square(y1 - y2);
897  if (d12 > 0.20f * 0.20f || d12 < 0.03f * 0.03f)
898  {
899  return square(x1 - x0) + square(y1 - y0);
900  }
901  else
902  { // Interpolate
903  double interp_x, interp_y;
904 
905  // math::closestFromPointToSegment(
907  x0, y0, // the point
908  x1, y1, x2, y2, // The segment
909  interp_x, interp_y // out
910  );
911 
912  return square(interp_x - x0) + square(interp_y - y0);
913  }
914 #endif
915 }
916 
917 /*---------------------------------------------------------------
918  boundingBox
919 ---------------------------------------------------------------*/
921  float& min_x, float& max_x, float& min_y, float& max_y, float& min_z,
922  float& max_z) const
923 {
924  MRPT_START
925 
926  const size_t nPoints = m_x.size();
927 
929  {
930  if (!nPoints)
931  {
933  m_bb_max_z = 0;
934  }
935  else
936  {
937 #if MRPT_HAS_SSE2
938  // Vectorized version: ~ 9x times faster
939 
940  // Number of 4-floats:
941  size_t nPackets = nPoints / 4;
942 
943  // For the bounding box:
944  __m128 x_mins = _mm_set1_ps(std::numeric_limits<float>::max());
945  __m128 x_maxs = _mm_set1_ps(std::numeric_limits<float>::min());
946  __m128 y_mins = x_mins, y_maxs = x_maxs;
947  __m128 z_mins = x_mins, z_maxs = x_maxs;
948 
949  const float* ptr_in_x = &m_x[0];
950  const float* ptr_in_y = &m_y[0];
951  const float* ptr_in_z = &m_z[0];
952 
953  for (; nPackets;
954  nPackets--, ptr_in_x += 4, ptr_in_y += 4, ptr_in_z += 4)
955  {
956  const __m128 xs = _mm_loadu_ps(ptr_in_x); // *Unaligned* load
957  x_mins = _mm_min_ps(x_mins, xs);
958  x_maxs = _mm_max_ps(x_maxs, xs);
959 
960  const __m128 ys = _mm_loadu_ps(ptr_in_y);
961  y_mins = _mm_min_ps(y_mins, ys);
962  y_maxs = _mm_max_ps(y_maxs, ys);
963 
964  const __m128 zs = _mm_loadu_ps(ptr_in_z);
965  z_mins = _mm_min_ps(z_mins, zs);
966  z_maxs = _mm_max_ps(z_maxs, zs);
967  }
968 
969  // Recover the min/max:
970  alignas(MRPT_MAX_STATIC_ALIGN_BYTES) float temp_nums[4];
971 
972  _mm_store_ps(temp_nums, x_mins);
973  m_bb_min_x =
974  min(min(temp_nums[0], temp_nums[1]),
975  min(temp_nums[2], temp_nums[3]));
976  _mm_store_ps(temp_nums, y_mins);
977  m_bb_min_y =
978  min(min(temp_nums[0], temp_nums[1]),
979  min(temp_nums[2], temp_nums[3]));
980  _mm_store_ps(temp_nums, z_mins);
981  m_bb_min_z =
982  min(min(temp_nums[0], temp_nums[1]),
983  min(temp_nums[2], temp_nums[3]));
984  _mm_store_ps(temp_nums, x_maxs);
985  m_bb_max_x =
986  max(max(temp_nums[0], temp_nums[1]),
987  max(temp_nums[2], temp_nums[3]));
988  _mm_store_ps(temp_nums, y_maxs);
989  m_bb_max_y =
990  max(max(temp_nums[0], temp_nums[1]),
991  max(temp_nums[2], temp_nums[3]));
992  _mm_store_ps(temp_nums, z_maxs);
993  m_bb_max_z =
994  max(max(temp_nums[0], temp_nums[1]),
995  max(temp_nums[2], temp_nums[3]));
996 
997  // extra
998  for (size_t k = 0; k < nPoints % 4; k++)
999  {
1000  m_bb_min_x = std::min(m_bb_min_x, ptr_in_x[k]);
1001  m_bb_max_x = std::max(m_bb_max_x, ptr_in_x[k]);
1002 
1003  m_bb_min_y = std::min(m_bb_min_y, ptr_in_y[k]);
1004  m_bb_max_y = std::max(m_bb_max_y, ptr_in_y[k]);
1005 
1006  m_bb_min_z = std::min(m_bb_min_z, ptr_in_z[k]);
1007  m_bb_max_z = std::max(m_bb_max_z, ptr_in_z[k]);
1008  }
1009 #else
1010  // Non vectorized version:
1012  (std::numeric_limits<float>::max)();
1013 
1015  -(std::numeric_limits<float>::max)();
1016 
1017  for (auto xi = m_x.begin(), yi = m_y.begin(), zi = m_z.begin();
1018  xi != m_x.end(); xi++, yi++, zi++)
1019  {
1020  m_bb_min_x = min(m_bb_min_x, *xi);
1021  m_bb_max_x = max(m_bb_max_x, *xi);
1022  m_bb_min_y = min(m_bb_min_y, *yi);
1023  m_bb_max_y = max(m_bb_max_y, *yi);
1024  m_bb_min_z = min(m_bb_min_z, *zi);
1025  m_bb_max_z = max(m_bb_max_z, *zi);
1026  }
1027 #endif
1028  }
1029  m_boundingBoxIsUpdated = true;
1030  }
1031 
1032  min_x = m_bb_min_x;
1033  max_x = m_bb_max_x;
1034  min_y = m_bb_min_y;
1035  max_y = m_bb_max_y;
1036  min_z = m_bb_min_z;
1037  max_z = m_bb_max_z;
1038  MRPT_END
1039 }
1040 
1041 /*---------------------------------------------------------------
1042  computeMatchingWith3D
1043 ---------------------------------------------------------------*/
1045  const mrpt::maps::CMetricMap* otherMap2, const CPose3D& otherMapPose,
1046  TMatchingPairList& correspondences, const TMatchingParams& params,
1047  TMatchingExtraResults& extraResults) const
1048 {
1049  MRPT_START
1050 
1051  extraResults = TMatchingExtraResults();
1052 
1053  ASSERT_ABOVE_(params.decimation_other_map_points, 0);
1054  ASSERT_BELOW_(
1055  params.offset_other_map_points, params.decimation_other_map_points);
1056 
1058  const auto* otherMap = static_cast<const CPointsMap*>(otherMap2);
1059 
1060  const size_t nLocalPoints = otherMap->size();
1061  const size_t nGlobalPoints = this->size();
1062  float _sumSqrDist = 0;
1063  size_t _sumSqrCount = 0;
1064  size_t nOtherMapPointsWithCorrespondence =
1065  0; // Number of points with one corrs. at least
1066 
1067  float local_x_min = std::numeric_limits<float>::max(),
1068  local_x_max = -std::numeric_limits<float>::max();
1069  float local_y_min = std::numeric_limits<float>::max(),
1070  local_y_max = -std::numeric_limits<float>::max();
1071  float local_z_min = std::numeric_limits<float>::max(),
1072  local_z_max = -std::numeric_limits<float>::max();
1073 
1074  double maxDistForCorrespondenceSquared;
1075 
1076  // Prepare output: no correspondences initially:
1077  correspondences.clear();
1078  correspondences.reserve(nLocalPoints);
1079 
1080  TMatchingPairList _correspondences;
1081  _correspondences.reserve(nLocalPoints);
1082 
1083  // Empty maps? Nothing to do
1084  if (!nGlobalPoints || !nLocalPoints) return;
1085 
1086  // Try to do matching only if the bounding boxes have some overlap:
1087  // Transform all local points:
1088  vector<float> x_locals(nLocalPoints), y_locals(nLocalPoints),
1089  z_locals(nLocalPoints);
1090 
1091  for (unsigned int localIdx = params.offset_other_map_points;
1092  localIdx < nLocalPoints;
1093  localIdx += params.decimation_other_map_points)
1094  {
1095  float x_local, y_local, z_local;
1096  otherMapPose.composePoint(
1097  otherMap->m_x[localIdx], otherMap->m_y[localIdx],
1098  otherMap->m_z[localIdx], x_local, y_local, z_local);
1099 
1100  x_locals[localIdx] = x_local;
1101  y_locals[localIdx] = y_local;
1102  z_locals[localIdx] = z_local;
1103 
1104  // Find the bounding box:
1105  local_x_min = min(local_x_min, x_local);
1106  local_x_max = max(local_x_max, x_local);
1107  local_y_min = min(local_y_min, y_local);
1108  local_y_max = max(local_y_max, y_local);
1109  local_z_min = min(local_z_min, z_local);
1110  local_z_max = max(local_z_max, z_local);
1111  }
1112 
1113  // Find the bounding box:
1114  float global_x_min, global_x_max, global_y_min, global_y_max, global_z_min,
1115  global_z_max;
1116  this->boundingBox(
1117  global_x_min, global_x_max, global_y_min, global_y_max, global_z_min,
1118  global_z_max);
1119 
1120  // Solo hacer matching si existe alguna posibilidad de que
1121  // los dos mapas se toquen:
1122  if (local_x_min > global_x_max || local_x_max < global_x_min ||
1123  local_y_min > global_y_max || local_y_max < global_y_min)
1124  return; // No need to compute: matching is ZERO.
1125 
1126  // Loop for each point in local map:
1127  // --------------------------------------------------
1128  for (unsigned int localIdx = params.offset_other_map_points;
1129  localIdx < nLocalPoints;
1130  localIdx += params.decimation_other_map_points)
1131  {
1132  // For speed-up:
1133  const float x_local = x_locals[localIdx];
1134  const float y_local = y_locals[localIdx];
1135  const float z_local = z_locals[localIdx];
1136 
1137  {
1138  // KD-TREE implementation
1139  // Use a KD-tree to look for the nearnest neighbor of:
1140  // (x_local, y_local, z_local)
1141  // In "this" (global/reference) points map.
1142 
1143  float tentativ_err_sq;
1144  const unsigned int tentativ_this_idx = kdTreeClosestPoint3D(
1145  x_local, y_local, z_local, // Look closest to this guy
1146  tentativ_err_sq // save here the min. distance squared
1147  );
1148 
1149  // Compute max. allowed distance:
1150  maxDistForCorrespondenceSquared = square(
1151  params.maxAngularDistForCorrespondence *
1152  params.angularDistPivotPoint.distanceTo(
1153  TPoint3D(x_local, y_local, z_local)) +
1154  params.maxDistForCorrespondence);
1155 
1156  // Distance below the threshold??
1157  if (tentativ_err_sq < maxDistForCorrespondenceSquared)
1158  {
1159  // Save all the correspondences:
1160  _correspondences.resize(_correspondences.size() + 1);
1161 
1162  TMatchingPair& p = _correspondences.back();
1163 
1164  p.this_idx = tentativ_this_idx;
1165  p.this_x = m_x[tentativ_this_idx];
1166  p.this_y = m_y[tentativ_this_idx];
1167  p.this_z = m_z[tentativ_this_idx];
1168 
1169  p.other_idx = localIdx;
1170  p.other_x = otherMap->m_x[localIdx];
1171  p.other_y = otherMap->m_y[localIdx];
1172  p.other_z = otherMap->m_z[localIdx];
1173 
1174  p.errorSquareAfterTransformation = tentativ_err_sq;
1175 
1176  // At least one:
1177  nOtherMapPointsWithCorrespondence++;
1178 
1179  // Accumulate the MSE:
1180  _sumSqrDist += p.errorSquareAfterTransformation;
1181  _sumSqrCount++;
1182  }
1183 
1184  } // End of test_match
1185  } // For each local point
1186 
1187  // Additional consistency filter: "onlyKeepTheClosest" up to now
1188  // led to just one correspondence for each "local map" point, but
1189  // many of them may have as corresponding pair the same "global point"!!
1190  // -------------------------------------------------------------------------
1191  if (params.onlyUniqueRobust)
1192  {
1193  ASSERTMSG_(
1194  params.onlyKeepTheClosest,
1195  "ERROR: onlyKeepTheClosest must be also set to true when "
1196  "onlyUniqueRobust=true.");
1197  _correspondences.filterUniqueRobustPairs(
1198  nGlobalPoints, correspondences);
1199  }
1200  else
1201  {
1202  correspondences.swap(_correspondences);
1203  }
1204 
1205  // If requested, copy sum of squared distances to output pointer:
1206  // -------------------------------------------------------------------
1207  extraResults.sumSqrDist =
1208  (_sumSqrCount) ? _sumSqrDist / static_cast<double>(_sumSqrCount) : 0;
1209  extraResults.correspondencesRatio = params.decimation_other_map_points *
1210  nOtherMapPointsWithCorrespondence /
1211  d2f(nLocalPoints);
1212 
1213  MRPT_END
1214 }
1215 
1216 /*---------------------------------------------------------------
1217  extractCylinder
1218 ---------------------------------------------------------------*/
1220  const TPoint2D& center, const double radius, const double zmin,
1221  const double zmax, CPointsMap* outMap)
1222 {
1223  outMap->clear();
1224  for (size_t k = 0; k < m_x.size(); k++)
1225  {
1226  if ((m_z[k] <= zmax && m_z[k] >= zmin) &&
1227  (sqrt(square(center.x - m_x[k]) + square(center.y - m_y[k])) <
1228  radius))
1229  outMap->insertPoint(m_x[k], m_y[k], m_z[k]);
1230  }
1231 }
1232 
1233 /*---------------------------------------------------------------
1234  extractPoints
1235 ---------------------------------------------------------------*/
1237  const TPoint3D& corner1, const TPoint3D& corner2, CPointsMap* outMap,
1238  double R, double G, double B)
1239 {
1240  outMap->clear();
1241  double minX, maxX, minY, maxY, minZ, maxZ;
1242  minX = min(corner1.x, corner2.x);
1243  maxX = max(corner1.x, corner2.x);
1244  minY = min(corner1.y, corner2.y);
1245  maxY = max(corner1.y, corner2.y);
1246  minZ = min(corner1.z, corner2.z);
1247  maxZ = max(corner1.z, corner2.z);
1248  for (size_t k = 0; k < m_x.size(); k++)
1249  {
1250  if ((m_x[k] >= minX && m_x[k] <= maxX) &&
1251  (m_y[k] >= minY && m_y[k] <= maxY) &&
1252  (m_z[k] >= minZ && m_z[k] <= maxZ))
1253  outMap->insertPointRGB(m_x[k], m_y[k], m_z[k], R, G, B);
1254  }
1255 }
1256 
1257 /*---------------------------------------------------------------
1258  compute3DDistanceToMesh
1259 ---------------------------------------------------------------*/
1261  const mrpt::maps::CMetricMap* otherMap2,
1262  [[maybe_unused]] const CPose3D& otherMapPose,
1263  float maxDistForCorrespondence, TMatchingPairList& correspondences,
1264  float& correspondencesRatio)
1265 {
1266  MRPT_START
1267 
1268  const auto* otherMap = static_cast<const CPointsMap*>(otherMap2);
1269 
1270  const size_t nLocalPoints = otherMap->size();
1271  const size_t nGlobalPoints = this->size();
1272  size_t nOtherMapPointsWithCorrespondence =
1273  0; // Number of points with one corrs. at least
1274 
1275  // Prepare output: no correspondences initially:
1276  correspondences.clear();
1277  correspondences.reserve(nLocalPoints);
1278  correspondencesRatio = 0;
1279 
1280  // aux correspondence vector
1281  TMatchingPairList _correspondences;
1282  _correspondences.reserve(nLocalPoints);
1283 
1284  // Hay mapa global?
1285  if (!nGlobalPoints) return; // No
1286 
1287  // Hay mapa local?
1288  if (!nLocalPoints) return; // No
1289 
1290  // we'll assume by now both reference systems are the same
1291  float local_x_min, local_x_max, local_y_min, local_y_max, local_z_min,
1292  local_z_max;
1293  otherMap->boundingBox(
1294  local_x_min, local_x_max, local_y_min, local_y_max, local_z_min,
1295  local_z_max);
1296 
1297  // Find the bounding box:
1298  float global_x_min, global_x_max, global_y_min, global_y_max, global_z_min,
1299  global_z_max;
1300  this->boundingBox(
1301  global_x_min, global_x_max, global_y_min, global_y_max, global_z_min,
1302  global_z_max);
1303 
1304  // Solo hacer matching si existe alguna posibilidad de que
1305  // los dos mapas se toquen:
1306  if (local_x_min > global_x_max || local_x_max < global_x_min ||
1307  local_y_min > global_y_max || local_y_max < global_y_min)
1308  return; // No hace falta hacer matching,
1309  // porque es de CERO.
1310 
1311  std::vector<std::vector<size_t>> vIdx;
1312 
1313  // Loop for each point in local map:
1314  // --------------------------------------------------
1315  std::vector<float> outX, outY, outZ, tentativeErrSq;
1316  std::vector<size_t> outIdx;
1317  for (unsigned int localIdx = 0; localIdx < nLocalPoints; ++localIdx)
1318  {
1319  // For speed-up:
1320  const float x_local = otherMap->m_x[localIdx];
1321  const float y_local = otherMap->m_y[localIdx];
1322  const float z_local = otherMap->m_z[localIdx];
1323 
1324  {
1325  // KD-TREE implementation
1326  // Use a KD-tree to look for the nearnest neighbor of:
1327  // (x_local, y_local, z_local)
1328  // In "this" (global/reference) points map.
1330  x_local, y_local, z_local, // Look closest to this guy
1331  3, // get the three closest points
1332  outX, outY, outZ, // output vectors
1333  outIdx, // output indexes
1334  tentativeErrSq // save here the min. distance squared
1335  );
1336 
1337  // get the centroid
1338  const float mX = (outX[0] + outX[1] + outX[2]) / 3.0;
1339  const float mY = (outY[0] + outY[1] + outY[2]) / 3.0;
1340  const float mZ = (outZ[0] + outZ[1] + outZ[2]) / 3.0;
1341 
1342  const float distanceForThisPoint = fabs(mrpt::math::distance(
1343  TPoint3D(x_local, y_local, z_local), TPoint3D(mX, mY, mZ)));
1344 
1345  // Distance below the threshold??
1346  if (distanceForThisPoint < maxDistForCorrespondence)
1347  {
1348  // Save all the correspondences:
1349  _correspondences.resize(_correspondences.size() + 1);
1350 
1351  TMatchingPair& p = _correspondences.back();
1352 
1353  p.this_idx = nOtherMapPointsWithCorrespondence++; // insert a
1354  // consecutive index
1355  // here
1356  p.this_x = mX;
1357  p.this_y = mY;
1358  p.this_z = mZ;
1359 
1360  p.other_idx = localIdx;
1361  p.other_x = otherMap->m_x[localIdx];
1362  p.other_y = otherMap->m_y[localIdx];
1363  p.other_z = otherMap->m_z[localIdx];
1364 
1365  p.errorSquareAfterTransformation = distanceForThisPoint;
1366 
1367  // save the indexes
1368  std::sort(outIdx.begin(), outIdx.end());
1369  vIdx.push_back(outIdx);
1370  }
1371  } // End of test_match
1372  } // For each local point
1373 
1374  // Additional consistency filter: "onlyKeepTheClosest" up to now
1375  // led to just one correspondence for each "local map" point, but
1376  // many of them may have as corresponding pair the same "global point"!!
1377  // -------------------------------------------------------------------------
1378  std::map<size_t, std::map<size_t, std::map<size_t, pair<size_t, float>>>>
1379  best; // 3D associative map
1380  TMatchingPairList::iterator it;
1381  for (it = _correspondences.begin(); it != _correspondences.end(); ++it)
1382  {
1383  const size_t i0 = vIdx[it->this_idx][0];
1384  const size_t i1 = vIdx[it->this_idx][1];
1385  const size_t i2 = vIdx[it->this_idx][2];
1386 
1387  if (best.find(i0) != best.end() &&
1388  best[i0].find(i1) != best[i0].end() &&
1389  best[i0][i1].find(i2) !=
1390  best[i0][i1]
1391  .end()) // if there is a match, check if it is better
1392  {
1393  if (best[i0][i1][i2].second > it->errorSquareAfterTransformation)
1394  {
1395  best[i0][i1][i2].first = it->this_idx;
1396  best[i0][i1][i2].second = it->errorSquareAfterTransformation;
1397  }
1398  }
1399  else // if there is no match
1400  {
1401  best[i0][i1][i2].first = it->this_idx;
1402  best[i0][i1][i2].second = it->errorSquareAfterTransformation;
1403  }
1404  } // end it correspondences
1405 
1406  for (it = _correspondences.begin(); it != _correspondences.end(); ++it)
1407  {
1408  const size_t i0 = vIdx[it->this_idx][0];
1409  const size_t i1 = vIdx[it->this_idx][1];
1410  const size_t i2 = vIdx[it->this_idx][2];
1411 
1412  if (best[i0][i1][i2].first == it->this_idx)
1413  correspondences.push_back(*it);
1414  }
1415 
1416  // The ratio of points in the other map with corrs:
1417  correspondencesRatio =
1418  nOtherMapPointsWithCorrespondence / d2f(nLocalPoints);
1419 
1420  MRPT_END
1421 }
1422 
1424  const mrpt::poses::CPose3D& pc_in_map, const float* xs, const float* ys,
1425  const float* zs, const std::size_t num_pts)
1426 {
1428 
1429  float closest_x, closest_y, closest_z;
1430  float closest_err;
1431  const float max_sqr_err = square(likelihoodOptions.max_corr_distance);
1432  double sumSqrDist = 0;
1433 
1434  std::size_t nPtsForAverage = 0;
1435  for (std::size_t i = 0; i < num_pts;
1436  i += likelihoodOptions.decimation, nPtsForAverage++)
1437  {
1438  // Transform the point from the scan reference to its global 3D
1439  // position:
1440  float xg, yg, zg;
1441  pc_in_map.composePoint(xs[i], ys[i], zs[i], xg, yg, zg);
1442 
1444  xg, yg, zg, // Look for the closest to this guy
1445  closest_x, closest_y,
1446  closest_z, // save here the closest match
1447  closest_err // save here the min. distance squared
1448  );
1449 
1450  // Put a limit:
1451  mrpt::keep_min(closest_err, max_sqr_err);
1452 
1453  sumSqrDist += static_cast<double>(closest_err);
1454  }
1455  if (nPtsForAverage) sumSqrDist /= nPtsForAverage;
1456 
1457  // Log-likelihood:
1458  return -sumSqrDist / likelihoodOptions.sigma_dist;
1459 
1460  MRPT_TRY_END
1461 }
1462 
1464  const CObservation& obs, const CPose3D& takenFrom)
1465 {
1466  // This function depends on the observation type:
1467  // -----------------------------------------------------
1469  {
1470  // Observation is a laser range scan:
1471  // -------------------------------------------
1472  const auto& o = static_cast<const CObservation2DRangeScan&>(obs);
1473 
1474  // Build (if not done before) the points map representation of this
1475  // observation:
1476  const auto* scanPoints = o.buildAuxPointsMap<CPointsMap>();
1477 
1478  const size_t N = scanPoints->m_x.size();
1479  if (!N || !this->size()) return -100;
1480 
1481  const float* xs = &scanPoints->m_x[0];
1482  const float* ys = &scanPoints->m_y[0];
1483  const float* zs = &scanPoints->m_z[0];
1484 
1485  if (takenFrom.isHorizontal())
1486  {
1487  double sumSqrDist = 0;
1488  float closest_x, closest_y;
1489  float closest_err;
1490  const float max_sqr_err =
1492 
1493  // optimized 2D version ---------------------------
1494  TPose2D takenFrom2D = CPose2D(takenFrom).asTPose();
1495 
1496  const double ccos = cos(takenFrom2D.phi);
1497  const double csin = sin(takenFrom2D.phi);
1498  int nPtsForAverage = 0;
1499 
1500  for (size_t i = 0; i < N;
1501  i += likelihoodOptions.decimation, nPtsForAverage++)
1502  {
1503  // Transform the point from the scan reference to its global
1504  // 3D position:
1505  const float xg = takenFrom2D.x + ccos * xs[i] - csin * ys[i];
1506  const float yg = takenFrom2D.y + csin * xs[i] + ccos * ys[i];
1507 
1509  xg, yg, // Look for the closest to this guy
1510  closest_x, closest_y, // save here the closest match
1511  closest_err // save here the min. distance squared
1512  );
1513 
1514  // Put a limit:
1515  mrpt::keep_min(closest_err, max_sqr_err);
1516 
1517  sumSqrDist += static_cast<double>(closest_err);
1518  }
1519  sumSqrDist /= nPtsForAverage;
1520  // Log-likelihood:
1521  return -sumSqrDist / likelihoodOptions.sigma_dist;
1522  }
1523  else
1524  {
1525  // Generic 3D version ---------------------------
1527  takenFrom, xs, ys, zs, N);
1528  }
1529  }
1530  else if (IS_CLASS(obs, CObservationVelodyneScan))
1531  {
1532  const auto& o = dynamic_cast<const CObservationVelodyneScan&>(obs);
1533 
1534  // Automatically generate pointcloud if needed:
1535  if (!o.point_cloud.size())
1536  const_cast<CObservationVelodyneScan&>(o).generatePointCloud();
1537 
1538  const size_t N = o.point_cloud.size();
1539  if (!N || !this->size()) return -100;
1540 
1541  const CPose3D sensorAbsPose = takenFrom + o.sensorPose;
1542 
1543  const float* xs = &o.point_cloud.x[0];
1544  const float* ys = &o.point_cloud.y[0];
1545  const float* zs = &o.point_cloud.z[0];
1546 
1548  sensorAbsPose, xs, ys, zs, N);
1549  }
1550  else if (IS_CLASS(obs, CObservationPointCloud))
1551  {
1552  const auto& o = dynamic_cast<const CObservationPointCloud&>(obs);
1553 
1554  const size_t N = o.pointcloud->size();
1555  if (!N || !this->size()) return -100;
1556 
1557  const CPose3D sensorAbsPose = takenFrom + o.sensorPose;
1558 
1559  auto xs = o.pointcloud->getPointsBufferRef_x();
1560  auto ys = o.pointcloud->getPointsBufferRef_y();
1561  auto zs = o.pointcloud->getPointsBufferRef_z();
1562 
1564  sensorAbsPose, &xs[0], &ys[0], &zs[0], N);
1565  }
1566 
1567  return .0;
1568 }
1569 
1570 namespace mrpt::obs
1571 {
1572 // Tricky way to call to a library that depends on us, a sort of "run-time"
1573 // linking: ptr_internal_build_points_map_from_scan2D is a functor in
1574 // "mrpt-obs", set by "mrpt-maps" at its startup.
1575 using scan2pts_functor = void (*)(
1577  mrpt::maps::CMetricMap::Ptr& out_map, const void* insertOps);
1578 
1580 } // namespace mrpt::obs
1581 
1584  mrpt::maps::CMetricMap::Ptr& out_map, const void* insertOps)
1585 {
1586  // Create on first call:
1587  if (out_map) return; // Already done!
1588 
1589  out_map = std::make_shared<CSimplePointsMap>();
1590 
1591  if (insertOps)
1592  static_cast<CSimplePointsMap*>(out_map.get())->insertionOptions =
1593  *static_cast<const CPointsMap::TInsertionOptions*>(insertOps);
1594 
1595  out_map->insertObservation(obs, nullptr);
1596 }
1597 
1599 {
1601  {
1604  }
1605 };
1606 
1607 // used just to set "ptr_internal_build_points_map_from_scan2D"
1609 
1610 // ================================ PLY files import & export virtual
1611 // methods
1612 // ================================
1613 
1614 /** In a base class, will be called after PLY_import_set_vertex_count() once
1615  * for each loaded point. \param pt_color Will be nullptr if the loaded file
1616  * does not provide color info.
1617  */
1619  const size_t idx, const mrpt::math::TPoint3Df& pt,
1620  [[maybe_unused]] const mrpt::img::TColorf* pt_color)
1621 {
1622  this->setPoint(idx, pt.x, pt.y, pt.z);
1623 }
1624 
1625 /** In a base class, return the number of vertices */
1626 size_t CPointsMap::PLY_export_get_vertex_count() const { return this->size(); }
1627 /** In a base class, will be called after PLY_export_get_vertex_count() once
1628  * for each exported point. \param pt_color Will be nullptr if the loaded
1629  * file does not provide color info.
1630  */
1632  const size_t idx, mrpt::math::TPoint3Df& pt, bool& pt_has_color,
1633  [[maybe_unused]] mrpt::img::TColorf& pt_color) const
1634 {
1635  pt_has_color = false;
1636 
1637  pt.x = m_x[idx];
1638  pt.y = m_y[idx];
1639  pt.z = m_z[idx];
1640 }
1641 
1642 // Generic implementation (a more optimized one should exist in derived
1643 // classes):
1644 void CPointsMap::addFrom(const CPointsMap& anotherMap)
1645 {
1646  const size_t nThis = this->size();
1647  const size_t nOther = anotherMap.size();
1648 
1649  const size_t nTot = nThis + nOther;
1650 
1651  this->resize(nTot);
1652 
1653  for (size_t i = 0, j = nThis; i < nOther; i++, j++)
1654  {
1655  m_x[j] = anotherMap.m_x[i];
1656  m_y[j] = anotherMap.m_y[i];
1657  m_z[j] = anotherMap.m_z[i];
1658  }
1659 
1660  // Also copy other data fields (color, ...)
1661  addFrom_classSpecific(anotherMap, nThis);
1662 
1663  mark_as_modified();
1664 }
1665 
1666 /*---------------------------------------------------------------
1667  applyDeletionMask
1668  ---------------------------------------------------------------*/
1669 void CPointsMap::applyDeletionMask(const std::vector<bool>& mask)
1670 {
1671  ASSERT_EQUAL_(size(), mask.size());
1672  // Remove marked points:
1673  const size_t n = mask.size();
1674  vector<float> Pt;
1675  size_t i, j;
1676  for (i = 0, j = 0; i < n; i++)
1677  {
1678  if (!mask[i])
1679  {
1680  // Pt[j] <---- Pt[i]
1681  this->getPointAllFieldsFast(i, Pt);
1682  this->setPointAllFieldsFast(j++, Pt);
1683  }
1684  }
1685 
1686  // Set new correct size:
1687  this->resize(j);
1688 
1689  mark_as_modified();
1690 }
1691 
1692 /*---------------------------------------------------------------
1693  insertAnotherMap
1694  ---------------------------------------------------------------*/
1696  const CPointsMap* otherMap, const CPose3D& otherPose)
1697 {
1698  const size_t N_this = size();
1699  const size_t N_other = otherMap->size();
1700 
1701  // Set the new size:
1702  this->resize(N_this + N_other);
1703 
1705  size_t src, dst;
1706  for (src = 0, dst = N_this; src < N_other; src++, dst++)
1707  {
1708  // Load the next point:
1709  otherMap->getPointFast(src, pt.x, pt.y, pt.z);
1710 
1711  // Translation:
1712  double gx, gy, gz;
1713  otherPose.composePoint(pt.x, pt.y, pt.z, gx, gy, gz);
1714 
1715  // Add to this map:
1716  this->setPointFast(dst, gx, gy, gz);
1717  }
1718 
1719  // Also copy other data fields (color, ...)
1720  addFrom_classSpecific(*otherMap, N_this);
1721 
1722  mark_as_modified();
1723 }
1724 
1725 /** Helper method for ::copyFrom() */
1727 {
1728  MRPT_START
1729 
1730  if (this == &obj) return;
1731 
1732  m_x = obj.m_x;
1733  m_y = obj.m_y;
1734  m_z = obj.m_z;
1735 
1739 
1740  // Fill missing fields (R,G,B,min_dist) with default values.
1741  this->resize(m_x.size());
1742 
1744 
1745  MRPT_END
1746 }
1747 
1748 /*---------------------------------------------------------------
1749  internal_insertObservation
1750 
1751  Insert the observation information into this map.
1752  ---------------------------------------------------------------*/
1754  const CObservation& obs, const CPose3D* robotPose)
1755 {
1756  MRPT_START
1757 
1758  CPose2D robotPose2D;
1759  CPose3D robotPose3D;
1760 
1761  if (robotPose)
1762  {
1763  robotPose2D = CPose2D(*robotPose);
1764  robotPose3D = (*robotPose);
1765  }
1766  else
1767  {
1768  // Default values are (0,0,0)
1769  }
1770 
1772  {
1773  /********************************************************************
1774  OBSERVATION TYPE: CObservation2DRangeScan
1775  ********************************************************************/
1776  mark_as_modified();
1777 
1778  const auto& o = static_cast<const CObservation2DRangeScan&>(obs);
1779  // Insert only HORIZONTAL scans??
1780  bool reallyInsertIt;
1781 
1783  reallyInsertIt =
1785  else
1786  reallyInsertIt = true;
1787 
1788  if (reallyInsertIt)
1789  {
1790  std::vector<bool> checkForDeletion;
1791 
1792  // 1) Fuse into the points map or add directly?
1793  // ----------------------------------------------
1795  {
1796  CSimplePointsMap auxMap;
1797  // Fuse:
1800 
1801  auxMap.loadFromRangeScan(
1802  o, // The laser range scan observation
1803  &robotPose3D // The robot pose
1804  );
1805 
1806  fuseWith(
1807  &auxMap, // Fuse with this map
1809  &checkForDeletion // Set to "false" if a point in "map"
1810  // has
1811  // been fused.
1812  );
1813 
1815  {
1816  // 2) Delete points in newly added free
1817  // region, thus dynamic areas:
1818  // --------------------------------------
1819  // Load scan as a polygon:
1820  CPolygon pol;
1821  const float *xs, *ys, *zs;
1822  size_t n;
1823  auxMap.getPointsBuffer(n, xs, ys, zs);
1824  pol.setAllVertices(n, xs, ys);
1825 
1826  // Check for deletion of points in "map"
1827  n = size();
1828  for (size_t i = 0; i < n; i++)
1829  {
1830  if (checkForDeletion[i]) // Default to true, unless
1831  // a
1832  // fused point, which must be
1833  // kept.
1834  {
1835  float x, y;
1836  getPoint(i, x, y);
1837  if (!pol.PointIntoPolygon(x, y))
1838  checkForDeletion[i] =
1839  false; // Out of polygon, don't delete
1840  }
1841  }
1842 
1843  // Create a new points list just with non-deleted
1844  // points.
1845  // ----------------------------------------------------------
1846  applyDeletionMask(checkForDeletion);
1847  }
1848  }
1849  else
1850  {
1851  // Don't fuse: Simply add
1854  o, // The laser range scan observation
1855  &robotPose3D // The robot pose
1856  );
1857  }
1858 
1859  return true;
1860  }
1861  // A planar map and a non-horizontal scan.
1862  else
1863  return false;
1864  }
1865  else if (IS_CLASS(obs, CObservation3DRangeScan))
1866  {
1867  /********************************************************************
1868  OBSERVATION TYPE: CObservation3DRangeScan
1869  ********************************************************************/
1870  mark_as_modified();
1871 
1872  const auto& o = static_cast<const CObservation3DRangeScan&>(obs);
1873  // Insert only HORIZONTAL scans??
1874  bool reallyInsertIt;
1875 
1877  reallyInsertIt =
1878  false; // Don't insert 3D range observation into planar map
1879  else
1880  reallyInsertIt = true;
1881 
1882  if (reallyInsertIt)
1883  {
1884  // 1) Fuse into the points map or add directly?
1885  // ----------------------------------------------
1887  {
1888  // Fuse:
1889  CSimplePointsMap auxMap;
1892 
1893  auxMap.loadFromRangeScan(
1894  o, // The laser range scan observation
1895  &robotPose3D // The robot pose
1896  );
1897 
1898  fuseWith(
1899  &auxMap, // Fuse with this map
1901  nullptr // rather than &checkForDeletion which we don't
1902  // need
1903  // for 3D observations
1904  );
1905  }
1906  else
1907  {
1908  // Don't fuse: Simply add
1911  o, // The laser range scan observation
1912  &robotPose3D // The robot pose
1913  );
1914  }
1915 
1916  return true;
1917  }
1918  // A planar map and a non-horizontal scan.
1919  else
1920  return false;
1921  }
1922  else if (IS_CLASS(obs, CObservationRange))
1923  {
1924  /********************************************************************
1925  OBSERVATION TYPE: CObservationRange (IRs, Sonars, etc.)
1926  ********************************************************************/
1927  mark_as_modified();
1928 
1929  const auto& o = static_cast<const CObservationRange&>(obs);
1930 
1931  const double aper_2 = 0.5 * o.sensorConeApperture;
1932 
1933  this->reserve(
1934  this->size() + o.sensedData.size() * 30); // faster push_back's.
1935 
1936  for (auto it = o.begin(); it != o.end(); ++it)
1937  {
1938  const CPose3D sensorPose = robotPose3D + CPose3D(it->sensorPose);
1939  const double rang = it->sensedDistance;
1940 
1941  if (rang <= 0 || rang < o.minSensorDistance ||
1942  rang > o.maxSensorDistance)
1943  continue;
1944 
1945  // Insert a few points with a given maximum separation between
1946  // them:
1947  const double arc_len = o.sensorConeApperture * rang;
1948  const unsigned int nSteps = round(1 + arc_len / 0.05);
1949  const double Aa = o.sensorConeApperture / double(nSteps);
1950  TPoint3D loc, glob;
1951 
1952  for (double a1 = -aper_2; a1 < aper_2; a1 += Aa)
1953  {
1954  for (double a2 = -aper_2; a2 < aper_2; a2 += Aa)
1955  {
1956  loc.x = cos(a1) * cos(a2) * rang;
1957  loc.y = cos(a1) * sin(a2) * rang;
1958  loc.z = sin(a1) * rang;
1959  sensorPose.composePoint(loc, glob);
1960 
1961  this->insertPointFast(glob.x, glob.y, glob.z);
1962  }
1963  }
1964  }
1965  return true;
1966  }
1967  else if (IS_CLASS(obs, CObservationVelodyneScan))
1968  {
1969  /********************************************************************
1970  OBSERVATION TYPE: CObservationVelodyneScan
1971  ********************************************************************/
1972  mark_as_modified();
1973 
1974  const auto& o = static_cast<const CObservationVelodyneScan&>(obs);
1975 
1976  // Automatically generate pointcloud if needed:
1977  if (!o.point_cloud.size())
1978  const_cast<CObservationVelodyneScan&>(o).generatePointCloud();
1979 
1981  {
1982  // Fuse:
1983  CSimplePointsMap auxMap;
1986  auxMap.loadFromVelodyneScan(o, &robotPose3D);
1987  fuseWith(
1988  &auxMap, insertionOptions.minDistBetweenLaserPoints, nullptr /* rather than &checkForDeletion which we don't need for 3D observations */);
1989  }
1990  else
1991  {
1992  // Don't fuse: Simply add
1994  loadFromVelodyneScan(o, &robotPose3D);
1995  }
1996  return true;
1997  }
1998  else if (IS_CLASS(obs, CObservationPointCloud))
1999  {
2000  mark_as_modified();
2001 
2002  const auto& o = static_cast<const CObservationPointCloud&>(obs);
2003  ASSERT_(o.pointcloud);
2004 
2006  {
2007  fuseWith(
2008  o.pointcloud.get(), insertionOptions.minDistBetweenLaserPoints, nullptr /* rather than &checkForDeletion which we don't need for 3D observations */);
2009  }
2010  else
2011  {
2012  // Don't fuse: Simply add
2014  this->insertAnotherMap(o.pointcloud.get(), o.sensorPose);
2015  }
2016  return true;
2017  }
2018  else
2019  {
2020  /********************************************************************
2021  OBSERVATION TYPE: Unknown
2022  ********************************************************************/
2023  return false;
2024  }
2025 
2026  MRPT_END
2027 }
2028 
2029 /*---------------------------------------------------------------
2030 Insert the contents of another map into this one, fusing the previous
2031 content with the new one. This means that points very close to existing ones
2032 will be "fused", rather than "added". This prevents the unbounded increase
2033 in size of these class of maps.
2034  ---------------------------------------------------------------*/
2036  CPointsMap* otherMap, float minDistForFuse,
2037  std::vector<bool>* notFusedPoints)
2038 {
2039  TMatchingPairList correspondences;
2040  TPoint3D a, b;
2041  const CPose2D nullPose(0, 0, 0);
2042 
2043  mark_as_modified();
2044 
2045  // const size_t nThis = this->size();
2046  const size_t nOther = otherMap->size();
2047 
2048  // Find correspondences between this map and the other one:
2049  // ------------------------------------------------------------
2051  TMatchingExtraResults extraResults;
2052 
2053  params.maxAngularDistForCorrespondence = 0;
2054  params.maxDistForCorrespondence = minDistForFuse;
2055 
2057  otherMap, // The other map
2058  nullPose, // The other map's pose
2059  correspondences, params, extraResults);
2060 
2061  // Initially, all set to "true" -> "not fused".
2062  if (notFusedPoints)
2063  {
2064  notFusedPoints->clear();
2065  notFusedPoints->reserve(m_x.size() + nOther);
2066  notFusedPoints->resize(m_x.size(), true);
2067  }
2068 
2069  // Speeds-up possible memory reallocations:
2070  reserve(m_x.size() + nOther);
2071 
2072  // Merge matched points from both maps:
2073  // AND add new points which have been not matched:
2074  // -------------------------------------------------
2075  for (size_t i = 0; i < nOther; i++)
2076  {
2077  otherMap->getPoint(i, a); // Get "local" point into "a"
2078  const unsigned long w_a = otherMap->getPointWeight(i);
2079 
2080  // Find closest correspondence of "a":
2081  int closestCorr = -1;
2082  float minDist = std::numeric_limits<float>::max();
2083  for (auto corrsIt = correspondences.begin();
2084  corrsIt != correspondences.end(); ++corrsIt)
2085  {
2086  if (corrsIt->other_idx == i)
2087  {
2088  float dist = square(corrsIt->other_x - corrsIt->this_x) +
2089  square(corrsIt->other_y - corrsIt->this_y) +
2090  square(corrsIt->other_z - corrsIt->this_z);
2091  if (dist < minDist)
2092  {
2093  minDist = dist;
2094  closestCorr = corrsIt->this_idx;
2095  }
2096  }
2097  } // End of for each correspondence...
2098 
2099  if (closestCorr != -1)
2100  { // Merge: FUSION
2101  getPoint(closestCorr, b);
2102  unsigned long w_b = getPointWeight(closestCorr);
2103 
2104  ASSERT_((w_a + w_b) > 0);
2105 
2106  const float F = 1.0f / (w_a + w_b);
2107 
2108  m_x[closestCorr] = F * (w_a * a.x + w_b * b.x);
2109  m_y[closestCorr] = F * (w_a * a.y + w_b * b.y);
2110  m_z[closestCorr] = F * (w_a * a.z + w_b * b.z);
2111 
2112  this->setPointWeight(closestCorr, w_a + w_b);
2113 
2114  // Append to fused points list
2115  if (notFusedPoints) (*notFusedPoints)[closestCorr] = false;
2116  }
2117  else
2118  { // New point: ADDITION
2119  this->insertPointFast(a.x, a.y, a.z);
2120  if (notFusedPoints) (*notFusedPoints).push_back(false);
2121  }
2122  }
2123 }
2124 
2127  const mrpt::poses::CPose3D* robotPose)
2128 {
2129  ASSERT_EQUAL_(scan.point_cloud.x.size(), scan.point_cloud.y.size());
2130  ASSERT_EQUAL_(scan.point_cloud.x.size(), scan.point_cloud.z.size());
2131  ASSERT_EQUAL_(scan.point_cloud.x.size(), scan.point_cloud.intensity.size());
2132 
2133  if (scan.point_cloud.x.empty()) return;
2134 
2135  this->mark_as_modified();
2136 
2137  // Insert vs. load and replace:
2139  resize(0); // Resize to 0 instead of clear() so the std::vector<>
2140  // memory is not actually deallocated and can be reused.
2141 
2142  // Alloc space:
2143  const size_t nOldPtsCount = this->size();
2144  const size_t nScanPts = scan.point_cloud.size();
2145  const size_t nNewPtsCount = nOldPtsCount + nScanPts;
2146  this->resize(nNewPtsCount);
2147 
2148  const float K = 1.0f / 255; // Intensity scale.
2149 
2150  // global 3D pose:
2151  CPose3D sensorGlobalPose;
2152  if (robotPose)
2153  sensorGlobalPose = *robotPose + scan.sensorPose;
2154  else
2155  sensorGlobalPose = scan.sensorPose;
2156 
2158  sensorGlobalPose.getHomogeneousMatrix(HM);
2159 
2160  const double m00 = HM(0, 0), m01 = HM(0, 1), m02 = HM(0, 2), m03 = HM(0, 3);
2161  const double m10 = HM(1, 0), m11 = HM(1, 1), m12 = HM(1, 2), m13 = HM(1, 3);
2162  const double m20 = HM(2, 0), m21 = HM(2, 1), m22 = HM(2, 2), m23 = HM(2, 3);
2163 
2164  // Copy points:
2165  for (size_t i = 0; i < nScanPts; i++)
2166  {
2167  const float inten = scan.point_cloud.intensity[i] * K;
2168  const double lx = scan.point_cloud.x[i];
2169  const double ly = scan.point_cloud.y[i];
2170  const double lz = scan.point_cloud.z[i];
2171 
2172  const double gx = m00 * lx + m01 * ly + m02 * lz + m03;
2173  const double gy = m10 * lx + m11 * ly + m12 * lz + m13;
2174  const double gz = m20 * lx + m21 * ly + m22 * lz + m23;
2175 
2176  this->setPointRGB(
2177  nOldPtsCount + i, gx, gy, gz, // XYZ
2178  inten, inten, inten // RGB
2179  );
2180  }
2181 }
void clear()
Erase all the contents of the map.
Definition: CMetricMap.cpp:30
#define IMPLEMENTS_VIRTUAL_SERIALIZABLE(class_name, base_class, NS)
This must be inserted as implementation of some required members for virtual CSerializable classes: ...
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
Definition: CPointsMap.cpp:721
void closestFromPointToLine(double Px, double Py, double x1, double y1, double x2, double y2, double &out_x, double &out_y)
Computes the closest point from a given point to a (infinite) line.
Definition: geometry.cpp:77
void writeToStream(mrpt::serialization::CArchive &out) const
Binary dump to stream - used in derived classes&#39; serialization.
Definition: CPointsMap.cpp:667
TLikelihoodOptions()
Initilization of default parameters.
void writeToStream(mrpt::serialization::CArchive &out) const
Binary dump to stream - for usage in derived classes&#39; serialization.
Definition: CPointsMap.cpp:642
void kdTreeNClosestPoint3DWithIdx(float x0, float y0, float z0, size_t knn, std::vector< float > &out_x, std::vector< float > &out_y, std::vector< float > &out_z, std::vector< size_t > &out_idx, std::vector< float > &out_dist_sqr) const
KD Tree-based search for the N closest points to some given 3D coordinates.
void insertAnotherMap(const CPointsMap *otherMap, const mrpt::poses::CPose3D &otherPose)
Insert the contents of another map into this one with some geometric transformation, without fusing close points.
Parameters for CMetricMap::compute3DMatchingRatio()
void keep_min(T &var, const K test_val)
If the second argument is below the first one, set the first argument to this lower value...
void getPoint(size_t index, float &x, float &y, float &z) const
Access to a given point from map, as a 2D point.
Definition: CPointsMap.cpp:198
void colormap(const TColormap &color_map, const float color_index, float &r, float &g, float &b)
Transform a float number in the range [0,1] into RGB components.
Definition: color_maps.cpp:114
A compile-time fixed-size numeric matrix container.
Definition: CMatrixFixed.h:33
bool isPlanarMap
If set to true, only HORIZONTAL (in the XY plane) measurements will be inserted in the map (Default v...
Definition: CPointsMap.h:254
mrpt::img::TColormap colormap
Colormap for points (index is "z" coordinates)
Definition: CPointsMap.h:331
virtual void addFrom(const CPointsMap &anotherMap)
Adds all the points from anotherMap to this map, without fusing.
void getPointFast(size_t index, float &x, float &y, float &z) const
Just like getPoint() but without checking out-of-bound index and without returning the point weight...
Definition: CPointsMap.h:499
Declares a class derived from "CObservation" that encapsules a single range measurement, and associated parameters.
#define MRPT_START
Definition: exceptions.h:241
A CObservation-derived class for RAW DATA (and optionally, point cloud) of scans from 3D Velodyne LID...
virtual void loadFromRangeScan(const mrpt::obs::CObservation2DRangeScan &rangeScan, const mrpt::poses::CPose3D *robotPose=nullptr)=0
Transform the range scan into a set of cartessian coordinated points.
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini"-like file or memory-stored string list.
Definition: CPointsMap.cpp:759
static Ptr Create(Args &&... args)
#define MRPT_TRY_END
The end of a standard MRPT "try...catch()" block that allows tracing throw the call stack after an ex...
Definition: exceptions.h:213
void internal_build_points_map_from_scan2D(const mrpt::obs::CObservation2DRangeScan &obs, mrpt::maps::CMetricMap::Ptr &out_map, const void *insertOps)
float sensorConeApperture
Cone aperture of each ultrasonic beam, in radians.
double x
X,Y coordinates.
Definition: TPose2D.h:30
#define THROW_EXCEPTION(msg)
Definition: exceptions.h:67
T x
X,Y coordinates.
Definition: TPoint2D.h:25
An observation from any sensor that can be summarized as a pointcloud.
bool enableSaveAs3DObject
(Default=true) If false, calling CMetricMap::getAs3DObject() will have no effects ...
size_t size(const MATRIXLIKE &m, const int dim)
int void fclose(FILE *f)
An OS-independent version of fclose.
Definition: os.cpp:275
#define ASSERT_BELOW_(__A, __B)
Definition: exceptions.h:149
const POINTSMAP * buildAuxPointsMap(const void *options=nullptr) const
Returns a cached points map representing this laser scan, building it upon the first call...
bool isHorizontal(const double tolerance=0) const
Return true if the 6D pose represents a Z axis almost exactly vertical (upwards or downwards)...
Definition: CPose3D.cpp:599
mrpt::img::TColorf color
Color of points.
Definition: CPointsMap.h:329
virtual void setPointAllFieldsFast(const size_t index, const std::vector< float > &point_data)=0
Set all the data fields for one point as a vector: depending on the implementation class this can be ...
const double G
void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const override
Returns a 3D object representing the map.
Definition: CPointsMap.cpp:772
void base_copyFrom(const CPointsMap &obj)
Helper method for ::copyFrom()
void setAllVertices(const std::vector< double > &x, const std::vector< double > &y)
Set all vertices at once.
Definition: CPolygon.cpp:121
A range or depth 3D scan measurement, as from a time-of-flight range camera or a structured-light dep...
void loadFromVelodyneScan(const mrpt::obs::CObservationVelodyneScan &scan, const mrpt::poses::CPose3D *robotPose=nullptr)
Like loadFromRangeScan() for Velodyne 3D scans.
mrpt::vision::TStereoCalibParams params
A wrapper of a TPolygon2D class, implementing CSerializable.
Definition: CPolygon.h:19
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
void internal_set_build_points_map_from_scan2D(scan2pts_functor fn)
void insertPoint(float x, float y, float z=0)
Provides a way to insert (append) individual points into the map: the missing fields of child classes...
Definition: CPointsMap.h:658
STL namespace.
virtual void getPointAllFieldsFast(const size_t index, std::vector< float > &point_data) const =0
Get all the data fields for one point as a vector: depending on the implementation class this can be ...
TMapGenericParams genericMapParams
Common params to all maps.
Definition: CMetricMap.h:274
virtual void reserve(size_t newLength)=0
Reserves memory for a given number of points: the size of the map does not change, it only reserves the memory.
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini"-like file or memory-stored string list.
Definition: CPointsMap.cpp:734
virtual void insertPointRGB(float x, float y, float z, [[maybe_unused]] float R, [[maybe_unused]] float G, [[maybe_unused]] float B)
overload (RGB data is ignored in classes without color information)
Definition: CPointsMap.h:669
void generatePointCloud(const TGeneratePointCloudParameters &params=TGeneratePointCloudParameters())
Generates the point cloud into the point cloud data fields in CObservationVelodyneScan::point_cloud w...
std::optional< std::reference_wrapper< T > > optional_ref
Shorter name for std::optional<std::reference_wrapper<T>>
Definition: optional_ref.h:20
void PLY_import_set_vertex(const size_t idx, const mrpt::math::TPoint3Df &pt, const mrpt::img::TColorf *pt_color=nullptr) override
In a base class, will be called after PLY_import_set_vertex_count() once for each loaded point...
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot/vehicle frame of reference.
size_t PLY_export_get_vertex_count() const override
In a base class, return the number of vertices.
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
Definition: CPointsMap.cpp:712
virtual unsigned int getPointWeight([[maybe_unused]] size_t index) const
Gets the point weight, which is ignored in all classes (defaults to 1) but in those which actually st...
Definition: CPointsMap.h:550
mrpt::math::TPose2D asTPose() const
Definition: CPose2D.cpp:468
float maxDistForCorr
(Default: 0.10f) The minimum distance between 2 non-probabilistic map elements for counting them as a...
static Ptr Create(Args &&... args)
Definition: CPointCloud.h:49
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
Definition: exceptions.h:97
#define MRPT_TRY_START
The start of a standard MRPT "try...catch()" block that allows tracing throw the call stack after an ...
Definition: exceptions.h:206
#define ASSERT_(f)
Defines an assertion mechanism.
Definition: exceptions.h:120
TPointCloud point_cloud
Optionally, raw data can be converted into a 3D point cloud (local coordinates wrt the sensor...
float d2f(const double d)
shortcut for static_cast<float>(double)
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors...
Definition: CPointsMap.h:67
This class allows loading and storing values and vectors of different types from a configuration text...
This base provides a set of functions for maths stuff.
double internal_computeObservationLikelihoodPointCloud3D(const mrpt::poses::CPose3D &pc_in_map, const float *xs, const float *ys, const float *zs, const std::size_t num_pts)
#define CLASS_ID(T)
Access to runtime class ID for a defined class name.
Definition: CObject.h:102
Additional results from the determination of matchings between point clouds, etc., apart from the pairings themselves.
double phi() const
Get the phi angle of the 2D pose (in radians)
Definition: CPose2D.h:86
void ReadAsAndCastTo(CAST_TO_TYPE &read_here)
Read a value from a stream stored in a type different of the target variable, making the conversion v...
Definition: CArchive.h:147
bool isPlanarScan(const double tolerance=0) const
Return true if the laser scanner is "horizontal", so it has an absolute value of "pitch" and "roll" l...
#define ASSERT_EQUAL_(__A, __B)
Assert comparing two values, reporting their actual values upon failure.
Definition: exceptions.h:137
double sigma_dist
Sigma squared (variance, in meters) of the exponential used to model the likelihood (default= 0...
Definition: CPointsMap.h:301
void getAllPoints(VECTOR &xs, VECTOR &ys, VECTOR &zs, size_t decimation=1) const
Returns a copy of the 2D/3D points as a std::vector of float coordinates.
Definition: CPointsMap.h:590
void loadFromRangeScan(const mrpt::obs::CObservation2DRangeScan &rangeScan, const mrpt::poses::CPose3D *robotPose=nullptr) override
See CPointsMap::loadFromRangeScan()
bool PointIntoPolygon(double x, double y) const
Check if a point is inside the polygon.
Definition: CPolygon.h:63
A list of TMatchingPair.
Definition: TMatchingPair.h:70
#define IS_DERIVED(obj, class_name)
True if the given reference to object (derived from mrpt::rtti::CObject) is an instance of the given ...
Definition: CObject.h:151
bool m_largestDistanceFromOriginIsUpdated
Auxiliary variables used in "getLargestDistanceFromOrigin".
Definition: CPointsMap.h:1148
void readFromStream(mrpt::serialization::CArchive &in)
Binary dump to stream - used in derived classes&#39; serialization.
Definition: CPointsMap.cpp:675
void extractCylinder(const mrpt::math::TPoint2D &center, const double radius, const double zmin, const double zmax, CPointsMap *outMap)
Extracts the points in the map within a cylinder in 3D defined the provided radius and zmin/zmax valu...
void fuseWith(CPointsMap *anotherMap, float minDistForFuse=0.02f, std::vector< bool > *notFusedPoints=nullptr)
Insert the contents of another map into this one, fusing the previous content with the new one...
void writeToStream(mrpt::serialization::CArchive &out) const
Binary dump to stream - for usage in derived classes&#39; serialization.
Definition: CPointsMap.cpp:606
This namespace contains representation of robot actions and observations.
string iniFile(myDataDir+string("benchmark-options.ini"))
void extractPoints(const mrpt::math::TPoint3D &corner1, const mrpt::math::TPoint3D &corner2, CPointsMap *outMap, double R=1, double G=1, double B=1)
Extracts the points in the map within the area defined by two corners.
#define IMPLEMENTS_MEXPLUS_FROM(complete_type)
#define IS_CLASS(obj, class_name)
True if the given reference to object (derived from mrpt::rtti::CObject) is of the given class...
Definition: CObject.h:146
virtual void addFrom_classSpecific(const CPointsMap &anotherMap, const size_t nPreviousPoints)=0
Auxiliary method called from within addFrom() automatically, to finish the copying of class-specific ...
TPoint3D_< double > TPoint3D
Lightweight 3D point.
Definition: TPoint3D.h:268
virtual void setPointWeight([[maybe_unused]] size_t index, [[maybe_unused]] unsigned long w)
Sets the point weight, which is ignored in all classes but those which actually store that field (Not...
Definition: CPointsMap.h:543
#define ASSERTMSG_(f, __ERROR_MSG)
Defines an assertion mechanism.
Definition: exceptions.h:108
double x() const
Common members of all points & poses classes.
Definition: CPoseOrPoint.h:143
float getLargestDistanceFromOrigin() const
This method returns the largest distance from the origin to any of the points, such as a sphere cente...
Definition: CPointsMap.cpp:822
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini"-like file or memory-stored string list.
Definition: CPointsMap.cpp:751
float m_largestDistanceFromOrigin
Auxiliary variables used in "getLargestDistanceFromOrigin".
Definition: CPointsMap.h:1143
void setPointFast(size_t index, float x, float y, float z)
Changes the coordinates of the given point (0-based index), without checking for out-of-bounds and wi...
Definition: CPointsMap.h:163
mrpt::maps::CPointsMap::Ptr pointcloud
The pointcloud.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
void compute3DDistanceToMesh(const mrpt::maps::CMetricMap *otherMap2, const mrpt::poses::CPose3D &otherMapPose, float maxDistForCorrespondence, mrpt::tfest::TMatchingPairList &correspondences, float &correspondencesRatio)
Computes the matchings between this and another 3D points map.
A structure for holding correspondences between two sets of points or points-like entities in 2D or 3...
Definition: TMatchingPair.h:31
struct mxArray_tag mxArray
Forward declaration for mxArray (avoid #including as much as possible to speed up compiling) ...
Definition: CSerializable.h:18
Undefined colormap [New in MRPT 2.0].
Definition: color_maps.h:33
void boundingBox(float &min_x, float &max_x, float &min_y, float &max_y, float &min_z, float &max_z) const
Computes the bounding box of all the points, or (0,0 ,0,0, 0,0) if there are no points.
Definition: CPointsMap.cpp:920
#define LOADABLEOPTS_DUMP_VAR(variableName, variableType)
Macro for dumping a variable to a stream, within the method "dumpToTextStream(out)" (Variable types a...
int fprintf(FILE *fil, const char *format,...) noexcept MRPT_printf_format_check(2
An OS-independent version of fprintf.
Definition: os.cpp:408
return_t square(const num_t x)
Inline function for the square of a number.
#define MRPT_LOAD_CONFIG_VAR( variableName, variableType, configFileObject, sectionNameStr)
An useful macro for loading variables stored in a INI-like file under a key with the same name that t...
mrpt::aligned_std_vector< float > m_z
Definition: CPointsMap.h:1135
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
Definition: CPointsMap.cpp:693
T x
X,Y,Z coordinates.
Definition: TPoint3D.h:29
double internal_computeObservationLikelihood(const mrpt::obs::CObservation &obs, const mrpt::poses::CPose3D &takenFrom) override
Internal method called by computeObservationLikelihood()
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
constexpr std::size_t size() const
Definition: TPoseOrPoint.h:67
virtual void resize(size_t newLength)=0
Resizes all point buffers so they can hold the given number of points: newly created points are set t...
void mark_as_modified() const
Users normally don&#39;t need to call this.
Definition: CPointsMap.h:1126
virtual const mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override
Returns information about the class of an object in runtime.
bool addToExistingPointsMap
Applicable to "loadFromRangeScan" only! If set to false, the points from the scan are loaded...
Definition: CPointsMap.h:239
Virtual base class for "archives": classes abstracting I/O streams.
Definition: CArchive.h:54
bool fuseWithExisting
If set to true (default=false), inserted points are "fused" with previously existent ones...
Definition: CPointsMap.h:250
mrpt::aligned_std_vector< float > m_y
Definition: CPointsMap.h:1135
float correspondencesRatio
The ratio [0,1] of points in otherMap with at least one correspondence.
TLikelihoodOptions likelihoodOptions
Definition: CPointsMap.h:310
void filterUniqueRobustPairs(const size_t num_elements_this_map, TMatchingPairList &out_filtered_list) const
Creates a filtered list of pairings with those ones which have a single correspondence which coincide...
void getPointsBuffer(size_t &outPointsCount, const float *&xs, const float *&ys, const float *&zs) const
Provides a direct access to points buffer, or nullptr if there is no points in the map...
Definition: CPointsMap.cpp:222
void setPoint(size_t index, float x, float y, float z)
Changes a given point from map, with Z defaulting to 0 if not provided.
Definition: CPointsMap.h:511
TRenderOptions renderOptions
Definition: CPointsMap.h:333
Declares a virtual base class for all metric maps storage classes.
Definition: CMetricMap.h:52
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
Definition: CPose2D.h:39
const float R
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:85
mrpt::vision::TStereoCalibResults out
Declares a class that represents any robot&#39;s observation.
Definition: CObservation.h:43
float compute3DMatchingRatio(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, const TMatchingRatioParams &params) const override
Computes the ratio in [0,1] of correspondences between "this" and the "otherMap" map, whose 6D pose relative to "this" is "otherMapPose" In the case of a multi-metric map, this returns the average between the maps.
Definition: CPointsMap.cpp:801
void kdtree_mark_as_outdated() const
To be called by child classes when KD tree data changes.
#define ASSERT_ABOVE_(__A, __B)
Definition: exceptions.h:155
#define MRPT_END
Definition: exceptions.h:245
An RGBA color - floats in the range [0,1].
Definition: TColor.h:88
#define LOADABLEOPTS_DUMP_VAR_DEG(variableName)
Macro for dumping a variable to a stream, transforming the argument from radians to degrees...
Lightweight 2D pose.
Definition: TPose2D.h:22
float horizontalTolerance
The tolerance in rads in pitch & roll for a laser scan to be considered horizontal, considered only when isPlanarMap=true (default=0).
Definition: CPointsMap.h:258
void determineMatching2D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose2D &otherMapPose, mrpt::tfest::TMatchingPairList &correspondences, const TMatchingParams &params, TMatchingExtraResults &extraResults) const override
Computes the matching between this and another 2D point map, which includes finding: ...
Definition: CPointsMap.cpp:281
bool derivedFrom(const TRuntimeClassId *pBaseClass) const
Definition: CObject.cpp:24
void readFromStream(mrpt::serialization::CArchive &in)
Binary dump to stream - for usage in derived classes&#39; serialization.
Definition: CPointsMap.cpp:618
bool internal_insertObservation(const mrpt::obs::CObservation &obs, const mrpt::poses::CPose3D *robotPose) override
This is a common version of CMetricMap::insertObservation() for point maps (actually, CMetricMap::internal_insertObservation), so derived classes don&#39;t need to worry implementing that method unless something special is really necesary.
void(*)(const mrpt::obs::CObservation2DRangeScan &obs, mrpt::maps::CMetricMap::Ptr &out_map, const void *insertOps) scan2pts_functor
TInsertionOptions insertionOptions
The options used when inserting observations in the map.
Definition: CPointsMap.h:274
MRPT_TODO("toPointCloud / calibration")
double max_corr_distance
Maximum distance in meters to consider for the numerator divided by "sigma_dist", so that each point ...
Definition: CPointsMap.h:305
FILE * fopen(const char *fileName, const char *mode) noexcept
An OS-independent version of fopen.
Definition: os.cpp:257
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::optional_ref< mrpt::math::CMatrixDouble33 > out_jacobian_df_dpoint=std::nullopt, mrpt::optional_ref< mrpt::math::CMatrixDouble36 > out_jacobian_df_dpose=std::nullopt, mrpt::optional_ref< mrpt::math::CMatrixDouble36 > out_jacobian_df_dse3=std::nullopt, bool use_small_rot_approx=false) const
An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose...
virtual const mrpt::maps::CSimplePointsMap * getAsSimplePointsMap() const
If the map is a simple points map or it&#39;s a multi-metric map that contains EXACTLY one simple points ...
Definition: CMetricMap.h:295
static TAuxLoadFunctor dummy_loader
#define MRPT_LOAD_CONFIG_VAR_DEGREES( variableName, configFileObject, sectionNameStr)
Loads a double variable, stored as radians but entered in the INI-file as degrees.
size_t kdTreeClosestPoint2D(float x0, float y0, float &out_x, float &out_y, float &out_dist_sqr) const
KD Tree-based search for the closest point (only ONE) to some given 2D coordinates.
virtual void insertPointFast(float x, float y, float z=0)=0
The virtual method for insertPoint() without calling mark_as_modified()
void determineMatching3D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, mrpt::tfest::TMatchingPairList &correspondences, const TMatchingParams &params, TMatchingExtraResults &extraResults) const override
Computes the matchings between this and another 3D points map - method used in 3D-ICP.
virtual void setPointRGB(size_t index, float x, float y, float z, [[maybe_unused]] float R, [[maybe_unused]] float G, [[maybe_unused]] float B)
overload (RGB data is ignored in classes without color information)
Definition: CPointsMap.h:533
float squareDistanceToClosestCorrespondence(float x0, float y0) const override
Returns the square distance from the 2D point (x0,y0) to the closest correspondence in the map...
Definition: CPointsMap.cpp:877
uint32_t decimation
Speed up the likelihood computation by considering only one out of N rays (default=10) ...
Definition: CPointsMap.h:308
Parameters for the determination of matchings between point clouds, etc.
mrpt::aligned_std_vector< float > m_x
The point coordinates.
Definition: CPointsMap.h:1135
size_t size() const
Save the point cloud as a PCL PCD file, in either ASCII or binary format.
Definition: CPointsMap.h:459
bool disableDeletion
If set to false (default=true) points in the same plane as the inserted scan and inside the free spac...
Definition: CPointsMap.h:246
Functions for estimating the optimal transformation between two frames of references given measuremen...
void clear()
Clear the contents of this container.
Definition: ts_hash_map.h:183
void getHomogeneousMatrix(mrpt::math::CMatrixDouble44 &out_HM) const
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (t...
Definition: CPose3D.cpp:781
double phi
Orientation (rads)
Definition: TPose2D.h:32
void PLY_export_get_vertex(const size_t idx, mrpt::math::TPoint3Df &pt, bool &pt_has_color, mrpt::img::TColorf &pt_color) const override
In a base class, will be called after PLY_export_get_vertex_count() once for each exported point...
float kdTreeClosestPoint2DsqrError(float x0, float y0) const
Like kdTreeClosestPoint2D, but just return the square error from some point to its closest neighbor...
void kdTreeTwoClosestPoint2D(float x0, float y0, float &out_x1, float &out_y1, float &out_x2, float &out_y2, float &out_dist_sqr1, float &out_dist_sqr2) const
KD Tree-based search for the TWO closest point to some given 2D coordinates.
double distance(const TPoint2D &p1, const TPoint2D &p2)
Gets the distance between two points in a 2D space.
Definition: geometry.cpp:1807
void applyDeletionMask(const std::vector< bool > &mask)
Remove from the map the points marked in a bool&#39;s array as "true".
int sprintf(char *buf, size_t bufSize, const char *format,...) noexcept MRPT_printf_format_check(3
An OS-independent version of sprintf (Notice the bufSize param, which may be ignored in some compiler...
size_t kdTreeClosestPoint3D(float x0, float y0, float z0, float &out_x, float &out_y, float &out_z, float &out_dist_sqr) const
KD Tree-based search for the closest point (only ONE) to some given 3D coordinates.
float minDistBetweenLaserPoints
The minimum distance between points (in 3D): If two points are too close, one of them is not inserted...
Definition: CPointsMap.h:235
void readFromStream(mrpt::serialization::CArchive &in)
Binary dump to stream - for usage in derived classes&#39; serialization.
Definition: CPointsMap.cpp:650
int round(const T value)
Returns the closer integer (int) to x.
Definition: round.h:24



Page generated by Doxygen 1.8.14 for MRPT 2.0.3 Git: 8e9e8af54 Wed May 13 17:41:24 2020 +0200 at miƩ may 13 17:55:54 CEST 2020