Visual Servoing Platform  version 3.6.1 under development (2024-05-03)
vpImageConvert_pcl.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2023 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See https://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Convert image types.
33  *
34 *****************************************************************************/
35 
41 #include <visp3/core/vpConfig.h>
42 
43 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON) && defined(VISP_HAVE_THREADS)
44 
45 #include <visp3/core/vpImageConvert.h>
46 
47 #if defined(_OPENMP)
48 #include <omp.h>
49 #endif
50 
73 int vpImageConvert::depthToPointCloud(const vpImage<uint16_t> &depth_raw, float depth_scale,
74  const vpCameraParameters &cam_depth,
75  pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud, std::mutex *pointcloud_mutex,
76  const vpImage<unsigned char> *depth_mask, float Z_min, float Z_max)
77 {
78 
79  int size = static_cast<int>(depth_raw.getSize());
80  unsigned int width = depth_raw.getWidth();
81  unsigned int height = depth_raw.getHeight();
82  int pcl_size = 0;
83 
84  if (depth_mask) {
85  if ((width != depth_mask->getWidth()) || (height != depth_mask->getHeight())) {
86  throw(vpImageException(vpImageException::notInitializedError, "Depth image and mask size differ"));
87  }
88  if (pointcloud_mutex) {
89  pointcloud_mutex->lock();
90  }
91  pointcloud->clear();
92 #if defined(_OPENMP)
93  std::mutex mutex;
94 #pragma omp parallel for
95 #endif
96  for (int p = 0; p < size; ++p) {
97  if (depth_mask->bitmap[p]) {
98  if (static_cast<int>(depth_raw.bitmap[p])) {
99  float Z = static_cast<float>(depth_raw.bitmap[p]) * depth_scale;
100  if (Z < Z_max) {
101  double x = 0;
102  double y = 0;
103  unsigned int j = p % width;
104  unsigned int i = (p - j) / width;
105  vpPixelMeterConversion::convertPoint(cam_depth, j, i, x, y);
106  vpColVector point_3D({ x * Z, y * Z, Z });
107  if (point_3D[2] > Z_min) {
108 #if defined(_OPENMP)
109  std::lock_guard<std::mutex> lock(mutex);
110 #endif
111  pointcloud->push_back(pcl::PointXYZ(point_3D[0], point_3D[1], point_3D[2]));
112  }
113  }
114  }
115  }
116  }
117  pcl_size = pointcloud->size();
118  if (pointcloud_mutex) {
119  pointcloud_mutex->unlock();
120  }
121  }
122  else {
123  if (pointcloud_mutex) {
124  pointcloud_mutex->lock();
125  }
126  pointcloud->clear();
127 #if defined(_OPENMP)
128  std::mutex mutex;
129 #pragma omp parallel for
130 #endif
131  for (int p = 0; p < size; ++p) {
132  if (static_cast<int>(depth_raw.bitmap[p])) {
133  float Z = static_cast<float>(depth_raw.bitmap[p]) * depth_scale;
134  if (Z < 2.5) {
135  double x = 0;
136  double y = 0;
137  unsigned int j = p % width;
138  unsigned int i = (p - j) / width;
139  vpPixelMeterConversion::convertPoint(cam_depth, j, i, x, y);
140  vpColVector point_3D({ x * Z, y * Z, Z, 1 });
141  if (point_3D[2] >= 0.1) {
142 #if defined(_OPENMP)
143  std::lock_guard<std::mutex> lock(mutex);
144 #endif
145  pointcloud->push_back(pcl::PointXYZ(point_3D[0], point_3D[1], point_3D[2]));
146  }
147  }
148  }
149  }
150  pcl_size = pointcloud->size();
151  if (pointcloud_mutex) {
152  pointcloud_mutex->unlock();
153  }
154  }
155 
156  return pcl_size;
157 }
158 
182 int vpImageConvert::depthToPointCloud(const vpImage<vpRGBa> &color, const vpImage<uint16_t> &depth_raw,
183  float depth_scale, const vpCameraParameters &cam_depth,
184  pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud, std::mutex *pointcloud_mutex,
185  const vpImage<unsigned char> *depth_mask, float Z_min, float Z_max)
186 {
187  int size = static_cast<int>(depth_raw.getSize());
188  unsigned int width = depth_raw.getWidth();
189  unsigned int height = depth_raw.getHeight();
190  int pcl_size = 0;
191 
192  if (depth_mask) {
193  if ((width != depth_mask->getWidth()) || (height != depth_mask->getHeight())) {
194  throw(vpImageException(vpImageException::notInitializedError, "Depth image and mask size differ"));
195  }
196  if (pointcloud_mutex) {
197  pointcloud_mutex->lock();
198  }
199  pointcloud->clear();
200 #if defined(_OPENMP)
201  std::mutex mutex;
202 #pragma omp parallel for
203 #endif
204  for (int p = 0; p < size; ++p) {
205  if (depth_mask->bitmap[p]) {
206  if (static_cast<int>(depth_raw.bitmap[p])) {
207  float Z = static_cast<float>(depth_raw.bitmap[p]) * depth_scale;
208  if (Z < Z_max) {
209  double x = 0;
210  double y = 0;
211  unsigned int j = p % width;
212  unsigned int i = (p - j) / width;
213  vpPixelMeterConversion::convertPoint(cam_depth, j, i, x, y);
214  vpColVector point_3D({ x * Z, y * Z, Z });
215  if (point_3D[2] > Z_min) {
216 #if defined(_OPENMP)
217  std::lock_guard<std::mutex> lock(mutex);
218 #endif
219 #if PCL_VERSION_COMPARE(>=,1,14,1)
220  pointcloud->push_back(pcl::PointXYZRGB(point_3D[0], point_3D[1], point_3D[2],
221  color.bitmap[p].R, color.bitmap[p].G, color.bitmap[p].B));
222 #else
223  pcl::PointXYZRGB pt(color.bitmap[p].R, color.bitmap[p].G, color.bitmap[p].B);
224  pt.x = point_3D[0];
225  pt.y = point_3D[1];
226  pt.z = point_3D[2];
227  pointcloud->push_back(pcl::PointXYZRGB(pt));
228 #endif
229  }
230  }
231  }
232  }
233  }
234  pcl_size = pointcloud->size();
235  if (pointcloud_mutex) {
236  pointcloud_mutex->unlock();
237  }
238  }
239  else {
240  if (pointcloud_mutex) {
241  pointcloud_mutex->lock();
242  }
243  pointcloud->clear();
244 #if defined(_OPENMP)
245  std::mutex mutex;
246 #pragma omp parallel for
247 #endif
248  for (int p = 0; p < size; ++p) {
249  if (static_cast<int>(depth_raw.bitmap[p])) {
250  float Z = static_cast<float>(depth_raw.bitmap[p]) * depth_scale;
251  if (Z < 2.5) {
252  double x = 0;
253  double y = 0;
254  unsigned int j = p % width;
255  unsigned int i = (p - j) / width;
256  vpPixelMeterConversion::convertPoint(cam_depth, j, i, x, y);
257  vpColVector point_3D({ x * Z, y * Z, Z, 1 });
258  if (point_3D[2] >= 0.1) {
259 #if defined(_OPENMP)
260  std::lock_guard<std::mutex> lock(mutex);
261 #endif
262 #if PCL_VERSION_COMPARE(>=,1,14,1)
263  pointcloud->push_back(pcl::PointXYZRGB(point_3D[0], point_3D[1], point_3D[2],
264  color.bitmap[p].R, color.bitmap[p].G, color.bitmap[p].B));
265 #else
266  pcl::PointXYZRGB pt(color.bitmap[p].R, color.bitmap[p].G, color.bitmap[p].B);
267  pt.x = point_3D[0];
268  pt.y = point_3D[1];
269  pt.z = point_3D[2];
270  pointcloud->push_back(pcl::PointXYZRGB(pt));
271 #endif
272  }
273  }
274  }
275  }
276  pcl_size = pointcloud->size();
277  if (pointcloud_mutex) {
278  pointcloud_mutex->unlock();
279  }
280  }
281 
282  return pcl_size;
283 }
284 #endif
Generic class defining intrinsic camera parameters.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:163
Error that can be emitted by the vpImage class and its derivatives.
@ notInitializedError
Image not initialized.
Definition of the vpImage class member functions.
Definition: vpImage.h:69
unsigned int getWidth() const
Definition: vpImage.h:245
unsigned int getSize() const
Definition: vpImage.h:224
Type * bitmap
points toward the bitmap
Definition: vpImage.h:139
unsigned int getHeight() const
Definition: vpImage.h:184
static void convertPoint(const vpCameraParameters &cam, const double &u, const double &v, double &x, double &y)
unsigned char B
Blue component.
Definition: vpRGBa.h:139
unsigned char R
Red component.
Definition: vpRGBa.h:137
unsigned char G
Green component.
Definition: vpRGBa.h:138