Point Cloud Library (PCL)  1.15.1-dev
point_types_conversion.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010-2011, Willow Garage, Inc.
6  *
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the copyright holder(s) nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * $Id$
37  */
38 
39 #pragma once
40 
41 #include <limits>
42 
43 #include <pcl/field_traits.h>
44 #include <pcl/point_cloud.h>
45 #include <pcl/point_types.h>
46 
47 #include <pcl/common/colors.h> // for RGB2sRGB_LUT
48 
49 namespace pcl
50 {
51  // r,g,b, i values are from 0 to 255
52  // h = [0,360]
53  // s, v values are from 0 to 1
54  // if s = 0 => h = 0
55 
56  /** \brief Convert a XYZRGB point type to a XYZI
57  * \param[in] in the input XYZRGB point
58  * \param[out] out the output XYZI point
59  */
60  inline void
62  PointXYZI& out)
63  {
64  out.x = in.x; out.y = in.y; out.z = in.z;
65  out.intensity = 0.299f * static_cast <float> (in.r) + 0.587f * static_cast <float> (in.g) + 0.114f * static_cast <float> (in.b);
66  }
67 
68  /** \brief Convert a RGB point type to a I
69  * \param[in] in the input RGB point
70  * \param[out] out the output Intensity point
71  */
72  inline void
73  PointRGBtoI (const RGB& in,
74  Intensity& out)
75  {
76  out.intensity = 0.299f * static_cast <float> (in.r) + 0.587f * static_cast <float> (in.g) + 0.114f * static_cast <float> (in.b);
77  }
78 
79  /** \brief Convert a RGB point type to a I
80  * \param[in] in the input RGB point
81  * \param[out] out the output Intensity point
82  */
83  inline void
84  PointRGBtoI (const RGB& in,
85  Intensity8u& out)
86  {
87  out.intensity = static_cast<std::uint8_t>(0.299f * static_cast <float> (in.r)
88  + 0.587f * static_cast <float> (in.g) + 0.114f * static_cast <float> (in.b));
89  }
90 
91  /** \brief Convert a RGB point type to a I
92  * \param[in] in the input RGB point
93  * \param[out] out the output Intensity point
94  */
95  inline void
96  PointRGBtoI (const RGB& in,
97  Intensity32u& out)
98  {
99  out.intensity = static_cast<std::uint32_t>(0.299f * static_cast <float> (in.r)
100  + 0.587f * static_cast <float> (in.g) + 0.114f * static_cast <float> (in.b));
101  }
102 
103  /** \brief Convert a XYZRGB point type to a XYZHSV
104  * \param[in] in the input XYZRGB point
105  * \param[out] out the output XYZHSV point
106  */
107  inline void
109  PointXYZHSV& out)
110  {
111  const unsigned char max = std::max (in.r, std::max (in.g, in.b));
112  const unsigned char min = std::min (in.r, std::min (in.g, in.b));
113 
114  out.x = in.x; out.y = in.y; out.z = in.z;
115  out.v = static_cast <float> (max) / 255.f;
116 
117  if (max == 0) // division by zero
118  {
119  out.s = 0.f;
120  out.h = 0.f; // h = -1.f;
121  return;
122  }
123 
124  const float diff = static_cast <float> (max - min);
125  out.s = diff / static_cast <float> (max);
126 
127  if (min == max) // diff == 0 -> division by zero
128  {
129  out.h = 0;
130  return;
131  }
132 
133  if (max == in.r) out.h = 60.f * ( static_cast <float> (in.g - in.b) / diff);
134  else if (max == in.g) out.h = 60.f * (2.f + static_cast <float> (in.b - in.r) / diff);
135  else out.h = 60.f * (4.f + static_cast <float> (in.r - in.g) / diff); // max == b
136 
137  if (out.h < 0.f) out.h += 360.f;
138  }
139 
140  /** \brief Convert a XYZRGB-based point type to a XYZLAB
141  * \param[in] in the input XYZRGB(XYZRGBA, XYZRGBL, etc.) point
142  * \param[out] out the output XYZLAB point
143  */
144  template <typename PointT, traits::HasColor<PointT> = true>
145  inline void
147  PointXYZLAB& out)
148  {
149  out.x = in.x;
150  out.y = in.y;
151  out.z = in.z;
152  out.data[3] = 1.0; // important for homogeneous coordinates
153 
154  // convert sRGB to CIELAB
155  // for sRGB -> CIEXYZ see http://www.easyrgb.com/index.php?X=MATH&H=02#text2
156  // for CIEXYZ -> CIELAB see http://www.easyrgb.com/index.php?X=MATH&H=07#text7
157  // an overview at: https://www.comp.nus.edu.sg/~leowwk/papers/colordiff.pdf
158 
159  const auto& sRGB_LUT = RGB2sRGB_LUT<double, 8>();
160 
161  const double R = sRGB_LUT[in.r];
162  const double G = sRGB_LUT[in.g];
163  const double B = sRGB_LUT[in.b];
164 
165  // linear sRGB -> CIEXYZ, D65 illuminant, observer at 2 degrees
166  const double X = R * 0.4124 + G * 0.3576 + B * 0.1805;
167  const double Y = R * 0.2126 + G * 0.7152 + B * 0.0722;
168  const double Z = R * 0.0193 + G * 0.1192 + B * 0.9505;
169 
170  // normalize X, Y, Z with tristimulus values for Xn, Yn, Zn
171  float f[3] = {static_cast<float>(X), static_cast<float>(Y), static_cast<float>(Z)};
172  f[0] /= 0.95047;
173  f[1] /= 1;
174  f[2] /= 1.08883;
175 
176  // CIEXYZ -> CIELAB
177  for (float & xyz : f) {
178  if (xyz > 0.008856) {
179  xyz = std::pow(xyz, 1.0 / 3.0);
180  }
181  else {
182  xyz = 7.787 * xyz + 16.0 / 116.0;
183  }
184  }
185 
186  out.L = 116.0f * f[1] - 16.0f;
187  out.a = 500.0f * (f[0] - f[1]);
188  out.b = 200.0f * (f[1] - f[2]);
189  }
190 
191  /** \brief Convert a XYZRGBA point type to a XYZHSV
192  * \param[in] in the input XYZRGBA point
193  * \param[out] out the output XYZHSV point
194  * \todo include the A parameter but how?
195  */
196  inline void
198  PointXYZHSV& out)
199  {
200  const unsigned char max = std::max (in.r, std::max (in.g, in.b));
201  const unsigned char min = std::min (in.r, std::min (in.g, in.b));
202 
203  out.x = in.x; out.y = in.y; out.z = in.z;
204  out.v = static_cast <float> (max) / 255.f;
205 
206  if (max == 0) // division by zero
207  {
208  out.s = 0.f;
209  out.h = 0.f;
210  return;
211  }
212 
213  const float diff = static_cast <float> (max - min);
214  out.s = diff / static_cast <float> (max);
215 
216  if (min == max) // diff == 0 -> division by zero
217  {
218  out.h = 0;
219  return;
220  }
221 
222  if (max == in.r) out.h = 60.f * ( static_cast <float> (in.g - in.b) / diff);
223  else if (max == in.g) out.h = 60.f * (2.f + static_cast <float> (in.b - in.r) / diff);
224  else out.h = 60.f * (4.f + static_cast <float> (in.r - in.g) / diff); // max == b
225 
226  if (out.h < 0.f) out.h += 360.f;
227  }
228 
229  /* \brief Convert a XYZHSV point type to a XYZRGB
230  * \param[in] in the input XYZHSV point
231  * \param[out] out the output XYZRGB point
232  */
233  inline void
235  PointXYZRGB& out)
236  {
237  out.x = in.x; out.y = in.y; out.z = in.z;
238  if (in.s == 0)
239  {
240  out.r = out.g = out.b = static_cast<std::uint8_t> (255 * in.v);
241  return;
242  }
243  float a = in.h / 60;
244  int i = static_cast<int> (std::floor (a));
245  float f = a - static_cast<float> (i);
246  float p = in.v * (1 - in.s);
247  float q = in.v * (1 - in.s * f);
248  float t = in.v * (1 - in.s * (1 - f));
249 
250  switch (i)
251  {
252  case 0:
253  {
254  out.r = static_cast<std::uint8_t> (255 * in.v);
255  out.g = static_cast<std::uint8_t> (255 * t);
256  out.b = static_cast<std::uint8_t> (255 * p);
257  break;
258  }
259  case 1:
260  {
261  out.r = static_cast<std::uint8_t> (255 * q);
262  out.g = static_cast<std::uint8_t> (255 * in.v);
263  out.b = static_cast<std::uint8_t> (255 * p);
264  break;
265  }
266  case 2:
267  {
268  out.r = static_cast<std::uint8_t> (255 * p);
269  out.g = static_cast<std::uint8_t> (255 * in.v);
270  out.b = static_cast<std::uint8_t> (255 * t);
271  break;
272  }
273  case 3:
274  {
275  out.r = static_cast<std::uint8_t> (255 * p);
276  out.g = static_cast<std::uint8_t> (255 * q);
277  out.b = static_cast<std::uint8_t> (255 * in.v);
278  break;
279  }
280  case 4:
281  {
282  out.r = static_cast<std::uint8_t> (255 * t);
283  out.g = static_cast<std::uint8_t> (255 * p);
284  out.b = static_cast<std::uint8_t> (255 * in.v);
285  break;
286  }
287  default:
288  {
289  out.r = static_cast<std::uint8_t> (255 * in.v);
290  out.g = static_cast<std::uint8_t> (255 * p);
291  out.b = static_cast<std::uint8_t> (255 * q);
292  break;
293  }
294  }
295  }
296 
297  /** \brief Convert a RGB point cloud to an Intensity
298  * \param[in] in the input RGB point cloud
299  * \param[out] out the output Intensity point cloud
300  */
301  inline void
304  {
305  out.width = in.width;
306  out.height = in.height;
307  for (const auto &point : in)
308  {
309  Intensity p;
310  PointRGBtoI (point, p);
311  out.push_back (p);
312  }
313  }
314 
315  /** \brief Convert a RGB point cloud to an Intensity
316  * \param[in] in the input RGB point cloud
317  * \param[out] out the output Intensity point cloud
318  */
319  inline void
322  {
323  out.width = in.width;
324  out.height = in.height;
325  for (const auto &point : in)
326  {
327  Intensity8u p;
328  PointRGBtoI (point, p);
329  out.push_back (p);
330  }
331  }
332 
333  /** \brief Convert a RGB point cloud to an Intensity
334  * \param[in] in the input RGB point cloud
335  * \param[out] out the output Intensity point cloud
336  */
337  inline void
340  {
341  out.width = in.width;
342  out.height = in.height;
343  for (const auto &point : in)
344  {
345  Intensity32u p;
346  PointRGBtoI (point, p);
347  out.push_back (p);
348  }
349  }
350 
351  /** \brief Convert a XYZRGB point cloud to a XYZHSV
352  * \param[in] in the input XYZRGB point cloud
353  * \param[out] out the output XYZHSV point cloud
354  */
355  inline void
358  {
359  out.width = in.width;
360  out.height = in.height;
361  for (const auto &point : in)
362  {
363  PointXYZHSV p;
364  PointXYZRGBtoXYZHSV (point, p);
365  out.push_back (p);
366  }
367  }
368 
369  /** \brief Convert a XYZHSV point cloud to a XYZRGB
370  * \param[in] in the input XYZHSV point cloud
371  * \param[out] out the output XYZRGB point cloud
372  */
373  inline void
376  {
377  out.width = in.width;
378  out.height = in.height;
379  for (const auto &point : in)
380  {
381  PointXYZRGB p;
382  PointXYZHSVtoXYZRGB (point, p);
383  out.push_back (p);
384  }
385  }
386 
387  /** \brief Convert a XYZRGB point cloud to a XYZHSV
388  * \param[in] in the input XYZRGB point cloud
389  * \param[out] out the output XYZHSV point cloud
390  */
391  inline void
394  {
395  out.width = in.width;
396  out.height = in.height;
397  for (const auto &point : in)
398  {
399  PointXYZHSV p;
400  PointXYZRGBAtoXYZHSV (point, p);
401  out.push_back (p);
402  }
403  }
404 
405  /** \brief Convert a XYZRGB point cloud to a XYZI
406  * \param[in] in the input XYZRGB point cloud
407  * \param[out] out the output XYZI point cloud
408  */
409  inline void
412  {
413  out.width = in.width;
414  out.height = in.height;
415  for (const auto &point : in)
416  {
417  PointXYZI p;
418  PointXYZRGBtoXYZI (point, p);
419  out.push_back (p);
420  }
421  }
422 
423  /** \brief Convert registered Depth image and RGB image to PointCloudXYZRGBA
424  * \param[in] depth the input depth image as intensity points in float
425  * \param[in] image the input RGB image
426  * \param[in] focal the focal length
427  * \param[out] out the output pointcloud
428  * **/
429  inline void
431  const PointCloud<RGB>& image,
432  const float& focal,
434  {
435  float bad_point = std::numeric_limits<float>::quiet_NaN();
436  std::size_t width_ = depth.width;
437  std::size_t height_ = depth.height;
438  float constant_ = 1.0f / focal;
439 
440  for (std::size_t v = 0; v < height_; v++)
441  {
442  for (std::size_t u = 0; u < width_; u++)
443  {
444  PointXYZRGBA pt;
445  float depth_ = depth.at (u, v).intensity;
446 
447  if (depth_ == 0)
448  {
449  pt.x = pt.y = pt.z = bad_point;
450  }
451  else
452  {
453  pt.z = depth_ * 0.001f;
454  pt.x = static_cast<float> (u) * pt.z * constant_;
455  pt.y = static_cast<float> (v) * pt.z * constant_;
456  }
457  pt.r = image.at (u, v).r;
458  pt.g = image.at (u, v).g;
459  pt.b = image.at (u, v).b;
460 
461  out.push_back (pt);
462  }
463  }
464  out.width = width_;
465  out.height = height_;
466  }
467 }
void push_back(const PointT &pt)
Insert a new point in the cloud, at the end of the container.
Definition: point_cloud.h:664
const PointT & at(int column, int row) const
Obtain the point given by the (column, row) coordinates.
Definition: point_cloud.h:263
std::uint32_t width
The point cloud width (if organized as an image-structure).
Definition: point_cloud.h:399
std::uint32_t height
The point cloud height (if organized as an image-structure).
Definition: point_cloud.h:401
Defines all the PCL implemented PointT point type structures.
@ B
Definition: norms.h:54
void PointXYZRGBtoXYZLAB(const PointT &in, PointXYZLAB &out)
Convert a XYZRGB-based point type to a XYZLAB.
void PointCloudXYZHSVtoXYZRGB(const PointCloud< PointXYZHSV > &in, PointCloud< PointXYZRGB > &out)
Convert a XYZHSV point cloud to a XYZRGB.
void PointCloudRGBtoI(const PointCloud< RGB > &in, PointCloud< Intensity > &out)
Convert a RGB point cloud to an Intensity.
void PointCloudXYZRGBAtoXYZHSV(const PointCloud< PointXYZRGBA > &in, PointCloud< PointXYZHSV > &out)
Convert a XYZRGB point cloud to a XYZHSV.
void PointXYZRGBtoXYZHSV(const PointXYZRGB &in, PointXYZHSV &out)
Convert a XYZRGB point type to a XYZHSV.
void PointXYZHSVtoXYZRGB(const PointXYZHSV &in, PointXYZRGB &out)
void PointXYZRGBAtoXYZHSV(const PointXYZRGBA &in, PointXYZHSV &out)
Convert a XYZRGBA point type to a XYZHSV.
void PointRGBtoI(const RGB &in, Intensity &out)
Convert a RGB point type to a I.
void PointCloudDepthAndRGBtoXYZRGBA(const PointCloud< Intensity > &depth, const PointCloud< RGB > &image, const float &focal, PointCloud< PointXYZRGBA > &out)
Convert registered Depth image and RGB image to PointCloudXYZRGBA.
void PointXYZRGBtoXYZI(const PointXYZRGB &in, PointXYZI &out)
Convert a XYZRGB point type to a XYZI.
void PointCloudXYZRGBtoXYZHSV(const PointCloud< PointXYZRGB > &in, PointCloud< PointXYZHSV > &out)
Convert a XYZRGB point cloud to a XYZHSV.
void PointCloudXYZRGBtoXYZI(const PointCloud< PointXYZRGB > &in, PointCloud< PointXYZI > &out)
Convert a XYZRGB point cloud to a XYZI.
A point structure representing the grayscale intensity in single-channel images.
A point structure representing the grayscale intensity in single-channel images.
A point structure representing the grayscale intensity in single-channel images.
A point structure representing Euclidean xyz coordinates, and the CIELAB color.
A point structure representing Euclidean xyz coordinates, and the RGBA color.
A point structure representing Euclidean xyz coordinates, and the RGB color.
A structure representing RGB color information.