Main MRPT website > C++ reference
MRPT logo
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-2014, 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/slam/CMetricMap.h>
20 
21 #include <mrpt/maps/link_pragmas.h>
22 #include <mrpt/utils/adapters.h>
23 
24 namespace mrpt
25 {
26 /** \ingroup mrpt_maps_grp */
27 namespace slam
28 {
29  // Fordward declarations:
30  class CSimplePointsMap;
31  class CObservation2DRangeScan;
32  class CObservation3DRangeScan;
33 
34  using namespace mrpt::poses;
35  using namespace mrpt::math;
36 
38 
39  // Forward decls. needed to make its static methods friends of CPointsMap
40  namespace detail {
41  template <class Derived> struct loadFromRangeImpl;
42  template <class Derived> struct pointmap_traits;
43  }
44 
45 
46  /** A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors.
47  * This is a virtual class, thus only a derived class can be instantiated by the user. The user most usually wants to use CSimplePointsMap.
48  *
49  * This class implements generic version of mrpt::slam::CMetric::insertObservation() accepting these types of sensory data:
50  * - mrpt::slam::CObservation2DRangeScan: 2D range scans
51  * - mrpt::slam::CObservation3DRangeScan: 3D range scans (Kinect, etc...)
52  * - mrpt::slam::CObservationRange: IRs, Sonars, etc.
53  *
54  * If built against liblas, this class also provides method for loading and saving in the standard LAS LiDAR point cloud format: saveLASFile(), loadLASFile()
55  *
56  * \sa CMetricMap, CPoint, mrpt::utils::CSerializable
57  * \ingroup mrpt_maps_grp
58  */
60  public CMetricMap,
61  public mrpt::utils::KDTreeCapable<CPointsMap>,
64  {
65  // This must be added to any CSerializable derived class:
67 
68  protected:
69  /** Helper struct used for \a internal_loadFromRangeScan2D_prepareOneRange() */
71  TLaserRange2DInsertContext(const CObservation2DRangeScan &_rangeScan) : HM(mrpt::math::UNINITIALIZED_MATRIX), rangeScan(_rangeScan)
72  { }
73  CMatrixDouble44 HM; //!< Homog matrix of the local sensor pose within the robot
75  std::vector<float> fVars; //!< Extra variables to be used as desired by the derived class.
76  std::vector<unsigned int> uVars;
77  std::vector<uint8_t> bVars;
78  };
79 
80  /** Helper struct used for \a internal_loadFromRangeScan3D_prepareOneRange() */
82  TLaserRange3DInsertContext(const CObservation3DRangeScan &_rangeScan) : HM(mrpt::math::UNINITIALIZED_MATRIX), rangeScan(_rangeScan)
83  { }
84  CMatrixDouble44 HM; //!< Homog matrix of the local sensor pose within the robot
86  float scan_x, scan_y,scan_z; //!< In \a internal_loadFromRangeScan3D_prepareOneRange, these are the local coordinates of the scan points being inserted right now.
87  std::vector<float> fVars; //!< Extra variables to be used as desired by the derived class.
88  std::vector<unsigned int> uVars;
89  std::vector<uint8_t> bVars;
90  };
91 
92  public:
93  CPointsMap(); //!< Ctor
94  virtual ~CPointsMap(); //!< Virtual destructor.
95 
96 
97  // --------------------------------------------
98  /** @name Pure virtual interfaces to be implemented by any class derived from CPointsMap
99  @{ */
100 
101  /** Reserves memory for a given number of points: the size of the map does not change, it only reserves the memory.
102  * This is useful for situations where it is approximately known the final size of the map. This method is more
103  * efficient than constantly increasing the size of the buffers. Refer to the STL C++ library's "reserve" methods.
104  */
105  virtual void reserve(size_t newLength) = 0;
106 
107  /** Resizes all point buffers so they can hold the given number of points: newly created points are set to default values,
108  * and old contents are not changed.
109  * \sa reserve, setPoint, setPointFast, setSize
110  */
111  virtual void resize(size_t newLength) = 0;
112 
113  /** Resizes all point buffers so they can hold the given number of points, *erasing* all previous contents
114  * and leaving all points to default values.
115  * \sa reserve, setPoint, setPointFast, setSize
116  */
117  virtual void setSize(size_t newLength) = 0;
118 
119  /** Changes the coordinates of the given point (0-based index), *without* checking for out-of-bounds and *without* calling mark_as_modified() \sa setPoint */
120  virtual void setPointFast(size_t index,float x, float y, float z)=0;
121 
122  /** The virtual method for \a insertPoint() *without* calling mark_as_modified() */
123  virtual void insertPointFast( float x, float y, float z = 0 ) = 0;
124 
125  /** Virtual assignment operator, copies as much common data (XYZ, color,...) as possible from the source map into this one. */
126  virtual void copyFrom(const CPointsMap &obj) = 0;
127 
128  /** Get all the data fields for one point as a vector: depending on the implementation class this can be [X Y Z] or [X Y Z R G B], etc...
129  * Unlike getPointAllFields(), this method does not check for index out of bounds
130  * \sa getPointAllFields, setPointAllFields, setPointAllFieldsFast
131  */
132  virtual void getPointAllFieldsFast( const size_t index, std::vector<float> & point_data ) const = 0;
133 
134  /** Set all the data fields for one point as a vector: depending on the implementation class this can be [X Y Z] or [X Y Z R G B], etc...
135  * Unlike setPointAllFields(), this method does not check for index out of bounds
136  * \sa setPointAllFields, getPointAllFields, getPointAllFieldsFast
137  */
138  virtual void setPointAllFieldsFast( const size_t index, const std::vector<float> & point_data ) = 0;
139 
140  protected:
141 
142  /** Auxiliary method called from within \a addFrom() automatically, to finish the copying of class-specific data */
143  virtual void addFrom_classSpecific(const CPointsMap &anotherMap, const size_t nPreviousPoints) = 0;
144 
145  public:
146 
147  /** @} */
148  // --------------------------------------------
149 
150 
151  /** Returns the square distance from the 2D point (x0,y0) to the closest correspondence in the map.
152  */
153  virtual float squareDistanceToClosestCorrespondence(
154  float x0,
155  float y0 ) const MRPT_OVERRIDE;
156 
157  inline float squareDistanceToClosestCorrespondenceT(const TPoint2D &p0) const {
158  return squareDistanceToClosestCorrespondence(static_cast<float>(p0.x),static_cast<float>(p0.y));
159  }
160 
161 
162  /** With this struct options are provided to the observation insertion process.
163  * \sa CObservation::insertIntoPointsMap
164  */
166  {
167  /** Initilization of default parameters */
169  /** See utils::CLoadableOptions */
170  void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source,const std::string &section);
171  /** See utils::CLoadableOptions */
172  void dumpToTextStream(CStream &out) const;
173 
174  float minDistBetweenLaserPoints; //!< The minimum distance between points (in 3D): If two points are too close, one of them is not inserted into the map. Default is 0.02 meters.
175  bool addToExistingPointsMap; //!< Applicable to "loadFromRangeScan" only! If set to false, the points from the scan are loaded, clearing all previous content. Default is false.
176  bool also_interpolate; //!< If set to true, far points (<1m) are interpolated with samples at "minDistSqrBetweenLaserPoints" intervals (Default is false).
177  bool disableDeletion; //!< If set to false (default=true) points in the same plane as the inserted scan and inside the free space, are erased: i.e. they don't exist yet.
178  bool fuseWithExisting; //!< If set to true (default=false), inserted points are "fused" with previously existent ones. This shrink the size of the points map, but its slower.
179  bool isPlanarMap; //!< If set to true, only HORIZONTAL (in the XY plane) measurements will be inserted in the map (Default value is false, thus 3D maps are generated). \sa horizontalTolerance
180  float horizontalTolerance; //!< The tolerance in rads in pitch & roll for a laser scan to be considered horizontal, considered only when isPlanarMap=true (default=0).
181  float maxDistForInterpolatePoints; //!< The maximum distance between two points to interpolate between them (ONLY when also_interpolate=true)
182  bool insertInvalidPoints; //!< Points with x,y,z coordinates set to zero will also be inserted
183 
184  void writeToStream(CStream &out) const; //!< Binary dump to stream - for usage in derived classes' serialization
185  void readFromStream(CStream &in); //!< Binary dump to stream - for usage in derived classes' serialization
186  };
187 
188  TInsertionOptions insertionOptions; //!< The options used when inserting observations in the map
189 
190  /** Options used when evaluating "computeObservationLikelihood" in the derived classes.
191  * \sa CObservation::computeObservationLikelihood
192  */
194  {
195  /** Initilization of default parameters
196  */
198  virtual ~TLikelihoodOptions() {}
199 
200  /** See utils::CLoadableOptions */
201  void loadFromConfigFile(
202  const mrpt::utils::CConfigFileBase &source,
203  const std::string &section);
204 
205  /** See utils::CLoadableOptions */
206  void dumpToTextStream(CStream &out) const;
207 
208  void writeToStream(CStream &out) const; //!< Binary dump to stream - for usage in derived classes' serialization
209  void readFromStream(CStream &in); //!< Binary dump to stream - for usage in derived classes' serialization
210 
211  double sigma_dist; //!< Sigma (standard deviation, in meters) of the exponential used to model the likelihood (default= 0.5meters)
212  double max_corr_distance; //!< Maximum distance in meters to consider for the numerator divided by "sigma_dist", so that each point has a minimum (but very small) likelihood to avoid underflows (default=1.0 meters)
213  uint32_t decimation; //!< Speed up the likelihood computation by considering only one out of N rays (default=10)
214  };
215 
217 
218 
219  /** Adds all the points from \a anotherMap to this map, without fusing.
220  * This operation can be also invoked via the "+=" operator, for example:
221  * \code
222  * CSimplePointsMap m1, m2;
223  * ...
224  * m1.addFrom( m2 ); // Add all points of m2 to m1
225  * m1 += m2; // Exactly the same than above
226  * \endcode
227  * \note The method in CPointsMap is generic but derived classes may redefine this virtual method to another one more optimized.
228  */
229  virtual void addFrom(const CPointsMap &anotherMap);
230 
231  /** This operator is synonymous with \a addFrom. \sa addFrom */
232  inline void operator +=(const CPointsMap &anotherMap)
233  {
234  this->addFrom(anotherMap);
235  }
236 
237  /** Insert the contents of another map into this one with some geometric transformation, without fusing close points.
238  * \param otherMap The other map whose points are to be inserted into this one.
239  * \param otherPose The pose of the other map in the coordinates of THIS map
240  * \sa fuseWith, addFrom
241  */
242  void insertAnotherMap(
243  const CPointsMap *otherMap,
244  const CPose3D &otherPose);
245 
246  // --------------------------------------------------
247  /** @name File input/output methods
248  @{ */
249 
250  /** Load from a text file. Each line should contain an "X Y" coordinate pair, separated by whitespaces.
251  * Returns false if any error occured, true elsewere.
252  */
253  inline bool load2D_from_text_file(const std::string &file) { return load2Dor3D_from_text_file(file,false); }
254 
255  /** Load from a text file. Each line should contain an "X Y Z" coordinate tuple, separated by whitespaces.
256  * Returns false if any error occured, true elsewere.
257  */
258  inline bool load3D_from_text_file(const std::string &file) { return load2Dor3D_from_text_file(file,true); }
259 
260  /** 2D or 3D generic implementation of \a load2D_from_text_file and load3D_from_text_file */
261  bool load2Dor3D_from_text_file(const std::string &file, const bool is_3D);
262 
263  /** Save to a text file. Each line will contain "X Y" point coordinates.
264  * Returns false if any error occured, true elsewere.
265  */
266  bool save2D_to_text_file(const std::string &file) const;
267 
268  /** Save to a text file. Each line will contain "X Y Z" point coordinates.
269  * Returns false if any error occured, true elsewere.
270  */
271  bool save3D_to_text_file(const std::string &file)const;
272 
273  /** This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >, as an image or in any other applicable way (Notice that other methods to save the map may be implemented in classes implementing this virtual interface).
274  */
276  const std::string &filNamePrefix
277  )const
278  {
279  std::string fil( filNamePrefix + std::string(".txt") );
280  save3D_to_text_file( fil );
281  }
282 
283  /** Save the point cloud as a PCL PCD file, in either ASCII or binary format (requires MRPT built against PCL) \return false on any error */
284  virtual bool savePCDFile(const std::string &filename, bool save_as_binary) const;
285 
286  /** Load the point cloud from a PCL PCD file (requires MRPT built against PCL) \return false on any error */
287  virtual bool loadPCDFile(const std::string &filename);
288 
289 
290  /** Optional settings for saveLASFile() */
292  {
293  // None.
294  };
295 
296  /** Optional settings for loadLASFile() */
298  {
299  // None.
300  };
301 
302  /** Extra information gathered from the LAS file header */
304  {
305  std::string FileSignature;
306  std::string SystemIdentifier;
307  std::string SoftwareIdentifier;
308  std::string project_guid;
309  std::string spatial_reference_proj4; //!< Proj.4 string describing the Spatial Reference System.
310  uint16_t creation_year;//!< Creation date (Year number)
311  uint16_t creation_DOY; //!< Creation day of year
312 
313  LAS_HeaderInfo() : creation_year(0),creation_DOY(0)
314  {}
315  };
316 
317  /** Save the point cloud as an ASPRS LAS binary file (requires MRPT built against liblas). Refer to http://www.liblas.org/
318  * \return false on any error */
319  virtual bool saveLASFile(const std::string &filename, const LAS_WriteParams & params = LAS_WriteParams() ) const;
320 
321  /** Load the point cloud from an ASPRS LAS binary file (requires MRPT built against liblas). Refer to http://www.liblas.org/
322  * \note Color (RGB) information will be taken into account if using the derived class mrpt::slam::CColouredPointsMap
323  * \return false on any error */
324  virtual bool loadLASFile(const std::string &filename, LAS_HeaderInfo &out_headerInfo, const LAS_LoadParams &params = LAS_LoadParams() );
325 
326  /** @} */ // End of: File input/output methods
327  // --------------------------------------------------
328 
329  /** Returns the number of stored points in the map.
330  */
331  inline size_t size() const { return x.size(); }
332 
333  /** Access to a given point from map, as a 2D point. First index is 0.
334  * \return The return value is the weight of the point (the times it has been fused), or 1 if weights are not used.
335  * \exception Throws std::exception on index out of bound.
336  * \sa setPoint, getPointFast
337  */
338  unsigned long getPoint(size_t index,float &x,float &y,float &z) const;
339  /// \overload
340  unsigned long getPoint(size_t index,float &x,float &y) const;
341  /// \overload
342  unsigned long getPoint(size_t index,double &x,double &y,double &z) const;
343  /// \overload
344  unsigned long getPoint(size_t index,double &x,double &y) const;
345  /// \overload
346  inline unsigned long getPoint(size_t index,mrpt::math::TPoint2D &p) const { return getPoint(index,p.x,p.y); }
347  /// \overload
348  inline unsigned long getPoint(size_t index,mrpt::math::TPoint3D &p) const { return getPoint(index,p.x,p.y,p.z); }
349 
350  /** Access to a given point from map, and its colors, if the map defines them (othersise, R=G=B=1.0). First index is 0.
351  * \return The return value is the weight of the point (the times it has been fused)
352  * \exception Throws std::exception on index out of bound.
353  */
354  virtual void getPoint( size_t index, float &x, float &y, float &z, float &R, float &G, float &B ) const
355  {
356  getPoint(index,x,y,z);
357  R=G=B=1;
358  }
359 
360  /** Just like \a getPoint() but without checking out-of-bound index and without returning the point weight, just XYZ.
361  */
362  inline void getPointFast(size_t index,float &x,float &y,float &z) const { x=this->x[index]; y=this->y[index]; z=this->z[index]; }
363 
364  /** Returns true if the point map has a color field for each point */
365  virtual bool hasColorPoints() const { return false; }
366 
367  /** Changes a given point from map, with Z defaulting to 0 if not provided.
368  * \exception Throws std::exception on index out of bound.
369  */
370  inline void setPoint(size_t index,float x, float y, float z) {
371  ASSERT_BELOW_(index,this->size())
372  setPointFast(index,x,y,z);
373  mark_as_modified();
374  }
375  /// \overload
376  inline void setPoint(size_t index,mrpt::math::TPoint2D &p) { setPoint(index,p.x,p.y,0); }
377  /// \overload
378  inline void setPoint(size_t index,mrpt::math::TPoint3D &p) { setPoint(index,p.x,p.y,p.z); }
379  /// \overload
380  inline void setPoint(size_t index,float x, float y) { setPoint(index,x,y,0); }
381  /// \overload (RGB data is ignored in classes without color information)
382  virtual void setPoint(size_t index,float x, float y, float z, float R, float G, float B)
383  {
385  setPoint(index,x,y,z);
386  }
387 
388  /// Sets the point weight, which is ignored in all classes but those which actually store that field (Note: No checks are done for out-of-bounds index). \sa getPointWeight
389  virtual void setPointWeight(size_t index,unsigned long w)
390  {
392  }
393  /// Gets the point weight, which is ignored in all classes (defaults to 1) but in those which actually store that field (Note: No checks are done for out-of-bounds index). \sa setPointWeight
394  virtual unsigned int getPointWeight(size_t index) const { MRPT_UNUSED_PARAM(index); return 1; }
395 
396 
397  /** Provides a direct access to points buffer, or NULL if there is no points in the map.
398  */
399  void getPointsBuffer( size_t &outPointsCount, const float *&xs, const float *&ys, const float *&zs ) const;
400 
401  /** Provides a direct access to a read-only reference of the internal point buffer. \sa getAllPoints */
402  inline const std::vector<float> & getPointsBufferRef_x() const { return x; }
403  /** Provides a direct access to a read-only reference of the internal point buffer. \sa getAllPoints */
404  inline const std::vector<float> & getPointsBufferRef_y() const { return y; }
405  /** Provides a direct access to a read-only reference of the internal point buffer. \sa getAllPoints */
406  inline const std::vector<float> & getPointsBufferRef_z() const { return z; }
407 
408  /** Returns a copy of the 2D/3D points as a std::vector of float coordinates.
409  * If decimation is greater than 1, only 1 point out of that number will be saved in the output, effectively performing a subsampling of the points.
410  * \sa getPointsBufferRef_x, getPointsBufferRef_y, getPointsBufferRef_z
411  * \tparam VECTOR can be std::vector<float or double> or any row/column Eigen::Array or Eigen::Matrix (this includes mrpt::math::CVectorFloat and mrpt::math::CVectorDouble).
412  */
413  template <class VECTOR>
414  void getAllPoints( VECTOR &xs, VECTOR &ys, VECTOR &zs, size_t decimation = 1 ) const
415  {
416  MRPT_START
417  ASSERT_(decimation>0)
418  const size_t Nout = x.size() / decimation;
419  xs.resize(Nout);
420  ys.resize(Nout);
421  zs.resize(Nout);
422  size_t idx_in, idx_out;
423  for (idx_in=0,idx_out=0;idx_out<Nout;idx_in+=decimation,++idx_out)
424  {
425  xs[idx_out]=x[idx_in];
426  ys[idx_out]=y[idx_in];
427  zs[idx_out]=z[idx_in];
428  }
429  MRPT_END
430  }
431 
432  inline void getAllPoints(std::vector<TPoint3D> &ps,size_t decimation=1) const {
433  std::vector<float> dmy1,dmy2,dmy3;
434  getAllPoints(dmy1,dmy2,dmy3,decimation);
435  ps.resize(dmy1.size());
436  for (size_t i=0;i<dmy1.size();i++) {
437  ps[i].x=static_cast<double>(dmy1[i]);
438  ps[i].y=static_cast<double>(dmy2[i]);
439  ps[i].z=static_cast<double>(dmy3[i]);
440  }
441  }
442 
443  /** Returns a copy of the 2D/3D points as a std::vector of float coordinates.
444  * If decimation is greater than 1, only 1 point out of that number will be saved in the output, effectively performing a subsampling of the points.
445  * \sa setAllPoints
446  */
447  void getAllPoints( std::vector<float> &xs, std::vector<float> &ys, size_t decimation = 1 ) const;
448 
449  inline void getAllPoints(std::vector<TPoint2D> &ps,size_t decimation=1) const {
450  std::vector<float> dmy1,dmy2;
451  getAllPoints(dmy1,dmy2,decimation);
452  ps.resize(dmy1.size());
453  for (size_t i=0;i<dmy1.size();i++) {
454  ps[i].x=static_cast<double>(dmy1[i]);
455  ps[i].y=static_cast<double>(dmy2[i]);
456  }
457  }
458 
459  /** Provides a way to insert (append) individual points into the map: the missing fields of child
460  * classes (color, weight, etc) are left to their default values
461  */
462  inline void insertPoint( float x, float y, float z=0 ) { insertPointFast(x,y,z); mark_as_modified(); }
463  /// \overload of \a insertPoint()
464  inline void insertPoint( const mrpt::math::TPoint3D &p ) { insertPoint(p.x,p.y,p.z); }
465  /// \overload (RGB data is ignored in classes without color information)
466  virtual void insertPoint( float x, float y, float z, float R, float G, float B )
467  {
469  insertPoint(x,y,z);
470  }
471 
472  /** 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).
473  * \tparam VECTOR can be mrpt::math::CVectorFloat or std::vector<float> or any other column or row Eigen::Matrix.
474  */
475  template <typename VECTOR>
476  inline void setAllPointsTemplate(const VECTOR &X,const VECTOR &Y,const VECTOR &Z = VECTOR())
477  {
478  const size_t N = X.size();
479  ASSERT_EQUAL_(X.size(),Y.size())
480  ASSERT_(Z.size()==0 || Z.size()==X.size())
481  this->setSize(N);
482  const bool z_valid = !Z.empty();
483  if (z_valid) for (size_t i=0;i<N;i++) { this->setPointFast(i,X[i],Y[i],Z[i]); }
484  else for (size_t i=0;i<N;i++) { this->setPointFast(i,X[i],Y[i],0); }
485  mark_as_modified();
486  }
487 
488  /** Set all the points at once from vectors with X,Y and Z coordinates. \sa getAllPoints */
489  inline void setAllPoints(const std::vector<float> &X,const std::vector<float> &Y,const std::vector<float> &Z) {
490  setAllPointsTemplate(X,Y,Z);
491  }
492 
493  /** Set all the points at once from vectors with X and Y coordinates (Z=0). \sa getAllPoints */
494  inline void setAllPoints(const std::vector<float> &X,const std::vector<float> &Y) {
495  setAllPointsTemplate(X,Y);
496  }
497 
498  /** Get all the data fields for one point as a vector: depending on the implementation class this can be [X Y Z] or [X Y Z R G B], etc...
499  * \sa getPointAllFieldsFast, setPointAllFields, setPointAllFieldsFast
500  */
501  void getPointAllFields( const size_t index, std::vector<float> & point_data ) const {
502  ASSERT_BELOW_(index,this->size())
503  getPointAllFieldsFast(index,point_data);
504  }
505 
506  /** Set all the data fields for one point as a vector: depending on the implementation class this can be [X Y Z] or [X Y Z R G B], etc...
507  * Unlike setPointAllFields(), this method does not check for index out of bounds
508  * \sa setPointAllFields, getPointAllFields, getPointAllFieldsFast
509  */
510  void setPointAllFields( const size_t index, const std::vector<float> & point_data ){
511  ASSERT_BELOW_(index,this->size())
512  setPointAllFieldsFast(index,point_data);
513  }
514 
515 
516  /** Delete points out of the given "z" axis range have been removed.
517  */
518  void clipOutOfRangeInZ(float zMin, float zMax);
519 
520  /** Delete points which are more far than "maxRange" away from the given "point".
521  */
522  void clipOutOfRange(const mrpt::math::TPoint2D &point, float maxRange);
523 
524  /** Remove from the map the points marked in a bool's array as "true".
525  * \exception std::exception If mask size is not equal to points count.
526  */
527  void applyDeletionMask( const std::vector<bool> &mask );
528 
529  // See docs in base class.
530  virtual void determineMatching2D(
531  const CMetricMap * otherMap,
532  const CPose2D & otherMapPose,
533  TMatchingPairList & correspondences,
534  const TMatchingParams & params,
535  TMatchingExtraResults & extraResults ) const;
536 
537  // See docs in base class
538  virtual void determineMatching3D(
539  const CMetricMap * otherMap,
540  const CPose3D & otherMapPose,
541  TMatchingPairList & correspondences,
542  const TMatchingParams & params,
543  TMatchingExtraResults & extraResults ) const;
544 
545  // See docs in base class
546  float compute3DMatchingRatio(
547  const CMetricMap *otherMap,
548  const CPose3D &otherMapPose,
549  float maxDistForCorr = 0.10f,
550  float maxMahaDistForCorr = 2.0f
551  ) const;
552 
553 
554  /** Computes the matchings between this and another 3D points map.
555  This method matches each point in the other map with the centroid of the 3 closest points in 3D
556  from this map (if the distance is below a defined threshold).
557 
558  * \param otherMap [IN] The other map to compute the matching with.
559  * \param otherMapPose [IN] The pose of the other map as seen from "this".
560  * \param maxDistForCorrespondence [IN] Maximum 2D linear distance between two points to be matched.
561  * \param correspondences [OUT] The detected matchings pairs.
562  * \param correspondencesRatio [OUT] The ratio [0,1] of points in otherMap with at least one correspondence.
563  *
564  * \sa determineMatching3D
565  */
566  void compute3DDistanceToMesh(
567  const CMetricMap *otherMap2,
568  const CPose3D &otherMapPose,
569  float maxDistForCorrespondence,
570  TMatchingPairList &correspondences,
571  float &correspondencesRatio );
572 
573  /** Transform the range scan into a set of cartessian coordinated
574  * points. The options in "insertionOptions" are considered in this method.
575  * \param rangeScan The scan to be inserted into this map
576  * \param robotPose The robot 3D pose, default to (0,0,0|0deg,0deg,0deg). It is used to compute the sensor pose relative to the robot actual pose. Recall sensor pose is embeded in the observation class.
577  *
578  * Only ranges marked as "valid=true" in the observation will be inserted
579  *
580  * \note Each derived class may enrich points in different ways (color, weight, etc..), so please refer to the description of the specific
581  * implementation of mrpt::slam::CPointsMap you are using.
582  * \note The actual generic implementation of this file lives in <src>/CPointsMap_crtp_common.h, but specific instantiations are generated at each derived class.
583  *
584  * \sa CObservation2DRangeScan, CObservation3DRangeScan
585  */
586  virtual void loadFromRangeScan(
587  const CObservation2DRangeScan &rangeScan,
588  const CPose3D *robotPose = NULL ) = 0;
589 
590  /** Overload of \a loadFromRangeScan() for 3D range scans (for example, Kinect observations).
591  *
592  * \param rangeScan The scan to be inserted into this map
593  * \param robotPose The robot 3D pose, default to (0,0,0|0deg,0deg,0deg). It is used to compute the sensor pose relative to the robot actual pose. Recall sensor pose is embeded in the observation class.
594  *
595  * \note Each derived class may enrich points in different ways (color, weight, etc..), so please refer to the description of the specific
596  * implementation of mrpt::slam::CPointsMap you are using.
597  * \note The actual generic implementation of this file lives in <src>/CPointsMap_crtp_common.h, but specific instantiations are generated at each derived class.
598  */
599  virtual void loadFromRangeScan(
600  const CObservation3DRangeScan &rangeScan,
601  const CPose3D *robotPose = NULL ) = 0;
602 
603  /** Insert the contents of another map into this one, fusing the previous content with the new one.
604  * This means that points very close to existing ones will be "fused", rather than "added". This prevents
605  * the unbounded increase in size of these class of maps.
606  * NOTICE that "otherMap" is neither translated nor rotated here, so if this is desired it must done
607  * before calling this method.
608  * \param otherMap The other map whose points are to be inserted into this one.
609  * \param minDistForFuse Minimum distance (in meters) between two points, each one in a map, to be considered the same one and be fused rather than added.
610  * \param notFusedPoints If a pointer is supplied, this list will contain at output a list with a "bool" value per point in "this" map. This will be false/true according to that point having been fused or not.
611  * \sa loadFromRangeScan, addFrom
612  */
613  void fuseWith(
614  CPointsMap *anotherMap,
615  float minDistForFuse = 0.02f,
616  std::vector<bool> *notFusedPoints = NULL);
617 
618  /** Replace each point \f$ p_i \f$ by \f$ p'_i = b \oplus p_i \f$ (pose compounding operator).
619  */
620  void changeCoordinatesReference(const CPose2D &b);
621 
622  /** Replace each point \f$ p_i \f$ by \f$ p'_i = b \oplus p_i \f$ (pose compounding operator).
623  */
624  void changeCoordinatesReference(const CPose3D &b);
625 
626  /** Copy all the points from "other" map to "this", replacing each point \f$ p_i \f$ by \f$ p'_i = b \oplus p_i \f$ (pose compounding operator).
627  */
628  void changeCoordinatesReference(const CPointsMap &other, const CPose3D &b);
629 
630  /** Returns true if the map is empty/no observation has been inserted.
631  */
632  virtual bool isEmpty() const;
633 
634  /** STL-like method to check whether the map is empty: */
635  inline bool empty() const { return isEmpty(); }
636 
637  /** Returns a 3D object representing the map.
638  * The color of the points is given by the static variables: COLOR_3DSCENE_R,COLOR_3DSCENE_G,COLOR_3DSCENE_B
639  * \sa mrpt::global_settings::POINTSMAPS_3DOBJECT_POINTSIZE
640  */
641  virtual void getAs3DObject ( mrpt::opengl::CSetOfObjectsPtr &outObj ) const;
642 
643  /** If the map is a simple points map or it's a multi-metric map that contains EXACTLY one simple points map, return it.
644  * Otherwise, return NULL
645  */
646  virtual const CSimplePointsMap * getAsSimplePointsMap() const { return NULL; }
647  virtual CSimplePointsMap * getAsSimplePointsMap() { return NULL; }
648 
649 
650  /** This method returns the largest distance from the origin to any of the points, such as a sphere centered at the origin with this radius cover ALL the points in the map (the results are buffered, such as, if the map is not modified, the second call will be much faster than the first one). */
651  float getLargestDistanceFromOrigin() const;
652 
653  /** Like \a getLargestDistanceFromOrigin() but returns in \a output_is_valid = false if the distance was not already computed, skipping its computation then, unlike getLargestDistanceFromOrigin() */
654  float getLargestDistanceFromOriginNoRecompute(bool &output_is_valid) const {
655  output_is_valid = m_largestDistanceFromOriginIsUpdated;
656  return m_largestDistanceFromOrigin;
657  }
658 
659  /** Computes the bounding box of all the points, or (0,0 ,0,0, 0,0) if there are no points.
660  * Results are cached unless the map is somehow modified to avoid repeated calculations.
661  */
662  void boundingBox( float &min_x,float &max_x,float &min_y,float &max_y,float &min_z,float &max_z ) const;
663 
664  inline void boundingBox(TPoint3D &pMin,TPoint3D &pMax) const {
665  float dmy1,dmy2,dmy3,dmy4,dmy5,dmy6;
666  boundingBox(dmy1,dmy2,dmy3,dmy4,dmy5,dmy6);
667  pMin.x=dmy1;
668  pMin.y=dmy3;
669  pMin.z=dmy5;
670  pMax.x=dmy2;
671  pMax.y=dmy4;
672  pMax.z=dmy6;
673  }
674 
675  /** Extracts the points in the map within a cylinder in 3D defined the provided radius and zmin/zmax values.
676  */
677  void extractCylinder( const mrpt::math::TPoint2D &center, const double radius, const double zmin, const double zmax, CPointsMap *outMap );
678 
679  /** Extracts the points in the map within the area defined by two corners.
680  * The points are coloured according the R,G,B input data.
681  */
682  void extractPoints( const TPoint3D &corner1, const TPoint3D &corner2, CPointsMap *outMap, const double &R = 1, const double &G = 1, const double &B = 1 );
683 
684  /** @name Filter-by-height stuff
685  @{ */
686 
687  /** Enable/disable the filter-by-height functionality \sa setHeightFilterLevels \note Default upon construction is disabled. */
688  inline void enableFilterByHeight(bool enable=true) { m_heightfilter_enabled=enable; }
689  /** Return whether filter-by-height is enabled \sa enableFilterByHeight */
690  inline bool isFilterByHeightEnabled() const { return m_heightfilter_enabled; }
691 
692  /** Set the min/max Z levels for points to be actually inserted in the map (only if \a enableFilterByHeight() was called before). */
693  inline void setHeightFilterLevels(const double _z_min, const double _z_max) { m_heightfilter_z_min=_z_min; m_heightfilter_z_max=_z_max; }
694  /** Get the min/max Z levels for points to be actually inserted in the map \sa enableFilterByHeight, setHeightFilterLevels */
695  inline void getHeightFilterLevels(double &_z_min, double &_z_max) const { _z_min=m_heightfilter_z_min; _z_max=m_heightfilter_z_max; }
696 
697  /** @} */
698 
699  /** The color [0,1] of points when extracted from getAs3DObject (default=blue) */
700  static float COLOR_3DSCENE_R;
701  static float COLOR_3DSCENE_G;
702  static float COLOR_3DSCENE_B;
703 
704 
705  // See docs in base class
706  virtual double computeObservationLikelihood( const CObservation *obs, const CPose3D &takenFrom );
707 
708  /** @name PCL library support
709  @{ */
710 
711 
712  /** Use to convert this MRPT point cloud object into a PCL point cloud object (PointCloud<PointXYZ>).
713  * Usage example:
714  * \code
715  * mrpt::slam::CPointsCloud pc;
716  * pcl::PointCloud<pcl::PointXYZ> cloud;
717  *
718  * pc.getPCLPointCloud(cloud);
719  * \endcode
720  * \sa setFromPCLPointCloud, CColouredPointsMap::getPCLPointCloudXYZRGB (for color data)
721  */
722  template <class POINTCLOUD>
723  void getPCLPointCloud(POINTCLOUD &cloud) const
724  {
725  const size_t nThis = this->size();
726  // Fill in the cloud data
727  cloud.width = nThis;
728  cloud.height = 1;
729  cloud.is_dense = false;
730  cloud.points.resize(cloud.width * cloud.height);
731  for (size_t i = 0; i < nThis; ++i) {
732  cloud.points[i].x =this->x[i];
733  cloud.points[i].y =this->y[i];
734  cloud.points[i].z =this->z[i];
735  }
736  }
737 
738  /** Loads a PCL point cloud into this MRPT class (note: this method ignores potential RGB information, see CColouredPointsMap::setFromPCLPointCloudRGB() ).
739  * Usage example:
740  * \code
741  * pcl::PointCloud<pcl::PointXYZ> cloud;
742  * mrpt::slam::CPointsCloud pc;
743  *
744  * pc.setFromPCLPointCloud(cloud);
745  * \endcode
746  * \sa getPCLPointCloud, CColouredPointsMap::setFromPCLPointCloudRGB()
747  */
748  template <class POINTCLOUD>
749  void setFromPCLPointCloud(const POINTCLOUD &cloud)
750  {
751  const size_t N = cloud.points.size();
752  clear();
753  reserve(N);
754  for (size_t i=0;i<N;++i)
755  this->insertPointFast(cloud.points[i].x,cloud.points[i].y,cloud.points[i].z);
756  }
757 
758  /** @} */
759 
760  /** @name Methods that MUST be implemented by children classes of KDTreeCapable
761  @{ */
762 
763  /// Must return the number of data points
764  inline size_t kdtree_get_point_count() const { return this->size(); }
765 
766  /// Returns the dim'th component of the idx'th point in the class:
767  inline float kdtree_get_pt(const size_t idx, int dim) const {
768  if (dim==0) return this->x[idx];
769  else if (dim==1) return this->y[idx];
770  else if (dim==2) return this->z[idx]; else return 0;
771  }
772 
773  /// Returns the distance between the vector "p1[0:size-1]" and the data point with index "idx_p2" stored in the class:
774  inline float kdtree_distance(const float *p1, const size_t idx_p2,size_t size) const
775  {
776  if (size==2)
777  {
778  const float d0 = p1[0]-x[idx_p2];
779  const float d1 = p1[1]-y[idx_p2];
780  return d0*d0+d1*d1;
781  }
782  else
783  {
784  const float d0 = p1[0]-x[idx_p2];
785  const float d1 = p1[1]-y[idx_p2];
786  const float d2 = p1[2]-z[idx_p2];
787  return d0*d0+d1*d1+d2*d2;
788  }
789  }
790 
791  // Optional bounding-box computation: return false to default to a standard bbox computation loop.
792  // Return true if the BBOX was already computed by the class and returned in "bb" so it can be avoided to redo it again.
793  // Look at bb.size() to find out the expected dimensionality (e.g. 2 or 3 for point clouds)
794  template <typename BBOX>
795  bool kdtree_get_bbox(BBOX &bb) const
796  {
797  float min_z,max_z;
798  this->boundingBox(
799  bb[0].low, bb[0].high,
800  bb[1].low, bb[1].high,
801  min_z,max_z);
802  if (bb.size()==3) {
803  bb[2].low = min_z; bb[2].high = max_z;
804  }
805  return true;
806  }
807 
808 
809  /** @} */
810 
811  protected:
812  std::vector<float> x,y,z; //!< The point coordinates
813 
814  CSinCosLookUpTableFor2DScans m_scans_sincos_cache; //!< Cache of sin/cos values for the latest 2D scan geometries.
815 
816  /** Auxiliary variables used in "getLargestDistanceFromOrigin"
817  * \sa getLargestDistanceFromOrigin
818  */
820 
821  /** Auxiliary variables used in "getLargestDistanceFromOrigin"
822  * \sa getLargestDistanceFromOrigin
823  */
825 
827  mutable float m_bb_min_x,m_bb_max_x, m_bb_min_y,m_bb_max_y, m_bb_min_z,m_bb_max_z;
828 
829 
830  /** Called only by this class or children classes, set m_largestDistanceFromOriginIsUpdated=false and such. */
831  inline void mark_as_modified() const
832  {
833  m_largestDistanceFromOriginIsUpdated=false;
834  m_boundingBoxIsUpdated = false;
835  kdtree_mark_as_outdated();
836  }
837 
838  /** This is a common version of CMetricMap::insertObservation() for point maps (actually, CMetricMap::internal_insertObservation),
839  * so derived classes don't need to worry implementing that method unless something special is really necesary.
840  * See mrpt::slam::CPointsMap for the enumeration of types of observations which are accepted.
841  */
842  bool internal_insertObservation(
843  const CObservation *obs,
844  const CPose3D *robotPose);
845 
846  /** Helper method for ::copyFrom() */
847  void base_copyFrom(const CPointsMap &obj);
848 
849 
850  /** @name PLY Import virtual methods to implement in base classes
851  @{ */
852  /** In a base class, reserve memory to prepare subsequent calls to PLY_import_set_face */
853  virtual void PLY_import_set_face_count(const size_t N) { MRPT_UNUSED_PARAM(N); }
854 
855  /** In a base class, will be called after PLY_import_set_vertex_count() once for each loaded point.
856  * \param pt_color Will be NULL if the loaded file does not provide color info.
857  */
858  virtual void PLY_import_set_vertex(const size_t idx, const mrpt::math::TPoint3Df &pt, const mrpt::utils::TColorf *pt_color = NULL);
859  /** @} */
860 
861  /** @name PLY Export virtual methods to implement in base classes
862  @{ */
863 
864  /** In a base class, return the number of vertices */
865  virtual size_t PLY_export_get_vertex_count() const;
866 
867  /** In a base class, return the number of faces */
868  virtual size_t PLY_export_get_face_count() const { return 0; }
869 
870  /** In a base class, will be called after PLY_export_get_vertex_count() once for each exported point.
871  * \param pt_color Will be NULL if the loaded file does not provide color info.
872  */
873  virtual void PLY_export_get_vertex(
874  const size_t idx,
876  bool &pt_has_color,
877  mrpt::utils::TColorf &pt_color) const;
878 
879  /** @} */
880 
881  /** The minimum and maximum height for a certain laser scan to be inserted into this map
882  * \sa m_heightfilter_enabled */
883  double m_heightfilter_z_min, m_heightfilter_z_max;
884 
885  /** Whether or not (default=not) filter the input points by height
886  * \sa m_heightfilter_z_min, m_heightfilter_z_max */
888 
889 
890  // Friend methods:
891  template <class Derived> friend struct detail::loadFromRangeImpl;
892  template <class Derived> friend struct detail::pointmap_traits;
893 
894 
895  }; // End of class def.
897 
898  } // End of namespace
899 
900  namespace global_settings
901  {
902  /** The size of points when exporting with getAs3DObject() (default=3.0)
903  * Affects to:
904  * - mrpt::slam::CPointsMap and all its children classes.
905  */
907  }
908 
909  namespace utils
910  {
911  /** Specialization mrpt::utils::PointCloudAdapter<mrpt::slam::CPointsMap> \ingroup mrpt_adapters_grp*/
912  template <>
913  class PointCloudAdapter<mrpt::slam::CPointsMap> : public detail::PointCloudAdapterHelperNoRGB<mrpt::slam::CPointsMap,float>
914  {
915  private:
917  public:
918  typedef float coords_t; //!< The type of each point XYZ coordinates
919  static const int HAS_RGB = 0; //!< Has any color RGB info?
920  static const int HAS_RGBf = 0; //!< Has native RGB info (as floats)?
921  static const int HAS_RGBu8 = 0; //!< Has native RGB info (as uint8_t)?
922 
923  /** Constructor (accept a const ref for convenience) */
924  inline PointCloudAdapter(const mrpt::slam::CPointsMap &obj) : m_obj(*const_cast<mrpt::slam::CPointsMap*>(&obj)) { }
925  /** Get number of points */
926  inline size_t size() const { return m_obj.size(); }
927  /** Set number of points (to uninitialized values) */
928  inline void resize(const size_t N) { m_obj.resize(N); }
929 
930  /** Get XYZ coordinates of i'th point */
931  template <typename T>
932  inline void getPointXYZ(const size_t idx, T &x,T &y, T &z) const {
933  m_obj.getPointFast(idx,x,y,z);
934  }
935  /** Set XYZ coordinates of i'th point */
936  inline void setPointXYZ(const size_t idx, const coords_t x,const coords_t y, const coords_t z) {
937  m_obj.setPointFast(idx,x,y,z);
938  }
939  }; // end of PointCloudAdapter<mrpt::slam::CPointsMap>
940 
941  }
942 
943 } // End of namespace
944 
945 #endif
#define ASSERT_EQUAL_(__A, __B)
virtual CSimplePointsMap * getAsSimplePointsMap()
Definition: CPointsMap.h:647
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
bool isPlanarMap
If set to true, only HORIZONTAL (in the XY plane) measurements will be inserted in the map (Default v...
Definition: CPointsMap.h:179
MAPS_IMPEXP float POINTSMAPS_3DOBJECT_POINTSIZE
The size of points when exporting with getAs3DObject() (default=3.0) Affects to:
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:389
virtual void PLY_import_set_face_count(const size_t N)
In a base class, reserve memory to prepare subsequent calls to PLY_import_set_face.
Definition: CPointsMap.h:853
double y
X,Y coordinates.
bool empty() const
STL-like method to check whether the map is empty:
Definition: CPointsMap.h:635
bool m_largestDistanceFromOriginIsUpdated
Auxiliary variables used in "getLargestDistanceFromOrigin".
Definition: CPointsMap.h:824
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:414
unsigned long getPoint(size_t index, mrpt::math::TPoint2D &p) const
Definition: CPointsMap.h:346
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:693
const std::vector< float > & getPointsBufferRef_y() const
Provides a direct access to a read-only reference of the internal point buffer.
Definition: CPointsMap.h:404
bool load2D_from_text_file(const std::string &file)
Load from a text file.
Definition: CPointsMap.h:253
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:362
PointCloudAdapter(const mrpt::slam::CPointsMap &obj)
Constructor (accept a const ref for convenience)
Definition: CPointsMap.h:924
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...
double max_corr_distance
Maximum distance in meters to consider for the numerator divided by "sigma_dist", so that each point ...
Definition: CPointsMap.h:212
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
A helper base class for those PointCloudAdapter<> which do not handle RGB data; it declares needed in...
Definition: adapters.h:48
virtual bool hasColorPoints() const
Returns true if the point map has a color field for each point.
Definition: CPointsMap.h:365
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:774
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:177
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:494
bool addToExistingPointsMap
Applicable to "loadFromRangeScan" only! If set to false, the points from the scan are loaded...
Definition: CPointsMap.h:175
#define ASSERT_BELOW_(__A, __B)
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:489
Options used when evaluating "computeObservationLikelihood" in the derived classes.
Definition: CPointsMap.h:193
float scan_z
In internal_loadFromRangeScan3D_prepareOneRange, these are the local coordinates of the scan points b...
Definition: CPointsMap.h:86
size_t size() const
Returns the number of stored points in the map.
Definition: CPointsMap.h:331
bool insertInvalidPoints
Points with x,y,z coordinates set to zero will also be inserted.
Definition: CPointsMap.h:182
bool m_heightfilter_enabled
Whether or not (default=not) filter the input points by height.
Definition: CPointsMap.h:887
TLikelihoodOptions likelihoodOptions
Definition: CPointsMap.h:216
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:510
void enableFilterByHeight(bool enable=true)
Enable/disable the filter-by-height functionality.
Definition: CPointsMap.h:688
CMatrixDouble44 HM
Homog matrix of the local sensor pose within the robot.
Definition: CPointsMap.h:84
With this struct options are provided to the observation insertion process.
Definition: CPointsMap.h:165
float squareDistanceToClosestCorrespondenceT(const TPoint2D &p0) const
Definition: CPointsMap.h:157
void resize(const size_t N)
Set number of points (to uninitialized values)
Definition: CPointsMap.h:928
Optional settings for loadLASFile()
Definition: CPointsMap.h:297
virtual void setPoint(size_t index, float x, float y, float z, float R, float G, float B)
Definition: CPointsMap.h:382
double z
X,Y,Z coordinates.
TInsertionOptions insertionOptions
The options used when inserting observations in the map.
Definition: CPointsMap.h:188
void mark_as_modified() const
Called only by this class or children classes, set m_largestDistanceFromOriginIsUpdated=false and suc...
Definition: CPointsMap.h:831
static float COLOR_3DSCENE_G
Definition: CPointsMap.h:701
void setFromPCLPointCloud(const POINTCLOUD &cloud)
Loads a PCL point cloud into this MRPT class (note: this method ignores potential RGB information...
Definition: CPointsMap.h:749
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:180
unsigned long getPoint(size_t index, mrpt::math::TPoint3D &p) const
Definition: CPointsMap.h:348
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:
TLaserRange3DInsertContext(const CObservation3DRangeScan &_rangeScan)
Definition: CPointsMap.h:82
Declares a virtual base class for all metric maps storage classes.
Definition: CMetricMap.h:83
virtual void insertPoint(float x, float y, float z, float R, float G, float B)
Definition: CPointsMap.h:466
static float COLOR_3DSCENE_R
The color [0,1] of points when extracted from getAs3DObject (default=blue)
Definition: CPointsMap.h:700
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:38
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:462
A numeric matrix of compile-time fixed size.
This base provides a set of functions for maths stuff.
Definition: CArray.h:18
#define DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
This declaration must be inserted in all CSerializable classes definition, before the class declarati...
void setPoint(size_t index, mrpt::math::TPoint2D &p)
Definition: CPointsMap.h:376
Lightweight 3D point (float version).
#define MRPT_END
uint16_t creation_year
Creation date (Year number)
Definition: CPointsMap.h:310
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
uint32_t decimation
Speed up the likelihood computation by considering only one out of N rays (default=10) ...
Definition: CPointsMap.h:213
float m_largestDistanceFromOrigin
Auxiliary variables used in "getLargestDistanceFromOrigin".
Definition: CPointsMap.h:819
Optional settings for saveLASFile()
Definition: CPointsMap.h:291
const CObservation3DRangeScan & rangeScan
Definition: CPointsMap.h:85
CMatrixDouble44 HM
Homog matrix of the local sensor pose within the robot.
Definition: CPointsMap.h:73
bool kdtree_get_bbox(BBOX &bb) const
Definition: CPointsMap.h:795
std::vector< T1 > & operator+=(std::vector< T1 > &a, const std::vector< T2 > &b)
a+=b (element-wise sum)
Definition: ops_vectors.h:70
TLaserRange2DInsertContext(const CObservation2DRangeScan &_rangeScan)
Definition: CPointsMap.h:71
A list of TMatchingPair.
Definition: TMatchingPair.h:66
Declares a class that represents any robot's observation.
Definition: CObservation.h:52
Helper struct used for internal_loadFromRangeScan2D_prepareOneRange()
Definition: CPointsMap.h:70
virtual size_t PLY_export_get_face_count() const
In a base class, return the number of faces.
Definition: CPointsMap.h:868
EIGEN_STRONG_INLINE void setSize(size_t row, size_t col)
Changes the size of matrix, maintaining its previous content as possible and padding with zeros where...
bool load3D_from_text_file(const std::string &file)
Load from a text file.
Definition: CPointsMap.h:258
void getPCLPointCloud(POINTCLOUD &cloud) const
Use to convert this MRPT point cloud object into a PCL point cloud object (PointCloud).
Definition: CPointsMap.h:723
size_t size() const
Get number of points.
Definition: CPointsMap.h:926
A smart look-up-table (LUT) of sin/cos values for 2D laser scans.
Helper struct used for internal_loadFromRangeScan3D_prepareOneRange()
Definition: CPointsMap.h:81
Parameters for the determination of matchings between point clouds, etc.
Definition: CMetricMap.h:32
void boundingBox(TPoint3D &pMin, TPoint3D &pMax) const
Definition: CPointsMap.h:664
A virtual base class that implements the capability of importing 3D point clouds and faces from a fil...
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:654
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:354
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:695
void getAllPoints(std::vector< TPoint3D > &ps, size_t decimation=1) const
Definition: CPointsMap.h:432
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Definition: CPoint.h:17
double m_heightfilter_z_min
The minimum and maximum height for a certain laser scan to be inserted into this map.
Definition: CPointsMap.h:883
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...
const std::vector< float > & getPointsBufferRef_z() const
Provides a direct access to a read-only reference of the internal point buffer.
Definition: CPointsMap.h:406
std::vector< float > fVars
Extra variables to be used as desired by the derived class.
Definition: CPointsMap.h:75
void insertPoint(const mrpt::math::TPoint3D &p)
Definition: CPointsMap.h:464
#define MRPT_START
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
An adapter to different kinds of point cloud object.
Definition: adapters.h:38
void setPoint(size_t index, float x, float y)
Definition: CPointsMap.h:380
void getPointXYZ(const size_t idx, T &x, T &y, T &z) const
Get XYZ coordinates of i'th point.
Definition: CPointsMap.h:932
static float COLOR_3DSCENE_B
Definition: CPointsMap.h:702
size_t size(const MATRIXLIKE &m, int dim)
Definition: bits.h:38
A class used to store a 2D pose.
Definition: CPose2D.h:36
float kdtree_get_pt(const size_t idx, int dim) const
Returns the dim'th component of the idx'th point in the class:
Definition: CPointsMap.h:767
bool isFilterByHeightEnabled() const
Return whether filter-by-height is enabled.
Definition: CPointsMap.h:690
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:69
float coords_t
The type of each point XYZ coordinates.
Definition: CPointsMap.h:918
bool fuseWithExisting
If set to true (default=false), inserted points are "fused" with previously existent ones...
Definition: CPointsMap.h:178
double sigma_dist
Sigma (standard deviation, in meters) of the exponential used to model the likelihood (default= 0...
Definition: CPointsMap.h:211
float minDistBetweenLaserPoints
The minimum distance between points (in 3D): If two points are too close, one of them is not inserted...
Definition: CPointsMap.h:174
size_t kdtree_get_point_count() const
Must return the number of data points.
Definition: CPointsMap.h:764
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:476
uint16_t creation_DOY
Creation day of year.
Definition: CPointsMap.h:311
const std::vector< float > & getPointsBufferRef_x() const
Provides a direct access to a read-only reference of the internal point buffer.
Definition: CPointsMap.h:402
#define ASSERT_(f)
A RGB color - floats in the range [0,1].
Definition: TColor.h:52
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:394
Additional results from the determination of matchings between point clouds, etc., apart from the pairings themselves.
Definition: CMetricMap.h:55
bool also_interpolate
If set to true, far points (<1m) are interpolated with samples at "minDistSqrBetweenLaserPoints" inte...
Definition: CPointsMap.h:176
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors...
Definition: CPointsMap.h:59
float maxDistForInterpolatePoints
The maximum distance between two points to interpolate between them (ONLY when also_interpolate=true)...
Definition: CPointsMap.h:181
void setPointXYZ(const size_t idx, const coords_t x, const coords_t y, const coords_t z)
Set XYZ coordinates of i'th point.
Definition: CPointsMap.h:936
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement (e...
virtual const CSimplePointsMap * getAsSimplePointsMap() const
If the map is a simple points map or it's a multi-metric map that contains EXACTLY one simple points ...
Definition: CPointsMap.h:646
Extra information gathered from the LAS file header.
Definition: CPointsMap.h:303
Lightweight 3D point.
void setPoint(size_t index, mrpt::math::TPoint3D &p)
Definition: CPointsMap.h:378
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
Lightweight 2D point.
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:501
A virtual base class that implements the capability of exporting 3D point clouds and faces to a file ...
std::string spatial_reference_proj4
Proj.4 string describing the Spatial Reference System.
Definition: CPointsMap.h:309
std::vector< float > fVars
Extra variables to be used as desired by the derived class.
Definition: CPointsMap.h:87
void getAllPoints(std::vector< TPoint2D > &ps, size_t decimation=1) const
Definition: CPointsMap.h:449
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:370
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
CSinCosLookUpTableFor2DScans m_scans_sincos_cache
Cache of sin/cos values for the latest 2D scan geometries.
Definition: CPointsMap.h:814
const CObservation2DRangeScan & rangeScan
Definition: CPointsMap.h:74
void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const
This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >...
Definition: CPointsMap.h:275
std::vector< float > z
The point coordinates.
Definition: CPointsMap.h:812



Page generated by Doxygen 1.8.8 for MRPT 1.2.2 SVN:Unversioned directory at Tue Oct 14 02:14:08 UTC 2014