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



Page generated by Doxygen 1.8.9.1 for MRPT 1.3.0 SVN: at Sun Sep 13 03:55:12 UTC 2015