Visual Servoing Platform  version 3.6.1 under development (2024-11-15)
testRealSense2_D435_align.cpp
1 /*
2  * ViSP, open source Visual Servoing Platform software.
3  * Copyright (C) 2005 - 2024 by Inria. All rights reserved.
4  *
5  * This software is free software; you can redistribute it and/or modify
6  * it under the terms of the GNU General Public License as published by
7  * the Free Software Foundation; either version 2 of the License, or
8  * (at your option) any later version.
9  * See the file LICENSE.txt at the root directory of this source
10  * distribution for additional information about the GNU GPL.
11  *
12  * For using ViSP with software that can not be combined with the GNU
13  * GPL, please contact Inria about acquiring a ViSP Professional
14  * Edition License.
15  *
16  * See https://visp.inria.fr for more information.
17  *
18  * This software was developed at:
19  * Inria Rennes - Bretagne Atlantique
20  * Campus Universitaire de Beaulieu
21  * 35042 Rennes Cedex
22  * France
23  *
24  * If you have questions regarding the use of this file, please contact
25  * Inria at visp@inria.fr
26  *
27  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29  *
30  * Description:
31  * Test Intel RealSense D435 acquisition with librealsense2.
32  */
38 #include <iostream>
39 #include <visp3/core/vpConfig.h>
40 
41 #if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) \
42  && defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI))
43 
44 #include <visp3/core/vpImage.h>
45 #include <visp3/core/vpImageConvert.h>
46 #include <visp3/core/vpMeterPixelConversion.h>
47 #include <visp3/gui/vpDisplayGDI.h>
48 #include <visp3/gui/vpDisplayX.h>
49 #include <visp3/sensor/vpRealSense2.h>
50 
51 #ifdef ENABLE_VISP_NAMESPACE
52 using namespace VISP_NAMESPACE_NAME;
53 #endif
54 
55 namespace
56 {
57 void createDepthHist(std::vector<uint32_t> &histogram2, const pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
58  double depth_scale)
59 {
60  std::fill(histogram2.begin(), histogram2.end(), 0);
61 
62  for (uint32_t i = 0; i < pointcloud->height; i++) {
63  for (uint32_t j = 0; j < pointcloud->width; j++) {
64  const pcl::PointXYZ &pcl_pt = pointcloud->at(j, i);
65  ++histogram2[static_cast<uint32_t>(pcl_pt.z * depth_scale)];
66  }
67  }
68 
69  for (int i = 2; i < 0x10000; i++)
70  histogram2[i] += histogram2[i - 1]; // Build a cumulative histogram for
71  // the indices in [1,0xFFFF]
72 }
73 
74 void createDepthHist(std::vector<uint32_t> &histogram2, const std::vector<vpColVector> &pointcloud, double depth_scale)
75 {
76  std::fill(histogram2.begin(), histogram2.end(), 0);
77 
78  for (size_t i = 0; i < pointcloud.size(); i++) {
79  const vpColVector &pt = pointcloud[i];
80  ++histogram2[static_cast<uint32_t>(pt[2] * depth_scale)];
81  }
82 
83  for (int i = 2; i < 0x10000; i++)
84  histogram2[i] += histogram2[i - 1]; // Build a cumulative histogram for
85  // the indices in [1,0xFFFF]
86 }
87 
88 unsigned char getDepthColor(const std::vector<uint32_t> &histogram2, double z, double depth_scale)
89 {
90  // 0-255 based on histogram location
91  return static_cast<unsigned char>(histogram2[static_cast<uint32_t>(z * depth_scale)] * 255 / histogram2[0xFFFF]);
92 }
93 } // namespace
94 
95 int main(int argc, char *argv[])
96 {
97  bool align_to_depth = false;
98  bool color_pointcloud = false;
99  bool col_vector = false;
100  bool no_align = false;
101  for (int i = 1; i < argc; i++) {
102  if (std::string(argv[i]) == "--align_to_depth") {
103  align_to_depth = true;
104  }
105  else if (std::string(argv[i]) == "--color") {
106  color_pointcloud = true;
107  }
108  else if (std::string(argv[i]) == "--col_vector") {
109  col_vector = true;
110  }
111  else if (std::string(argv[i]) == "--no_align") {
112  no_align = true;
113  }
114  }
115 
116  std::cout << "align_to_depth: " << align_to_depth << std::endl;
117  std::cout << "color_pointcloud: " << color_pointcloud << std::endl;
118  std::cout << "col_vector: " << col_vector << std::endl;
119  std::cout << "no_align: " << no_align << std::endl;
120 
121  vpRealSense2 rs;
122  rs2::config config;
123  const int width = 640, height = 480, fps = 30;
124  config.enable_stream(RS2_STREAM_COLOR, width, height, RS2_FORMAT_RGBA8, fps);
125  config.enable_stream(RS2_STREAM_DEPTH, width, height, RS2_FORMAT_Z16, fps);
126  config.enable_stream(RS2_STREAM_INFRARED, width, height, RS2_FORMAT_Y8, fps);
127  rs.open(config);
128  const double depth_scale = 1.0 / rs.getDepthScale();
129 
130  vpImage<vpRGBa> I_color(height, width), I_depth(height, width), I_pcl(height, width), I_pcl2(height, width);
131  vpImage<vpRGBa> I_display(height * 2, width), I_display2(height * 2, width), I_display3(height * 2, width);
132  vpImage<uint16_t> I_depth_raw(height, width);
133 
134 #ifdef VISP_HAVE_X11
135  vpDisplayX d1, d2, d3;
136 #else
137  vpDisplayGDI d1, d2, d3;
138 #endif
139  d1.init(I_display, 0, 0, "Color + depth");
140  d2.init(I_display2, width, 0, "Color + ROS pointcloud");
141  d3.init(I_display3, 2 * width, 0, "Color + pointcloud");
142 
143  pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
144  pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud_color(new pcl::PointCloud<pcl::PointXYZRGB>());
145  std::vector<vpColVector> vp_pointcloud;
146  std::vector<uint32_t> histogram(0x10000), histogram2(0x10000);
147 
148  rs2::align align_to(align_to_depth ? RS2_STREAM_DEPTH : RS2_STREAM_COLOR);
149  vpCameraParameters cam_projection =
150  align_to_depth ? rs.getCameraParameters(RS2_STREAM_DEPTH) : rs.getCameraParameters(RS2_STREAM_COLOR);
151 
152  while (true) {
153  if (color_pointcloud) {
154  rs.acquire(reinterpret_cast<unsigned char *>(I_color.bitmap),
155  reinterpret_cast<unsigned char *>(I_depth_raw.bitmap), &vp_pointcloud, pointcloud_color, nullptr,
156  no_align ? nullptr : &align_to);
157  }
158  else {
159  rs.acquire(reinterpret_cast<unsigned char *>(I_color.bitmap),
160  reinterpret_cast<unsigned char *>(I_depth_raw.bitmap), &vp_pointcloud, pointcloud, nullptr,
161  no_align ? nullptr : &align_to);
162  }
163 
164  vpImageConvert::createDepthHistogram(I_depth_raw, I_depth);
165 
166  I_pcl = vpRGBa(0, 0, 0);
167  if (color_pointcloud) {
168  for (uint32_t i = 0; i < pointcloud_color->height; i++) {
169  for (uint32_t j = 0; j < pointcloud_color->width; j++) {
170  const pcl::PointXYZRGB &pcl_pt = pointcloud_color->at(j, i);
171  double Z = pcl_pt.z;
172  if (Z > 1e-2) {
173  double x = pcl_pt.x / Z;
174  double y = pcl_pt.y / Z;
175 
176  vpImagePoint imPt;
177  vpMeterPixelConversion::convertPoint(cam_projection, x, y, imPt);
178  unsigned int u =
179  std::min<unsigned int>(static_cast<unsigned int>(width - 1), static_cast<unsigned int>(std::max<double>(0.0, imPt.get_u())));
180  unsigned int v =
181  std::min<unsigned int>(static_cast<unsigned int>(height - 1), static_cast<unsigned int>(std::max<double>(0.0, imPt.get_v())));
182  I_pcl[v][u] = vpRGBa(pcl_pt.r, pcl_pt.g, pcl_pt.b);
183  }
184  }
185  }
186  }
187  else {
188  createDepthHist(histogram, pointcloud, depth_scale);
189 
190  for (uint32_t i = 0; i < pointcloud->height; i++) {
191  for (uint32_t j = 0; j < pointcloud->width; j++) {
192  const pcl::PointXYZ &pcl_pt = pointcloud->at(j, i);
193  double Z = pcl_pt.z;
194  if (Z > 1e-2) {
195  double x = pcl_pt.x / Z;
196  double y = pcl_pt.y / Z;
197 
198  vpImagePoint imPt;
199  vpMeterPixelConversion::convertPoint(cam_projection, x, y, imPt);
200  unsigned int u =
201  std::min<unsigned int>(static_cast<unsigned int>(width - 1), static_cast<unsigned int>(std::max<double>(0.0, imPt.get_u())));
202  unsigned int v =
203  std::min<unsigned int>(static_cast<unsigned int>(height - 1), static_cast<unsigned int>(std::max<double>(0.0, imPt.get_v())));
204  unsigned char depth_viz = getDepthColor(histogram, pcl_pt.z, depth_scale);
205  I_pcl[v][u] = vpRGBa(depth_viz, depth_viz, depth_viz);
206  }
207  }
208  }
209  }
210 
211  I_pcl2 = vpRGBa(0, 0, 0);
212  createDepthHist(histogram2, vp_pointcloud, depth_scale);
213  for (size_t i = 0; i < vp_pointcloud.size(); i++) {
214  const vpColVector &pt = vp_pointcloud[i];
215  double Z = pt[2];
216  if (Z > 1e-2) {
217  double x = pt[0] / Z;
218  double y = pt[1] / Z;
219 
220  vpImagePoint imPt;
221  vpMeterPixelConversion::convertPoint(cam_projection, x, y, imPt);
222  unsigned int u =
223  std::min<unsigned int>(static_cast<unsigned int>(width - 1), static_cast<unsigned int>(std::max<double>(0.0, imPt.get_u())));
224  unsigned int v =
225  std::min<unsigned int>(static_cast<unsigned int>(height - 1), static_cast<unsigned int>(std::max<double>(0.0, imPt.get_v())));
226  unsigned char depth_viz = getDepthColor(histogram2, Z, depth_scale);
227  I_pcl2[v][u] = vpRGBa(depth_viz, depth_viz, depth_viz);
228  }
229  }
230 
231  I_display.insert(I_color, vpImagePoint(0, 0));
232  I_display.insert(I_depth, vpImagePoint(I_color.getHeight(), 0));
233 
234  I_display2.insert(I_color, vpImagePoint(0, 0));
235  I_display2.insert(I_pcl, vpImagePoint(I_color.getHeight(), 0));
236 
237  I_display3.insert(I_color, vpImagePoint(0, 0));
238  I_display3.insert(I_pcl2, vpImagePoint(I_color.getHeight(), 0));
239 
240  vpDisplay::display(I_display);
241  vpDisplay::display(I_display2);
242  vpDisplay::display(I_display3);
243 
244  const int nb_lines = 5;
245  for (int i = 1; i < nb_lines; i++) {
246  const int col_idx = i * (width / nb_lines);
247  vpDisplay::displayLine(I_display, 0, col_idx, I_display.getRows() - 1, col_idx, vpColor::green, 2);
248  vpDisplay::displayLine(I_display2, 0, col_idx, I_display.getRows() - 1, col_idx, vpColor::green, 2);
249  vpDisplay::displayLine(I_display3, 0, col_idx, I_display.getRows() - 1, col_idx, vpColor::green, 2);
250  }
251 
252  vpDisplay::flush(I_display);
253  vpDisplay::flush(I_display2);
254  vpDisplay::flush(I_display3);
255 
256  if (vpDisplay::getClick(I_display, false) || vpDisplay::getClick(I_display2, false) ||
257  vpDisplay::getClick(I_display3, false)) {
258  break;
259  }
260  }
261 
262  return EXIT_SUCCESS;
263 }
264 
265 #else
266 int main() { return EXIT_SUCCESS; }
267 #endif
Generic class defining intrinsic camera parameters.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
static const vpColor green
Definition: vpColor.h:220
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:130
void init(vpImage< unsigned char > &I, int winx=-1, int winy=-1, const std::string &title="") VP_OVERRIDE
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
static void displayLine(const vpImage< unsigned char > &I, const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness=1, bool segment=true)
static void flush(const vpImage< unsigned char > &I)
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:82
double get_u() const
Definition: vpImagePoint.h:136
double get_v() const
Definition: vpImagePoint.h:147
static void convertPoint(const vpCameraParameters &cam, const double &x, const double &y, double &u, double &v)
Definition: vpRGBa.h:65
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion, int index=-1) const
void acquire(vpImage< unsigned char > &grey, double *ts=nullptr)
bool open(const rs2::config &cfg=rs2::config())
float getDepthScale()