Test Intel RealSense D435 acquisition with librealsense2 (PCL demo).
#include <iostream>
#include <visp3/core/vpConfig.h>
#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_THREADS) \
&& (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON) && defined(VISP_HAVE_PCL_VISUALIZATION)
#include <visp3/core/vpImage.h>
#include <visp3/core/vpImageConvert.h>
#include <visp3/core/vpTime.h>
#include <visp3/gui/vpDisplayGDI.h>
#include <visp3/gui/vpDisplayX.h>
#include <visp3/gui/vpDisplayPCL.h>
#include <visp3/sensor/vpRealSense2.h>
int main(int argc, char *argv[])
{
#ifdef ENABLE_VISP_NAMESPACE
#endif
bool opt_pcl_color = false;
bool opt_show_infrared2 = false;
bool display_helper = false;
for (int i = 1; i < argc; i++) {
if (std::string(argv[i]) == "--pcl-color") {
opt_pcl_color = true;
}
else if (std::string(argv[i]) == "--show-infrared2") {
opt_show_infrared2 = true;
}
else if ((std::string(argv[i]) == "--help") || (std::string(argv[i]) == "-h")) {
display_helper = true;
}
else {
display_helper = true;
std::cout << "\nERROR" << std::endl;
std::cout << " Wrong command line option." << std::endl;
}
if (display_helper) {
std::cout << "\nSYNOPSIS " << std::endl
<< " " << argv[0]
<< " [--pcl-color]"
<< " [--show-infrared2]"
<< " [--help,-h]"
<< std::endl;
std::cout << "\nOPTIONS " << std::endl
<< " --pcl-color" << std::endl
<< " Enable textured point cloud visualization." << std::endl
<< std::endl
<< " --show-infrared2" << std::endl
<< " Display also the infrared2 stream." << std::endl
<< std::endl
<< " --help, -h" << std::endl
<< " Display this helper message." << std::endl
<< std::endl;
return EXIT_SUCCESS;
}
}
const int width = 640, height = 480, fps = 30;
rs2::config config;
config.enable_stream(RS2_STREAM_COLOR, width, height, RS2_FORMAT_RGBA8, fps);
config.enable_stream(RS2_STREAM_DEPTH, width, height, RS2_FORMAT_Z16, fps);
config.enable_stream(RS2_STREAM_INFRARED, 1, width, height, RS2_FORMAT_Y8, fps);
config.enable_stream(RS2_STREAM_INFRARED, 2, width, height, RS2_FORMAT_Y8, fps);
vpImage<vpRGBa> color(
static_cast<unsigned int>(height),
static_cast<unsigned int>(width));
vpImage<vpRGBa> depth_color(
static_cast<unsigned int>(height),
static_cast<unsigned int>(width));
vpImage<uint16_t> depth_raw(
static_cast<unsigned int>(height),
static_cast<unsigned int>(width));
#ifdef VISP_HAVE_X11
vpDisplayX d1, d2, d3, d4;
#else
#endif
d1.
init(color, 0, 0,
"Color");
d2.init(depth_color, color.
getWidth() + 80, 0,
"Depth");
d3.init(infrared1, 0, color.
getHeight() + 70,
"Infrared left");
if (opt_show_infrared2) {
}
std::mutex mutex;
pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud_color(new pcl::PointCloud<pcl::PointXYZRGB>());
if (opt_pcl_color) {
pcl_viewer.
startThread(std::ref(mutex), pointcloud_color);
}
else {
}
std::vector<double> time_vector;
while (true) {
{
std::lock_guard<std::mutex> lock(mutex);
if (opt_pcl_color) {
rs.
acquire(
reinterpret_cast<unsigned char *
>(color.
bitmap),
reinterpret_cast<unsigned char *
>(depth_raw.
bitmap),
nullptr, pointcloud_color,
reinterpret_cast<unsigned char *
>(infrared1.
bitmap),
opt_show_infrared2 ?
reinterpret_cast<unsigned char *
>(infrared2.
bitmap) :
nullptr,
nullptr);
}
else {
rs.
acquire(
reinterpret_cast<unsigned char *
>(color.
bitmap),
reinterpret_cast<unsigned char *
>(depth_raw.
bitmap),
nullptr, pointcloud,
reinterpret_cast<unsigned char *
>(infrared1.
bitmap),
opt_show_infrared2 ?
reinterpret_cast<unsigned char *
>(infrared2.
bitmap) :
nullptr,
nullptr);
}
}
break;
}
}
return EXIT_SUCCESS;
}
#else
int main()
{
#if !defined(VISP_HAVE_REALSENSE2)
std::cout << "Install librealsense2 to make this test work." << std::endl;
#endif
#if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI)
std::cout << "X11 or GDI are needed." << std::endl;
#endif
#if !defined(VISP_HAVE_PCL)
std::cout << "Install PCL to make this test work." << std::endl;
#endif
return EXIT_SUCCESS;
}
#endif
void start(bool reset=true)
Display for windows using GDI (available on any windows 32 platform).
void startThread(std::mutex &mutex, pcl::PointCloud< pcl::PointXYZ >::Ptr pointcloud)
void init(vpImage< unsigned char > &I, int winx=-1, int winy=-1, const std::string &title="") VP_OVERRIDE
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 createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)
unsigned int getWidth() const
Type * bitmap
points toward the bitmap
unsigned int getHeight() const
static double getMedian(const std::vector< double > &v)
static double getMean(const std::vector< double > &v)
void acquire(vpImage< unsigned char > &grey, double *ts=nullptr)
bool open(const rs2::config &cfg=rs2::config())
VISP_EXPORT std::string getDateTime(const std::string &format="%Y/%m/%d %H:%M:%S")