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



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019