Main MRPT website > C++ reference for MRPT 1.9.9
CColouredPointsMap.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-2018, 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 #pragma once
10 
11 #include <mrpt/maps/CPointsMap.h>
12 #include <mrpt/obs/obs_frwds.h>
15 #include <mrpt/math/CMatrix.h>
17 
18 namespace mrpt
19 {
20 namespace maps
21 {
22 /** A map of 2D/3D points with individual colours (RGB).
23  * For different color schemes, see CColouredPointsMap::colorScheme
24  * Colors are defined in the range [0,1].
25  * \sa mrpt::maps::CPointsMap, mrpt::maps::CMetricMap,
26  * mrpt::serialization::CSerializable
27  * \ingroup mrpt_maps_grp
28  */
30 {
32 
33  public:
34  // --------------------------------------------
35  /** @name Pure virtual interfaces to be implemented by any class derived
36  from CPointsMap
37  @{ */
38 
39  virtual void reserve(size_t newLength) override; // See base class docs
40  virtual void resize(size_t newLength) override; // See base class docs
41  virtual void setSize(size_t newLength) override; // See base class docs
42 
43  /** Changes the coordinates of the given point (0-based index), *without*
44  * checking for out-of-bounds and *without* calling mark_as_modified() \sa
45  * setPoint */
46  virtual void setPointFast(size_t index, float x, float y, float z) override
47  {
48  m_x[index] = x;
49  m_y[index] = y;
50  m_z[index] = z;
51  }
52 
53  /** The virtual method for \a insertPoint() *without* calling
54  * mark_as_modified() */
55  virtual void insertPointFast(float x, float y, float z = 0) override;
56 
57  /** Virtual assignment operator, to be implemented in derived classes */
58  virtual void copyFrom(const CPointsMap& obj) override;
59 
60  /** Get all the data fields for one point as a vector: [X Y Z R G B]
61  * Unlike getPointAllFields(), this method does not check for index out of
62  * bounds
63  * \sa getPointAllFields, setPointAllFields, setPointAllFieldsFast
64  */
65  virtual void getPointAllFieldsFast(
66  const size_t index, std::vector<float>& point_data) const override
67  {
68  point_data.resize(6);
69  point_data[0] = m_x[index];
70  point_data[1] = m_y[index];
71  point_data[2] = m_z[index];
72  point_data[3] = m_color_R[index];
73  point_data[4] = m_color_G[index];
74  point_data[5] = m_color_B[index];
75  }
76 
77  /** Set all the data fields for one point as a vector: [X Y Z R G B]
78  * Unlike setPointAllFields(), this method does not check for index out of
79  * bounds
80  * \sa setPointAllFields, getPointAllFields, getPointAllFieldsFast
81  */
82  virtual void setPointAllFieldsFast(
83  const size_t index, const std::vector<float>& point_data) override
84  {
85  ASSERTDEB_(point_data.size() == 6);
86  m_x[index] = point_data[0];
87  m_y[index] = point_data[1];
88  m_z[index] = point_data[2];
89  m_color_R[index] = point_data[3];
90  m_color_G[index] = point_data[4];
91  m_color_B[index] = point_data[5];
92  }
93 
94  /** See CPointsMap::loadFromRangeScan() */
95  virtual void loadFromRangeScan(
96  const mrpt::obs::CObservation2DRangeScan& rangeScan,
97  const mrpt::poses::CPose3D* robotPose = nullptr) override;
98  /** See CPointsMap::loadFromRangeScan() */
99  virtual void loadFromRangeScan(
100  const mrpt::obs::CObservation3DRangeScan& rangeScan,
101  const mrpt::poses::CPose3D* robotPose = nullptr) override;
102 
103  protected:
104  /** Auxiliary method called from within \a addFrom() automatically, to
105  * finish the copying of class-specific data */
106  virtual void addFrom_classSpecific(
107  const CPointsMap& anotherMap, const size_t nPreviousPoints) override;
108 
109  // Friend methods:
110  template <class Derived>
112  template <class Derived>
113  friend struct detail::pointmap_traits;
114 
115  public:
116  /** @} */
117  // --------------------------------------------
118 
119  /** Save to a text file. In each line contains X Y Z (meters) R G B (range
120  * [0,1]) for each point in the map.
121  * Returns false if any error occured, true elsewere.
122  */
123  bool save3D_and_colour_to_text_file(const std::string& file) const;
124 
125  /** Changes a given point from map. First index is 0.
126  * \exception Throws std::exception on index out of bound.
127  */
128  virtual void setPoint(
129  size_t index, float x, float y, float z, float R, float G,
130  float B) override;
131 
132  // The following overloads must be repeated here (from CPointsMap) due to
133  // the shadowing of the above "setPoint()"
134  /// \overload
135  inline void setPoint(size_t index, float x, float y, float z)
136  {
137  ASSERT_BELOW_(index, this->size());
138  setPointFast(index, x, y, z);
140  }
141  /// \overload
142  inline void setPoint(size_t index, mrpt::math::TPoint3Df& p)
143  {
144  setPoint(index, p.x, p.y, p.z);
145  }
146  /// \overload
147  inline void setPoint(size_t index, float x, float y)
148  {
149  setPoint(index, x, y, 0);
150  }
151 
152  /** Adds a new point given its coordinates and color (colors range is [0,1])
153  */
154  virtual void insertPoint(
155  float x, float y, float z, float R, float G, float B) override;
156  // The following overloads must be repeated here (from CPointsMap) due to
157  // the shadowing of the above "insertPoint()"
158  /// \overload
159  template <typename POINT_T>
160  inline void insertPoint(const POINT_T& p)
161  {
162  insertPoint(p[0], p[1], p[2]);
163  }
164  /// \overload
165  inline void insertPoint(float x, float y, float z)
166  {
167  insertPointFast(x, y, z);
169  }
170 
171  /** Changes just the color of a given point from the map. First index is 0.
172  * \exception Throws std::exception on index out of bound.
173  */
174  void setPointColor(size_t index, float R, float G, float B);
175 
176  /** Like \c setPointColor but without checking for out-of-index erors */
177  inline void setPointColor_fast(size_t index, float R, float G, float B)
178  {
179  m_color_R[index] = R;
180  m_color_G[index] = G;
181  m_color_B[index] = B;
182  }
183 
184  /** Retrieves a point and its color (colors range is [0,1])
185  */
186  virtual void getPoint(
187  size_t index, float& x, float& y, float& z, float& R, float& G,
188  float& B) const override;
189 
190  /** Retrieves a point */
191  unsigned long getPoint(size_t index, float& x, float& y, float& z) const;
192 
193  /** Retrieves a point color (colors range is [0,1]) */
194  void getPointColor(size_t index, float& R, float& G, float& B) const;
195 
196  /** Like \c getPointColor but without checking for out-of-index erors */
197  inline void getPointColor_fast(
198  size_t index, float& R, float& G, float& B) const
199  {
200  R = m_color_R[index];
201  G = m_color_G[index];
202  B = m_color_B[index];
203  }
204 
205  /** Returns true if the point map has a color field for each point */
206  virtual bool hasColorPoints() const override { return true; }
207  /** Override of the default 3D scene builder to account for the individual
208  * points' color.
209  */
210  virtual void getAs3DObject(
211  mrpt::opengl::CSetOfObjects::Ptr& outObj) const override;
212 
213  /** Colour a set of points from a CObservationImage and the global pose of
214  * the robot */
216  const mrpt::obs::CObservationImage& obs,
217  const mrpt::poses::CPose3D& robotPose);
218 
219  /** The choices for coloring schemes:
220  * - cmFromHeightRelativeToSensor: The Z coordinate wrt the sensor will
221  *be
222  *used to obtain the color using the limits z_min,z_max.
223  * - cmFromIntensityImage: When inserting 3D range scans, take the
224  *color
225  *from the intensity image channel, if available.
226  * \sa TColourOptions
227  */
229  {
234  // Remember: if new values are added, also update TEnumType below!
235  };
236 
237  /** The definition of parameters for generating colors from laser scans */
239  {
240  /** Initilization of default parameters */
241  TColourOptions();
242  void loadFromConfigFile(
244  const std::string& section) override; // See base docs
245  void dumpToTextStream(
246  std::ostream& out) const override; // See base docs
247 
249  float z_min, z_max;
250  float d_max;
251  };
252 
253  /** The options employed when inserting laser scans in the map. */
255 
256  /** Reset the minimum-observed-distance buffer for all the points to a
257  * predefined value */
258  void resetPointsMinDist(float defValue = 2000.0f);
259 
260  /** @name PCL library support
261  @{ */
262 
263  /** Save the point cloud as a PCL PCD file, in either ASCII or binary format
264  * \return false on any error */
265  virtual bool savePCDFile(
266  const std::string& filename, bool save_as_binary) const override;
267 
268  /** Loads a PCL point cloud (WITH RGB information) into this MRPT class (for
269  * clouds without RGB data, see CPointsMap::setFromPCLPointCloud() ).
270  * Usage example:
271  * \code
272  * pcl::PointCloud<pcl::PointXYZRGB> cloud;
273  * mrpt::maps::CColouredPointsMap pc;
274  *
275  * pc.setFromPCLPointCloudRGB(cloud);
276  * \endcode
277  * \sa CPointsMap::setFromPCLPointCloud()
278  */
279  template <class POINTCLOUD>
280  void setFromPCLPointCloudRGB(const POINTCLOUD& cloud)
281  {
282  const size_t N = cloud.points.size();
283  clear();
284  reserve(N);
285  const float f = 1.0f / 255.0f;
286  for (size_t i = 0; i < N; ++i)
287  this->insertPoint(
288  cloud.points[i].x, cloud.points[i].y, cloud.points[i].z,
289  cloud.points[i].r * f, cloud.points[i].g * f,
290  cloud.points[i].b * f);
291  }
292 
293  /** Like CPointsMap::getPCLPointCloud() but for PointCloud<PointXYZRGB> */
294  template <class POINTCLOUD>
295  void getPCLPointCloudXYZRGB(POINTCLOUD& cloud) const
296  {
297  const size_t nThis = this->size();
298  this->getPCLPointCloud(cloud); // 1st: xyz data
299  // 2nd: RGB data
300  for (size_t i = 0; i < nThis; ++i)
301  {
302  float R, G, B;
303  this->getPointColor_fast(i, R, G, B);
304  cloud.points[i].r = static_cast<uint8_t>(R * 255);
305  cloud.points[i].g = static_cast<uint8_t>(G * 255);
306  cloud.points[i].b = static_cast<uint8_t>(B * 255);
307  }
308  }
309  /** @} */
310 
311  protected:
312  /** The color data */
314 
315  /** Minimum distance from where the points have been seen */
316  // std::vector<float> m_min_dist;
317 
318  /** Clear the map, erasing all the points */
319  virtual void internal_clear() override;
320 
321  /** @name Redefinition of PLY Import virtual methods from CPointsMap
322  @{ */
323  /** In a base class, will be called after PLY_import_set_vertex_count() once
324  * for each loaded point.
325  * \param pt_color Will be nullptr if the loaded file does not provide
326  * color info.
327  */
328  virtual void PLY_import_set_vertex(
329  const size_t idx, const mrpt::math::TPoint3Df& pt,
330  const mrpt::img::TColorf* pt_color = nullptr) override;
331 
332  /** In a base class, reserve memory to prepare subsequent calls to
333  * PLY_import_set_vertex */
334  virtual void PLY_import_set_vertex_count(const size_t N) override;
335  /** @} */
336 
337  /** @name Redefinition of PLY Export virtual methods from CPointsMap
338  @{ */
340  const size_t idx, mrpt::math::TPoint3Df& pt, bool& pt_has_color,
341  mrpt::img::TColorf& pt_color) const override;
342  /** @} */
343 
345  mrpt::maps::CPointsMap::TInsertionOptions insertionOpts;
346  mrpt::maps::CPointsMap::TLikelihoodOptions likelihoodOpts;
349 
350 }; // End of class def.
351 
352 } // namespace maps
353 
354 #include <mrpt/opengl/pointcloud_adapters.h>
355 namespace opengl
356 {
357 /** Specialization
358  * mrpt::opengl::PointCloudAdapter<mrpt::maps::CColouredPointsMap> \ingroup
359  * mrpt_adapters_grp */
360 template <>
362 {
363  private:
365 
366  public:
367  /** The type of each point XYZ coordinates */
368  using coords_t = float;
369  /** Has any color RGB info? */
370  static const int HAS_RGB = 1;
371  /** Has native RGB info (as floats)? */
372  static const int HAS_RGBf = 1;
373  /** Has native RGB info (as uint8_t)? */
374  static const int HAS_RGBu8 = 0;
375 
376  /** Constructor (accept a const ref for convenience) */
378  : m_obj(*const_cast<mrpt::maps::CColouredPointsMap*>(&obj))
379  {
380  }
381  /** Get number of points */
382  inline size_t size() const { return m_obj.size(); }
383  /** Set number of points (to uninitialized values) */
384  inline void resize(const size_t N) { m_obj.resize(N); }
385  /** Get XYZ coordinates of i'th point */
386  template <typename T>
387  inline void getPointXYZ(const size_t idx, T& x, T& y, T& z) const
388  {
389  m_obj.getPointFast(idx, x, y, z);
390  }
391  /** Set XYZ coordinates of i'th point */
392  inline void setPointXYZ(
393  const size_t idx, const coords_t x, const coords_t y, const coords_t z)
394  {
395  m_obj.setPointFast(idx, x, y, z);
396  }
397 
398  /** Get XYZ_RGBf coordinates of i'th point */
399  template <typename T>
400  inline void getPointXYZ_RGBf(
401  const size_t idx, T& x, T& y, T& z, float& r, float& g, float& b) const
402  {
403  m_obj.getPoint(idx, x, y, z, r, g, b);
404  }
405  /** Set XYZ_RGBf coordinates of i'th point */
406  inline void setPointXYZ_RGBf(
407  const size_t idx, const coords_t x, const coords_t y, const coords_t z,
408  const float r, const float g, const float b)
409  {
410  m_obj.setPoint(idx, x, y, z, r, g, b);
411  }
412 
413  /** Get XYZ_RGBu8 coordinates of i'th point */
414  template <typename T>
415  inline void getPointXYZ_RGBu8(
416  const size_t idx, T& x, T& y, T& z, uint8_t& r, uint8_t& g,
417  uint8_t& b) const
418  {
419  float Rf, Gf, Bf;
420  m_obj.getPoint(idx, x, y, z, Rf, Gf, Bf);
421  r = Rf * 255;
422  g = Gf * 255;
423  b = Bf * 255;
424  }
425  /** Set XYZ_RGBu8 coordinates of i'th point */
426  inline void setPointXYZ_RGBu8(
427  const size_t idx, const coords_t x, const coords_t y, const coords_t z,
428  const uint8_t r, const uint8_t g, const uint8_t b)
429  {
430  m_obj.setPoint(idx, x, y, z, r / 255.f, g / 255.f, b / 255.f);
431  }
432 
433  /** Get RGBf color of i'th point */
434  inline void getPointRGBf(
435  const size_t idx, float& r, float& g, float& b) const
436  {
437  m_obj.getPointColor_fast(idx, r, g, b);
438  }
439  /** Set XYZ_RGBf coordinates of i'th point */
440  inline void setPointRGBf(
441  const size_t idx, const float r, const float g, const float b)
442  {
443  m_obj.setPointColor_fast(idx, r, g, b);
444  }
445 
446  /** Get RGBu8 color of i'th point */
447  inline void getPointRGBu8(
448  const size_t idx, uint8_t& r, uint8_t& g, uint8_t& b) const
449  {
450  float R, G, B;
451  m_obj.getPointColor_fast(idx, R, G, B);
452  r = R * 255;
453  g = G * 255;
454  b = B * 255;
455  }
456  /** Set RGBu8 coordinates of i'th point */
457  inline void setPointRGBu8(
458  const size_t idx, const uint8_t r, const uint8_t g, const uint8_t b)
459  {
460  m_obj.setPointColor_fast(idx, r / 255.f, g / 255.f, b / 255.f);
461  }
462 
463 }; // end of PointCloudAdapter<mrpt::maps::CColouredPointsMap>
464 } // namespace opengl
465 } // namespace mrpt
466 
470  cmFromHeightRelativeToSensor);
473  cmFromHeightRelativeToSensorJet);
476  cmFromHeightRelativeToSensorGray);
mrpt::math::TPoint3Df
Lightweight 3D point (float version).
Definition: lightweight_geom_data.h:315
mrpt::opengl::PointCloudAdapter
An adapter to different kinds of point cloud object.
Definition: pointcloud_adapters.h:39
mrpt::opengl::PointCloudAdapter< mrpt::maps::CColouredPointsMap >::coords_t
float coords_t
The type of each point XYZ coordinates.
Definition: CColouredPointsMap.h:368
mrpt::maps::CColouredPointsMap::setPointColor
void setPointColor(size_t index, float R, float G, float B)
Changes just the color of a given point from the map.
Definition: CColouredPointsMap.cpp:346
mrpt::opengl::PointCloudAdapter< mrpt::maps::CColouredPointsMap >::setPointXYZ_RGBu8
void setPointXYZ_RGBu8(const size_t idx, const coords_t x, const coords_t y, const coords_t z, const uint8_t r, const uint8_t g, const uint8_t b)
Set XYZ_RGBu8 coordinates of i'th point.
Definition: CColouredPointsMap.h:426
mrpt::maps::CColouredPointsMap::TColourOptions::dumpToTextStream
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form,...
Definition: CColouredPointsMap.cpp:418
mrpt::maps::CColouredPointsMap::save3D_and_colour_to_text_file
bool save3D_and_colour_to_text_file(const std::string &file) const
Save to a text file.
Definition: CColouredPointsMap.cpp:599
mrpt::maps::CPointsMap::size
size_t size() const
Returns the number of stored points in the map.
Definition: CPointsMap.h:408
mrpt::maps::CColouredPointsMap::PLY_import_set_vertex
virtual void PLY_import_set_vertex(const size_t idx, const mrpt::math::TPoint3Df &pt, const mrpt::img::TColorf *pt_color=nullptr) override
In a base class, will be called after PLY_import_set_vertex_count() once for each loaded point.
Definition: CColouredPointsMap.cpp:632
mrpt::maps::CPointsMap::TLikelihoodOptions
Options used when evaluating "computeObservationLikelihood" in the derived classes.
Definition: CPointsMap.h:263
mrpt::opengl::PointCloudAdapter< mrpt::maps::CColouredPointsMap >::getPointRGBu8
void getPointRGBu8(const size_t idx, uint8_t &r, uint8_t &g, uint8_t &b) const
Get RGBu8 color of i'th point.
Definition: CColouredPointsMap.h:447
mrpt::maps::CColouredPointsMap
A map of 2D/3D points with individual colours (RGB).
Definition: CColouredPointsMap.h:29
MRPT_ENUM_TYPE_END
#define MRPT_ENUM_TYPE_END()
Definition: TEnumType.h:74
mrpt::maps::CPointsMap::getPointFast
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:450
mrpt::maps::CColouredPointsMap::colorScheme
TColourOptions colorScheme
The options employed when inserting laser scans in the map.
Definition: CColouredPointsMap.h:254
G
const double G
Definition: vision_stereo_rectify/test.cpp:31
mrpt::maps::CColouredPointsMap::insertPointFast
virtual void insertPointFast(float x, float y, float z=0) override
The virtual method for insertPoint() without calling mark_as_modified()
Definition: CColouredPointsMap.cpp:355
CPointsMap.h
mrpt::maps::CColouredPointsMap::cmFromIntensityImage
@ cmFromIntensityImage
Definition: CColouredPointsMap.h:233
mrpt::obs::CObservation2DRangeScan
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
Definition: CObservation2DRangeScan.h:56
mrpt::maps::CColouredPointsMap::setPoint
virtual void setPoint(size_t index, float x, float y, float z, float R, float G, float B) override
Changes a given point from map.
Definition: CColouredPointsMap.cpp:330
mrpt::maps::CColouredPointsMap::TColourOptions::z_min
float z_min
Definition: CColouredPointsMap.h:249
mrpt::maps::CPointsMap::TInsertionOptions
With this struct options are provided to the observation insertion process.
Definition: CPointsMap.h:205
mrpt::maps::CColouredPointsMap::setPointColor_fast
void setPointColor_fast(size_t index, float R, float G, float B)
Like setPointColor but without checking for out-of-index erors.
Definition: CColouredPointsMap.h:177
mrpt::maps::CColouredPointsMap::hasColorPoints
virtual bool hasColorPoints() const override
Returns true if the point map has a color field for each point.
Definition: CColouredPointsMap.h:206
mrpt::maps::CColouredPointsMap::TColourOptions::scheme
TColouringMethod scheme
Definition: CColouredPointsMap.h:248
mrpt::maps::CColouredPointsMap::m_color_R
mrpt::aligned_std_vector< float > m_color_R
The color data.
Definition: CColouredPointsMap.h:313
MRPT_FILL_ENUM_MEMBER
MRPT_FILL_ENUM_MEMBER(mrpt::maps::CColouredPointsMap::TColouringMethod, cmFromHeightRelativeToSensor)
mrpt::opengl::PointCloudAdapter< mrpt::maps::CColouredPointsMap >::size
size_t size() const
Get number of points.
Definition: CColouredPointsMap.h:382
obj
GLsizei GLsizei GLuint * obj
Definition: glext.h:4070
mrpt::maps::CColouredPointsMap::TColourOptions::z_max
float z_max
Definition: CColouredPointsMap.h:249
mrpt::maps::CColouredPointsMap::internal_clear
virtual void internal_clear() override
Minimum distance from where the points have been seen.
Definition: CColouredPointsMap.cpp:313
CMatrix.h
mrpt::opengl::PointCloudAdapter< mrpt::maps::CColouredPointsMap >::getPointXYZ_RGBu8
void getPointXYZ_RGBu8(const size_t idx, T &x, T &y, T &z, uint8_t &r, uint8_t &g, uint8_t &b) const
Get XYZ_RGBu8 coordinates of i'th point.
Definition: CColouredPointsMap.h:415
mrpt::maps::CColouredPointsMap::m_color_G
mrpt::aligned_std_vector< float > m_color_G
Definition: CColouredPointsMap.h:313
mrpt::maps::CColouredPointsMap::reserve
virtual void reserve(size_t newLength) override
Reserves memory for a given number of points: the size of the map does not change,...
Definition: CColouredPointsMap.cpp:78
mrpt::maps::CColouredPointsMap::TColourOptions::TColourOptions
TColourOptions()
Initilization of default parameters.
Definition: CColouredPointsMap.cpp:404
mrpt::maps::CPointsMap
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors.
Definition: CPointsMap.h:64
mrpt::maps::CColouredPointsMap::resize
virtual void resize(size_t newLength) override
Resizes all point buffers so they can hold the given number of points: newly created points are set t...
Definition: CColouredPointsMap.cpp:91
mrpt
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Definition: CKalmanFilterCapable.h:30
g
GLubyte g
Definition: glext.h:6279
uint8_t
unsigned char uint8_t
Definition: rptypes.h:41
mrpt::maps::CColouredPointsMap::setFromPCLPointCloudRGB
void setFromPCLPointCloudRGB(const POINTCLOUD &cloud)
Loads a PCL point cloud (WITH RGB information) into this MRPT class (for clouds without RGB data,...
Definition: CColouredPointsMap.h:280
R
const float R
Definition: CKinematicChain.cpp:138
p
GLfloat GLfloat p
Definition: glext.h:6305
MRPT_ENUM_TYPE_BEGIN
#define MRPT_ENUM_TYPE_BEGIN(_ENUM_TYPE_WITH_NS)
Definition: TEnumType.h:58
mrpt::opengl::PointCloudAdapter< mrpt::maps::CColouredPointsMap >::resize
void resize(const size_t N)
Set number of points (to uninitialized values)
Definition: CColouredPointsMap.h:384
mrpt::maps::CColouredPointsMap::getPCLPointCloudXYZRGB
void getPCLPointCloudXYZRGB(POINTCLOUD &cloud) const
Like CPointsMap::getPCLPointCloud() but for PointCloud<PointXYZRGB>
Definition: CColouredPointsMap.h:295
mrpt::opengl::PointCloudAdapter< mrpt::maps::CColouredPointsMap >::setPointXYZ_RGBf
void setPointXYZ_RGBf(const size_t idx, const coords_t x, const coords_t y, const coords_t z, const float r, const float g, const float b)
Set XYZ_RGBf coordinates of i'th point.
Definition: CColouredPointsMap.h:406
source
GLsizei GLsizei GLchar * source
Definition: glext.h:4082
r
GLdouble GLdouble GLdouble r
Definition: glext.h:3705
mrpt::aligned_std_vector
std::vector< T, mrpt::aligned_allocator_cpp11< T > > aligned_std_vector
Definition: aligned_std_vector.h:15
ASSERT_BELOW_
#define ASSERT_BELOW_(__A, __B)
Definition: exceptions.h:165
mrpt::maps::CColouredPointsMap::savePCDFile
virtual bool savePCDFile(const std::string &filename, bool save_as_binary) const override
Save the point cloud as a PCL PCD file, in either ASCII or binary format.
Definition: CColouredPointsMap.cpp:687
mrpt::obs::CObservation3DRangeScan
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement,...
Definition: CObservation3DRangeScan.h:224
mrpt::maps::CColouredPointsMap::insertPoint
virtual void insertPoint(float x, float y, float z, float R, float G, float B) override
Adds a new point given its coordinates and color (colors range is [0,1])
Definition: CColouredPointsMap.cpp:367
mrpt::config::CConfigFileBase
This class allows loading and storing values and vectors of different types from a configuration text...
Definition: config/CConfigFileBase.h:44
mrpt::maps::CColouredPointsMap::setPoint
void setPoint(size_t index, mrpt::math::TPoint3Df &p)
This is an overloaded member function, provided for convenience. It differs from the above function o...
Definition: CColouredPointsMap.h:142
mrpt::maps::CColouredPointsMap::insertPoint
void insertPoint(float x, float y, float z)
This is an overloaded member function, provided for convenience. It differs from the above function o...
Definition: CColouredPointsMap.h:165
mrpt::opengl::PointCloudAdapter< mrpt::maps::CColouredPointsMap >::PointCloudAdapter
PointCloudAdapter(const mrpt::maps::CColouredPointsMap &obj)
Constructor (accept a const ref for convenience)
Definition: CColouredPointsMap.h:377
mrpt::maps::CColouredPointsMap::TColourOptions::d_max
float d_max
Definition: CColouredPointsMap.h:250
mrpt::poses::CPose3D
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
index
GLuint index
Definition: glext.h:4054
mrpt::maps::CColouredPointsMap::PLY_import_set_vertex_count
virtual void PLY_import_set_vertex_count(const size_t N) override
In a base class, reserve memory to prepare subsequent calls to PLY_import_set_vertex.
Definition: CColouredPointsMap.cpp:622
b
GLubyte GLubyte b
Definition: glext.h:6279
mrpt::maps::CColouredPointsMap::getPoint
virtual void getPoint(size_t index, float &x, float &y, float &z, float &R, float &G, float &B) const override
Retrieves a point and its color (colors range is [0,1])
Definition: CColouredPointsMap.cpp:445
mrpt::img::TColorf
A RGB color - floats in the range [0,1].
Definition: TColor.h:79
mrpt::maps::CColouredPointsMap::setSize
virtual void setSize(size_t newLength) override
Resizes all point buffers so they can hold the given number of points, erasing all previous contents ...
Definition: CColouredPointsMap.cpp:105
mrpt::maps::CColouredPointsMap::copyFrom
virtual void copyFrom(const CPointsMap &obj) override
Virtual assignment operator, to be implemented in derived classes
Definition: CColouredPointsMap.cpp:119
TEnumType.h
mrpt::maps::CColouredPointsMap::cmFromHeightRelativeToSensorGray
@ cmFromHeightRelativeToSensorGray
Definition: CColouredPointsMap.h:232
mrpt::config::CLoadableOptions
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
Definition: config/CLoadableOptions.h:28
mrpt::maps::CPointsMap::m_z
mrpt::aligned_std_vector< float > m_z
Definition: CPointsMap.h:1094
mrpt::opengl::PointCloudAdapter< mrpt::maps::CColouredPointsMap >::setPointRGBu8
void setPointRGBu8(const size_t idx, const uint8_t r, const uint8_t g, const uint8_t b)
Set RGBu8 coordinates of i'th point.
Definition: CColouredPointsMap.h:457
mrpt::maps::CPointsMap::getPCLPointCloud
void getPCLPointCloud(POINTCLOUD &cloud) const
Use to convert this MRPT point cloud object into a PCL point cloud object (PointCloud<PointXYZ>).
Definition: CPointsMap.h:981
mrpt::maps::CColouredPointsMap::setPointFast
virtual void setPointFast(size_t index, float x, float y, float z) override
Changes the coordinates of the given point (0-based index), without checking for out-of-bounds and wi...
Definition: CColouredPointsMap.h:46
obs_frwds.h
mrpt::opengl::PointCloudAdapter< mrpt::maps::CColouredPointsMap >::getPointXYZ
void getPointXYZ(const size_t idx, T &x, T &y, T &z) const
Get XYZ coordinates of i'th point.
Definition: CColouredPointsMap.h:387
mrpt::maps::CPointsMap::m_y
mrpt::aligned_std_vector< float > m_y
Definition: CPointsMap.h:1094
mrpt::maps::CColouredPointsMap::cmFromHeightRelativeToSensorJet
@ cmFromHeightRelativeToSensorJet
Definition: CColouredPointsMap.h:231
mrpt::opengl::PointCloudAdapter< mrpt::maps::CColouredPointsMap >::getPointXYZ_RGBf
void getPointXYZ_RGBf(const size_t idx, T &x, T &y, T &z, float &r, float &g, float &b) const
Get XYZ_RGBf coordinates of i'th point.
Definition: CColouredPointsMap.h:400
mrpt::opengl::CSetOfObjects::Ptr
std::shared_ptr< CSetOfObjects > Ptr
Definition: CSetOfObjects.h:30
mrpt::maps::detail::pointmap_traits
Definition: CPointsMap.h:39
mrpt::maps::CColouredPointsMap::PLY_export_get_vertex
void PLY_export_get_vertex(const size_t idx, mrpt::math::TPoint3Df &pt, bool &pt_has_color, mrpt::img::TColorf &pt_color) const override
In a base class, will be called after PLY_export_get_vertex_count() once for each exported point.
Definition: CColouredPointsMap.cpp:647
mrpt::maps::CColouredPointsMap::resetPointsMinDist
void resetPointsMinDist(float defValue=2000.0f)
Reset the minimum-observed-distance buffer for all the points to a predefined value.
Definition: CColouredPointsMap.cpp:593
mrpt::maps::CColouredPointsMap::TColourOptions
The definition of parameters for generating colors from laser scans.
Definition: CColouredPointsMap.h:238
mrpt::maps::CColouredPointsMap::TColouringMethod
TColouringMethod
The choices for coloring schemes:
Definition: CColouredPointsMap.h:228
MAP_DEFINITION_START
#define MAP_DEFINITION_START(_CLASS_NAME_)
Add a MAP_DEFINITION_START() ...
Definition: TMetricMapTypesRegistry.h:57
mrpt::maps::CColouredPointsMap::TColourOptions::loadFromConfigFile
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini"-like file or memory-stored string list.
Definition: CColouredPointsMap.cpp:409
mrpt::maps::CColouredPointsMap::setPoint
void setPoint(size_t index, float x, float y)
This is an overloaded member function, provided for convenience. It differs from the above function o...
Definition: CColouredPointsMap.h:147
mrpt::maps::CColouredPointsMap::m_color_B
mrpt::aligned_std_vector< float > m_color_B
Definition: CColouredPointsMap.h:313
MAP_DEFINITION_END
#define MAP_DEFINITION_END(_CLASS_NAME_)
Definition: TMetricMapTypesRegistry.h:67
mrpt::opengl::PointCloudAdapter< mrpt::maps::CColouredPointsMap >::getPointRGBf
void getPointRGBf(const size_t idx, float &r, float &g, float &b) const
Get RGBf color of i'th point.
Definition: CColouredPointsMap.h:434
DEFINE_SERIALIZABLE
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
Definition: CSerializable.h:102
mrpt::maps::CColouredPointsMap::loadFromRangeScan
virtual void loadFromRangeScan(const mrpt::obs::CObservation2DRangeScan &rangeScan, const mrpt::poses::CPose3D *robotPose=nullptr) override
See CPointsMap::loadFromRangeScan()
Definition: CColouredPointsMap.cpp:1075
mrpt::maps::CColouredPointsMap::setPointAllFieldsFast
virtual void setPointAllFieldsFast(const size_t index, const std::vector< float > &point_data) override
Set all the data fields for one point as a vector: [X Y Z R G B] Unlike setPointAllFields(),...
Definition: CColouredPointsMap.h:82
mrpt::opengl::PointCloudAdapter< mrpt::maps::CColouredPointsMap >::setPointRGBf
void setPointRGBf(const size_t idx, const float r, const float g, const float b)
Set XYZ_RGBf coordinates of i'th point.
Definition: CColouredPointsMap.h:440
mrpt::opengl::PointCloudAdapter< mrpt::maps::CColouredPointsMap >::setPointXYZ
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: CColouredPointsMap.h:392
mrpt::maps::CPointsMap::mark_as_modified
void mark_as_modified() const
Users normally don't need to call this.
Definition: CPointsMap.h:1085
mrpt::maps::CColouredPointsMap::addFrom_classSpecific
virtual void addFrom_classSpecific(const CPointsMap &anotherMap, const size_t nPreviousPoints) override
Auxiliary method called from within addFrom() automatically, to finish the copying of class-specific ...
Definition: CColouredPointsMap.cpp:665
mrpt::maps::CColouredPointsMap::colourFromObservation
bool colourFromObservation(const mrpt::obs::CObservationImage &obs, const mrpt::poses::CPose3D &robotPose)
Colour a set of points from a CObservationImage and the global pose of the robot.
Definition: CColouredPointsMap.cpp:504
mrpt::maps::CPointsMap::m_x
mrpt::aligned_std_vector< float > m_x
The point coordinates.
Definition: CPointsMap.h:1094
z
GLdouble GLdouble z
Definition: glext.h:3872
ASSERTDEB_
#define ASSERTDEB_(f)
Defines an assertion mechanism - only when compiled in debug.
Definition: exceptions.h:205
CObservationImage.h
string
GLsizei const GLchar ** string
Definition: glext.h:4101
mrpt::maps::CColouredPointsMap::getPointColor_fast
void getPointColor_fast(size_t index, float &R, float &G, float &B) const
Like getPointColor but without checking for out-of-index erors.
Definition: CColouredPointsMap.h:197
mrpt::maps::CColouredPointsMap::cmFromHeightRelativeToSensor
@ cmFromHeightRelativeToSensor
Definition: CColouredPointsMap.h:230
mrpt::maps::detail::loadFromRangeImpl
Definition: CPointsMap.h:37
mrpt::maps::CMetricMap::clear
void clear()
Erase all the contents of the map.
Definition: CMetricMap.cpp:31
mrpt::maps::CColouredPointsMap::getPointAllFieldsFast
virtual void getPointAllFieldsFast(const size_t index, std::vector< float > &point_data) const override
Get all the data fields for one point as a vector: [X Y Z R G B] Unlike getPointAllFields(),...
Definition: CColouredPointsMap.h:65
mrpt::maps::CColouredPointsMap::setPoint
void setPoint(size_t index, float x, float y, float z)
This is an overloaded member function, provided for convenience. It differs from the above function o...
Definition: CColouredPointsMap.h:135
CSerializable.h
mrpt::maps::CColouredPointsMap::getAs3DObject
virtual void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const override
Override of the default 3D scene builder to account for the individual points' color.
Definition: CColouredPointsMap.cpp:383
mrpt::maps::CColouredPointsMap::insertPoint
void insertPoint(const POINT_T &p)
This is an overloaded member function, provided for convenience. It differs from the above function o...
Definition: CColouredPointsMap.h:160
mrpt::obs::CObservationImage
Declares a class derived from "CObservation" that encapsules an image from a camera,...
Definition: CObservationImage.h:35
y
GLenum GLint GLint y
Definition: glext.h:3538
x
GLenum GLint x
Definition: glext.h:3538
mrpt::opengl::PointCloudAdapter< mrpt::maps::CColouredPointsMap >::m_obj
mrpt::maps::CColouredPointsMap & m_obj
Definition: CColouredPointsMap.h:364
mrpt::maps::CColouredPointsMap::getPointColor
void getPointColor(size_t index, float &R, float &G, float &B) const
Retrieves a point color (colors range is [0,1])
Definition: CColouredPointsMap.cpp:462



Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST