Main MRPT website > C++ reference for MRPT 1.9.9
CPointsMap.h
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 #ifndef CPOINTSMAP_H
10 #define CPOINTSMAP_H
11 
12 #include <mrpt/maps/CMetricMap.h>
21 #include <mrpt/obs/obs_frwds.h>
22 #include <mrpt/utils/adapters.h>
23 
24 // Add for declaration of mexplus::from template specialization
26 
27 namespace mrpt
28 {
29 /** \ingroup mrpt_maps_grp */
30 namespace maps
31 {
32 // Forward decls. needed to make its static methods friends of CPointsMap
33 namespace detail
34 {
35 template <class Derived>
37 template <class Derived>
39 }
40 
41 /** A cloud of points in 2D or 3D, which can be built from a sequence of laser
42  * scans or other sensors.
43  * This is a virtual class, thus only a derived class can be instantiated by
44  * the user. The user most usually wants to use CSimplePointsMap.
45  *
46  * This class implements generic version of
47  * mrpt::maps::CMetric::insertObservation() accepting these types of sensory
48  * data:
49  * - mrpt::obs::CObservation2DRangeScan: 2D range scans
50  * - mrpt::obs::CObservation3DRangeScan: 3D range scans (Kinect, etc...)
51  * - mrpt::obs::CObservationRange: IRs, Sonars, etc.
52  * - mrpt::obs::CObservationVelodyneScan
53  *
54  * Loading and saving in the standard LAS LiDAR point cloud format is supported
55  * by installing `libLAS` and including the
56  * header `<mrpt/maps/CPointsMaps_liblas.h>` in your program. Since MRPT 1.5.0
57  * there is no need to build MRPT against libLAS to use this feature.
58  * See LAS functions in \ref mrpt_maps_liblas_grp.
59  *
60  * \sa CMetricMap, CPoint, mrpt::utils::CSerializable
61  * \ingroup mrpt_maps_grp
62  */
63 class CPointsMap : public CMetricMap,
64  public mrpt::math::KDTreeCapable<CPointsMap>,
67 {
69  // This must be added for declaration of MEX-related functions
71 
72  protected:
73  /** Helper struct used for \a internal_loadFromRangeScan2D_prepareOneRange()
74  */
76  {
78  const mrpt::obs::CObservation2DRangeScan& _rangeScan)
79  : HM(mrpt::math::UNINITIALIZED_MATRIX), rangeScan(_rangeScan)
80  {
81  }
82  /** Homog matrix of the local sensor pose within the robot */
85  /** Extra variables to be used as desired by the derived class. */
86  std::vector<float> fVars;
87  std::vector<unsigned int> uVars;
88  std::vector<uint8_t> bVars;
89  };
90 
91  /** Helper struct used for \a internal_loadFromRangeScan3D_prepareOneRange()
92  */
94  {
96  const mrpt::obs::CObservation3DRangeScan& _rangeScan)
97  : HM(mrpt::math::UNINITIALIZED_MATRIX), rangeScan(_rangeScan)
98  {
99  }
100  /** Homog matrix of the local sensor pose within the robot */
103  /** In \a internal_loadFromRangeScan3D_prepareOneRange, these are the
104  * local coordinates of the scan points being inserted right now. */
106  /** Extra variables to be used as desired by the derived class. */
107  std::vector<float> fVars;
108  std::vector<unsigned int> uVars;
109  std::vector<uint8_t> bVars;
110  };
111 
112  public:
113  /** Ctor */
114  CPointsMap();
115  /** Virtual destructor. */
116  virtual ~CPointsMap();
117 
118  // --------------------------------------------
119  /** @name Pure virtual interfaces to be implemented by any class derived
120  from CPointsMap
121  @{ */
122 
123  /** Reserves memory for a given number of points: the size of the map does
124  * not change, it only reserves the memory.
125  * This is useful for situations where it is approximately known the final
126  * size of the map. This method is more
127  * efficient than constantly increasing the size of the buffers. Refer to
128  * the STL C++ library's "reserve" methods.
129  */
130  virtual void reserve(size_t newLength) = 0;
131 
132  /** Resizes all point buffers so they can hold the given number of points:
133  * newly created points are set to default values,
134  * and old contents are not changed.
135  * \sa reserve, setPoint, setPointFast, setSize
136  */
137  virtual void resize(size_t newLength) = 0;
138 
139  /** Resizes all point buffers so they can hold the given number of points,
140  * *erasing* all previous contents
141  * and leaving all points to default values.
142  * \sa reserve, setPoint, setPointFast, setSize
143  */
144  virtual void setSize(size_t newLength) = 0;
145 
146  /** Changes the coordinates of the given point (0-based index), *without*
147  * checking for out-of-bounds and *without* calling mark_as_modified() \sa
148  * setPoint */
149  virtual void setPointFast(size_t index, float x, float y, float z) = 0;
150 
151  /** The virtual method for \a insertPoint() *without* calling
152  * mark_as_modified() */
153  virtual void insertPointFast(float x, float y, float z = 0) = 0;
154 
155  /** Virtual assignment operator, copies as much common data (XYZ, color,...)
156  * as possible from the source map into this one. */
157  virtual void copyFrom(const CPointsMap& obj) = 0;
158 
159  /** Get all the data fields for one point as a vector: depending on the
160  * implementation class this can be [X Y Z] or [X Y Z R G B], etc...
161  * Unlike getPointAllFields(), this method does not check for index out of
162  * bounds
163  * \sa getPointAllFields, setPointAllFields, setPointAllFieldsFast
164  */
165  virtual void getPointAllFieldsFast(
166  const size_t index, std::vector<float>& point_data) const = 0;
167 
168  /** Set all the data fields for one point as a vector: depending on the
169  * implementation class this can be [X Y Z] or [X Y Z R G B], etc...
170  * Unlike setPointAllFields(), this method does not check for index out of
171  * bounds
172  * \sa setPointAllFields, getPointAllFields, getPointAllFieldsFast
173  */
174  virtual void setPointAllFieldsFast(
175  const size_t index, const std::vector<float>& point_data) = 0;
176 
177  protected:
178  /** Auxiliary method called from within \a addFrom() automatically, to
179  * finish the copying of class-specific data */
180  virtual void addFrom_classSpecific(
181  const CPointsMap& anotherMap, const size_t nPreviousPoints) = 0;
182 
183  public:
184  /** @} */
185  // --------------------------------------------
186 
187  /** Returns the square distance from the 2D point (x0,y0) to the closest
188  * correspondence in the map.
189  */
191  float x0, float y0) const override;
192 
194  const mrpt::math::TPoint2D& p0) const
195  {
197  static_cast<float>(p0.x), static_cast<float>(p0.y));
198  }
199 
200  /** With this struct options are provided to the observation insertion
201  * process.
202  * \sa CObservation::insertIntoPointsMap
203  */
205  {
206  /** Initilization of default parameters */
208  void loadFromConfigFile(
210  const std::string& section) override; // See base docs
211  void dumpToTextStream(
212  mrpt::utils::CStream& out) const override; // See base docs
213 
214  /** The minimum distance between points (in 3D): If two points are too
215  * close, one of them is not inserted into the map. Default is 0.02
216  * meters. */
218  /** Applicable to "loadFromRangeScan" only! If set to false, the points
219  * from the scan are loaded, clearing all previous content. Default is
220  * false. */
222  /** If set to true, far points (<1m) are interpolated with samples at
223  * "minDistSqrBetweenLaserPoints" intervals (Default is false). */
225  /** If set to false (default=true) points in the same plane as the
226  * inserted scan and inside the free space, are erased: i.e. they don't
227  * exist yet. */
229  /** If set to true (default=false), inserted points are "fused" with
230  * previously existent ones. This shrink the size of the points map, but
231  * its slower. */
233  /** If set to true, only HORIZONTAL (in the XY plane) measurements will
234  * be inserted in the map (Default value is false, thus 3D maps are
235  * generated). \sa horizontalTolerance */
237  /** The tolerance in rads in pitch & roll for a laser scan to be
238  * considered horizontal, considered only when isPlanarMap=true
239  * (default=0). */
241  /** The maximum distance between two points to interpolate between them
242  * (ONLY when also_interpolate=true) */
244  /** Points with x,y,z coordinates set to zero will also be inserted */
246 
247  /** Binary dump to stream - for usage in derived classes' serialization
248  */
249  void writeToStream(mrpt::utils::CStream& out) const;
250  /** Binary dump to stream - for usage in derived classes' serialization
251  */
253  };
254 
255  /** The options used when inserting observations in the map */
257 
258  /** Options used when evaluating "computeObservationLikelihood" in the
259  * derived classes.
260  * \sa CObservation::computeObservationLikelihood
261  */
263  {
264  /** Initilization of default parameters
265  */
267  virtual ~TLikelihoodOptions() {}
268  void loadFromConfigFile(
270  const std::string& section) override; // See base docs
271  void dumpToTextStream(
272  mrpt::utils::CStream& out) const override; // See base docs
273 
274  /** Binary dump to stream - for usage in derived classes' serialization
275  */
276  void writeToStream(mrpt::utils::CStream& out) const;
277  /** Binary dump to stream - for usage in derived classes' serialization
278  */
280 
281  /** Sigma squared (variance, in meters) of the exponential used to model
282  * the likelihood (default= 0.5^2 meters) */
283  double sigma_dist;
284  /** Maximum distance in meters to consider for the numerator divided by
285  * "sigma_dist", so that each point has a minimum (but very small)
286  * likelihood to avoid underflows (default=1.0 meters) */
288  /** Speed up the likelihood computation by considering only one out of N
289  * rays (default=10) */
291  };
292 
294 
295  /** Adds all the points from \a anotherMap to this map, without fusing.
296  * This operation can be also invoked via the "+=" operator, for example:
297  * \code
298  * mrpt::maps::CSimplePointsMap m1, m2;
299  * ...
300  * m1.addFrom( m2 ); // Add all points of m2 to m1
301  * m1 += m2; // Exactly the same than above
302  * \endcode
303  * \note The method in CPointsMap is generic but derived classes may
304  * redefine this virtual method to another one more optimized.
305  */
306  virtual void addFrom(const CPointsMap& anotherMap);
307 
308  /** This operator is synonymous with \a addFrom. \sa addFrom */
309  inline void operator+=(const CPointsMap& anotherMap)
310  {
311  this->addFrom(anotherMap);
312  }
313 
314  /** Insert the contents of another map into this one with some geometric
315  * transformation, without fusing close points.
316  * \param otherMap The other map whose points are to be inserted into this
317  * one.
318  * \param otherPose The pose of the other map in the coordinates of THIS map
319  * \sa fuseWith, addFrom
320  */
321  void insertAnotherMap(
322  const CPointsMap* otherMap, const mrpt::poses::CPose3D& otherPose);
323 
324  // --------------------------------------------------
325  /** @name File input/output methods
326  @{ */
327 
328  /** Load from a text file. Each line should contain an "X Y" coordinate
329  * pair, separated by whitespaces.
330  * Returns false if any error occured, true elsewere.
331  */
332  inline bool load2D_from_text_file(const std::string& file)
333  {
334  return load2Dor3D_from_text_file(file, false);
335  }
336 
337  /** Load from a text file. Each line should contain an "X Y Z" coordinate
338  * tuple, separated by whitespaces.
339  * Returns false if any error occured, true elsewere.
340  */
341  inline bool load3D_from_text_file(const std::string& file)
342  {
343  return load2Dor3D_from_text_file(file, true);
344  }
345 
346  /** 2D or 3D generic implementation of \a load2D_from_text_file and
347  * load3D_from_text_file */
348  bool load2Dor3D_from_text_file(const std::string& file, const bool is_3D);
349 
350  /** Save to a text file. Each line will contain "X Y" point coordinates.
351  * Returns false if any error occured, true elsewere.
352  */
353  bool save2D_to_text_file(const std::string& file) const;
354 
355  /** Save to a text file. Each line will contain "X Y Z" point coordinates.
356  * Returns false if any error occured, true elsewere.
357  */
358  bool save3D_to_text_file(const std::string& file) const;
359 
360  /** This virtual method saves the map to a file "filNamePrefix"+<
361  * some_file_extension >, as an image or in any other applicable way (Notice
362  * that other methods to save the map may be implemented in classes
363  * implementing this virtual interface) */
365  const std::string& filNamePrefix) const override
366  {
367  std::string fil(filNamePrefix + std::string(".txt"));
368  save3D_to_text_file(fil);
369  }
370 
371  /** Save the point cloud as a PCL PCD file, in either ASCII or binary format
372  * (requires MRPT built against PCL) \return false on any error */
373  virtual bool savePCDFile(
374  const std::string& filename, bool save_as_binary) const;
375 
376  /** Load the point cloud from a PCL PCD file (requires MRPT built against
377  * PCL) \return false on any error */
378  virtual bool loadPCDFile(const std::string& filename);
379 
380  /** @} */ // End of: File input/output methods
381  // --------------------------------------------------
382 
383  /** Returns the number of stored points in the map.
384  */
385  inline size_t size() const { return x.size(); }
386  /** Access to a given point from map, as a 2D point. First index is 0.
387  * \return The return value is the weight of the point (the times it has
388  * been fused), or 1 if weights are not used.
389  * \exception Throws std::exception on index out of bound.
390  * \sa setPoint, getPointFast
391  */
392  unsigned long getPoint(size_t index, float& x, float& y, float& z) const;
393  /// \overload
394  unsigned long getPoint(size_t index, float& x, float& y) const;
395  /// \overload
396  unsigned long getPoint(size_t index, double& x, double& y, double& z) const;
397  /// \overload
398  unsigned long getPoint(size_t index, double& x, double& y) const;
399  /// \overload
400  inline unsigned long getPoint(size_t index, mrpt::math::TPoint2D& p) const
401  {
402  return getPoint(index, p.x, p.y);
403  }
404  /// \overload
405  inline unsigned long getPoint(size_t index, mrpt::math::TPoint3D& p) const
406  {
407  return getPoint(index, p.x, p.y, p.z);
408  }
409 
410  /** Access to a given point from map, and its colors, if the map defines
411  * them (othersise, R=G=B=1.0). First index is 0.
412  * \return The return value is the weight of the point (the times it has
413  * been fused)
414  * \exception Throws std::exception on index out of bound.
415  */
416  virtual void getPoint(
417  size_t index, float& x, float& y, float& z, float& R, float& G,
418  float& B) const
419  {
420  getPoint(index, x, y, z);
421  R = G = B = 1;
422  }
423 
424  /** Just like \a getPoint() but without checking out-of-bound index and
425  * without returning the point weight, just XYZ.
426  */
427  inline void getPointFast(size_t index, float& x, float& y, float& z) const
428  {
429  x = this->x[index];
430  y = this->y[index];
431  z = this->z[index];
432  }
433 
434  /** Returns true if the point map has a color field for each point */
435  virtual bool hasColorPoints() const { return false; }
436  /** Changes a given point from map, with Z defaulting to 0 if not provided.
437  * \exception Throws std::exception on index out of bound.
438  */
439  inline void setPoint(size_t index, float x, float y, float z)
440  {
441  ASSERT_BELOW_(index, this->size())
442  setPointFast(index, x, y, z);
444  }
445  /// \overload
446  inline void setPoint(size_t index, const mrpt::math::TPoint2D& p)
447  {
448  setPoint(index, p.x, p.y, 0);
449  }
450  /// \overload
451  inline void setPoint(size_t index, const mrpt::math::TPoint3D& p)
452  {
453  setPoint(index, p.x, p.y, p.z);
454  }
455  /// \overload
456  inline void setPoint(size_t index, float x, float y)
457  {
458  setPoint(index, x, y, 0);
459  }
460  /// overload (RGB data is ignored in classes without color information)
461  virtual void setPoint(
462  size_t index, float x, float y, float z, float R, float G, float B)
463  {
467  setPoint(index, x, y, z);
468  }
469 
470  /// Sets the point weight, which is ignored in all classes but those which
471  /// actually store that field (Note: No checks are done for out-of-bounds
472  /// index). \sa getPointWeight
473  virtual void setPointWeight(size_t index, unsigned long w)
474  {
477  }
478  /// Gets the point weight, which is ignored in all classes (defaults to 1)
479  /// but in those which actually store that field (Note: No checks are done
480  /// for out-of-bounds index). \sa setPointWeight
481  virtual unsigned int getPointWeight(size_t index) const
482  {
484  return 1;
485  }
486 
487  /** Provides a direct access to points buffer, or nullptr if there is no
488  * points in the map.
489  */
490  void getPointsBuffer(
491  size_t& outPointsCount, const float*& xs, const float*& ys,
492  const float*& zs) const;
493 
494  /** Provides a direct access to a read-only reference of the internal point
495  * buffer. \sa getAllPoints */
496  inline const std::vector<float>& getPointsBufferRef_x() const { return x; }
497  /** Provides a direct access to a read-only reference of the internal point
498  * buffer. \sa getAllPoints */
499  inline const std::vector<float>& getPointsBufferRef_y() const { return y; }
500  /** Provides a direct access to a read-only reference of the internal point
501  * buffer. \sa getAllPoints */
502  inline const std::vector<float>& getPointsBufferRef_z() const { return z; }
503  /** Returns a copy of the 2D/3D points as a std::vector of float
504  * coordinates.
505  * If decimation is greater than 1, only 1 point out of that number will be
506  * saved in the output, effectively performing a subsampling of the points.
507  * \sa getPointsBufferRef_x, getPointsBufferRef_y, getPointsBufferRef_z
508  * \tparam VECTOR can be std::vector<float or double> or any row/column
509  * Eigen::Array or Eigen::Matrix (this includes mrpt::math::CVectorFloat and
510  * mrpt::math::CVectorDouble).
511  */
512  template <class VECTOR>
514  VECTOR& xs, VECTOR& ys, VECTOR& zs, size_t decimation = 1) const
515  {
516  MRPT_START
517  ASSERT_(decimation > 0)
518  const size_t Nout = x.size() / decimation;
519  xs.resize(Nout);
520  ys.resize(Nout);
521  zs.resize(Nout);
522  size_t idx_in, idx_out;
523  for (idx_in = 0, idx_out = 0; idx_out < Nout;
524  idx_in += decimation, ++idx_out)
525  {
526  xs[idx_out] = x[idx_in];
527  ys[idx_out] = y[idx_in];
528  zs[idx_out] = z[idx_in];
529  }
530  MRPT_END
531  }
532 
533  /** Gets all points as a STL-like container.
534  * \tparam CONTAINER Any STL-like container of mrpt::math::TPoint3D,
535  * mrpt::math::TPoint3Df or anything having members `x`,`y`,`z`.
536  * Note that this method is not efficient for large point clouds. Fastest
537  * methods are getPointsBuffer() or getPointsBufferRef_x(),
538  * getPointsBufferRef_y(), getPointsBufferRef_z()
539  */
540  template <class CONTAINER>
541  void getAllPoints(CONTAINER& ps, size_t decimation = 1) const
542  {
543  std::vector<float> dmy1, dmy2, dmy3;
544  getAllPoints(dmy1, dmy2, dmy3, decimation);
545  ps.resize(dmy1.size());
546  for (size_t i = 0; i < dmy1.size(); i++)
547  {
548  ps[i].x = dmy1[i];
549  ps[i].y = dmy2[i];
550  ps[i].z = dmy3[i];
551  }
552  }
553 
554  /** Returns a copy of the 2D/3D points as a std::vector of float
555  * coordinates.
556  * If decimation is greater than 1, only 1 point out of that number will be
557  * saved in the output, effectively performing a subsampling of the points.
558  * \sa setAllPoints
559  */
560  void getAllPoints(
561  std::vector<float>& xs, std::vector<float>& ys,
562  size_t decimation = 1) const;
563 
564  inline void getAllPoints(
565  std::vector<mrpt::math::TPoint2D>& ps, size_t decimation = 1) const
566  {
567  std::vector<float> dmy1, dmy2;
568  getAllPoints(dmy1, dmy2, decimation);
569  ps.resize(dmy1.size());
570  for (size_t i = 0; i < dmy1.size(); i++)
571  {
572  ps[i].x = static_cast<double>(dmy1[i]);
573  ps[i].y = static_cast<double>(dmy2[i]);
574  }
575  }
576 
577  /** Provides a way to insert (append) individual points into the map: the
578  * missing fields of child
579  * classes (color, weight, etc) are left to their default values
580  */
581  inline void insertPoint(float x, float y, float z = 0)
582  {
583  insertPointFast(x, y, z);
585  }
586  /// \overload
587  inline void insertPoint(const mrpt::math::TPoint3D& p)
588  {
589  insertPoint(p.x, p.y, p.z);
590  }
591  /// overload (RGB data is ignored in classes without color information)
592  virtual void insertPoint(
593  float x, float y, float z, float R, float G, float B)
594  {
598  insertPoint(x, y, z);
599  }
600 
601  /** Set all the points at once from vectors with X,Y and Z coordinates (if Z
602  * is not provided, it will be set to all zeros).
603  * \tparam VECTOR can be mrpt::math::CVectorFloat or std::vector<float> or
604  * any other column or row Eigen::Matrix.
605  */
606  template <typename VECTOR>
607  inline void setAllPointsTemplate(
608  const VECTOR& X, const VECTOR& Y, const VECTOR& Z = VECTOR())
609  {
610  const size_t N = X.size();
611  ASSERT_EQUAL_(X.size(), Y.size())
612  ASSERT_(Z.size() == 0 || Z.size() == X.size())
613  this->setSize(N);
614  const bool z_valid = !Z.empty();
615  if (z_valid)
616  for (size_t i = 0; i < N; i++)
617  {
618  this->setPointFast(i, X[i], Y[i], Z[i]);
619  }
620  else
621  for (size_t i = 0; i < N; i++)
622  {
623  this->setPointFast(i, X[i], Y[i], 0);
624  }
626  }
627 
628  /** Set all the points at once from vectors with X,Y and Z coordinates. \sa
629  * getAllPoints */
630  inline void setAllPoints(
631  const std::vector<float>& X, const std::vector<float>& Y,
632  const std::vector<float>& Z)
633  {
634  setAllPointsTemplate(X, Y, Z);
635  }
636 
637  /** Set all the points at once from vectors with X and Y coordinates (Z=0).
638  * \sa getAllPoints */
639  inline void setAllPoints(
640  const std::vector<float>& X, const std::vector<float>& Y)
641  {
642  setAllPointsTemplate(X, Y);
643  }
644 
645  /** Get all the data fields for one point as a vector: depending on the
646  * implementation class this can be [X Y Z] or [X Y Z R G B], etc...
647  * \sa getPointAllFieldsFast, setPointAllFields, setPointAllFieldsFast
648  */
650  const size_t index, std::vector<float>& point_data) const
651  {
652  ASSERT_BELOW_(index, this->size())
653  getPointAllFieldsFast(index, point_data);
654  }
655 
656  /** Set all the data fields for one point as a vector: depending on the
657  * implementation class this can be [X Y Z] or [X Y Z R G B], etc...
658  * Unlike setPointAllFields(), this method does not check for index out of
659  * bounds
660  * \sa setPointAllFields, getPointAllFields, getPointAllFieldsFast
661  */
663  const size_t index, const std::vector<float>& point_data)
664  {
665  ASSERT_BELOW_(index, this->size())
666  setPointAllFieldsFast(index, point_data);
667  }
668 
669  /** Delete points out of the given "z" axis range have been removed.
670  */
671  void clipOutOfRangeInZ(float zMin, float zMax);
672 
673  /** Delete points which are more far than "maxRange" away from the given
674  * "point".
675  */
676  void clipOutOfRange(const mrpt::math::TPoint2D& point, float maxRange);
677 
678  /** Remove from the map the points marked in a bool's array as "true".
679  * \exception std::exception If mask size is not equal to points count.
680  */
681  void applyDeletionMask(const std::vector<bool>& mask);
682 
683  // See docs in base class.
684  virtual void determineMatching2D(
685  const mrpt::maps::CMetricMap* otherMap,
686  const mrpt::poses::CPose2D& otherMapPose,
687  mrpt::utils::TMatchingPairList& correspondences,
688  const TMatchingParams& params,
689  TMatchingExtraResults& extraResults) const override;
690 
691  // See docs in base class
692  virtual void determineMatching3D(
693  const mrpt::maps::CMetricMap* otherMap,
694  const mrpt::poses::CPose3D& otherMapPose,
695  mrpt::utils::TMatchingPairList& correspondences,
696  const TMatchingParams& params,
697  TMatchingExtraResults& extraResults) const override;
698 
699  // See docs in base class
701  const mrpt::maps::CMetricMap* otherMap,
702  const mrpt::poses::CPose3D& otherMapPose,
703  const TMatchingRatioParams& params) const override;
704 
705  /** Computes the matchings between this and another 3D points map.
706  This method matches each point in the other map with the centroid of the
707  3 closest points in 3D
708  from this map (if the distance is below a defined threshold).
709  * \param otherMap [IN] The other map to compute the
710  matching with.
711  * \param otherMapPose [IN] The pose of the other map as seen
712  from "this".
713  * \param maxDistForCorrespondence [IN] Maximum 2D linear distance
714  between two points to be matched.
715  * \param correspondences [OUT] The detected matchings pairs.
716  * \param correspondencesRatio [OUT] The ratio [0,1] of points in
717  otherMap with at least one correspondence.
718  *
719  * \sa determineMatching3D
720  */
722  const mrpt::maps::CMetricMap* otherMap2,
723  const mrpt::poses::CPose3D& otherMapPose,
724  float maxDistForCorrespondence,
725  mrpt::utils::TMatchingPairList& correspondences,
726  float& correspondencesRatio);
727 
728  /** Transform the range scan into a set of cartessian coordinated
729  * points. The options in "insertionOptions" are considered in this
730  *method.
731  * \param rangeScan The scan to be inserted into this map
732  * \param robotPose Default to (0,0,0|0deg,0deg,0deg). Changes the frame of
733  *reference for the point cloud (i.e. the vehicle/robot pose in world
734  *coordinates).
735  *
736  * Only ranges marked as "valid=true" in the observation will be inserted
737  *
738  * \note Each derived class may enrich points in different ways (color,
739  *weight, etc..), so please refer to the description of the specific
740  * implementation of mrpt::maps::CPointsMap you are using.
741  * \note The actual generic implementation of this file lives in
742  *<src>/CPointsMap_crtp_common.h, but specific instantiations are generated
743  *at each derived class.
744  *
745  * \sa CObservation2DRangeScan, CObservation3DRangeScan
746  */
747  virtual void loadFromRangeScan(
748  const mrpt::obs::CObservation2DRangeScan& rangeScan,
749  const mrpt::poses::CPose3D* robotPose = nullptr) = 0;
750 
751  /** Overload of \a loadFromRangeScan() for 3D range scans (for example,
752  * Kinect observations).
753  *
754  * \param rangeScan The scan to be inserted into this map
755  * \param robotPose Default to (0,0,0|0deg,0deg,0deg). Changes the frame of
756  * reference for the point cloud (i.e. the vehicle/robot pose in world
757  * coordinates).
758  *
759  * \note Each derived class may enrich points in different ways (color,
760  * weight, etc..), so please refer to the description of the specific
761  * implementation of mrpt::maps::CPointsMap you are using.
762  * \note The actual generic implementation of this file lives in
763  * <src>/CPointsMap_crtp_common.h, but specific instantiations are generated
764  * at each derived class.
765  * \sa loadFromVelodyneScan
766  */
767  virtual void loadFromRangeScan(
768  const mrpt::obs::CObservation3DRangeScan& rangeScan,
769  const mrpt::poses::CPose3D* robotPose = nullptr) = 0;
770 
771  /** Like \a loadFromRangeScan() for Velodyne 3D scans. Points are translated
772  * and rotated according to the \a sensorPose field in the observation and,
773  * if provided, to the \a robotPose parameter.
774  *
775  * \param scan The Raw LIDAR data to be inserted into this map. It MUST
776  * contain point cloud data, generated by calling to \a
777  * mrpt::obs::CObservationVelodyneScan::generatePointCloud() prior to
778  * insertion in this map.
779  * \param robotPose Default to (0,0,0|0deg,0deg,0deg). Changes the frame of
780  * reference for the point cloud (i.e. the vehicle/robot pose in world
781  * coordinates).
782  * \sa loadFromRangeScan
783  */
786  const mrpt::poses::CPose3D* robotPose = nullptr);
787 
788  /** Insert the contents of another map into this one, fusing the previous
789  *content with the new one.
790  * This means that points very close to existing ones will be "fused",
791  *rather than "added". This prevents
792  * the unbounded increase in size of these class of maps.
793  * NOTICE that "otherMap" is neither translated nor rotated here, so if
794  *this is desired it must done
795  * before calling this method.
796  * \param otherMap The other map whose points are to be inserted into this
797  *one.
798  * \param minDistForFuse Minimum distance (in meters) between two points,
799  *each one in a map, to be considered the same one and be fused rather than
800  *added.
801  * \param notFusedPoints If a pointer is supplied, this list will contain at
802  *output a list with a "bool" value per point in "this" map. This will be
803  *false/true according to that point having been fused or not.
804  * \sa loadFromRangeScan, addFrom
805  */
806  void fuseWith(
807  CPointsMap* anotherMap, float minDistForFuse = 0.02f,
808  std::vector<bool>* notFusedPoints = nullptr);
809 
810  /** Replace each point \f$ p_i \f$ by \f$ p'_i = b \oplus p_i \f$ (pose
811  * compounding operator).
812  */
814 
815  /** Replace each point \f$ p_i \f$ by \f$ p'_i = b \oplus p_i \f$ (pose
816  * compounding operator).
817  */
819 
820  /** Copy all the points from "other" map to "this", replacing each point \f$
821  * p_i \f$ by \f$ p'_i = b \oplus p_i \f$ (pose compounding operator).
822  */
824  const CPointsMap& other, const mrpt::poses::CPose3D& b);
825 
826  /** Returns true if the map is empty/no observation has been inserted.
827  */
828  virtual bool isEmpty() const override;
829 
830  /** STL-like method to check whether the map is empty: */
831  inline bool empty() const { return isEmpty(); }
832  /** Returns a 3D object representing the map.
833  * The color of the points is controlled by COLOR_3DSCENE()
834  * \sa mrpt::global_settings::POINTSMAPS_3DOBJECT_POINTSIZE
835  */
836  virtual void getAs3DObject(
837  mrpt::opengl::CSetOfObjects::Ptr& outObj) const override;
838 
839  /** If the map is a simple points map or it's a multi-metric map that
840  * contains EXACTLY one simple points map, return it.
841  * Otherwise, return NULL
842  */
844  const override
845  {
846  return nullptr;
847  }
849  {
850  return nullptr;
851  }
852 
853  /** This method returns the largest distance from the origin to any of the
854  * points, such as a sphere centered at the origin with this radius cover
855  * ALL the points in the map (the results are buffered, such as, if the map
856  * is not modified, the second call will be much faster than the first one).
857  */
858  float getLargestDistanceFromOrigin() const;
859 
860  /** Like \a getLargestDistanceFromOrigin() but returns in \a output_is_valid
861  * = false if the distance was not already computed, skipping its
862  * computation then, unlike getLargestDistanceFromOrigin() */
863  float getLargestDistanceFromOriginNoRecompute(bool& output_is_valid) const
864  {
865  output_is_valid = m_largestDistanceFromOriginIsUpdated;
867  }
868 
869  /** Computes the bounding box of all the points, or (0,0 ,0,0, 0,0) if there
870  * are no points.
871  * Results are cached unless the map is somehow modified to avoid repeated
872  * calculations.
873  */
874  void boundingBox(
875  float& min_x, float& max_x, float& min_y, float& max_y, float& min_z,
876  float& max_z) const;
877 
878  inline void boundingBox(
879  mrpt::math::TPoint3D& pMin, mrpt::math::TPoint3D& pMax) const
880  {
881  float dmy1, dmy2, dmy3, dmy4, dmy5, dmy6;
882  boundingBox(dmy1, dmy2, dmy3, dmy4, dmy5, dmy6);
883  pMin.x = dmy1;
884  pMin.y = dmy3;
885  pMin.z = dmy5;
886  pMax.x = dmy2;
887  pMax.y = dmy4;
888  pMax.z = dmy6;
889  }
890 
891  /** Extracts the points in the map within a cylinder in 3D defined the
892  * provided radius and zmin/zmax values.
893  */
894  void extractCylinder(
895  const mrpt::math::TPoint2D& center, const double radius,
896  const double zmin, const double zmax, CPointsMap* outMap);
897 
898  /** Extracts the points in the map within the area defined by two corners.
899  * The points are coloured according the R,G,B input data.
900  */
901  void extractPoints(
902  const mrpt::math::TPoint3D& corner1,
903  const mrpt::math::TPoint3D& corner2, CPointsMap* outMap,
904  const double& R = 1, const double& G = 1, const double& B = 1);
905 
906  /** @name Filter-by-height stuff
907  @{ */
908 
909  /** Enable/disable the filter-by-height functionality \sa
910  * setHeightFilterLevels \note Default upon construction is disabled. */
911  inline void enableFilterByHeight(bool enable = true)
912  {
913  m_heightfilter_enabled = enable;
914  }
915  /** Return whether filter-by-height is enabled \sa enableFilterByHeight */
916  inline bool isFilterByHeightEnabled() const
917  {
918  return m_heightfilter_enabled;
919  }
920 
921  /** Set the min/max Z levels for points to be actually inserted in the map
922  * (only if \a enableFilterByHeight() was called before). */
923  inline void setHeightFilterLevels(const double _z_min, const double _z_max)
924  {
925  m_heightfilter_z_min = _z_min;
926  m_heightfilter_z_max = _z_max;
927  }
928  /** Get the min/max Z levels for points to be actually inserted in the map
929  * \sa enableFilterByHeight, setHeightFilterLevels */
930  inline void getHeightFilterLevels(double& _z_min, double& _z_max) const
931  {
932  _z_min = m_heightfilter_z_min;
933  _z_max = m_heightfilter_z_max;
934  }
935 
936  /** @} */
937 
938  /** The color of points in getAs3DObject() (default=blue) */
939  static void COLOR_3DSCENE(const mrpt::utils::TColorf &value);
941 
942  // See docs in base class
944  const mrpt::obs::CObservation* obs,
945  const mrpt::poses::CPose3D& takenFrom) override;
946 
947  /** @name PCL library support
948  @{ */
949 
950  /** Use to convert this MRPT point cloud object into a PCL point cloud
951  * object (PointCloud<PointXYZ>).
952  * Usage example:
953  * \code
954  * mrpt::maps::CPointsCloud pc;
955  * pcl::PointCloud<pcl::PointXYZ> cloud;
956  *
957  * pc.getPCLPointCloud(cloud);
958  * \endcode
959  * \sa setFromPCLPointCloud, CColouredPointsMap::getPCLPointCloudXYZRGB
960  * (for color data)
961  */
962  template <class POINTCLOUD>
963  void getPCLPointCloud(POINTCLOUD& cloud) const
964  {
965  const size_t nThis = this->size();
966  // Fill in the cloud data
967  cloud.width = nThis;
968  cloud.height = 1;
969  cloud.is_dense = false;
970  cloud.points.resize(cloud.width * cloud.height);
971  for (size_t i = 0; i < nThis; ++i)
972  {
973  cloud.points[i].x = this->x[i];
974  cloud.points[i].y = this->y[i];
975  cloud.points[i].z = this->z[i];
976  }
977  }
978 
979  /** Loads a PCL point cloud into this MRPT class (note: this method ignores
980  * potential RGB information, see
981  * CColouredPointsMap::setFromPCLPointCloudRGB() ).
982  * Usage example:
983  * \code
984  * pcl::PointCloud<pcl::PointXYZ> cloud;
985  * mrpt::maps::CPointsCloud pc;
986  *
987  * pc.setFromPCLPointCloud(cloud);
988  * \endcode
989  * \sa getPCLPointCloud, CColouredPointsMap::setFromPCLPointCloudRGB()
990  */
991  template <class POINTCLOUD>
992  void setFromPCLPointCloud(const POINTCLOUD& cloud)
993  {
994  const size_t N = cloud.points.size();
995  clear();
996  reserve(N);
997  for (size_t i = 0; i < N; ++i)
998  this->insertPointFast(
999  cloud.points[i].x, cloud.points[i].y, cloud.points[i].z);
1000  }
1001 
1002  /** @} */
1003 
1004  /** @name Methods that MUST be implemented by children classes of
1005  KDTreeCapable
1006  @{ */
1007 
1008  /// Must return the number of data points
1009  inline size_t kdtree_get_point_count() const { return this->size(); }
1010  /// Returns the dim'th component of the idx'th point in the class:
1011  inline float kdtree_get_pt(const size_t idx, int dim) const
1012  {
1013  if (dim == 0)
1014  return this->x[idx];
1015  else if (dim == 1)
1016  return this->y[idx];
1017  else if (dim == 2)
1018  return this->z[idx];
1019  else
1020  return 0;
1021  }
1022 
1023  /// Returns the distance between the vector "p1[0:size-1]" and the data
1024  /// point with index "idx_p2" stored in the class:
1025  inline float kdtree_distance(
1026  const float* p1, const size_t idx_p2, size_t size) const
1027  {
1028  if (size == 2)
1029  {
1030  const float d0 = p1[0] - x[idx_p2];
1031  const float d1 = p1[1] - y[idx_p2];
1032  return d0 * d0 + d1 * d1;
1033  }
1034  else
1035  {
1036  const float d0 = p1[0] - x[idx_p2];
1037  const float d1 = p1[1] - y[idx_p2];
1038  const float d2 = p1[2] - z[idx_p2];
1039  return d0 * d0 + d1 * d1 + d2 * d2;
1040  }
1041  }
1042 
1043  // Optional bounding-box computation: return false to default to a standard
1044  // bbox computation loop.
1045  // Return true if the BBOX was already computed by the class and returned
1046  // in "bb" so it can be avoided to redo it again.
1047  // Look at bb.size() to find out the expected dimensionality (e.g. 2 or 3
1048  // for point clouds)
1049  template <typename BBOX>
1050  bool kdtree_get_bbox(BBOX& bb) const
1051  {
1052  float min_z, max_z;
1053  this->boundingBox(
1054  bb[0].low, bb[0].high, bb[1].low, bb[1].high, min_z, max_z);
1055  if (bb.size() == 3)
1056  {
1057  bb[2].low = min_z;
1058  bb[2].high = max_z;
1059  }
1060  return true;
1061  }
1062  /** @} */
1063 
1064  /** Users normally don't need to call this. Called by this class or children
1065  * classes, set m_largestDistanceFromOriginIsUpdated=false, invalidates the
1066  * kd-tree cache, and such. */
1067  inline void mark_as_modified() const
1068  {
1070  m_boundingBoxIsUpdated = false;
1072  }
1073 
1074  protected:
1075  /** The point coordinates */
1076  std::vector<float> x, y, z;
1077 
1078  /** Cache of sin/cos values for the latest 2D scan geometries. */
1080 
1081  /** Auxiliary variables used in "getLargestDistanceFromOrigin"
1082  * \sa getLargestDistanceFromOrigin
1083  */
1085 
1086  /** Auxiliary variables used in "getLargestDistanceFromOrigin"
1087  * \sa getLargestDistanceFromOrigin
1088  */
1090 
1093  m_bb_max_z;
1094 
1095  /** This is a common version of CMetricMap::insertObservation() for point
1096  * maps (actually, CMetricMap::internal_insertObservation),
1097  * so derived classes don't need to worry implementing that method unless
1098  * something special is really necesary.
1099  * See mrpt::maps::CPointsMap for the enumeration of types of observations
1100  * which are accepted. */
1102  const mrpt::obs::CObservation* obs,
1103  const mrpt::poses::CPose3D* robotPose) override;
1104 
1105  /** Helper method for ::copyFrom() */
1106  void base_copyFrom(const CPointsMap& obj);
1107 
1108  /** @name PLY Import virtual methods to implement in base classes
1109  @{ */
1110  /** In a base class, reserve memory to prepare subsequent calls to
1111  * PLY_import_set_face */
1112  virtual void PLY_import_set_face_count(const size_t N) override
1113  {
1114  MRPT_UNUSED_PARAM(N);
1115  }
1116 
1117  /** In a base class, will be called after PLY_import_set_vertex_count() once
1118  * for each loaded point.
1119  * \param pt_color Will be nullptr if the loaded file does not provide
1120  * color info.
1121  */
1122  virtual void PLY_import_set_vertex(
1123  const size_t idx, const mrpt::math::TPoint3Df& pt,
1124  const mrpt::utils::TColorf* pt_color = nullptr) override;
1125  /** @} */
1126 
1127  /** @name PLY Export virtual methods to implement in base classes
1128  @{ */
1129  size_t PLY_export_get_vertex_count() const override;
1130  size_t PLY_export_get_face_count() const override { return 0; }
1131  virtual void PLY_export_get_vertex(
1132  const size_t idx, mrpt::math::TPoint3Df& pt, bool& pt_has_color,
1133  mrpt::utils::TColorf& pt_color) const override;
1134  /** @} */
1135 
1136  /** The minimum and maximum height for a certain laser scan to be inserted
1137  * into this map
1138  * \sa m_heightfilter_enabled */
1140 
1141  /** Whether or not (default=not) filter the input points by height
1142  * \sa m_heightfilter_z_min, m_heightfilter_z_max */
1144 
1145  // Friend methods:
1146  template <class Derived>
1148  template <class Derived>
1150 
1151 }; // End of class def.
1152 
1153 } // End of namespace
1154 
1155 namespace global_settings
1156 {
1157 /** The size of points when exporting with getAs3DObject() (default=3.0)
1158  * Affects to:
1159  * - mrpt::maps::CPointsMap and all its children classes.
1160  */
1163 }
1164 
1165 namespace utils
1166 {
1167 /** Specialization mrpt::utils::PointCloudAdapter<mrpt::maps::CPointsMap>
1168  * \ingroup mrpt_adapters_grp*/
1169 template <>
1171  : public detail::PointCloudAdapterHelperNoRGB<mrpt::maps::CPointsMap, float>
1172 {
1173  private:
1175 
1176  public:
1177  /** The type of each point XYZ coordinates */
1178  typedef float coords_t;
1179  /** Has any color RGB info? */
1180  static const int HAS_RGB = 0;
1181  /** Has native RGB info (as floats)? */
1182  static const int HAS_RGBf = 0;
1183  /** Has native RGB info (as uint8_t)? */
1184  static const int HAS_RGBu8 = 0;
1185 
1186  /** Constructor (accept a const ref for convenience) */
1188  : m_obj(*const_cast<mrpt::maps::CPointsMap*>(&obj))
1189  {
1190  }
1191  /** Get number of points */
1192  inline size_t size() const { return m_obj.size(); }
1193  /** Set number of points (to uninitialized values) */
1194  inline void resize(const size_t N) { m_obj.resize(N); }
1195  /** Get XYZ coordinates of i'th point */
1196  template <typename T>
1197  inline void getPointXYZ(const size_t idx, T& x, T& y, T& z) const
1198  {
1199  m_obj.getPointFast(idx, x, y, z);
1200  }
1201  /** Set XYZ coordinates of i'th point */
1202  inline void setPointXYZ(
1203  const size_t idx, const coords_t x, const coords_t y, const coords_t z)
1204  {
1205  m_obj.setPointFast(idx, x, y, z);
1206  }
1207 }; // end of PointCloudAdapter<mrpt::maps::CPointsMap>
1208 }
1209 
1210 } // End of namespace
1211 
1212 #endif
#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...
const std::vector< float > & getPointsBufferRef_x() const
Provides a direct access to a read-only reference of the internal point buffer.
Definition: CPointsMap.h:496
TLikelihoodOptions()
Initilization of default parameters.
Definition: CPointsMap.cpp:706
void setFromPCLPointCloud(const POINTCLOUD &cloud)
Loads a PCL point cloud into this MRPT class (note: this method ignores potential RGB information...
Definition: CPointsMap.h:992
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
void setAllPointsTemplate(const VECTOR &X, const VECTOR &Y, const VECTOR &Z=VECTOR())
Set all the points at once from vectors with X,Y and Z coordinates (if Z is not provided, it will be set to all zeros).
Definition: CPointsMap.h:607
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
bool empty() const
STL-like method to check whether the map is empty:
Definition: CPointsMap.h:831
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 getPointXYZ(const size_t idx, T &x, T &y, T &z) const
Get XYZ coordinates of i&#39;th point.
Definition: CPointsMap.h:1197
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
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
bool m_heightfilter_enabled
Whether or not (default=not) filter the input points by height.
Definition: CPointsMap.h:1143
static mrpt::utils::TColorf COLOR_3DSCENE()
Definition: CPointsMap.cpp:69
void operator+=(const CPointsMap &anotherMap)
This operator is synonymous with addFrom.
Definition: CPointsMap.h:309
size_t PLY_export_get_face_count() const override
In a base class, return the number of faces.
Definition: CPointsMap.h:1130
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
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.
const mrpt::obs::CObservation2DRangeScan & rangeScan
Definition: CPointsMap.h:84
const mrpt::obs::CObservation3DRangeScan & rangeScan
Definition: CPointsMap.h:102
const std::vector< float > & getPointsBufferRef_y() const
Provides a direct access to a read-only reference of the internal point buffer.
Definition: CPointsMap.h:499
A helper base class for those PointCloudAdapter<> which do not handle RGB data; it declares needed in...
Definition: adapters.h:51
void setAllPoints(const std::vector< float > &X, const std::vector< float > &Y)
Set all the points at once from vectors with X and Y coordinates (Z=0).
Definition: CPointsMap.h:639
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 ...
#define DECLARE_MEXPLUS_FROM(complete_type)
This must be inserted if a custom conversion method for MEX API is implemented in the class...
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
virtual mrpt::maps::CSimplePointsMap * getAsSimplePointsMap() override
Definition: CPointsMap.h:848
void base_copyFrom(const CPointsMap &obj)
Helper method for ::copyFrom()
#define ASSERT_BELOW_(__A, __B)
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...
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.
void getAllPoints(std::vector< mrpt::math::TPoint2D > &ps, size_t decimation=1) const
Definition: CPointsMap.h:564
size_t kdtree_get_point_count() const
Must return the number of data points.
Definition: CPointsMap.h:1009
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
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
void getAllPoints(CONTAINER &ps, size_t decimation=1) const
Gets all points as a STL-like container.
Definition: CPointsMap.h:541
void setPointXYZ(const size_t idx, const coords_t x, const coords_t y, const coords_t z)
Set XYZ coordinates of i&#39;th point.
Definition: CPointsMap.h:1202
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 ...
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
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
float kdtree_distance(const float *p1, const size_t idx_p2, size_t size) const
Returns the distance between the vector "p1[0:size-1]" and the data point with index "idx_p2" stored ...
Definition: CPointsMap.h:1025
GLsizei GLsizei GLuint * obj
Definition: glext.h:4070
float squareDistanceToClosestCorrespondenceT(const mrpt::math::TPoint2D &p0) const
Definition: CPointsMap.h:193
size_t size() const
Get number of points.
Definition: CPointsMap.h:1192
size_t PLY_export_get_vertex_count() const override
In a base class, return the number of vertices.
bool save3D_to_text_file(const std::string &file) const
Save to a text file.
Definition: CPointsMap.cpp:114
virtual void getPoint(size_t index, float &x, float &y, float &z, float &R, float &G, float &B) const
Access to a given point from map, and its colors, if the map defines them (othersise, R=G=B=1.0).
Definition: CPointsMap.h:416
GLubyte GLubyte GLubyte GLubyte w
Definition: glext.h:4178
float maxDistForInterpolatePoints
The maximum distance between two points to interpolate between them (ONLY when also_interpolate=true)...
Definition: CPointsMap.h:243
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
virtual void PLY_import_set_face_count(const size_t N) override
In a base class, reserve memory to prepare subsequent calls to PLY_import_set_face.
Definition: CPointsMap.h:1112
This class allows loading and storing values and vectors of different types from a configuration text...
#define DEFINE_VIRTUAL_SERIALIZABLE(class_name)
This declaration must be inserted in virtual CSerializable classes definition:
bool kdtree_get_bbox(BBOX &bb) const
Definition: CPointsMap.h:1050
unsigned long getPoint(size_t index, mrpt::math::TPoint2D &p) const
Definition: CPointsMap.h:400
A generic adaptor class for providing Nearest Neighbor (NN) lookup via the nanoflann library...
Definition: KDTreeCapable.h:81
void setPointAllFields(const size_t index, const std::vector< float > &point_data)
Set all the data fields for one point as a vector: depending on the implementation class this can be ...
Definition: CPointsMap.h:662
bool isFilterByHeightEnabled() const
Return whether filter-by-height is enabled.
Definition: CPointsMap.h:916
With this struct options are provided to the observation insertion process.
Definition: CPointsMap.h:204
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.
bool insertInvalidPoints
Points with x,y,z coordinates set to zero will also be inserted.
Definition: CPointsMap.h:245
TLaserRange3DInsertContext(const mrpt::obs::CObservation3DRangeScan &_rangeScan)
Definition: CPointsMap.h:95
float kdtree_get_pt(const size_t idx, int dim) const
Returns the dim&#39;th component of the idx&#39;th point in the class:
Definition: CPointsMap.h:1011
void writeToStream(mrpt::utils::CStream &out) const
Binary dump to stream - for usage in derived classes&#39; serialization.
Definition: CPointsMap.cpp:711
Additional results from the determination of matchings between point clouds, etc., apart from the pairings themselves.
Lightweight 3D point (float version).
#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.
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 DECLARE_MEX_CONVERSION
This must be inserted if a custom conversion method for MEX API is implemented in the class...
void setAllPoints(const std::vector< float > &X, const std::vector< float > &Y, const std::vector< float > &Z)
Set all the points at once from vectors with X,Y and Z coordinates.
Definition: CPointsMap.h:630
A smart look-up-table (LUT) of sin/cos values for 2D laser scans.
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
mrpt::math::CMatrixDouble44 HM
Homog matrix of the local sensor pose within the robot.
Definition: CPointsMap.h:101
float coords_t
The type of each point XYZ coordinates.
Definition: CPointsMap.h:1178
A list of TMatchingPair.
Definition: TMatchingPair.h:93
void setPoint(size_t index, const mrpt::math::TPoint3D &p)
Definition: CPointsMap.h:451
void getHeightFilterLevels(double &_z_min, double &_z_max) const
Get the min/max Z levels for points to be actually inserted in the map.
Definition: CPointsMap.h:930
void setPoint(size_t index, float x, float y)
Definition: CPointsMap.h:456
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...
float scan_x
In internal_loadFromRangeScan3D_prepareOneRange, these are the local coordinates of the scan points b...
Definition: CPointsMap.h:105
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
GLubyte GLubyte b
Definition: glext.h:6279
virtual const mrpt::maps::CSimplePointsMap * getAsSimplePointsMap() const override
If the map is a simple points map or it&#39;s a multi-metric map that contains EXACTLY one simple points ...
Definition: CPointsMap.h:843
TLaserRange2DInsertContext(const mrpt::obs::CObservation2DRangeScan &_rangeScan)
Definition: CPointsMap.h:77
std::vector< float > fVars
Extra variables to be used as desired by the derived class.
Definition: CPointsMap.h:86
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...
bool load2D_from_text_file(const std::string &file)
Load from a text file.
Definition: CPointsMap.h:332
A virtual base class that implements the capability of importing 3D point clouds and faces from a fil...
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
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
std::vector< float > fVars
Extra variables to be used as desired by the derived class.
Definition: CPointsMap.h:107
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
virtual void setPoint(size_t index, float x, float y, float z, float R, float G, float B)
overload (RGB data is ignored in classes without color information)
Definition: CPointsMap.h:461
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
void setHeightFilterLevels(const double _z_min, const double _z_max)
Set the min/max Z levels for points to be actually inserted in the map (only if enableFilterByHeight(...
Definition: CPointsMap.h:923
void readFromStream(mrpt::utils::CStream &in)
Binary dump to stream - for usage in derived classes&#39; serialization.
Definition: CPointsMap.cpp:719
bool also_interpolate
If set to true, far points (<1m) are interpolated with samples at "minDistSqrBetweenLaserPoints" inte...
Definition: CPointsMap.h:224
void clipOutOfRangeInZ(float zMin, float zMax)
Delete points out of the given "z" axis range have been removed.
Definition: CPointsMap.cpp:280
mrpt::obs::CSinCosLookUpTableFor2DScans m_scans_sincos_cache
Cache of sin/cos values for the latest 2D scan geometries.
Definition: CPointsMap.h:1079
#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
void getPointAllFields(const size_t index, std::vector< float > &point_data) const
Get all the data fields for one point as a vector: depending on the implementation class this can be ...
Definition: CPointsMap.h:649
TLikelihoodOptions likelihoodOptions
Definition: CPointsMap.h:293
bool load3D_from_text_file(const std::string &file)
Load from a text file.
Definition: CPointsMap.h:341
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 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 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
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
Options used when evaluating "computeObservationLikelihood" in the derived classes.
Definition: CPointsMap.h:262
unsigned long getPoint(size_t index, mrpt::math::TPoint3D &p) const
Definition: CPointsMap.h:405
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 kdtree_mark_as_outdated() const
To be called by child classes when KD tree data changes.
virtual void insertPoint(float x, float y, float z, float R, float G, float B)
overload (RGB data is ignored in classes without color information)
Definition: CPointsMap.h:592
void setPoint(size_t index, const mrpt::math::TPoint2D &p)
Definition: CPointsMap.h:446
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
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
GLsizei GLsizei GLchar * source
Definition: glext.h:4082
#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)
const std::vector< float > & getPointsBufferRef_z() const
Provides a direct access to a read-only reference of the internal point buffer.
Definition: CPointsMap.h:502
virtual ~CPointsMap()
Virtual destructor.
Definition: CPointsMap.cpp:91
PointCloudAdapter(const mrpt::maps::CPointsMap &obj)
Constructor (accept a const ref for convenience)
Definition: CPointsMap.h:1187
Helper struct used for internal_loadFromRangeScan3D_prepareOneRange()
Definition: CPointsMap.h:93
GLenum GLint GLint y
Definition: glext.h:3538
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
GLsizei const GLfloat * value
Definition: glext.h:4117
void enableFilterByHeight(bool enable=true)
Enable/disable the filter-by-height functionality.
Definition: CPointsMap.h:911
GLsizeiptr size
Definition: glext.h:3923
An adapter to different kinds of point cloud object.
Definition: adapters.h:41
void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const override
This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >...
Definition: CPointsMap.h:364
virtual void insertPointFast(float x, float y, float z=0)=0
The virtual method for insertPoint() without calling mark_as_modified()
virtual void setSize(size_t newLength)=0
Resizes all point buffers so they can hold the given number of points, erasing all previous contents ...
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.
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.
mrpt::math::CMatrixDouble44 HM
Homog matrix of the local sensor pose within the robot.
Definition: CPointsMap.h:83
unsigned __int32 uint32_t
Definition: rptypes.h:47
Lightweight 2D point.
size_t size() const
Returns the number of stored points in the map.
Definition: CPointsMap.h:385
float getLargestDistanceFromOriginNoRecompute(bool &output_is_valid) const
Like getLargestDistanceFromOrigin() but returns in output_is_valid = false if the distance was not al...
Definition: CPointsMap.h:863
A virtual base class that implements the capability of exporting 3D point clouds and faces to a file ...
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
void boundingBox(mrpt::math::TPoint3D &pMin, mrpt::math::TPoint3D &pMax) const
Definition: CPointsMap.h:878
void insertPoint(const mrpt::math::TPoint3D &p)
Definition: CPointsMap.h:587
virtual bool hasColorPoints() const
Returns true if the point map has a color field for each point.
Definition: CPointsMap.h:435
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
Helper struct used for internal_loadFromRangeScan2D_prepareOneRange()
Definition: CPointsMap.h:75
void resize(const size_t N)
Set number of points (to uninitialized values)
Definition: CPointsMap.h:1194
void applyDeletionMask(const std::vector< bool > &mask)
Remove from the map the points marked in a bool&#39;s array as "true".
double m_heightfilter_z_min
The minimum and maximum height for a certain laser scan to be inserted into this map.
Definition: CPointsMap.h:1139
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