Visual Servoing Platform  version 3.6.1 under development (2024-11-15)
tutorial-hsv-segmentation-pcl.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_COMMON) && 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>
13 #include <visp3/sensor/vpRealSense2.h>
14 
15 int main(int argc, const char *argv[])
16 {
17 #ifdef ENABLE_VISP_NAMESPACE
18  using namespace VISP_NAMESPACE_NAME;
19 #endif
20 
21  std::string opt_hsv_filename = "calib/hsv-thresholds.yml";
22 
23  for (int i = 1; i < argc; i++) {
24  if ((std::string(argv[i]) == "--hsv-thresholds") && ((i+1) < argc)) {
25  opt_hsv_filename = std::string(argv[++i]);
26  }
27  else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
28  std::cout << "\nSYNOPSIS " << std::endl
29  << argv[0]
30  << " [--hsv-thresholds <filename.yml>]"
31  << " [--help,-h]"
32  << std::endl;
33  std::cout << "\nOPTIONS " << std::endl
34  << " --hsv-thresholds <filename.yaml>" << std::endl
35  << " Path to a yaml filename that contains H <min,max>, S <min,max>, V <min,max> threshold values." << std::endl
36  << " An Example of such a file could be:" << std::endl
37  << " rows: 6" << std::endl
38  << " cols: 1" << std::endl
39  << " data:" << std::endl
40  << " - [0]" << std::endl
41  << " - [42]" << std::endl
42  << " - [177]" << std::endl
43  << " - [237]" << std::endl
44  << " - [148]" << std::endl
45  << " - [208]" << std::endl
46  << std::endl
47  << " --help, -h" << std::endl
48  << " Display this helper message." << std::endl
49  << std::endl;
50  return EXIT_SUCCESS;
51  }
52  }
53 
54  vpColVector hsv_values;
55  if (vpColVector::loadYAML(opt_hsv_filename, hsv_values)) {
56  std::cout << "Load HSV threshold values from " << opt_hsv_filename << std::endl;
57  std::cout << "HSV low/high values: " << hsv_values.t() << std::endl;
58  }
59  else {
60  std::cout << "Warning: unable to load HSV thresholds values from " << opt_hsv_filename << std::endl;
61  return EXIT_FAILURE;
62  }
63 
65  int width = 848, height = 480, fps = 60;
66  vpRealSense2 rs;
67  rs2::config config;
68  config.enable_stream(RS2_STREAM_COLOR, width, height, RS2_FORMAT_RGBA8, fps);
69  config.enable_stream(RS2_STREAM_DEPTH, width, height, RS2_FORMAT_Z16, fps);
70  config.disable_stream(RS2_STREAM_INFRARED, 1);
71  config.disable_stream(RS2_STREAM_INFRARED, 2);
72  rs2::align align_to(RS2_STREAM_COLOR);
74 
75  rs.open(config);
76 
78  float depth_scale = rs.getDepthScale();
79  vpCameraParameters cam_depth = rs.getCameraParameters(RS2_STREAM_DEPTH,
82 
83  vpImage<vpRGBa> I(height, width);
84  vpImage<unsigned char> H(height, width);
85  vpImage<unsigned char> S(height, width);
86  vpImage<unsigned char> V(height, width);
87  vpImage<unsigned char> mask(height, width, 0);
88  vpImage<uint16_t> depth_raw(height, width);
89  vpImage<vpRGBa> I_segmented(height, width);
90 
91  vpDisplayX d_I(I, 0, 0, "Current frame");
92  vpDisplayX d_I_segmented(I_segmented, I.getWidth()+75, 0, "HSV segmented frame");
93 
94  bool quit = false;
95  double loop_time = 0., total_loop_time = 0.;
96  long nb_iter = 0;
97 
99  float Z_min = 0.1;
100  float Z_max = 2.5;
101  pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
103 
104  while (!quit) {
105  double t = vpTime::measureTimeMs();
107  rs.acquire((unsigned char *)I.bitmap, (unsigned char *)(depth_raw.bitmap), NULL, NULL, &align_to);
109 
111  vpImageConvert::RGBaToHSV(reinterpret_cast<unsigned char *>(I.bitmap),
112  reinterpret_cast<unsigned char *>(H.bitmap),
113  reinterpret_cast<unsigned char *>(S.bitmap),
114  reinterpret_cast<unsigned char *>(V.bitmap), I.getSize());
116 
118  vpImageTools::inRange(reinterpret_cast<unsigned char *>(H.bitmap),
119  reinterpret_cast<unsigned char *>(S.bitmap),
120  reinterpret_cast<unsigned char *>(V.bitmap),
121  hsv_values,
122  reinterpret_cast<unsigned char *>(mask.bitmap),
123  mask.getSize());
125 
126  vpImageTools::inMask(I, mask, I_segmented);
127 
129  vpImageConvert::depthToPointCloud(depth_raw, depth_scale, cam_depth, pointcloud, nullptr, &mask, Z_min, Z_max);
131 
133  int pcl_size = pointcloud->size();
135 
136  std::cout << "Segmented point cloud size: " << pcl_size << std::endl;
137 
139  vpDisplay::display(I_segmented);
140  vpDisplay::displayText(I, 20, 20, "Click to quit...", vpColor::red);
141 
142  if (vpDisplay::getClick(I, false)) {
143  quit = true;
144  }
145 
146  vpDisplay::flush(I);
147  vpDisplay::flush(I_segmented);
148  nb_iter++;
149  loop_time = vpTime::measureTimeMs() - t;
150  total_loop_time += loop_time;
151  }
152 
153  std::cout << "Mean loop time: " << total_loop_time / nb_iter << std::endl;
154  return EXIT_SUCCESS;
155 }
156 #else
157 int main()
158 {
159 #if !defined(VISP_HAVE_REALSENSE2)
160  std::cout << "This tutorial needs librealsense as 3rd party." << std::endl;
161 #endif
162 #if !defined(VISP_HAVE_PCL)
163  std::cout << "This tutorial needs pcl library as 3rd party." << std::endl;
164 #endif
165 #if !defined(VISP_HAVE_X11)
166  std::cout << "This tutorial needs X11 3rd party enabled." << std::endl;
167 #endif
168  std::cout << "Install missing 3rd party, configure and rebuild ViSP." << std::endl;
169  return EXIT_SUCCESS;
170 }
171 #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()