42 #include <visp3/core/vpConfig.h> 44 #if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_CPP11_COMPATIBILITY) && \ 45 (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) 47 #include <visp3/core/vpImage.h> 48 #include <visp3/core/vpImageConvert.h> 49 #include <visp3/gui/vpDisplayGDI.h> 50 #include <visp3/gui/vpDisplayX.h> 51 #include <visp3/sensor/vpRealSense2.h> 54 #include <pcl/visualization/cloud_viewer.h> 55 #include <pcl/visualization/pcl_visualizer.h> 60 #if VISP_HAVE_OPENCV_VERSION >= 0x030000 61 #include <opencv2/core.hpp> 62 #include <opencv2/highgui.hpp> 69 pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(
new pcl::PointCloud<pcl::PointXYZ>());
70 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud_color(
new pcl::PointCloud<pcl::PointXYZRGB>());
71 bool cancelled =
false, update_pointcloud =
false;
76 explicit ViewerWorker(
const bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) {}
81 pcl::visualization::PCLVisualizer::Ptr viewer(
new pcl::visualization::PCLVisualizer(
"3D Viewer " + date));
82 pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(pointcloud_color);
83 pcl::PointCloud<pcl::PointXYZ>::Ptr local_pointcloud(
new pcl::PointCloud<pcl::PointXYZ>());
84 pcl::PointCloud<pcl::PointXYZRGB>::Ptr local_pointcloud_color(
new pcl::PointCloud<pcl::PointXYZRGB>());
86 viewer->setBackgroundColor(0, 0, 0);
87 viewer->initCameraParameters();
88 viewer->setPosition(640 + 80, 480 + 80);
89 viewer->setCameraPosition(0, 0, -0.25, 0, -1, 0);
90 viewer->setSize(640, 480);
93 bool local_update =
false, local_cancelled =
false;
94 while (!local_cancelled) {
96 std::unique_lock<std::mutex> lock(m_mutex, std::try_to_lock);
98 if (lock.owns_lock()) {
99 local_update = update_pointcloud;
100 update_pointcloud =
false;
101 local_cancelled = cancelled;
105 local_pointcloud_color = pointcloud_color->makeShared();
107 local_pointcloud = pointcloud->makeShared();
113 if (local_update && !local_cancelled) {
114 local_update =
false;
118 viewer->addPointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb,
"RGB sample cloud");
119 viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1,
122 viewer->addPointCloud<pcl::PointXYZ>(local_pointcloud,
"sample cloud");
123 viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1,
"sample cloud");
128 viewer->updatePointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb,
"RGB sample cloud");
130 viewer->updatePointCloud<pcl::PointXYZ>(local_pointcloud,
"sample cloud");
138 std::cout <<
"End of point cloud display thread" << std::endl;
146 void getPointcloud(
const rs2::depth_frame &depth_frame, std::vector<vpColVector> &pointcloud)
148 auto vf = depth_frame.as<rs2::video_frame>();
149 const int width = vf.get_width();
150 const int height = vf.get_height();
151 pointcloud.resize((
size_t)(width * height));
154 rs2::points points = pc.calculate(depth_frame);
155 auto vertices = points.get_vertices();
157 for (
size_t i = 0; i < points.size(); i++) {
159 v[0] = vertices[i].x;
160 v[1] = vertices[i].y;
161 v[2] = vertices[i].z;
175 void getNativeFrame(
const rs2::frame &frame,
unsigned char *
const data)
177 auto vf = frame.as<rs2::video_frame>();
178 int size = vf.get_width() * vf.get_height();
180 switch (frame.get_profile().format()) {
181 case RS2_FORMAT_RGB8:
182 case RS2_FORMAT_BGR8:
183 memcpy(data, (
void *)frame.get_data(), size * 3);
186 case RS2_FORMAT_RGBA8:
187 case RS2_FORMAT_BGRA8:
188 memcpy(data, (
void *)frame.get_data(), size * 4);
193 memcpy(data, (
unsigned char *)frame.get_data(), size * 2);
197 memcpy(data, (
unsigned char *)frame.get_data(), size);
205 #if VISP_HAVE_OPENCV_VERSION >= 0x030000 206 void frame_to_mat(
const rs2::frame &f, cv::Mat &img)
208 auto vf = f.as<rs2::video_frame>();
209 const int w = vf.get_width();
210 const int h = vf.get_height();
211 const int size = w * h;
213 if (f.get_profile().format() == RS2_FORMAT_BGR8) {
214 memcpy(static_cast<void*>(img.ptr<cv::Vec3b>()), f.get_data(), size * 3);
215 }
else if (f.get_profile().format() == RS2_FORMAT_RGB8) {
216 cv::Mat tmp(h, w, CV_8UC3, (
void *)f.get_data(), cv::Mat::AUTO_STEP);
217 cv::cvtColor(tmp, img, cv::COLOR_RGB2BGR);
218 }
else if (f.get_profile().format() == RS2_FORMAT_Y8) {
219 memcpy(img.ptr<uchar>(), f.get_data(), size);
225 int main(
int argc,
char *argv[])
228 bool pcl_color =
false;
230 bool show_info =
false;
232 for (
int i = 1; i < argc; i++) {
234 if (std::string(argv[i]) ==
"--pcl_color") {
238 if (std::string(argv[i]) ==
"--show_info") {
246 std::cout <<
"RealSense:\n" << rs << std::endl;
252 config.enable_stream(RS2_STREAM_COLOR, 1280, 720, RS2_FORMAT_RGBA8, 30);
253 config.enable_stream(RS2_STREAM_DEPTH, 1280, 720, RS2_FORMAT_Z16, 30);
254 config.enable_stream(RS2_STREAM_INFRARED, 1, 1280, 720, RS2_FORMAT_Y8, 30);
255 config.enable_stream(RS2_STREAM_INFRARED, 2, 1280, 720, RS2_FORMAT_Y8, 30);
259 auto color_profile = profile.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>();
260 vpImage<vpRGBa> color((
unsigned int)color_profile.height(), (
unsigned int)color_profile.width());
262 auto depth_profile = profile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();
263 vpImage<vpRGBa> depth_color((
unsigned int)depth_profile.height(), (
unsigned int)depth_profile.width());
264 vpImage<uint16_t> depth_raw((
unsigned int)depth_profile.height(), (
unsigned int)depth_profile.width());
266 auto infrared_profile = profile.get_stream(RS2_STREAM_INFRARED).as<rs2::video_stream_profile>();
267 vpImage<unsigned char> infrared1((
unsigned int)infrared_profile.height(), (
unsigned int)infrared_profile.width());
268 vpImage<unsigned char> infrared2((
unsigned int)infrared_profile.height(), (
unsigned int)infrared_profile.width());
275 d1.
init(color, 0, 0,
"Color");
276 d2.
init(depth_color, color.getWidth(), 0,
"Depth");
277 d3.
init(infrared1, 0, color.getHeight() + 100,
"Infrared left");
278 d4.
init(infrared2, color.getWidth(), color.getHeight() + 100,
"Infrared right");
280 std::vector<vpColVector> pointcloud_colvector;
283 ViewerWorker viewer_colvector(
false, mutex);
284 std::thread viewer_colvector_thread(&ViewerWorker::run, &viewer_colvector);
289 std::cout <<
"Color intrinsics:\n" 292 std::cout <<
"Color intrinsics:\n" 295 std::cout <<
"Depth intrinsics:\n" 298 std::cout <<
"Depth intrinsics:\n" 301 std::cout <<
"Infrared intrinsics:\n" 304 std::cout <<
"Infrared intrinsics:\n" 308 std::cout <<
"depth_M_color:\n" << rs.
getTransformation(RS2_STREAM_COLOR, RS2_STREAM_DEPTH) << std::endl;
309 std::cout <<
"color_M_infrared:\n" << rs.
getTransformation(RS2_STREAM_INFRARED, RS2_STREAM_COLOR) << std::endl;
311 std::vector<double> time_vector;
316 auto data = pipe.wait_for_frames();
317 auto color_frame = data.get_color_frame();
318 getNativeFrame(color_frame, (
unsigned char *)color.bitmap);
320 auto depth_frame = data.get_depth_frame();
321 getNativeFrame(depth_frame, (
unsigned char *)depth_raw.bitmap);
323 #if (RS2_API_VERSION >= ((2 * 10000) + (10 * 100) + 0)) 325 auto infrared1_frame = data.get_infrared_frame(1);
326 getNativeFrame(infrared1_frame, (
unsigned char *)infrared1.bitmap);
328 auto infrared2_frame = data.get_infrared_frame(2);
329 getNativeFrame(infrared2_frame, (
unsigned char *)infrared2.bitmap);
333 getPointcloud(depth_frame, pointcloud_colvector);
336 std::lock_guard<std::mutex> lock(mutex);
338 pointcloud->width = depth_profile.width();
339 pointcloud->height = depth_profile.height();
340 pointcloud->points.resize(pointcloud_colvector.size());
341 for (
size_t i = 0; i < pointcloud_colvector.size(); i++) {
342 pointcloud->points[(size_t)i].x = pointcloud_colvector[i][0];
343 pointcloud->points[(size_t)i].y = pointcloud_colvector[i][1];
344 pointcloud->points[(size_t)i].z = pointcloud_colvector[i][2];
347 update_pointcloud =
true;
372 d2.
close(depth_color);
378 std::lock_guard<std::mutex> lock(mutex);
382 viewer_colvector_thread.join();
384 std::cout <<
"Acquisition1 - Mean time: " <<
vpMath::getMean(time_vector)
385 <<
" ms ; Median time: " <<
vpMath::getMedian(time_vector) <<
" ms" << std::endl;
387 config.disable_all_streams();
388 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 60);
389 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 60);
390 config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 60);
393 color_profile = profile.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>();
394 color.init((
unsigned int)color_profile.height(), (
unsigned int)color_profile.width());
396 depth_profile = profile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();
397 depth_color.init((
unsigned int)depth_profile.height(), (
unsigned int)depth_profile.width());
398 depth_raw.init((
unsigned int)depth_profile.height(), (
unsigned int)depth_profile.width());
400 infrared_profile = profile.get_stream(RS2_STREAM_INFRARED).as<rs2::video_stream_profile>();
401 infrared1.init((
unsigned int)infrared_profile.height(), (
unsigned int)infrared_profile.width());
403 d1.
init(color, 0, 0,
"Color");
404 d2.
init(depth_color, color.getWidth(), 0,
"Depth");
405 d3.
init(infrared1, 0, color.getHeight() + 100,
"Infrared");
409 ViewerWorker viewer(pcl_color, mutex);
410 std::thread viewer_thread(&ViewerWorker::run, &viewer);
413 std::cout <<
"\n" << std::endl;
414 std::cout <<
"Color intrinsics:\n" 417 std::cout <<
"Color intrinsics:\n" 420 std::cout <<
"Depth intrinsics:\n" 423 std::cout <<
"Depth intrinsics:\n" 426 std::cout <<
"Infrared intrinsics:\n" 429 std::cout <<
"Infrared intrinsics:\n" 433 std::cout <<
"depth_M_color:\n" << rs.
getTransformation(RS2_STREAM_COLOR, RS2_STREAM_DEPTH) << std::endl;
434 std::cout <<
"color_M_infrared:\n" << rs.
getTransformation(RS2_STREAM_INFRARED, RS2_STREAM_COLOR) << std::endl;
443 std::lock_guard<std::mutex> lock(mutex);
446 rs.
acquire((
unsigned char *)color.bitmap, (
unsigned char *)depth_raw.bitmap, NULL, pointcloud_color,
447 (
unsigned char *)infrared1.bitmap);
449 rs.
acquire((
unsigned char *)color.bitmap, (
unsigned char *)depth_raw.bitmap, NULL, pointcloud,
450 (
unsigned char *)infrared1.bitmap);
453 update_pointcloud =
true;
456 rs.
acquire((
unsigned char *)color.bitmap, (
unsigned char *)depth_raw.bitmap, NULL,
457 (
unsigned char *)infrared1.bitmap);
479 std::lock_guard<std::mutex> lock(mutex);
483 viewer_thread.join();
487 d2.
close(depth_color);
489 std::cout <<
"Acquisition2 - Mean time: " <<
vpMath::getMean(time_vector)
490 <<
" ms ; Median time: " <<
vpMath::getMedian(time_vector) <<
" ms" << std::endl;
492 #if VISP_HAVE_OPENCV_VERSION >= 0x030000 494 config.disable_all_streams();
495 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_BGR8, 60);
496 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 60);
497 config.enable_stream(RS2_STREAM_INFRARED, 1, 640, 480, RS2_FORMAT_Y8, 60);
498 config.enable_stream(RS2_STREAM_INFRARED, 2, 640, 480, RS2_FORMAT_Y8, 60);
501 color_profile = profile.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>();
502 cv::Mat mat_color(color_profile.height(), color_profile.width(), CV_8UC3);
504 depth_profile = profile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();
505 cv::Mat mat_depth(depth_profile.height(), depth_profile.width(), CV_8UC3);
506 rs2::colorizer color_map;
508 infrared_profile = profile.get_stream(RS2_STREAM_INFRARED).as<rs2::video_stream_profile>();
509 cv::Mat mat_infrared1(infrared_profile.height(), infrared_profile.width(), CV_8U);
510 cv::Mat mat_infrared2(infrared_profile.height(), infrared_profile.width(), CV_8U);
517 auto data = pipe.wait_for_frames();
518 frame_to_mat(data.get_color_frame(), mat_color);
519 #if (RS2_API_VERSION >= ((2 * 10000) + (16 * 100) + 0)) 520 frame_to_mat(data.get_depth_frame().apply_filter(color_map), mat_depth);
522 frame_to_mat(color_map(data.get_depth_frame()), mat_depth);
525 cv::imshow(
"OpenCV color", mat_color);
526 cv::imshow(
"OpenCV depth", mat_depth);
528 #if (RS2_API_VERSION >= ((2 * 10000) + (10 * 100) + 0)) 530 frame_to_mat(data.get_infrared_frame(1), mat_infrared1);
531 frame_to_mat(data.get_infrared_frame(2), mat_infrared2);
533 cv::imshow(
"OpenCV infrared left", mat_infrared1);
534 cv::imshow(
"OpenCV infrared right", mat_infrared2);
538 if (cv::waitKey(10) == 27)
542 std::cout <<
"Acquisition3 - Mean time: " <<
vpMath::getMean(time_vector)
543 <<
" ms ; Median time: " <<
vpMath::getMedian(time_vector) <<
" ms" << std::endl;
552 #if !defined(VISP_HAVE_REALSENSE2) 553 std::cout <<
"Install librealsense2 to make this test work." << std::endl;
555 #if !defined(VISP_HAVE_CPP11_COMPATIBILITY) 556 std::cout <<
"Build ViSP with C++11 compiler flag (cmake -DUSE_CPP11=ON) " 557 "to make this test work" 560 #if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI) 561 std::cout <<
"X11 or GDI are needed." << std::endl;
rs2::pipeline_profile & getPipelineProfile()
Get a reference to rs2::pipeline_profile.
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void close(vpImage< unsigned char > &I)
static double getMedian(const std::vector< double > &v)
Display for windows using GDI (available on any windows 32 platform).
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
void open(const rs2::config &cfg=rs2::config())
static void flush(const vpImage< unsigned char > &I)
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion) const
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)
static void display(const vpImage< unsigned char > &I)
void acquire(vpImage< unsigned char > &grey)
rs2::pipeline & getPipeline()
Get a reference to rs2::pipeline.
vpHomogeneousMatrix getTransformation(const rs2_stream &from, const rs2_stream &to) const
Implementation of column vector and the associated operations.
void init(vpImage< unsigned char > &I, int winx=-1, int winy=-1, const std::string &title="")
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)