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