4#include <visp3/core/vpConfig.h>
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>
20#ifdef ENABLE_VISP_NAMESPACE
29typedef enum DisplayMode
42std::string displayModeToString(
const DisplayMode &mode)
62DisplayMode displayModeFromString(
const std::string &name)
64 DisplayMode res = DisplayMode::MODE_COUNT;
65 bool wasFound =
false;
68 while ((i < DisplayMode::MODE_COUNT) && (!wasFound)) {
69 DisplayMode candidate = (DisplayMode)i;
70 if (lowerCaseName == displayModeToString(candidate)) {
87std::string getAvailableDisplayMode(
const std::string &prefix =
"< ",
const std::string &sep =
" , ",
const std::string &suffix =
" >")
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;
94 DisplayMode candidate = (DisplayMode)(DisplayMode::MODE_COUNT - 1);
95 modes += displayModeToString(candidate) + suffix;
100int main(
int argc,
const char *argv[])
102 std::string opt_hsv_filename =
"calib/hsv-thresholds.yml";
103 bool opt_pcl_textured =
false;
104 bool opt_verbose =
false;
106 int opt_height = 480;
108 DisplayMode opt_mode = DisplayMode::MONOTHREAD;
112 if (((std::string(argv[i]) ==
"--width") || (std::string(argv[i]) ==
"-v")) && ((i+1) < argc)) {
113 opt_width = std::atoi(argv[++i]);
115 else if (((std::string(argv[i]) ==
"--height") || (std::string(argv[i]) ==
"-h")) && ((i+1) < argc)) {
116 opt_height = std::atoi(argv[++i]);
118 else if (std::string(argv[i]) ==
"--display-mode" && i + 1 < argc) {
119 opt_mode = displayModeFromString(std::string(argv[i + 1]));
122 else if ((std::string(argv[i]) ==
"--fps") && ((i+1) < argc)) {
123 opt_fps = std::atoi(argv[++i]);
125 else if (std::string(argv[i]) ==
"--texture") {
126 opt_pcl_textured =
true;
128 else if ((std::string(argv[i]) ==
"--hsv-thresholds") && ((i+1) < argc)) {
129 opt_hsv_filename = std::string(argv[++i]);
131 else if ((std::string(argv[i]) ==
"--verbose") || (std::string(argv[i]) ==
"-v")) {
134 else if ((std::string(argv[i]) ==
"--help") || (std::string(argv[i]) ==
"-h")) {
135 std::cout <<
"\nSYNOPSIS " << std::endl
137 <<
" [--width,-w <image width>]"
138 <<
" [--height,-h <image height>]"
139 <<
" [--fps <framerate>]"
141 <<
" [--hsv-thresholds <filename.yml>]"
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
150 <<
" --height,-h <image height>" << std::endl
151 <<
" Realsense camera image height." << std::endl
152 <<
" Default: " << opt_height << std::endl
154 <<
" --fps <framerate>" << std::endl
155 <<
" Realsense camera framerate." << std::endl
156 <<
" Default: " << opt_fps << std::endl
158 <<
" --texture" << std::endl
159 <<
" Enable textured point cloud adding RGB information to the 3D point." << 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
174 <<
" --verbose, -v" << std::endl
175 <<
" Enable verbose mode." << std::endl
177 <<
" --help, -h" << std::endl
178 <<
" Display this helper message." << std::endl
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;
191 std::cout <<
"Warning: unable to load HSV thresholds values from " << opt_hsv_filename << std::endl;
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);
214#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
229 double loop_time = 0., total_loop_time = 0.;
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>());
240 std::mutex pointcloud_mutex;
242 if (opt_mode == DisplayMode::THREADED) {
243 if (opt_pcl_textured) {
244 pcl_viewer.startThread(std::ref(pointcloud_mutex), pointcloud_color);
247 pcl_viewer.startThread(std::ref(pointcloud_mutex), pointcloud);
251 if (opt_pcl_textured) {
252 pcl_viewer.addPointCloud(std::ref(pointcloud_mutex), pointcloud_color);
255 pcl_viewer.addPointCloud(std::ref(pointcloud_mutex), pointcloud);
262 rs.
acquire((
unsigned char *)I.bitmap, (
unsigned char *)(depth_raw.bitmap), NULL, NULL, &align_to);
264#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
269 reinterpret_cast<unsigned char *
>(H.bitmap),
270 reinterpret_cast<unsigned char *
>(S.bitmap),
271 reinterpret_cast<unsigned char *
>(V.bitmap), I.getSize());
274 reinterpret_cast<unsigned char *
>(S.bitmap),
275 reinterpret_cast<unsigned char *
>(V.bitmap),
277 reinterpret_cast<unsigned char *
>(mask.bitmap),
285 if (opt_pcl_textured) {
292 std::cout <<
"Segmented point cloud size: " << pcl_size << std::endl;
305 if (opt_mode == DisplayMode::MONOTHREAD) {
306 const bool blocking_mode =
false;
307 pcl_viewer.display(blocking_mode);
315 total_loop_time += loop_time;
318 std::cout <<
"Mean loop time: " << total_loop_time / nb_iter << std::endl;
320#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
321 if (d_I !=
nullptr) {
325 if (d_I_segmented !=
nullptr) {
326 delete d_I_segmented;
334#if !defined(VISP_HAVE_REALSENSE2)
335 std::cout <<
"This tutorial needs librealsense as 3rd party." << std::endl;
337#if !defined(VISP_HAVE_PCL)
338 std::cout <<
"This tutorial needs pcl library as 3rd party." << std::endl;
340#if !defined(VISP_HAVE_PCL_VISUALIZATION)
341 std::cout <<
"This tutorial needs pcl visualization module." << std::endl;
343#if !defined(VISP_HAVE_X11)
344 std::cout <<
"This tutorial needs X11 3rd party enabled." << std::endl;
346 std::cout <<
"Install missing 3rd party, configure and rebuild ViSP." << std::endl;
static bool loadYAML(const std::string &filename, vpArray2D< double > &A, char *header=nullptr)
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
Implementation of column vector and the associated operations.
Class that defines generic functionalities for display.
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)
Definition of the vpImage class member functions.
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())
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()