43 #include <visp3/core/vpImageConvert.h> 44 #include <visp3/gui/vpDisplayGDI.h> 45 #include <visp3/gui/vpDisplayX.h> 46 #include <visp3/io/vpImageIo.h> 47 #include <visp3/sensor/vpRealSense.h> 49 #if defined(VISP_HAVE_REALSENSE) && defined(VISP_HAVE_CPP11_COMPATIBILITY) && \ 50 (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) 55 #include <pcl/visualization/cloud_viewer.h> 56 #include <pcl/visualization/pcl_visualizer.h> 64 pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(
new pcl::PointCloud<pcl::PointXYZ>());
65 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud_color(
new pcl::PointCloud<pcl::PointXYZRGB>());
66 bool cancelled =
false, update_pointcloud =
false;
71 explicit ViewerWorker(
const bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) {}
76 pcl::visualization::PCLVisualizer::Ptr viewer(
new pcl::visualization::PCLVisualizer(
"3D Viewer " + date));
77 pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(pointcloud_color);
78 pcl::PointCloud<pcl::PointXYZ>::Ptr local_pointcloud(
new pcl::PointCloud<pcl::PointXYZ>());
79 pcl::PointCloud<pcl::PointXYZRGB>::Ptr local_pointcloud_color(
new pcl::PointCloud<pcl::PointXYZRGB>());
81 viewer->setBackgroundColor(0, 0, 0);
82 viewer->initCameraParameters();
83 viewer->setPosition(640 + 80, 480 + 80);
84 viewer->setCameraPosition(0, 0, -0.25, 0, -1, 0);
85 viewer->setSize(640, 480);
88 bool local_update =
false, local_cancelled =
false;
89 while (!local_cancelled) {
91 std::unique_lock<std::mutex> lock(m_mutex, std::try_to_lock);
93 if (lock.owns_lock()) {
94 local_update = update_pointcloud;
95 update_pointcloud =
false;
96 local_cancelled = cancelled;
100 local_pointcloud_color = pointcloud_color->makeShared();
102 local_pointcloud = pointcloud->makeShared();
108 if (local_update && !local_cancelled) {
109 local_update =
false;
113 viewer->addPointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb,
"RGB sample cloud");
114 viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1,
117 viewer->addPointCloud<pcl::PointXYZ>(local_pointcloud,
"sample cloud");
118 viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1,
"sample cloud");
123 viewer->updatePointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb,
"RGB sample cloud");
125 viewer->updatePointCloud<pcl::PointXYZ>(local_pointcloud,
"sample cloud");
133 std::cout <<
"End of point cloud display thread" << std::endl;
140 #endif //#ifdef VISP_HAVE_PCL 142 void test_R200(
vpRealSense &rs,
const std::map<rs::stream, bool> &enables,
143 const std::map<rs::stream, vpRealSense::vpRsStreamParams> ¶ms,
144 const std::map<rs::option, double> &options,
const std::string &title,
145 const bool depth_color_visualization =
false,
const rs::stream &color_stream = rs::stream::color,
146 const rs::stream &depth_stream = rs::stream::depth,
147 const rs::stream &infrared2_stream = rs::stream::infrared2,
bool display_pcl =
false,
148 bool pcl_color =
false)
150 std::cout << std::endl;
152 std::map<rs::stream, bool>::const_iterator it_enable;
153 std::map<rs::stream, vpRealSense::vpRsStreamParams>::const_iterator it_param;
155 for (it_enable = enables.begin(), it_param = params.begin(); it_enable != enables.end(); ++it_enable) {
158 if (it_enable->second) {
159 it_param = params.find(it_enable->first);
161 if (it_param != params.end()) {
177 bool direct_infrared_conversion =
false;
178 for (it_enable = enables.begin(); it_enable != enables.end(); ++it_enable) {
179 if (it_enable->second) {
180 switch (it_enable->first) {
181 case rs::stream::color:
186 case rs::stream::depth:
193 case rs::stream::infrared:
198 it_param = params.find(it_enable->first);
199 if (it_param != params.end()) {
200 direct_infrared_conversion = it_param->second.m_streamFormat == rs::format::y8;
204 case rs::stream::infrared2:
209 it_param = params.find(it_enable->first);
210 if (it_param != params.end()) {
211 direct_infrared_conversion = it_param->second.m_streamFormat == rs::format::y8;
221 #if defined(VISP_HAVE_X11) 223 #elif defined(VISP_HAVE_GDI) 227 for (it_enable = enables.begin(); it_enable != enables.end(); ++it_enable) {
228 if (it_enable->second) {
229 switch (it_enable->first) {
230 case rs::stream::color:
231 dc.
init(I_color, 0, 0,
"Color frame");
234 case rs::stream::depth:
235 if (depth_color_visualization) {
236 dd.
init(I_depth_color, (
int)I_color.
getWidth() + 80, 0,
"Depth frame");
238 dd.
init(I_depth, (
int)I_color.
getWidth() + 80, 0,
"Depth frame");
242 case rs::stream::infrared:
246 case rs::stream::infrared2:
257 std::cout <<
"direct_infrared_conversion=" << direct_infrared_conversion << std::endl;
261 ViewerWorker viewer(pcl_color, mutex);
262 std::thread viewer_thread;
265 viewer_thread = std::thread(&ViewerWorker::run, &viewer);
274 std::vector<double> time_vector;
279 for (std::map<rs::option, double>::const_iterator it = options.begin(); it != options.end(); ++it) {
280 dev->set_option(it->first, it->second);
285 std::lock_guard<std::mutex> lock(mutex);
287 if (direct_infrared_conversion) {
289 rs.
acquire((
unsigned char *)I_color.
bitmap, (
unsigned char *)depth.
bitmap, NULL, pointcloud_color,
290 (
unsigned char *)I_infrared.
bitmap, (
unsigned char *)I_infrared2.
bitmap, color_stream,
291 depth_stream, rs::stream::infrared, infrared2_stream);
293 rs.
acquire((
unsigned char *)I_color.
bitmap, (
unsigned char *)depth.
bitmap, NULL, pointcloud,
294 (
unsigned char *)I_infrared.
bitmap, (
unsigned char *)I_infrared2.
bitmap, color_stream,
295 depth_stream, rs::stream::infrared, infrared2_stream);
299 rs.
acquire((
unsigned char *)I_color.
bitmap, (
unsigned char *)depth.
bitmap, NULL, pointcloud_color,
300 (
unsigned char *)infrared.
bitmap, (
unsigned char *)infrared2.
bitmap, color_stream, depth_stream,
301 rs::stream::infrared, infrared2_stream);
303 rs.
acquire((
unsigned char *)I_color.
bitmap, (
unsigned char *)depth.
bitmap, NULL, pointcloud,
304 (
unsigned char *)infrared.
bitmap, (
unsigned char *)infrared2.
bitmap, color_stream, depth_stream,
305 rs::stream::infrared, infrared2_stream);
312 update_pointcloud =
true;
315 if (direct_infrared_conversion) {
317 (
unsigned char *)I_infrared.
bitmap, (
unsigned char *)I_infrared2.
bitmap, color_stream, depth_stream,
318 rs::stream::infrared, infrared2_stream);
321 (
unsigned char *)infrared.
bitmap, (
unsigned char *)infrared2.
bitmap, color_stream, depth_stream,
322 rs::stream::infrared, infrared2_stream);
328 if (depth_color_visualization) {
335 if (depth_color_visualization) {
344 if (depth_color_visualization) {
367 std::lock_guard<std::mutex> lock(mutex);
371 viewer_thread.join();
376 <<
" ms ; Median time: " <<
vpMath::getMedian(time_vector) <<
" ms" << std::endl;
383 int main(
int argc,
char *argv[])
390 if (rs_get_device_name((
const rs_device *)rs.
getHandler(),
nullptr) != std::string(
"Intel RealSense R200")) {
391 std::cout <<
"This test file is used to test the Intel RealSense R200 only." << std::endl;
395 std::cout <<
"API version: " << rs_get_api_version(
nullptr) << std::endl;
396 std::cout <<
"Firmware: " << rs_get_device_firmware_version((
const rs_device *)rs.
getHandler(),
nullptr)
398 std::cout <<
"RealSense sensor characteristics: \n" << rs << std::endl;
402 std::map<rs::stream, bool> enables;
403 std::map<rs::stream, vpRealSense::vpRsStreamParams> params;
404 std::map<rs::option, double> options;
406 enables[rs::stream::color] =
false;
407 enables[rs::stream::depth] =
true;
408 enables[rs::stream::infrared] =
false;
409 enables[rs::stream::infrared2] =
false;
413 options[rs::option::r200_lr_auto_exposure_enabled] = 1;
415 test_R200(rs, enables, params, options,
"R200_DEPTH_Z16_640x480_90FPS + r200_lr_auto_exposure_enabled",
true);
417 enables[rs::stream::color] =
false;
418 enables[rs::stream::depth] =
true;
419 enables[rs::stream::infrared] =
true;
420 enables[rs::stream::infrared2] =
true;
426 options[rs::option::r200_lr_auto_exposure_enabled] = 0;
427 options[rs::option::r200_emitter_enabled] = 0;
429 test_R200(rs, enables, params, options,
430 "R200_DEPTH_Z16_640x480_90FPS + R200_INFRARED_Y8_640x480_90FPS " 431 "+ R200_INFRARED2_Y8_640x480_90FPS + " 432 "!r200_lr_auto_exposure_enabled + !r200_emitter_enabled",
435 enables[rs::stream::color] =
false;
436 enables[rs::stream::depth] =
true;
437 enables[rs::stream::infrared] =
true;
438 enables[rs::stream::infrared2] =
true;
444 options[rs::option::r200_lr_auto_exposure_enabled] = 1;
445 options[rs::option::r200_emitter_enabled] = 1;
447 test_R200(rs, enables, params, options,
448 "R200_DEPTH_Z16_628x468_90FPS + " 449 "R200_INFRARED_Y16_640x480_90FPS + " 450 "R200_INFRARED2_Y16_640x480_90FPS");
452 enables[rs::stream::color] =
false;
453 enables[rs::stream::depth] =
true;
454 enables[rs::stream::infrared] =
true;
455 enables[rs::stream::infrared2] =
true;
463 test_R200(rs, enables, params, options,
464 "R200_DEPTH_Z16_628x468_90FPS + R200_INFRARED_Y8_640x480_90FPS " 465 "+ R200_INFRARED2_Y8_640x480_90FPS");
467 enables[rs::stream::color] =
true;
468 enables[rs::stream::depth] =
true;
469 enables[rs::stream::infrared] =
true;
470 enables[rs::stream::infrared2] =
true;
477 test_R200(rs, enables, params, options,
478 "R200_COLOR_RGBA8_640x480_30FPS + R200_DEPTH_Z16_628x468_90FPS " 479 "+ R200_INFRARED_Y8_640x480_90FPS + " 480 "R200_INFRARED2_Y8_640x480_90FPS",
483 enables[rs::stream::color] =
true;
484 enables[rs::stream::depth] =
false;
485 enables[rs::stream::infrared] =
false;
486 enables[rs::stream::infrared2] =
false;
490 test_R200(rs, enables, params, options,
"R200_COLOR_RGBA8_1920x1080_30FPS");
492 enables[rs::stream::color] =
true;
493 enables[rs::stream::depth] =
false;
494 enables[rs::stream::infrared] =
false;
495 enables[rs::stream::infrared2] =
false;
498 test_R200(rs, enables, params, options,
"R200_COLOR_RGBA8_640x480_60FPS");
500 enables[rs::stream::color] =
true;
501 enables[rs::stream::depth] =
true;
502 enables[rs::stream::infrared] =
true;
503 enables[rs::stream::infrared2] =
true;
514 rs::stream color_stream = argc > 2 ? (rs::stream)atoi(argv[2]) : rs::stream::color_aligned_to_depth;
515 std::cout <<
"\ncolor_stream: " << color_stream << std::endl;
517 rs::stream depth_stream = argc > 3 ? (rs::stream)atoi(argv[3]) : rs::stream::depth_aligned_to_rectified_color;
518 std::cout <<
"depth_stream: " << depth_stream << std::endl;
520 rs::stream infrared2_stream = argc > 4 ? (rs::stream)atoi(argv[4]) : rs::stream::infrared2_aligned_to_depth;
521 std::cout <<
"infrared2_stream: " << infrared2_stream << std::endl;
523 test_R200(rs, enables, params, options,
524 "R200_COLOR_ALIGNED_TO_DEPTH_RGBA8_640x480_60FPS + " 525 "R200_DEPTH_ALIGNED_TO_RECTIFIED_COLOR_Z16_640x480_60FPS + " 526 "R200_INFRARED_Y8_640x480_60FPS + " 527 "R200_INFRARED2_ALIGNED_TO_DEPTH_Y8_640x480_60FPS",
528 true, color_stream, depth_stream, infrared2_stream);
530 #if (!defined(__APPLE__) && !defined(__MACH__)) // Not OSX, since viewer->spinOnce (10); produces a 533 enables[rs::stream::color] =
true;
534 enables[rs::stream::depth] =
true;
535 enables[rs::stream::infrared] =
true;
536 enables[rs::stream::infrared2] =
true;
546 test_R200(rs, enables, params, options,
547 "R200_COLOR_RGBA8_640x480_60FPS + R200_DEPTH_Z16_640x480_60FPS + " 548 "R200_INFRARED_Y8_640x480_60FPS + R200_INFRARED2_Y8_640x480_60FPS",
549 false, rs::stream::color, rs::stream::depth, rs::stream::infrared2,
true,
550 (argc > 1 ? (
bool)(atoi(argv[1]) > 0) :
false));
553 std::cerr <<
"RealSense error " << e.
what() << std::endl;
554 }
catch (
const rs::error &e) {
555 std::cerr <<
"RealSense error calling " << e.get_failed_function() <<
"(" << e.get_failed_args()
556 <<
"): " << e.what() << std::endl;
557 }
catch (
const std::exception &e) {
558 std::cerr << e.what() << std::endl;
567 #if !defined(VISP_HAVE_REALSENSE) 568 std::cout <<
"Install RealSense SDK to make this test working. X11 or GDI " 571 #elif !defined(VISP_HAVE_CPP11_COMPATIBILITY) 572 std::cout <<
"Build ViSP with c++11 compiler flag (cmake -DUSE_CPP11=ON) " 573 "to make this test working" 575 #elif !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI) 576 std::cout <<
"X11 or GDI are needed!" << std::endl;
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
unsigned int getWidth() const
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
void init(unsigned int height, unsigned int width)
Set the size of the image.
rs::device * getHandler() const
Get access to device handler.
Type * bitmap
points toward the bitmap
static double getMedian(const std::vector< double > &v)
Display for windows using GDI (available on any windows 32 platform).
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
error that can be emited by ViSP classes.
void acquire(std::vector< vpColVector > &pointcloud)
static void flush(const vpImage< unsigned char > &I)
VISP_EXPORT double measureTimeMs()
VISP_EXPORT std::string getDateTime(const std::string &format="%Y/%m/%d %H:%M:%S")
static double getMean(const std::vector< double > &v)
const char * what() const
static void display(const vpImage< unsigned char > &I)
rs::intrinsics getIntrinsics(const rs::stream &stream) const
void setStreamSettings(const rs::stream &stream, const rs::preset &preset)
void setEnableStream(const rs::stream &stream, const bool status)
unsigned int getHeight() const
void init(vpImage< unsigned char > &I, int winx=-1, int winy=-1, const std::string &title="")
Definition of the vpImage class member functions.
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)