4#include <visp3/core/vpConfig.h>
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>
16int main(
int argc,
const char *argv[])
18#ifdef ENABLE_VISP_NAMESPACE
22 std::string opt_hsv_filename =
"calib/hsv-thresholds.yml";
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]);
28 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
29 std::cout <<
"\nSYNOPSIS " << std::endl
31 <<
" [--hsv-thresholds <filename.yml>]"
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
48 <<
" --help, -h" << std::endl
49 <<
" Display this helper message." << std::endl
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;
61 std::cout <<
"Warning: unable to load HSV thresholds values from " << opt_hsv_filename << std::endl;
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);
89#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
104 double loop_time = 0., total_loop_time = 0.;
110 pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(
new pcl::PointCloud<pcl::PointXYZ>());
116 rs.
acquire((
unsigned char *)I.bitmap, (
unsigned char *)(depth_raw.bitmap), NULL, NULL, &align_to);
120#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
124 reinterpret_cast<unsigned char *
>(H.bitmap),
125 reinterpret_cast<unsigned char *
>(S.bitmap),
126 reinterpret_cast<unsigned char *
>(V.bitmap), I.getSize());
131#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
135 reinterpret_cast<unsigned char *
>(S.bitmap),
136 reinterpret_cast<unsigned char *
>(V.bitmap),
138 reinterpret_cast<unsigned char *
>(mask.bitmap),
150 int pcl_size = pointcloud->size();
153 std::cout <<
"Segmented point cloud size: " << pcl_size << std::endl;
167 total_loop_time += loop_time;
170 std::cout <<
"Mean loop time: " << total_loop_time / nb_iter << std::endl;
172#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
173 if (d_I !=
nullptr) {
177 if (d_I_segmented !=
nullptr) {
178 delete d_I_segmented;
186#if !defined(VISP_HAVE_REALSENSE2)
187 std::cout <<
"This tutorial needs librealsense as 3rd party." << std::endl;
189#if !defined(VISP_HAVE_PCL)
190 std::cout <<
"This tutorial needs pcl library as 3rd party." << std::endl;
192#if !defined(VISP_HAVE_X11)
193 std::cout <<
"This tutorial needs X11 3rd party enabled." << std::endl;
195 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()