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



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 3a26b90fd Wed Mar 25 20:17:03 2020 +0100 at miƩ mar 25 23:05:41 CET 2020