Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
tutorial-hsv-segmentation-pcl-viewer.cpp
1
2
3#include <iostream>
4#include <visp3/core/vpConfig.h>
5
6#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_VISUALIZATION) && defined(VISP_HAVE_THREADS) && defined(VISP_HAVE_DISPLAY)
7#include <visp3/core/vpCameraParameters.h>
8#include <visp3/core/vpHSV.h>
9#include <visp3/core/vpImageConvert.h>
10#include <visp3/core/vpImageTools.h>
11#include <visp3/core/vpPixelMeterConversion.h>
12#include <visp3/core/vpColorDepthConversion.h>
13#include <visp3/core/vpIoTools.h>
14#include <visp3/gui/vpDisplayFactory.h>
16#include <visp3/gui/vpDisplayPCL.h>
18#include <visp3/sensor/vpRealSense2.h>
19
20#ifdef ENABLE_VISP_NAMESPACE
21using namespace VISP_NAMESPACE_NAME;
22#endif
23
25
29typedef enum DisplayMode
30{
31 MONOTHREAD = 0,
32 THREADED = 1,
33 MODE_COUNT = 2
34} DisplayMode;
35
42std::string displayModeToString(const DisplayMode &mode)
43{
44 switch (mode) {
45 case MONOTHREAD:
46 return "monothread";
47 case THREADED:
48 return "threaded";
49 default:
50 break;
51 }
52 return "unknown";
53}
54
62DisplayMode displayModeFromString(const std::string &name)
63{
64 DisplayMode res = DisplayMode::MODE_COUNT;
65 bool wasFound = false;
66 std::string lowerCaseName = vpIoTools::toLowerCase(name);
67 unsigned int i = 0;
68 while ((i < DisplayMode::MODE_COUNT) && (!wasFound)) {
69 DisplayMode candidate = (DisplayMode)i;
70 if (lowerCaseName == displayModeToString(candidate)) {
71 res = candidate;
72 wasFound = true;
73 }
74 ++i;
75 }
76 return res;
77}
78
87std::string getAvailableDisplayMode(const std::string &prefix = "< ", const std::string &sep = " , ", const std::string &suffix = " >")
88{
89 std::string modes(prefix);
90 for (unsigned int i = 0; i < DisplayMode::MODE_COUNT - 1; ++i) {
91 DisplayMode candidate = (DisplayMode)i;
92 modes += displayModeToString(candidate) + sep;
93 }
94 DisplayMode candidate = (DisplayMode)(DisplayMode::MODE_COUNT - 1);
95 modes += displayModeToString(candidate) + suffix;
96 return modes;
97}
99
100int main(int argc, const char *argv[])
101{
102 std::string opt_hsv_filename = "calib/hsv-thresholds.yml";
103 bool opt_pcl_textured = false;
104 bool opt_verbose = false;
105 int opt_width = 848;
106 int opt_height = 480;
107 int opt_fps = 60;
108 DisplayMode opt_mode = DisplayMode::MONOTHREAD;
109
110 int i = 1;
111 while (i < argc) {
112 if (((std::string(argv[i]) == "--width") || (std::string(argv[i]) == "-v")) && ((i+1) < argc)) {
113 opt_width = std::atoi(argv[++i]);
114 }
115 else if (((std::string(argv[i]) == "--height") || (std::string(argv[i]) == "-h")) && ((i+1) < argc)) {
116 opt_height = std::atoi(argv[++i]);
117 }
118 else if (std::string(argv[i]) == "--display-mode" && i + 1 < argc) {
119 opt_mode = displayModeFromString(std::string(argv[i + 1]));
120 ++i;
121 }
122 else if ((std::string(argv[i]) == "--fps") && ((i+1) < argc)) {
123 opt_fps = std::atoi(argv[++i]);
124 }
125 else if (std::string(argv[i]) == "--texture") {
126 opt_pcl_textured = true;
127 }
128 else if ((std::string(argv[i]) == "--hsv-thresholds") && ((i+1) < argc)) {
129 opt_hsv_filename = std::string(argv[++i]);
130 }
131 else if ((std::string(argv[i]) == "--verbose") || (std::string(argv[i]) == "-v")) {
132 opt_verbose = true;
133 }
134 else if ((std::string(argv[i]) == "--help") || (std::string(argv[i]) == "-h")) {
135 std::cout << "\nSYNOPSIS " << std::endl
136 << argv[0]
137 << " [--width,-w <image width>]"
138 << " [--height,-h <image height>]"
139 << " [--fps <framerate>]"
140 << " [--texture]"
141 << " [--hsv-thresholds <filename.yml>]"
142 << " [--verbose,-v]"
143 << " [--help,-h]"
144 << std::endl;
145 std::cout << "\nOPTIONS " << std::endl
146 << " --width,-w <image width>" << std::endl
147 << " Realsense camera image width." << std::endl
148 << " Default: " << opt_width << std::endl
149 << std::endl
150 << " --height,-h <image height>" << std::endl
151 << " Realsense camera image height." << std::endl
152 << " Default: " << opt_height << std::endl
153 << std::endl
154 << " --fps <framerate>" << std::endl
155 << " Realsense camera framerate." << std::endl
156 << " Default: " << opt_fps << std::endl
157 << std::endl
158 << " --texture" << std::endl
159 << " Enable textured point cloud adding RGB information to the 3D point." << std::endl
160 << std::endl
161 << " --hsv-thresholds <filename.yaml>" << std::endl
162 << " Path to a yaml filename that contains H <min,max>, S <min,max>, V <min,max> threshold values." << std::endl
163 << " An Example of such a file could be:" << std::endl
164 << " rows: 6" << std::endl
165 << " cols: 1" << std::endl
166 << " data:" << std::endl
167 << " - [0]" << std::endl
168 << " - [42]" << std::endl
169 << " - [177]" << std::endl
170 << " - [237]" << std::endl
171 << " - [148]" << std::endl
172 << " - [208]" << std::endl
173 << std::endl
174 << " --verbose, -v" << std::endl
175 << " Enable verbose mode." << std::endl
176 << std::endl
177 << " --help, -h" << std::endl
178 << " Display this helper message." << std::endl
179 << std::endl;
180 return EXIT_SUCCESS;
181 }
182 ++i;
183 }
184
185 vpColVector hsv_values;
186 if (vpColVector::loadYAML(opt_hsv_filename, hsv_values)) {
187 std::cout << "Load HSV threshold values from " << opt_hsv_filename << std::endl;
188 std::cout << "HSV low/high values: " << hsv_values.t() << std::endl;
189 }
190 else {
191 std::cout << "Warning: unable to load HSV thresholds values from " << opt_hsv_filename << std::endl;
192 return EXIT_FAILURE;
193 }
194
195 vpRealSense2 rs;
196 rs2::config config;
197 config.enable_stream(RS2_STREAM_COLOR, opt_width, opt_height, RS2_FORMAT_RGBA8, opt_fps);
198 config.enable_stream(RS2_STREAM_DEPTH, opt_width, opt_height, RS2_FORMAT_Z16, opt_fps);
199 config.disable_stream(RS2_STREAM_INFRARED, 1);
200 config.disable_stream(RS2_STREAM_INFRARED, 2);
201 rs2::align align_to(RS2_STREAM_COLOR);
202
203 rs.open(config);
204
205 float depth_scale = rs.getDepthScale();
208
209 vpImage<vpRGBa> I(opt_height, opt_width);
210 vpImage<unsigned char> mask(opt_height, opt_width);
211 vpImage<uint16_t> depth_raw(opt_height, opt_width);
212 vpImage<vpRGBa> I_segmented(opt_height, opt_width);
213
214#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
216
217 std::shared_ptr<vpDisplay> d_I = vpDisplayFactory::createDisplay(I, 0, 0, "Current frame");
218 std::shared_ptr<vpDisplay> d_I_segmented = vpDisplayFactory::createDisplay(I_segmented, I.getWidth()+75, 0, "HSV segmented frame");
219#else
220 vpImage<unsigned char> H(opt_height, opt_width);
221 vpImage<unsigned char> S(opt_height, opt_width);
222 vpImage<unsigned char> V(opt_height, opt_width);
223
224 vpDisplay *d_I = vpDisplayFactory::allocateDisplay(I, 0, 0, "Current frame");
225 vpDisplay *d_I_segmented = vpDisplayFactory::allocateDisplay(I_segmented, I.getWidth()+75, 0, "HSV segmented frame");
226#endif
227
228 bool quit = false;
229 double loop_time = 0., total_loop_time = 0.;
230 long nb_iter = 0;
231 float Z_min = 0.1;
232 float Z_max = 2.5;
233
235 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud_color(new pcl::PointCloud<pcl::PointXYZRGB>());
236 pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
238
240 std::mutex pointcloud_mutex;
241 vpDisplayPCL pcl_viewer(opt_width, opt_height);
242 if (opt_mode == DisplayMode::THREADED) {
243 if (opt_pcl_textured) {
244 pcl_viewer.startThread(std::ref(pointcloud_mutex), pointcloud_color);
245 }
246 else {
247 pcl_viewer.startThread(std::ref(pointcloud_mutex), pointcloud);
248 }
249 }
250 else {
251 if (opt_pcl_textured) {
252 pcl_viewer.addPointCloud(std::ref(pointcloud_mutex), pointcloud_color);
253 }
254 else {
255 pcl_viewer.addPointCloud(std::ref(pointcloud_mutex), pointcloud);
256 }
257 }
259
260 while (!quit) {
261 double t = vpTime::measureTimeMs();
262 rs.acquire((unsigned char *)I.bitmap, (unsigned char *)(depth_raw.bitmap), NULL, NULL, &align_to);
263
264#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
266 vpImageTools::inRange(Ihsv, hsv_values, mask);
267#else
268 vpImageConvert::RGBaToHSV(reinterpret_cast<unsigned char *>(I.bitmap),
269 reinterpret_cast<unsigned char *>(H.bitmap),
270 reinterpret_cast<unsigned char *>(S.bitmap),
271 reinterpret_cast<unsigned char *>(V.bitmap), I.getSize());
272
273 vpImageTools::inRange(reinterpret_cast<unsigned char *>(H.bitmap),
274 reinterpret_cast<unsigned char *>(S.bitmap),
275 reinterpret_cast<unsigned char *>(V.bitmap),
276 hsv_values,
277 reinterpret_cast<unsigned char *>(mask.bitmap),
278 mask.getSize());
279#endif
280
281 vpImageTools::inMask(I, mask, I_segmented);
282
284 int pcl_size;
285 if (opt_pcl_textured) {
286 pcl_size = vpImageConvert::depthToPointCloud(I, depth_raw, depth_scale, cam_depth, pointcloud_color, &pointcloud_mutex, &mask, Z_min, Z_max);
287 }
288 else {
289 pcl_size = vpImageConvert::depthToPointCloud(depth_raw, depth_scale, cam_depth, pointcloud, &pointcloud_mutex, &mask, Z_min, Z_max);
290 }
291 if (opt_verbose) {
292 std::cout << "Segmented point cloud size: " << pcl_size << std::endl;
293 }
295
297 vpDisplay::display(I_segmented);
298 vpDisplay::displayText(I, 20, 20, "Click to quit...", vpColor::red);
299
300 if (vpDisplay::getClick(I, false)) {
301 quit = true;
302 }
303
305 if (opt_mode == DisplayMode::MONOTHREAD) {
306 const bool blocking_mode = false;
307 pcl_viewer.display(blocking_mode);
308 }
310
312 vpDisplay::flush(I_segmented);
313 nb_iter++;
314 loop_time = vpTime::measureTimeMs() - t;
315 total_loop_time += loop_time;
316 }
317
318 std::cout << "Mean loop time: " << total_loop_time / nb_iter << std::endl;
319
320#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
321 if (d_I != nullptr) {
322 delete d_I;
323 }
324
325 if (d_I_segmented != nullptr) {
326 delete d_I_segmented;
327 }
328#endif
329 return EXIT_SUCCESS;
330}
331#else
332int main()
333{
334#if !defined(VISP_HAVE_REALSENSE2)
335 std::cout << "This tutorial needs librealsense as 3rd party." << std::endl;
336#endif
337#if !defined(VISP_HAVE_PCL)
338 std::cout << "This tutorial needs pcl library as 3rd party." << std::endl;
339#endif
340#if !defined(VISP_HAVE_PCL_VISUALIZATION)
341 std::cout << "This tutorial needs pcl visualization module." << std::endl;
342#endif
343#if !defined(VISP_HAVE_X11)
344 std::cout << "This tutorial needs X11 3rd party enabled." << std::endl;
345#endif
346 std::cout << "Install missing 3rd party, configure and rebuild ViSP." << std::endl;
347 return EXIT_SUCCESS;
348}
349#endif
static bool loadYAML(const std::string &filename, vpArray2D< double > &A, char *header=nullptr)
Definition vpArray2D.h:874
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
Implementation of column vector and the associated operations.
vpRowVector t() const
static const vpColor red
Definition vpColor.h:198
Class that defines generic functionalities for display.
Definition vpDisplay.h:171
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 RGBaToHSV(const unsigned char *rgba, double *hue, double *saturation, double *value, unsigned int size)
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
static int inMask(const vpImage< vpRGBa > &I, const vpImage< bool > &mask, vpImage< vpRGBa > &I_mask)
static int inRange(const unsigned char *hue, const unsigned char *saturation, const unsigned char *value, const vpColVector &hsv_range, unsigned char *mask, unsigned int size)
Definition of the vpImage class member functions.
Definition vpImage.h:131
static std::string toLowerCase(const std::string &input)
Return a lower-case version of the string input . Numbers and special characters stay the same.
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()
static std::enable_if< std::is_same< MaskType, unsignedchar >::value||std::is_same< MaskType, bool >::value, int >::type depthToPointCloud(const vpImage< uint16_t > &depth_raw, float depth_scale, const vpCameraParameters &cam_depth, pcl::PointCloud< pcl::PointXYZ >::Ptr pointcloud, std::mutex *pointcloud_mutex=nullptr, const vpImage< MaskType > *depth_mask=nullptr, float Z_min=0.2, float Z_max=2.5)
Convert a raw depth image into a pcl::PointCloud that has no texture.
std::shared_ptr< vpDisplay > createDisplay()
Return a smart pointer vpDisplay specialization if a GUI library is available or nullptr otherwise.
vpDisplay * allocateDisplay()
Return a newly allocated vpDisplay specialization if a GUI library is available or nullptr otherwise.
VISP_EXPORT double measureTimeMs()