MRPT  1.9.9
CColouredPointsMap.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2019, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 #pragma once
10 
11 #include <mrpt/maps/CPointsMap.h>
12 #include <mrpt/math/CMatrixF.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  CColouredPointsMap() = default;
35 
37  {
39  }
41  {
43  return *this;
44  }
45 
46  // --------------------------------------------
47  /** @name Pure virtual interfaces to be implemented by any class derived
48  from CPointsMap
49  @{ */
50 
51  void reserve(size_t newLength) override; // See base class docs
52  void resize(size_t newLength) override; // See base class docs
53  void setSize(size_t newLength) override; // See base class docs
54 
55  /** The virtual method for \a insertPoint() *without* calling
56  * mark_as_modified() */
57  void insertPointFast(float x, float y, float z = 0) override;
58 
59  /** Get all the data fields for one point as a vector: [X Y Z R G B]
60  * Unlike getPointAllFields(), this method does not check for index out of
61  * bounds
62  * \sa getPointAllFields, setPointAllFields, setPointAllFieldsFast
63  */
65  const size_t index, std::vector<float>& point_data) const override
66  {
67  point_data.resize(6);
68  point_data[0] = m_x[index];
69  point_data[1] = m_y[index];
70  point_data[2] = m_z[index];
71  point_data[3] = m_color_R[index];
72  point_data[4] = m_color_G[index];
73  point_data[5] = m_color_B[index];
74  }
75 
76  /** Set all the data fields for one point as a vector: [X Y Z R G B]
77  * Unlike setPointAllFields(), this method does not check for index out of
78  * bounds
79  * \sa setPointAllFields, getPointAllFields, getPointAllFieldsFast
80  */
82  const size_t index, const std::vector<float>& point_data) override
83  {
84  ASSERTDEB_(point_data.size() == 6);
85  m_x[index] = point_data[0];
86  m_y[index] = point_data[1];
87  m_z[index] = point_data[2];
88  m_color_R[index] = point_data[3];
89  m_color_G[index] = point_data[4];
90  m_color_B[index] = point_data[5];
91  }
92 
93  /** See CPointsMap::loadFromRangeScan() */
94  void loadFromRangeScan(
95  const mrpt::obs::CObservation2DRangeScan& rangeScan,
96  const mrpt::poses::CPose3D* robotPose = nullptr) override;
97  /** See CPointsMap::loadFromRangeScan() */
98  void loadFromRangeScan(
99  const mrpt::obs::CObservation3DRangeScan& rangeScan,
100  const mrpt::poses::CPose3D* robotPose = nullptr) override;
101 
102  protected:
103  void impl_copyFrom(const CPointsMap& obj) override;
105  const CPointsMap& anotherMap, const size_t nPreviousPoints) override;
106 
107  // Friend methods:
108  template <class Derived>
110  template <class Derived>
111  friend struct detail::pointmap_traits;
112 
113  public:
114  /** @} */
115  // --------------------------------------------
116 
117  /** Save to a text file. In each line contains X Y Z (meters) R G B (range
118  * [0,1]) for each point in the map.
119  * Returns false if any error occured, true elsewere.
120  */
121  bool save3D_and_colour_to_text_file(const std::string& file) const;
122 
123  /** Changes a given point from map. First index is 0.
124  * \exception Throws std::exception on index out of bound.
125  */
126  void setPointRGB(
127  size_t index, float x, float y, float z, float R, float G,
128  float B) override;
129 
130  /** Adds a new point given its coordinates and color (colors range is [0,1])
131  */
132  void insertPointRGB(
133  float x, float y, float z, float R, float G, float B) override;
134 
135  /** Changes just the color of a given point from the map. First index is 0.
136  * \exception Throws std::exception on index out of bound.
137  */
138  void setPointColor(size_t index, float R, float G, float B);
139 
140  /** Like \c setPointColor but without checking for out-of-index erors */
141  inline void setPointColor_fast(size_t index, float R, float G, float B)
142  {
143  m_color_R[index] = R;
144  m_color_G[index] = G;
145  m_color_B[index] = B;
146  }
147 
148  /** Retrieves a point and its color (colors range is [0,1])
149  */
150  void getPointRGB(
151  size_t index, float& x, float& y, float& z, float& R, float& G,
152  float& B) const override;
153 
154  /** Retrieves a point color (colors range is [0,1]) */
155  void getPointColor(size_t index, float& R, float& G, float& B) const;
156 
157  /** Like \c getPointColor but without checking for out-of-index erors */
158  inline void getPointColor_fast(
159  size_t index, float& R, float& G, float& B) const
160  {
161  R = m_color_R[index];
162  G = m_color_G[index];
163  B = m_color_B[index];
164  }
165 
166  /** Returns true if the point map has a color field for each point */
167  bool hasColorPoints() const override { return true; }
168  /** Override of the default 3D scene builder to account for the individual
169  * points' color.
170  */
171  void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr& outObj) const override;
172 
173  /** Colour a set of points from a CObservationImage and the global pose of
174  * the robot */
176  const mrpt::obs::CObservationImage& obs,
177  const mrpt::poses::CPose3D& robotPose);
178 
179  /** The choices for coloring schemes:
180  * - cmFromHeightRelativeToSensor: The Z coordinate wrt the sensor will
181  *be
182  *used to obtain the color using the limits z_min,z_max.
183  * - cmFromIntensityImage: When inserting 3D range scans, take the
184  *color
185  *from the intensity image channel, if available.
186  * \sa TColourOptions
187  */
189  {
194  // Remember: if new values are added, also update TEnumType below!
195  };
196 
197  /** The definition of parameters for generating colors from laser scans */
199  {
200  /** Initilization of default parameters */
201  TColourOptions();
202  void loadFromConfigFile(
204  const std::string& section) override; // See base docs
205  void dumpToTextStream(
206  std::ostream& out) const override; // See base docs
207 
209  float z_min{-10}, z_max{10};
210  float d_max{5};
211  };
212 
213  /** The options employed when inserting laser scans in the map. */
215 
216  /** Reset the minimum-observed-distance buffer for all the points to a
217  * predefined value */
218  void resetPointsMinDist(float defValue = 2000.0f);
219 
220  /** @name PCL library support
221  @{ */
222 
223  /** Save the point cloud as a PCL PCD file, in either ASCII or binary format
224  * \return false on any error */
225  bool savePCDFile(
226  const std::string& filename, bool save_as_binary) const override;
227 
228  /** Loads a PCL point cloud (WITH RGB information) into this MRPT class (for
229  * clouds without RGB data, see CPointsMap::setFromPCLPointCloud() ).
230  * Usage example:
231  * \code
232  * pcl::PointCloud<pcl::PointXYZRGB> cloud;
233  * mrpt::maps::CColouredPointsMap pc;
234  *
235  * pc.setFromPCLPointCloudRGB(cloud);
236  * \endcode
237  * \sa CPointsMap::setFromPCLPointCloud()
238  */
239  template <class POINTCLOUD>
240  void setFromPCLPointCloudRGB(const POINTCLOUD& cloud)
241  {
242  const size_t N = cloud.points.size();
243  clear();
244  reserve(N);
245  const float f = 1.0f / 255.0f;
246  for (size_t i = 0; i < N; ++i)
247  this->insertPoint(
248  cloud.points[i].x, cloud.points[i].y, cloud.points[i].z,
249  cloud.points[i].r * f, cloud.points[i].g * f,
250  cloud.points[i].b * f);
251  }
252 
253  /** Like CPointsMap::getPCLPointCloud() but for PointCloud<PointXYZRGB> */
254  template <class POINTCLOUD>
255  void getPCLPointCloudXYZRGB(POINTCLOUD& cloud) const
256  {
257  const size_t nThis = this->size();
258  this->getPCLPointCloud(cloud); // 1st: xyz data
259  // 2nd: RGB data
260  for (size_t i = 0; i < nThis; ++i)
261  {
262  float R, G, B;
263  this->getPointColor_fast(i, R, G, B);
264  cloud.points[i].r = static_cast<uint8_t>(R * 255);
265  cloud.points[i].g = static_cast<uint8_t>(G * 255);
266  cloud.points[i].b = static_cast<uint8_t>(B * 255);
267  }
268  }
269  /** @} */
270 
271  protected:
272  /** The color data */
274 
275  /** Minimum distance from where the points have been seen */
276  // std::vector<float> m_min_dist;
277 
278  /** Clear the map, erasing all the points */
279  void internal_clear() override;
280 
281  /** @name Redefinition of PLY Import virtual methods from CPointsMap
282  @{ */
283  /** In a base class, will be called after PLY_import_set_vertex_count() once
284  * for each loaded point.
285  * \param pt_color Will be nullptr if the loaded file does not provide
286  * color info.
287  */
289  const size_t idx, const mrpt::math::TPoint3Df& pt,
290  const mrpt::img::TColorf* pt_color = nullptr) override;
291 
292  /** In a base class, reserve memory to prepare subsequent calls to
293  * PLY_import_set_vertex */
294  void PLY_import_set_vertex_count(const size_t N) override;
295  /** @} */
296 
297  /** @name Redefinition of PLY Export virtual methods from CPointsMap
298  @{ */
300  const size_t idx, mrpt::math::TPoint3Df& pt, bool& pt_has_color,
301  mrpt::img::TColorf& pt_color) const override;
302  /** @} */
303 
305  mrpt::maps::CPointsMap::TInsertionOptions insertionOpts;
306  mrpt::maps::CPointsMap::TLikelihoodOptions likelihoodOpts;
309 
310 }; // End of class def.
311 
312 } // namespace maps
313 
314 #include <mrpt/opengl/pointcloud_adapters.h>
315 namespace opengl
316 {
317 /** Specialization
318  * mrpt::opengl::PointCloudAdapter<mrpt::maps::CColouredPointsMap> \ingroup
319  * mrpt_adapters_grp */
320 template <>
322 {
323  private:
325 
326  public:
327  /** The type of each point XYZ coordinates */
328  using coords_t = float;
329  /** Has any color RGB info? */
330  static constexpr bool HAS_RGB = true;
331  /** Has native RGB info (as floats)? */
332  static constexpr bool HAS_RGBf = true;
333  /** Has native RGB info (as uint8_t)? */
334  static constexpr bool HAS_RGBu8 = false;
335 
336  /** Constructor (accept a const ref for convenience) */
338  : m_obj(*const_cast<mrpt::maps::CColouredPointsMap*>(&obj))
339  {
340  }
341  /** Get number of points */
342  inline size_t size() const { return m_obj.size(); }
343  /** Set number of points (to uninitialized values) */
344  inline void resize(const size_t N) { m_obj.resize(N); }
345  /** Does nothing as of now */
346  inline void setDimensions(const size_t& height, const size_t& width) {}
347  /** Get XYZ coordinates of i'th point */
348  template <typename T>
349  inline void getPointXYZ(const size_t idx, T& x, T& y, T& z) const
350  {
351  m_obj.getPointFast(idx, x, y, z);
352  }
353  /** Set XYZ coordinates of i'th point */
354  inline void setPointXYZ(
355  const size_t idx, const coords_t x, const coords_t y, const coords_t z)
356  {
357  m_obj.setPointFast(idx, x, y, z);
358  }
359 
360  /** Get XYZ_RGBf coordinates of i'th point */
361  template <typename T>
362  inline void getPointXYZ_RGBf(
363  const size_t idx, T& x, T& y, T& z, float& r, float& g, float& b) const
364  {
365  m_obj.getPointRGB(idx, x, y, z, r, g, b);
366  }
367  /** Set XYZ_RGBf coordinates of i'th point */
368  inline void setPointXYZ_RGBf(
369  const size_t idx, const coords_t x, const coords_t y, const coords_t z,
370  const float r, const float g, const float b)
371  {
372  m_obj.setPointRGB(idx, x, y, z, r, g, b);
373  }
374 
375  /** Get XYZ_RGBu8 coordinates of i'th point */
376  template <typename T>
377  inline void getPointXYZ_RGBu8(
378  const size_t idx, T& x, T& y, T& z, uint8_t& r, uint8_t& g,
379  uint8_t& b) const
380  {
381  float Rf, Gf, Bf;
382  m_obj.getPointRGB(idx, x, y, z, Rf, Gf, Bf);
383  r = Rf * 255;
384  g = Gf * 255;
385  b = Bf * 255;
386  }
387  /** Set XYZ_RGBu8 coordinates of i'th point */
388  inline void setPointXYZ_RGBu8(
389  const size_t idx, const coords_t x, const coords_t y, const coords_t z,
390  const uint8_t r, const uint8_t g, const uint8_t b)
391  {
392  m_obj.setPointRGB(idx, x, y, z, r / 255.f, g / 255.f, b / 255.f);
393  }
394 
395  /** Get RGBf color of i'th point */
396  inline void getPointRGBf(
397  const size_t idx, float& r, float& g, float& b) const
398  {
399  m_obj.getPointColor_fast(idx, r, g, b);
400  }
401  /** Set XYZ_RGBf coordinates of i'th point */
402  inline void setPointRGBf(
403  const size_t idx, const float r, const float g, const float b)
404  {
405  m_obj.setPointColor_fast(idx, r, g, b);
406  }
407 
408  /** Get RGBu8 color of i'th point */
409  inline void getPointRGBu8(
410  const size_t idx, uint8_t& r, uint8_t& g, uint8_t& b) const
411  {
412  float R, G, B;
413  m_obj.getPointColor_fast(idx, R, G, B);
414  r = R * 255;
415  g = G * 255;
416  b = B * 255;
417  }
418  /** Set RGBu8 coordinates of i'th point */
419  inline void setPointRGBu8(
420  const size_t idx, const uint8_t r, const uint8_t g, const uint8_t b)
421  {
422  m_obj.setPointColor_fast(idx, r / 255.f, g / 255.f, b / 255.f);
423  }
424 
425 }; // end of PointCloudAdapter<mrpt::maps::CColouredPointsMap>
426 } // namespace opengl
427 } // namespace mrpt
428 
432  cmFromHeightRelativeToSensor);
435  cmFromHeightRelativeToSensorJet);
438  cmFromHeightRelativeToSensorGray);
PointCloudAdapter(const mrpt::maps::CColouredPointsMap &obj)
Constructor (accept a const ref for convenience)
void clear()
Erase all the contents of the map.
Definition: CMetricMap.cpp:30
void setSize(size_t newLength) override
Resizes all point buffers so they can hold the given number of points, erasing all previous contents ...
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 ...
TColouringMethod
The choices for coloring schemes:
Declares a class derived from "CObservation" that encapsules an image from a camera, whose relative pose to robot is also stored.
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:462
GLdouble GLdouble z
Definition: glext.h:3879
void insertPointFast(float x, float y, float z=0) override
The virtual method for insertPoint() without calling mark_as_modified()
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
CPointsMap & operator=(const CPointsMap &o)
Definition: CPointsMap.h:120
bool save3D_and_colour_to_text_file(const std::string &file) const
Save to a text file.
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
void getPointRGBu8(const size_t idx, uint8_t &r, uint8_t &g, uint8_t &b) const
Get RGBu8 color of i&#39;th point.
TColourOptions()
Initilization of default parameters.
const double G
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(), this method does not check for index out of bounds.
void internal_clear() override
Minimum distance from where the points have been seen.
#define MAP_DEFINITION_START(_CLASS_NAME_)
Add a MAP_DEFINITION_START() ...
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.
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(), this method does not check for index out of bounds.
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement, as from a time-of-flight range camera or any other RGBD sensor.
mrpt::aligned_std_vector< float > m_color_R
The color data.
void setPointColor_fast(size_t index, float R, float G, float B)
Like setPointColor but without checking for out-of-index erors.
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:625
void getPointRGBf(const size_t idx, float &r, float &g, float &b) const
Get RGBf color of i&#39;th point.
void setFromPCLPointCloudRGB(const POINTCLOUD &cloud)
Loads a PCL point cloud (WITH RGB information) into this MRPT class (for clouds without RGB data...
float coords_t
The type of each point XYZ coordinates.
std::vector< T, mrpt::aligned_allocator_cpp11< T > > aligned_std_vector
GLsizei GLsizei GLuint * obj
Definition: glext.h:4085
GLenum GLsizei width
Definition: glext.h:3535
TColourOptions colorScheme
The options employed when inserting laser scans in the map.
void resize(const size_t N)
Set number of points (to uninitialized values)
void reserve(size_t newLength) override
Reserves memory for a given number of points: the size of the map does not change, it only reserves the memory.
unsigned char uint8_t
Definition: rptypes.h:44
With this struct options are provided to the observation insertion process.
Definition: CPointsMap.h:219
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors...
Definition: CPointsMap.h:65
This class allows loading and storing values and vectors of different types from a configuration text...
mrpt::aligned_std_vector< float > m_color_B
MRPT_FILL_ENUM_MEMBER(mrpt::maps::CColouredPointsMap::TColouringMethod, cmFromHeightRelativeToSensor)
An adapter to different kinds of point cloud object.
Lightweight 3D point (float version).
Definition: TPoint3D.h:21
GLuint index
Definition: glext.h:4068
void setPointRGB(size_t index, float x, float y, float z, float R, float G, float B) override
Changes a given point from map.
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&#39;th point.
GLubyte g
Definition: glext.h:6372
GLubyte GLubyte b
Definition: glext.h:6372
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.
void insertPointRGB(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])
#define MRPT_ENUM_TYPE_END()
Definition: TEnumType.h:78
void getPCLPointCloud(POINTCLOUD &cloud) const
Use to convert this MRPT point cloud object into a PCL point cloud object (PointCloud<PointXYZ>).
Definition: CPointsMap.h:991
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.
A map of 2D/3D points with individual colours (RGB).
GLsizei const GLchar ** string
Definition: glext.h:4116
void setPointFast(size_t index, float x, float y, float z)
Changes the coordinates of the given point (0-based index), without checking for out-of-bounds and wi...
Definition: CPointsMap.h:159
CColouredPointsMap operator=(const CPointsMap &o)
mrpt::aligned_std_vector< float > m_color_G
void setDimensions(const size_t &height, const size_t &width)
Does nothing as of now.
void getPCLPointCloudXYZRGB(POINTCLOUD &cloud) const
Like CPointsMap::getPCLPointCloud() but for PointCloud<PointXYZRGB>
void setPointRGBf(const size_t idx, const float r, const float g, const float b)
Set XYZ_RGBf coordinates of i&#39;th point.
void getPointXYZ(const size_t idx, T &x, T &y, T &z) const
Get XYZ coordinates of i&#39;th point.
mrpt::aligned_std_vector< float > m_z
Definition: CPointsMap.h:1104
void setPointXYZ(const size_t idx, const coords_t x, const coords_t y, const coords_t z)
Set XYZ coordinates of i&#39;th point.
void getPointRGB(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])
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
GLdouble GLdouble GLdouble r
Definition: glext.h:3711
mrpt::aligned_std_vector< float > m_y
Definition: CPointsMap.h:1104
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&#39;th point.
const float R
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:84
bool hasColorPoints() const override
Returns true if the point map has a color field for each point.
void resetPointsMinDist(float defValue=2000.0f)
Reset the minimum-observed-distance buffer for all the points to a predefined value.
Options used when evaluating "computeObservationLikelihood" in the derived classes.
Definition: CPointsMap.h:277
#define ASSERTDEB_(f)
Defines an assertion mechanism - only when compiled in debug.
Definition: exceptions.h:190
void PLY_export_get_vertex(const size_t idx, mrpt::math::TPoint3Df &pt, bool &pt_has_color, mrpt::img::TColorf &pt_color) const override
In a base class, will be called after PLY_export_get_vertex_count() once for each exported point...
void loadFromRangeScan(const mrpt::obs::CObservation2DRangeScan &rangeScan, const mrpt::poses::CPose3D *robotPose=nullptr) override
See CPointsMap::loadFromRangeScan()
A RGB color - floats in the range [0,1].
Definition: TColor.h:77
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...
CColouredPointsMap(const CPointsMap &o)
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...
GLsizei GLsizei GLchar * source
Definition: glext.h:4097
void setPointRGBu8(const size_t idx, const uint8_t r, const uint8_t g, const uint8_t b)
Set RGBu8 coordinates of i&#39;th point.
GLenum GLint GLint y
Definition: glext.h:3542
The definition of parameters for generating colors from laser scans.
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&#39;th point.
void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const override
Override of the default 3D scene builder to account for the individual points&#39; color.
GLenum GLint x
Definition: glext.h:3542
void impl_copyFrom(const CPointsMap &obj) override
Virtual assignment operator, copies as much common data (XYZ, color,...) as possible from the source ...
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&#39;th point.
GLenum GLsizei GLsizei height
Definition: glext.h:3558
#define MRPT_ENUM_TYPE_BEGIN(_ENUM_TYPE_WITH_NS)
Definition: TEnumType.h:62
mrpt::aligned_std_vector< float > m_x
The point coordinates.
Definition: CPointsMap.h:1104
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. ...
#define MAP_DEFINITION_END(_CLASS_NAME_)
size_t size() const
Returns the number of stored points in the map.
Definition: CPointsMap.h:422
void getPointColor_fast(size_t index, float &R, float &G, float &B) const
Like getPointColor but without checking for out-of-index erors.
void getPointColor(size_t index, float &R, float &G, float &B) const
Retrieves a point color (colors range is [0,1])
void setPointColor(size_t index, float R, float G, float B)
Changes just the color of a given point from the map.



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 8fe78517f Sun Jul 14 19:43:28 2019 +0200 at lun oct 28 02:10:00 CET 2019