Visual Servoing Platform  version 3.6.1 under development (2024-11-15)
tutorial-hsv-segmentation-pcl-viewer.cpp
1 
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_X11)
7 #include <visp3/core/vpCameraParameters.h>
8 #include <visp3/core/vpImageConvert.h>
9 #include <visp3/core/vpImageTools.h>
10 #include <visp3/core/vpPixelMeterConversion.h>
11 #include <visp3/core/vpColorDepthConversion.h>
12 #include <visp3/gui/vpDisplayX.h>
14 #include <visp3/gui/vpDisplayPCL.h>
16 #include <visp3/sensor/vpRealSense2.h>
17 
18 int main(int argc, const char *argv[])
19 {
20 #ifdef ENABLE_VISP_NAMESPACE
21  using namespace VISP_NAMESPACE_NAME;
22 #endif
23 
24  std::string opt_hsv_filename = "calib/hsv-thresholds.yml";
25  bool opt_pcl_textured = false;
26  bool opt_verbose = false;
27  int opt_width = 848;
28  int opt_height = 480;
29  int opt_fps = 60;
30 
31  for (int i = 1; i < argc; i++) {
32  if (((std::string(argv[i]) == "--width") || (std::string(argv[i]) == "-v")) && ((i+1) < argc)) {
33  opt_width = std::atoi(argv[++i]);
34  }
35  else if (((std::string(argv[i]) == "--height") || (std::string(argv[i]) == "-h")) && ((i+1) < argc)) {
36  opt_height = std::atoi(argv[++i]);
37  }
38  else if ((std::string(argv[i]) == "--fps") && ((i+1) < argc)) {
39  opt_fps = std::atoi(argv[++i]);
40  }
41  else if (std::string(argv[i]) == "--texture") {
42  opt_pcl_textured = true;
43  }
44  else if ((std::string(argv[i]) == "--hsv-thresholds") && ((i+1) < argc)) {
45  opt_hsv_filename = std::string(argv[++i]);
46  }
47  else if ((std::string(argv[i]) == "--verbose") || (std::string(argv[i]) == "-v")) {
48  opt_verbose = true;
49  }
50  else if ((std::string(argv[i]) == "--help") || (std::string(argv[i]) == "-h")) {
51  std::cout << "\nSYNOPSIS " << std::endl
52  << argv[0]
53  << " [--width,-w <image width>]"
54  << " [--height,-h <image height>]"
55  << " [--fps <framerate>]"
56  << " [--texture]"
57  << " [--hsv-thresholds <filename.yml>]"
58  << " [--verbose,-v]"
59  << " [--help,-h]"
60  << std::endl;
61  std::cout << "\nOPTIONS " << std::endl
62  << " --width,-w <image width>" << std::endl
63  << " Realsense camera image width." << std::endl
64  << " Default: " << opt_width << std::endl
65  << std::endl
66  << " --height,-h <image height>" << std::endl
67  << " Realsense camera image height." << std::endl
68  << " Default: " << opt_height << std::endl
69  << std::endl
70  << " --fps <framerate>" << std::endl
71  << " Realsense camera framerate." << std::endl
72  << " Default: " << opt_fps << std::endl
73  << std::endl
74  << " --texture" << std::endl
75  << " Enable textured point cloud adding RGB information to the 3D point." << std::endl
76  << std::endl
77  << " --hsv-thresholds <filename.yaml>" << std::endl
78  << " Path to a yaml filename that contains H <min,max>, S <min,max>, V <min,max> threshold values." << std::endl
79  << " An Example of such a file could be:" << std::endl
80  << " rows: 6" << std::endl
81  << " cols: 1" << std::endl
82  << " data:" << std::endl
83  << " - [0]" << std::endl
84  << " - [42]" << std::endl
85  << " - [177]" << std::endl
86  << " - [237]" << std::endl
87  << " - [148]" << std::endl
88  << " - [208]" << std::endl
89  << std::endl
90  << " --verbose, -v" << std::endl
91  << " Enable verbose mode." << std::endl
92  << std::endl
93  << " --help, -h" << std::endl
94  << " Display this helper message." << std::endl
95  << std::endl;
96  return EXIT_SUCCESS;
97  }
98  }
99 
100  vpColVector hsv_values;
101  if (vpColVector::loadYAML(opt_hsv_filename, hsv_values)) {
102  std::cout << "Load HSV threshold values from " << opt_hsv_filename << std::endl;
103  std::cout << "HSV low/high values: " << hsv_values.t() << std::endl;
104  }
105  else {
106  std::cout << "Warning: unable to load HSV thresholds values from " << opt_hsv_filename << std::endl;
107  return EXIT_FAILURE;
108  }
109 
110  vpRealSense2 rs;
111  rs2::config config;
112  config.enable_stream(RS2_STREAM_COLOR, opt_width, opt_height, RS2_FORMAT_RGBA8, opt_fps);
113  config.enable_stream(RS2_STREAM_DEPTH, opt_width, opt_height, RS2_FORMAT_Z16, opt_fps);
114  config.disable_stream(RS2_STREAM_INFRARED, 1);
115  config.disable_stream(RS2_STREAM_INFRARED, 2);
116  rs2::align align_to(RS2_STREAM_COLOR);
117 
118  rs.open(config);
119 
120  float depth_scale = rs.getDepthScale();
121  vpCameraParameters cam_depth = rs.getCameraParameters(RS2_STREAM_DEPTH,
123 
124  vpImage<vpRGBa> I(opt_height, opt_width);
125  vpImage<unsigned char> H(opt_height, opt_width);
126  vpImage<unsigned char> S(opt_height, opt_width);
127  vpImage<unsigned char> V(opt_height, opt_width);
128  vpImage<unsigned char> mask(opt_height, opt_width);
129  vpImage<uint16_t> depth_raw(opt_height, opt_width);
130  vpImage<vpRGBa> I_segmented(opt_height, opt_width);
131 
132  vpDisplayX d_I(I, 0, 0, "Current frame");
133  vpDisplayX d_I_segmented(I_segmented, I.getWidth()+75, 0, "HSV segmented frame");
134 
135  bool quit = false;
136  double loop_time = 0., total_loop_time = 0.;
137  long nb_iter = 0;
138  float Z_min = 0.1;
139  float Z_max = 2.5;
140 
142  pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud_color(new pcl::PointCloud<pcl::PointXYZRGB>());
143  pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
145 
147  std::mutex pointcloud_mutex;
148  vpDisplayPCL pcl_viewer(opt_width, opt_height);
149  if (opt_pcl_textured) {
150  pcl_viewer.startThread(std::ref(pointcloud_mutex), pointcloud_color);
151  }
152  else {
153  pcl_viewer.startThread(std::ref(pointcloud_mutex), pointcloud);
154  }
156 
157  while (!quit) {
158  double t = vpTime::measureTimeMs();
159  rs.acquire((unsigned char *)I.bitmap, (unsigned char *)(depth_raw.bitmap), NULL, NULL, &align_to);
160 
161  vpImageConvert::RGBaToHSV(reinterpret_cast<unsigned char *>(I.bitmap),
162  reinterpret_cast<unsigned char *>(H.bitmap),
163  reinterpret_cast<unsigned char *>(S.bitmap),
164  reinterpret_cast<unsigned char *>(V.bitmap), I.getSize());
165 
166  vpImageTools::inRange(reinterpret_cast<unsigned char *>(H.bitmap),
167  reinterpret_cast<unsigned char *>(S.bitmap),
168  reinterpret_cast<unsigned char *>(V.bitmap),
169  hsv_values,
170  reinterpret_cast<unsigned char *>(mask.bitmap),
171  mask.getSize());
172 
173  vpImageTools::inMask(I, mask, I_segmented);
174 
176  int pcl_size;
177  if (opt_pcl_textured) {
178  pcl_size = vpImageConvert::depthToPointCloud(I, depth_raw, depth_scale, cam_depth, pointcloud_color, &pointcloud_mutex, &mask, Z_min, Z_max);
179  }
180  else {
181  pcl_size = vpImageConvert::depthToPointCloud(depth_raw, depth_scale, cam_depth, pointcloud, &pointcloud_mutex, &mask, Z_min, Z_max);
182  }
183  if (opt_verbose) {
184  std::cout << "Segmented point cloud size: " << pcl_size << std::endl;
185  }
187 
189  vpDisplay::display(I_segmented);
190  vpDisplay::displayText(I, 20, 20, "Click to quit...", vpColor::red);
191 
192  if (vpDisplay::getClick(I, false)) {
193  quit = true;
194  }
195 
196  vpDisplay::flush(I);
197  vpDisplay::flush(I_segmented);
198  nb_iter++;
199  loop_time = vpTime::measureTimeMs() - t;
200  total_loop_time += loop_time;
201  }
202 
203  std::cout << "Mean loop time: " << total_loop_time / nb_iter << std::endl;
204  return EXIT_SUCCESS;
205 }
206 #else
207 int main()
208 {
209 #if !defined(VISP_HAVE_REALSENSE2)
210  std::cout << "This tutorial needs librealsense as 3rd party." << std::endl;
211 #endif
212 #if !defined(VISP_HAVE_PCL)
213  std::cout << "This tutorial needs pcl library as 3rd party." << std::endl;
214 #endif
215 #if !defined(VISP_HAVE_PCL_VISUALIZATION)
216  std::cout << "This tutorial needs pcl visualization module." << std::endl;
217 #endif
218 #if !defined(VISP_HAVE_X11)
219  std::cout << "This tutorial needs X11 3rd party enabled." << std::endl;
220 #endif
221  std::cout << "Install missing 3rd party, configure and rebuild ViSP." << std::endl;
222  return EXIT_SUCCESS;
223 }
224 #endif
static bool loadYAML(const std::string &filename, vpArray2D< double > &A, char *header=nullptr)
Definition: vpArray2D.h:783
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
vpRowVector t() const
static const vpColor red
Definition: vpColor.h:217
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 int 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< unsigned char > *mask=nullptr, float Z_min=0.2, float Z_max=2.5)
static void RGBaToHSV(const unsigned char *rgba, double *hue, double *saturation, double *value, unsigned int size)
static int inMask(const vpImage< unsigned char > &I, const vpImage< unsigned char > &mask, vpImage< unsigned char > &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)
unsigned int getWidth() const
Definition: vpImage.h:242
unsigned int getSize() const
Definition: vpImage.h:221
Type * bitmap
points toward the bitmap
Definition: vpImage.h:135
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()
VISP_EXPORT double measureTimeMs()