Visual Servoing Platform version 3.6.0
Loading...
Searching...
No Matches
testRealSense_SR300.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 * Test Intel RealSense acquisition.
33 *
34*****************************************************************************/
35
41#include <iostream>
42
43#include <visp3/core/vpImageConvert.h>
44#include <visp3/gui/vpDisplayGDI.h>
45#include <visp3/gui/vpDisplayX.h>
46#include <visp3/io/vpImageIo.h>
47#include <visp3/sensor/vpRealSense.h>
48
49#if defined(VISP_HAVE_REALSENSE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \
50 (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI))
51#include <mutex>
52#include <thread>
53
54#ifdef VISP_HAVE_PCL
55#include <pcl/visualization/cloud_viewer.h>
56#include <pcl/visualization/pcl_visualizer.h>
57#endif
58
59namespace
60{
61
62#ifdef VISP_HAVE_PCL
63// Global variables
64pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
65pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud_color(new pcl::PointCloud<pcl::PointXYZRGB>());
66bool cancelled = false, update_pointcloud = false;
67
68class ViewerWorker
69{
70public:
71 explicit ViewerWorker(bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) {}
72
73 void run()
74 {
75 std::string date = vpTime::getDateTime();
76 pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("3D Viewer " + date));
77 pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(pointcloud_color);
78 pcl::PointCloud<pcl::PointXYZ>::Ptr local_pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
79 pcl::PointCloud<pcl::PointXYZRGB>::Ptr local_pointcloud_color(new pcl::PointCloud<pcl::PointXYZRGB>());
80
81 viewer->setBackgroundColor(0, 0, 0);
82 viewer->initCameraParameters();
83 viewer->setPosition(640 + 80, 480 + 80);
84 viewer->setCameraPosition(0, 0, -0.25, 0, -1, 0);
85 viewer->setSize(640, 480);
86
87 bool init = true;
88 bool local_update = false, local_cancelled = false;
89 while (!local_cancelled) {
90 {
91 std::unique_lock<std::mutex> lock(m_mutex, std::try_to_lock);
92
93 if (lock.owns_lock()) {
94 local_update = update_pointcloud;
95 update_pointcloud = false;
96 local_cancelled = cancelled;
97
98 if (local_update) {
99 if (m_colorMode) {
100 local_pointcloud_color = pointcloud_color->makeShared();
101 } else {
102 local_pointcloud = pointcloud->makeShared();
103 }
104 }
105 }
106 }
107
108 if (local_update && !local_cancelled) {
109 local_update = false;
110
111 if (init) {
112 if (m_colorMode) {
113 viewer->addPointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb, "RGB sample cloud");
114 viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1,
115 "RGB sample cloud");
116 } else {
117 viewer->addPointCloud<pcl::PointXYZ>(local_pointcloud, "sample cloud");
118 viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud");
119 }
120 init = false;
121 } else {
122 if (m_colorMode) {
123 viewer->updatePointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb, "RGB sample cloud");
124 } else {
125 viewer->updatePointCloud<pcl::PointXYZ>(local_pointcloud, "sample cloud");
126 }
127 }
128 }
129
130 viewer->spinOnce(5);
131 }
132
133 std::cout << "End of point cloud display thread" << std::endl;
134 }
135
136private:
137 bool m_colorMode;
138 std::mutex &m_mutex;
139};
140#endif //#ifdef VISP_HAVE_PCL
141
142void test_SR300(vpRealSense &rs, const std::map<rs::stream, bool> &enables,
143 const std::map<rs::stream, vpRealSense::vpRsStreamParams> &params, const std::string &title,
144 bool depth_color_visualization = false, const rs::stream &color_stream = rs::stream::color,
145 const rs::stream &depth_stream = rs::stream::depth, bool display_pcl = false, bool pcl_color = false)
146{
147 std::cout << std::endl;
148
149 std::map<rs::stream, bool>::const_iterator it_enable;
150 std::map<rs::stream, vpRealSense::vpRsStreamParams>::const_iterator it_param;
151
152 for (it_enable = enables.begin(), it_param = params.begin(); it_enable != enables.end(); ++it_enable) {
153 rs.setEnableStream(it_enable->first, it_enable->second);
154
155 if (it_enable->second) {
156 it_param = params.find(it_enable->first);
157
158 if (it_param != params.end()) {
159 rs.setStreamSettings(it_param->first, it_param->second);
160 }
161 }
162 }
163
164 rs.open();
165
166 vpImage<uint16_t> depth;
168 vpImage<vpRGBa> I_depth_color;
169
170 vpImage<vpRGBa> I_color;
171 vpImage<uint16_t> infrared;
172 vpImage<unsigned char> I_infrared;
173
174 bool direct_infrared_conversion = false;
175 for (it_enable = enables.begin(); it_enable != enables.end(); ++it_enable) {
176 if (it_enable->second) {
177 switch (it_enable->first) {
178 case rs::stream::color:
179 I_color.init((unsigned int)rs.getIntrinsics(it_enable->first).height,
180 (unsigned int)rs.getIntrinsics(it_enable->first).width);
181 break;
182
183 case rs::stream::depth:
184 depth.init((unsigned int)rs.getIntrinsics(it_enable->first).height,
185 (unsigned int)rs.getIntrinsics(it_enable->first).width);
186 I_depth.init(depth.getHeight(), depth.getWidth());
187 I_depth_color.init(depth.getHeight(), depth.getWidth());
188 break;
189
190 case rs::stream::infrared:
191 infrared.init((unsigned int)rs.getIntrinsics(it_enable->first).height,
192 (unsigned int)rs.getIntrinsics(it_enable->first).width);
193 I_infrared.init(infrared.getHeight(), infrared.getWidth());
194
195 it_param = params.find(it_enable->first);
196 if (it_param != params.end()) {
197 direct_infrared_conversion = it_param->second.m_streamFormat == rs::format::y8;
198 }
199 break;
200
201 default:
202 break;
203 }
204 }
205 }
206
207#if defined(VISP_HAVE_X11)
208 vpDisplayX dc, dd, di;
209#elif defined(VISP_HAVE_GDI)
210 vpDisplayGDI dc, dd, di;
211#endif
212
213 for (it_enable = enables.begin(); it_enable != enables.end(); ++it_enable) {
214 if (it_enable->second) {
215 switch (it_enable->first) {
216 case rs::stream::color:
217 dc.init(I_color, 0, 0, "Color frame");
218 break;
219
220 case rs::stream::depth:
221 if (depth_color_visualization) {
222 dd.init(I_depth_color, (int)I_color.getWidth() + 80, 0, "Depth frame");
223 } else {
224 dd.init(I_depth, (int)I_color.getWidth() + 80, 0, "Depth frame");
225 }
226 break;
227
228 case rs::stream::infrared:
229 di.init(I_infrared, 0, (int)(std::max)(I_color.getHeight(), I_depth.getHeight()) + 30, "Infrared frame");
230 break;
231
232 default:
233 break;
234 }
235 }
236 }
237
238 if (rs.getHandler()->is_stream_enabled(rs::stream::infrared)) {
239 std::cout << "direct_infrared_conversion=" << direct_infrared_conversion << std::endl;
240 }
241
242#ifdef VISP_HAVE_PCL
243 std::mutex mutex;
244 ViewerWorker viewer(pcl_color, mutex);
245 std::thread viewer_thread;
246
247 if (display_pcl) {
248 viewer_thread = std::thread(&ViewerWorker::run, &viewer);
249 }
250#else
251 display_pcl = false;
252#endif
253
254 // Test stream acquisition during 10 s
255 std::vector<double> time_vector;
256 double t_begin = vpTime::measureTimeMs();
257 while (true) {
258 double t = vpTime::measureTimeMs();
259
260 if (display_pcl) {
261#ifdef VISP_HAVE_PCL
262 std::lock_guard<std::mutex> lock(mutex);
263
264 if (direct_infrared_conversion) {
265 if (pcl_color) {
266 rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud_color,
267 (unsigned char *)I_infrared.bitmap, NULL, color_stream, depth_stream);
268 } else {
269 rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud,
270 (unsigned char *)I_infrared.bitmap, NULL, color_stream, depth_stream);
271 }
272 } else {
273 if (pcl_color) {
274 rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud_color,
275 (unsigned char *)infrared.bitmap, NULL, color_stream, depth_stream);
276 } else {
277 rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud,
278 (unsigned char *)infrared.bitmap, NULL, color_stream, depth_stream);
279 }
280
281 vpImageConvert::convert(infrared, I_infrared);
282 }
283
284 update_pointcloud = true;
285#endif
286 } else {
287 if (direct_infrared_conversion) {
288 rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL,
289 (unsigned char *)I_infrared.bitmap, NULL, color_stream, depth_stream);
290 } else {
291 rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL,
292 (unsigned char *)infrared.bitmap, NULL, color_stream, depth_stream);
293 vpImageConvert::convert(infrared, I_infrared);
294 }
295 }
296
297 if (depth_color_visualization) {
298 vpImageConvert::createDepthHistogram(depth, I_depth_color);
299 } else {
301 }
302
303 vpDisplay::display(I_color);
304 if (depth_color_visualization) {
305 vpDisplay::display(I_depth_color);
306 } else {
307 vpDisplay::display(I_depth);
308 }
309 vpDisplay::display(I_infrared);
310
311 vpDisplay::flush(I_color);
312 if (depth_color_visualization) {
313 vpDisplay::flush(I_depth_color);
314 } else {
315 vpDisplay::flush(I_depth);
316 }
317 vpDisplay::flush(I_infrared);
318
319 if (vpDisplay::getClick(I_color, false) ||
320 (depth_color_visualization ? vpDisplay::getClick(I_depth_color, false) : vpDisplay::getClick(I_depth, false)) ||
321 vpDisplay::getClick(I_infrared, false)) {
322 break;
323 }
324
325 time_vector.push_back(vpTime::measureTimeMs() - t);
326 if (vpTime::measureTimeMs() - t_begin >= 10000) {
327 break;
328 }
329 }
330
331 if (display_pcl) {
332#ifdef VISP_HAVE_PCL
333 {
334 std::lock_guard<std::mutex> lock(mutex);
335 cancelled = true;
336 }
337
338 viewer_thread.join();
339#endif
340 }
341
342 std::cout << title << " - Mean time: " << vpMath::getMean(time_vector)
343 << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl;
344
345 rs.close();
346}
347
348} // namespace
349
350int main(int argc, char *argv[])
351{
352 try {
353 vpRealSense rs;
354
355 rs.setEnableStream(rs::stream::color, false);
356 rs.open();
357 if (rs_get_device_name((const rs_device *)rs.getHandler(), nullptr) != std::string("Intel RealSense SR300")) {
358 std::cout << "This test file is used to test the Intel RealSense SR300 only." << std::endl;
359 return EXIT_SUCCESS;
360 }
361
362 std::cout << "API version: " << rs_get_api_version(nullptr) << std::endl;
363 std::cout << "Firmware: " << rs_get_device_firmware_version((const rs_device *)rs.getHandler(), nullptr)
364 << std::endl;
365 std::cout << "RealSense sensor characteristics: \n" << rs << std::endl;
366
367 rs.close();
368
369 std::map<rs::stream, bool> enables;
370 std::map<rs::stream, vpRealSense::vpRsStreamParams> params;
371
372 enables[rs::stream::color] = false;
373 enables[rs::stream::depth] = true;
374 enables[rs::stream::infrared] = false;
375
376 params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 240, rs::format::z16, 110);
377
378 test_SR300(rs, enables, params, "SR300_DEPTH_Z16_640x240_110FPS");
379
380 enables[rs::stream::color] = true;
381 enables[rs::stream::depth] = false;
382 enables[rs::stream::infrared] = false;
383
384 params[rs::stream::color] = vpRealSense::vpRsStreamParams(1920, 1080, rs::format::rgba8, 30);
385
386 test_SR300(rs, enables, params, "SR300_COLOR_RGBA8_1920x1080_30FPS");
387
388 enables[rs::stream::color] = false;
389 enables[rs::stream::depth] = false;
390 enables[rs::stream::infrared] = true;
391
392 params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y16, 200);
393
394 test_SR300(rs, enables, params, "SR300_INFRARED_Y16_640x480_200FPS");
395
396 enables[rs::stream::color] = false;
397 enables[rs::stream::depth] = true;
398 enables[rs::stream::infrared] = false;
399
400 params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 60);
401
402 test_SR300(rs, enables, params, "SR300_DEPTH_Z16_640x480_60FPS", true);
403
404 enables[rs::stream::color] = false;
405 enables[rs::stream::depth] = true;
406 enables[rs::stream::infrared] = true;
407
408 params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 60);
409 params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 60);
410
411 test_SR300(rs, enables, params, "SR300_DEPTH_Z16_640x480_60FPS + SR300_INFRARED_Y8_640x480_60FPS", true);
412
413#if (!defined(__APPLE__) && !defined(__MACH__)) // Not OSX, since viewer->spinOnce (10); produces a
414 // segfault on OSX
415
416 enables[rs::stream::color] = true;
417 enables[rs::stream::depth] = true;
418 enables[rs::stream::infrared] = true;
419
420 params[rs::stream::color] = vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 60);
421 params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 60);
422 params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 60);
423
424 // depth == 0 ; color == 1 ; rectified_color == 6 ; color_aligned_to_depth
425 // == 7 ; depth_aligned_to_color == 9 ; depth_aligned_to_rectified_color
426 // == 10 argv[1] <==> color stream
427 rs::stream color_stream = argc > 1 ? (rs::stream)atoi(argv[1]) : rs::stream::color;
428 std::cout << "\ncolor_stream: " << color_stream << std::endl;
429 // argv[2] <==> depth stream
430 rs::stream depth_stream = argc > 2 ? (rs::stream)atoi(argv[2]) : rs::stream::depth;
431 std::cout << "depth_stream: " << depth_stream << std::endl;
432
433 test_SR300(rs, enables, params,
434 "SR300_COLOR_RGBA8_640x480_60FPS + "
435 "SR300_DEPTH_Z16_640x480_60FPS + "
436 "SR300_INFRARED_Y8_640x480_60FPS",
437 true, color_stream, depth_stream, true, true);
438#endif
439
440 // Color stream aligned to depth
441 enables[rs::stream::color] = true;
442 enables[rs::stream::depth] = true;
443 enables[rs::stream::infrared] = false;
444
445 params[rs::stream::color] = vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 30);
446 params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 30);
447
448 test_SR300(rs, enables, params,
449 "SR300_COLOR_ALIGNED_TO_DEPTH_RGBA8_640x480_30FPS + "
450 "SR300_DEPTH_Z16_640x480_30FPS",
451 true, rs::stream::color_aligned_to_depth);
452
453 // Depth stream aligned to color
454 test_SR300(rs, enables, params,
455 "SR300_COLOR_RGBA8_640x480_30FPS + "
456 "SR300_DEPTH_ALIGNED_TO_COLOR_Z16_640x480_30FPS",
457 true, rs::stream::color, rs::stream::depth_aligned_to_color);
458
459 rs.setEnableStream(rs::stream::color, true);
460 rs.setEnableStream(rs::stream::depth, false);
461 rs.setEnableStream(rs::stream::infrared, true);
462 rs.setStreamSettings(rs::stream::color, vpRealSense::vpRsStreamParams(640, 480, rs::format::bgr8, 60));
463 rs.setStreamSettings(rs::stream::infrared, vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 200));
464 rs.open();
465
466 cv::Mat color_mat(480, 640, CV_8UC3);
467 cv::Mat infrared_mat(480, 640, CV_8U);
468
469 double t_begin = vpTime::measureTimeMs();
470 while (true) {
471 rs.acquire(color_mat.data, NULL, NULL, infrared_mat.data);
472
473 cv::imshow("Color mat", color_mat);
474 cv::imshow("Infrared mat", infrared_mat);
475 char c = cv::waitKey(1);
476 if (c == 27) {
477 break;
478 }
479
480 if (vpTime::measureTimeMs() - t_begin >= 10000) {
481 break;
482 }
483 }
484 } catch (const vpException &e) {
485 std::cerr << "RealSense error " << e.what() << std::endl;
486 } catch (const rs::error &e) {
487 std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args()
488 << "): " << e.what() << std::endl;
489 } catch (const std::exception &e) {
490 std::cerr << e.what() << std::endl;
491 }
492
493 return EXIT_SUCCESS;
494}
495
496#else
497int main()
498{
499#if !defined(VISP_HAVE_REALSENSE)
500 std::cout << "Install librealsense to make this test work." << std::endl;
501#endif
502#if !(VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
503 std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11) "
504 "to make this test work."
505 << std::endl;
506#endif
507#if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI)
508 std::cout << "X11 or GDI are needed." << std::endl;
509#endif
510 return EXIT_SUCCESS;
511}
512#endif
Display for windows using GDI (available on any windows 32 platform).
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Definition vpDisplayX.h:132
void init(vpImage< unsigned char > &I, int win_x=-1, int win_y=-1, const std::string &win_title="")
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)
error that can be emitted by ViSP classes.
Definition vpException.h:59
const char * what() const
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
Definition of the vpImage class member functions.
Definition vpImage.h:135
void init(unsigned int height, unsigned int width)
Set the size of the image.
Definition vpImage.h:639
unsigned int getWidth() const
Definition vpImage.h:242
Type * bitmap
points toward the bitmap
Definition vpImage.h:139
unsigned int getHeight() const
Definition vpImage.h:184
static double getMedian(const std::vector< double > &v)
Definition vpMath.cpp:314
static double getMean(const std::vector< double > &v)
Definition vpMath.cpp:294
void setStreamSettings(const rs::stream &stream, const rs::preset &preset)
rs::device * getHandler() const
Get access to device handler.
void acquire(std::vector< vpColVector > &pointcloud)
void setEnableStream(const rs::stream &stream, bool status)
rs::intrinsics getIntrinsics(const rs::stream &stream) const
VISP_EXPORT double measureTimeMs()
VISP_EXPORT std::string getDateTime(const std::string &format="%Y/%m/%d %H:%M:%S")