This example shows how to retrieve data from a RealSense RGB-D sensor with librealsense2.
#include <iostream>
#include <visp3/core/vpConfig.h>
#if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI))
#include <visp3/core/vpTime.h>
#include <visp3/core/vpImageConvert.h>
#include <visp3/gui/vpDisplayGDI.h>
#include <visp3/gui/vpDisplayX.h>
#include <visp3/gui/vpDisplayPCL.h>
#include <visp3/sensor/vpRealSense2.h>
int main()
{
#ifdef ENABLE_VISP_NAMESPACE
#endif
try {
std::cout << "Product line: " << product_line << std::endl;
if (product_line == "T200") {
std::cout << "This example doesn't support T200 product line family !" << std::endl;
return EXIT_SUCCESS;
}
rs2::config config;
config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
<< std::endl;
<< std::endl;
std::cout <<
"Extrinsics cMd: \n" << rs.
getTransformation(RS2_STREAM_COLOR, RS2_STREAM_DEPTH) << std::endl;
std::cout <<
"Extrinsics dMc: \n" << rs.
getTransformation(RS2_STREAM_DEPTH, RS2_STREAM_COLOR) << std::endl;
std::cout <<
"Extrinsics cMi: \n" << rs.
getTransformation(RS2_STREAM_COLOR, RS2_STREAM_INFRARED) << std::endl;
std::cout <<
"Extrinsics dMi: \n" << rs.
getTransformation(RS2_STREAM_DEPTH, RS2_STREAM_INFRARED) << std::endl;
#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON) && defined(VISP_HAVE_THREADS)
std::mutex mutex;
pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud_color(new pcl::PointCloud<pcl::PointXYZRGB>());
#if defined(VISP_HAVE_PCL_VISUALIZATION)
pcl_viewer.
startThread(std::ref(mutex), pointcloud_color);
#endif
#endif
#if defined(VISP_HAVE_X11)
vpDisplayX dc(color, 10, 10, "Color image");
vpDisplayX di(infrared,
static_cast<int>(color.
getWidth()) + 80, 10,
"Infrared image");
vpDisplayX dd(depth_display, 10,
static_cast<int>(color.
getHeight()) + 70,
"Depth image");
#elif defined(VISP_HAVE_GDI)
#endif
while (true) {
#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON) && defined(VISP_HAVE_THREADS)
{
std::lock_guard<std::mutex> lock(mutex);
rs.
acquire(
reinterpret_cast<unsigned char *
>(color.
bitmap),
reinterpret_cast<unsigned char *
>(depth.
bitmap),
nullptr, pointcloud_color,
reinterpret_cast<unsigned char *
>(infrared.
bitmap));
}
#else
rs.
acquire(
reinterpret_cast<unsigned char *
>(color.
bitmap),
reinterpret_cast<unsigned char *
>(depth.
bitmap),
nullptr,
reinterpret_cast<unsigned char *
>(infrared.
bitmap));
#endif
break;
}
}
std::cout << "RealSense sensor characteristics: \n" << rs << std::endl;
}
std::cerr <<
"RealSense error " << e.
what() << std::endl;
}
catch (const std::exception &e) {
std::cerr << e.
what() << std::endl;
}
return EXIT_SUCCESS;
}
#else
int main()
{
#if !defined(VISP_HAVE_REALSENSE2)
std::cout << "You do not have realsense2 SDK functionality enabled..." << std::endl;
std::cout << "Tip:" << std::endl;
std::cout << "- Install librealsense2, configure again ViSP using cmake and build again this example" << std::endl;
return EXIT_SUCCESS;
#endif
return EXIT_SUCCESS;
}
#endif
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
Display for windows using GDI (available on any windows 32 platform).
void startThread(std::mutex &mutex, pcl::PointCloud< pcl::PointXYZ >::Ptr pointcloud)
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)
error that can be emitted by ViSP classes.
const char * what() const
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
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())
rs2_intrinsics getIntrinsics(const rs2_stream &stream, int index=-1) const
std::string getProductLine()
vpHomogeneousMatrix getTransformation(const rs2_stream &from, const rs2_stream &to, int from_index=-1) const
VISP_EXPORT std::string getDateTime(const std::string &format="%Y/%m/%d %H:%M:%S")
VISP_EXPORT double measureTimeMs()