Visual Servoing Platform  version 3.6.1 under development (2024-11-15)
testRealSense2_D435.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 acquisition with librealsense2.
32  */
38 #include <iostream>
39 
40 #include <visp3/core/vpConfig.h>
41 
42 #if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) \
43  && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI))
44 
45 #include <visp3/core/vpImage.h>
46 #include <visp3/core/vpImageConvert.h>
47 #include <visp3/gui/vpDisplayGDI.h>
48 #include <visp3/gui/vpDisplayX.h>
49 #include <visp3/sensor/vpRealSense2.h>
50 
51 int main(int argc, char *argv[])
52 {
53 #ifdef ENABLE_VISP_NAMESPACE
54  using namespace VISP_NAMESPACE_NAME;
55 #endif
56  bool show_info = false;
57 
58  for (int i = 1; i < argc; i++) {
59  if (std::string(argv[i]) == "--show_info") {
60  show_info = true;
61  }
62  }
63 
64  if (show_info) {
65  vpRealSense2 rs;
66  rs.open();
67  std::cout << "RealSense:\n" << rs << std::endl;
68  return EXIT_SUCCESS;
69  }
70 
71  int width = 1280, height = 720, fps = 30;
72  vpRealSense2 rs;
73  rs2::config config;
74  config.enable_stream(RS2_STREAM_COLOR, width, height, RS2_FORMAT_RGBA8, fps);
75  config.enable_stream(RS2_STREAM_DEPTH, width, height, RS2_FORMAT_Z16, fps);
76  config.enable_stream(RS2_STREAM_INFRARED, 1, width, height, RS2_FORMAT_Y8, fps);
77  config.enable_stream(RS2_STREAM_INFRARED, 2, width, height, RS2_FORMAT_Y8, fps);
78  rs.open(config);
79 
80  vpImage<vpRGBa> color(static_cast<unsigned int>(height), static_cast<unsigned int>(width));
81  vpImage<vpRGBa> depth_color(static_cast<unsigned int>(height), static_cast<unsigned int>(width));
82  vpImage<uint16_t> depth_raw(static_cast<unsigned int>(height), static_cast<unsigned int>(width));
83  vpImage<unsigned char> infrared1(static_cast<unsigned int>(height), static_cast<unsigned int>(width));
84  vpImage<unsigned char> infrared2(static_cast<unsigned int>(height), static_cast<unsigned int>(width));
85 
86 #ifdef VISP_HAVE_X11
87  vpDisplayX d1, d2, d3, d4;
88 #else
89  vpDisplayGDI d1, d2, d3, d4;
90 #endif
91  d1.init(color, 0, 0, "Color");
92  d2.init(depth_color, color.getWidth(), 0, "Depth");
93  d3.init(infrared1, 0, color.getHeight() + 100, "Infrared left");
94  d4.init(infrared2, color.getWidth(), color.getHeight() + 100, "Infrared right");
95 
96  std::vector<vpColVector> pointcloud_colvector;
97 
98  std::vector<double> time_vector;
99  double t_begin = vpTime::measureTimeMs();
100  while (vpTime::measureTimeMs() - t_begin < 10000) {
101  double t = vpTime::measureTimeMs();
102 
103  rs.acquire(reinterpret_cast<unsigned char *>(color.bitmap), reinterpret_cast<unsigned char *>(depth_raw.bitmap),
104  &pointcloud_colvector, reinterpret_cast<unsigned char *>(infrared1.bitmap),
105  reinterpret_cast<unsigned char *>(infrared2.bitmap), nullptr);
106 
107  vpImageConvert::createDepthHistogram(depth_raw, depth_color);
108 
109  vpDisplay::display(color);
110  vpDisplay::display(depth_color);
111  vpDisplay::display(infrared1);
112  vpDisplay::display(infrared2);
113 
114  vpDisplay::displayText(color, 20, 20, "Click to quit.", vpColor::red);
115  vpDisplay::displayText(depth_color, 20, 20, "Click to quit.", vpColor::red);
116  vpDisplay::displayText(infrared1, 20, 20, "Click to quit.", vpColor::red);
117  vpDisplay::displayText(infrared2, 20, 20, "Click to quit.", vpColor::red);
118 
119  vpDisplay::flush(color);
120  vpDisplay::flush(depth_color);
121  vpDisplay::flush(infrared1);
122  vpDisplay::flush(infrared2);
123 
124  time_vector.push_back(vpTime::measureTimeMs() - t);
125  if (vpDisplay::getClick(color, false) || vpDisplay::getClick(depth_color, false) ||
126  vpDisplay::getClick(infrared1, false) || vpDisplay::getClick(infrared2, false)) {
127  break;
128  }
129  }
130 
131  // test open -> close -> open sequence
132  rs.close();
133  d1.close(color);
134  d2.close(depth_color);
135  d3.close(infrared1);
136  d4.close(infrared2);
137 
138  std::cout << "Acquisition1 - Mean time: " << vpMath::getMean(time_vector)
139  << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl;
140 
141  width = 640;
142  height = 480;
143  fps = 60;
144  config.disable_all_streams();
145  config.enable_stream(RS2_STREAM_COLOR, width, height, RS2_FORMAT_RGBA8, fps);
146  config.enable_stream(RS2_STREAM_DEPTH, width, height, RS2_FORMAT_Z16, fps);
147  config.enable_stream(RS2_STREAM_INFRARED, width, height, RS2_FORMAT_Y8, fps);
148  rs.open(config);
149 
150  color.init(static_cast<unsigned int>(height), static_cast<unsigned int>(width));
151  depth_color.init(static_cast<unsigned int>(height), static_cast<unsigned int>(width));
152  depth_raw.init(static_cast<unsigned int>(height), static_cast<unsigned int>(width));
153  infrared1.init(static_cast<unsigned int>(height), static_cast<unsigned int>(width));
154 
155  d1.init(color, 0, 0, "Color");
156  d2.init(depth_color, color.getWidth(), 0, "Depth");
157  d3.init(infrared1, 0, color.getHeight() + 100, "Infrared");
158 
159  time_vector.clear();
160  t_begin = vpTime::measureTimeMs();
161  while (vpTime::measureTimeMs() - t_begin < 10000) {
162  double t = vpTime::measureTimeMs();
163 
164  rs.acquire(reinterpret_cast<unsigned char *>(color.bitmap), reinterpret_cast<unsigned char *>(depth_raw.bitmap),
165  nullptr, reinterpret_cast<unsigned char *>(infrared1.bitmap));
166 
167  vpImageConvert::createDepthHistogram(depth_raw, depth_color);
168 
169  vpDisplay::display(color);
170  vpDisplay::display(depth_color);
171  vpDisplay::display(infrared1);
172 
173  vpDisplay::displayText(color, 20, 20, "Click to quit.", vpColor::red);
174  vpDisplay::displayText(depth_color, 20, 20, "Click to quit.", vpColor::red);
175  vpDisplay::displayText(infrared1, 20, 20, "Click to quit.", vpColor::red);
176 
177  vpDisplay::flush(color);
178  vpDisplay::flush(depth_color);
179  vpDisplay::flush(infrared1);
180 
181  time_vector.push_back(vpTime::measureTimeMs() - t);
182  if (vpDisplay::getClick(color, false) || vpDisplay::getClick(depth_color, false) ||
183  vpDisplay::getClick(infrared1, false)) {
184  break;
185  }
186  }
187 
188  std::cout << "Acquisition2 - Mean time: " << vpMath::getMean(time_vector)
189  << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl;
190 
191  return EXIT_SUCCESS;
192 }
193 
194 #else
195 int main()
196 {
197 #if !defined(VISP_HAVE_REALSENSE2)
198  std::cout << "Install librealsense2 to make this test work." << std::endl;
199 #endif
200 #if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI)
201  std::cout << "X11 or GDI are needed." << std::endl;
202 #endif
203  return EXIT_SUCCESS;
204 }
205 #endif
static const vpColor red
Definition: vpColor.h:217
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 flush(const vpImage< unsigned char > &I)
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)
static double getMedian(const std::vector< double > &v)
Definition: vpMath.cpp:322
static double getMean(const std::vector< double > &v)
Definition: vpMath.cpp:302
void acquire(vpImage< unsigned char > &grey, double *ts=nullptr)
bool open(const rs2::config &cfg=rs2::config())
VISP_EXPORT double measureTimeMs()