Visual Servoing Platform version 3.6.0
Loading...
Searching...
No Matches
testRealSense2_D435_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 * Test Intel RealSense acquisition with librealsense2 (PCL demo).
33 *
34*****************************************************************************/
40#include <iostream>
41
42#include <visp3/core/vpConfig.h>
43
44#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \
45 (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_PCL)
46
47#include <mutex>
48#include <thread>
49
50#include <pcl/visualization/cloud_viewer.h>
51#include <pcl/visualization/pcl_visualizer.h>
52
53#include <visp3/core/vpImage.h>
54#include <visp3/core/vpImageConvert.h>
55#include <visp3/gui/vpDisplayGDI.h>
56#include <visp3/gui/vpDisplayX.h>
57#include <visp3/sensor/vpRealSense2.h>
58
59namespace
60{
61// Global variables
62pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
63pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud_color(new pcl::PointCloud<pcl::PointXYZRGB>());
64bool cancelled = false, update_pointcloud = false;
65
66class ViewerWorker
67{
68public:
69 explicit ViewerWorker(bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) {}
70
71 void run()
72 {
73 std::string date = vpTime::getDateTime();
74 pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("3D Viewer " + date));
75 pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(pointcloud_color);
76 pcl::PointCloud<pcl::PointXYZ>::Ptr local_pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
77 pcl::PointCloud<pcl::PointXYZRGB>::Ptr local_pointcloud_color(new pcl::PointCloud<pcl::PointXYZRGB>());
78
79 viewer->setBackgroundColor(0, 0, 0);
80 viewer->initCameraParameters();
81 viewer->setPosition(640 + 80, 480 + 80);
82 viewer->setCameraPosition(0, 0, -0.25, 0, -1, 0);
83 viewer->setSize(640, 480);
84
85 bool init = true;
86 bool local_update = false, local_cancelled = false;
87 while (!local_cancelled) {
88 {
89 std::unique_lock<std::mutex> lock(m_mutex, std::try_to_lock);
90
91 if (lock.owns_lock()) {
92 local_update = update_pointcloud;
93 update_pointcloud = false;
94 local_cancelled = cancelled;
95
96 if (local_update) {
97 if (m_colorMode) {
98 local_pointcloud_color = pointcloud_color->makeShared();
99 } else {
100 local_pointcloud = pointcloud->makeShared();
101 }
102 }
103 }
104 }
105
106 if (local_update && !local_cancelled) {
107 local_update = false;
108
109 if (init) {
110 if (m_colorMode) {
111 viewer->addPointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb, "RGB sample cloud");
112 viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1,
113 "RGB sample cloud");
114 } else {
115 viewer->addPointCloud<pcl::PointXYZ>(local_pointcloud, "sample cloud");
116 viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud");
117 }
118 init = false;
119 } else {
120 if (m_colorMode) {
121 viewer->updatePointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb, "RGB sample cloud");
122 } else {
123 viewer->updatePointCloud<pcl::PointXYZ>(local_pointcloud, "sample cloud");
124 }
125 }
126 }
127
128 viewer->spinOnce(5);
129 }
130
131 std::cout << "End of point cloud display thread" << std::endl;
132 }
133
134private:
135 bool m_colorMode;
136 std::mutex &m_mutex;
137};
138} // namespace
139
140int main(int argc, char *argv[])
141{
142 bool pcl_color = false;
143 bool show_infrared2 = false;
144 for (int i = 1; i < argc; i++) {
145 if (std::string(argv[i]) == "--pcl_color") {
146 pcl_color = true;
147 } else if (std::string(argv[i]) == "--show_infrared2") {
148 show_infrared2 = true;
149 }
150 }
151
152 const int width = 640, height = 480, fps = 30;
153 vpRealSense2 rs;
154 rs2::config config;
155 config.enable_stream(RS2_STREAM_COLOR, width, height, RS2_FORMAT_RGBA8, fps);
156 config.enable_stream(RS2_STREAM_DEPTH, width, height, RS2_FORMAT_Z16, fps);
157 config.enable_stream(RS2_STREAM_INFRARED, 1, width, height, RS2_FORMAT_Y8, fps);
158 config.enable_stream(RS2_STREAM_INFRARED, 2, width, height, RS2_FORMAT_Y8, fps);
159 rs.open(config);
160
161 vpImage<vpRGBa> color(static_cast<unsigned int>(height), static_cast<unsigned int>(width));
162 vpImage<vpRGBa> depth_color(static_cast<unsigned int>(height), static_cast<unsigned int>(width));
163 vpImage<uint16_t> depth_raw(static_cast<unsigned int>(height), static_cast<unsigned int>(width));
164 vpImage<unsigned char> infrared1(static_cast<unsigned int>(height), static_cast<unsigned int>(width));
165 vpImage<unsigned char> infrared2(static_cast<unsigned int>(height), static_cast<unsigned int>(width));
166
167#ifdef VISP_HAVE_X11
168 vpDisplayX d1, d2, d3, d4;
169#else
170 vpDisplayGDI d1, d2, d3, d4;
171#endif
172 d1.init(color, 0, 0, "Color");
173 d2.init(depth_color, color.getWidth(), 0, "Depth");
174 d3.init(infrared1, 0, color.getHeight() + 100, "Infrared left");
175 if (show_infrared2) {
176 d4.init(infrared2, color.getWidth(), color.getHeight() + 100, "Infrared right");
177 }
178
179 std::mutex mutex;
180 ViewerWorker viewer_pointcloud(pcl_color, mutex);
181 std::thread viewer_thread(&ViewerWorker::run, &viewer_pointcloud);
182
183 std::vector<double> time_vector;
184 vpChrono chrono;
185 while (true) {
186 chrono.start();
187 {
188 std::lock_guard<std::mutex> lock(mutex);
189
190 if (pcl_color) {
191 rs.acquire(reinterpret_cast<unsigned char *>(color.bitmap), reinterpret_cast<unsigned char *>(depth_raw.bitmap),
192 NULL, pointcloud_color, reinterpret_cast<unsigned char *>(infrared1.bitmap),
193 show_infrared2 ? reinterpret_cast<unsigned char *>(infrared2.bitmap) : NULL, NULL);
194 } else {
195 rs.acquire(reinterpret_cast<unsigned char *>(color.bitmap), reinterpret_cast<unsigned char *>(depth_raw.bitmap),
196 NULL, pointcloud, reinterpret_cast<unsigned char *>(infrared1.bitmap),
197 show_infrared2 ? reinterpret_cast<unsigned char *>(infrared2.bitmap) : NULL, NULL);
198 }
199
200 update_pointcloud = true;
201 }
202
203 vpImageConvert::createDepthHistogram(depth_raw, depth_color);
204
205 vpDisplay::display(color);
206 vpDisplay::display(depth_color);
207 vpDisplay::display(infrared1);
208 vpDisplay::display(infrared2);
209
210 vpDisplay::displayText(color, 20, 20, "Click to quit.", vpColor::red);
211 vpDisplay::displayText(depth_color, 20, 20, "Click to quit.", vpColor::red);
212 vpDisplay::displayText(infrared1, 20, 20, "Click to quit.", vpColor::red);
213 vpDisplay::displayText(infrared2, 20, 20, "Click to quit.", vpColor::red);
214
215 vpDisplay::flush(color);
216 vpDisplay::flush(depth_color);
217 vpDisplay::flush(infrared1);
218 vpDisplay::flush(infrared2);
219
220 chrono.stop();
221 time_vector.push_back(chrono.getDurationMs());
222 if (vpDisplay::getClick(color, false) || vpDisplay::getClick(depth_color, false) ||
223 vpDisplay::getClick(infrared1, false) || vpDisplay::getClick(infrared2, false)) {
224 break;
225 }
226 }
227
228 {
229 std::lock_guard<std::mutex> lock(mutex);
230 cancelled = true;
231 }
232 viewer_thread.join();
233
234 std::cout << "Acquisition - Mean time: " << vpMath::getMean(time_vector)
235 << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl;
236
237 return EXIT_SUCCESS;
238}
239
240#else
241int main()
242{
243#if !defined(VISP_HAVE_REALSENSE2)
244 std::cout << "Install librealsense2 to make this test work." << std::endl;
245#endif
246#if !(VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
247 std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11) "
248 "to make this test work"
249 << std::endl;
250#endif
251#if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI)
252 std::cout << "X11 or GDI are needed." << std::endl;
253#endif
254#if !defined(VISP_HAVE_PCL)
255 std::cout << "Install PCL to make this test work." << std::endl;
256#endif
257 return EXIT_SUCCESS;
258}
259#endif
void start(bool reset=true)
Definition vpTime.cpp:397
void stop()
Definition vpTime.cpp:412
double getDurationMs()
Definition vpTime.cpp:386
static const vpColor red
Definition vpColor.h:211
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)
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)
Definition of the vpImage class member functions.
Definition vpImage.h:135
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 acquire(vpImage< unsigned char > &grey, double *ts=NULL)
bool open(const rs2::config &cfg=rs2::config())
VISP_EXPORT std::string getDateTime(const std::string &format="%Y/%m/%d %H:%M:%S")