43 #include <visp3/core/vpConfig.h> 45 #if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_CPP11_COMPATIBILITY) && \ 46 (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) 48 #include <visp3/core/vpImage.h> 49 #include <visp3/core/vpImageConvert.h> 50 #include <visp3/gui/vpDisplayGDI.h> 51 #include <visp3/gui/vpDisplayX.h> 52 #include <visp3/sensor/vpRealSense2.h> 55 #include <pcl/visualization/cloud_viewer.h> 56 #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(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[])
227 bool pcl_color =
false;
228 bool show_info =
false;
230 for (
int i = 1; i < argc; i++) {
231 if (std::string(argv[i]) ==
"--pcl_color") {
233 }
else if (std::string(argv[i]) ==
"--show_info") {
241 std::cout <<
"RealSense:\n" << rs << std::endl;
247 config.enable_stream(RS2_STREAM_COLOR, 1920, 1080, RS2_FORMAT_RGBA8, 30);
248 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
249 config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y16, 30);
253 auto color_profile = profile.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>();
254 vpImage<vpRGBa> color((
unsigned int)color_profile.height(), (
unsigned int)color_profile.width());
256 auto depth_profile = profile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();
257 vpImage<vpRGBa> depth_color((
unsigned int)depth_profile.height(), (
unsigned int)depth_profile.width());
258 vpImage<uint16_t> depth_raw((
unsigned int)depth_profile.height(), (
unsigned int)depth_profile.width());
260 auto infrared_profile = profile.get_stream(RS2_STREAM_INFRARED).as<rs2::video_stream_profile>();
261 vpImage<unsigned char> infrared((
unsigned int)infrared_profile.height(), (
unsigned int)infrared_profile.width());
262 vpImage<uint16_t> infrared_raw((
unsigned int)infrared_profile.height(), (
unsigned int)infrared_profile.width());
269 d1.
init(color, 0, 0,
"Color");
270 d2.
init(depth_color, color.getWidth(), 0,
"Depth");
271 d3.
init(infrared, 0, color.getHeight() + 100,
"Infrared");
273 std::vector<vpColVector> pointcloud_colvector;
276 ViewerWorker viewer_colvector(
false, mutex);
277 std::thread viewer_colvector_thread(&ViewerWorker::run, &viewer_colvector);
282 std::cout <<
"Color intrinsics:\n" 285 std::cout <<
"Color intrinsics:\n" 288 std::cout <<
"Depth intrinsics:\n" 291 std::cout <<
"Depth intrinsics:\n" 294 std::cout <<
"Infrared intrinsics:\n" 297 std::cout <<
"Infrared intrinsics:\n" 301 std::cout <<
"depth_M_color:\n" << rs.
getTransformation(RS2_STREAM_COLOR, RS2_STREAM_DEPTH) << std::endl;
302 std::cout <<
"color_M_infrared:\n" << rs.
getTransformation(RS2_STREAM_INFRARED, RS2_STREAM_COLOR) << std::endl;
304 std::vector<double> time_vector;
309 auto data = pipe.wait_for_frames();
310 auto color_frame = data.get_color_frame();
311 getNativeFrame(color_frame, (
unsigned char *)color.bitmap);
313 auto depth_frame = data.get_depth_frame();
314 getNativeFrame(depth_frame, (
unsigned char *)depth_raw.bitmap);
316 auto infrared_frame = data.first(RS2_STREAM_INFRARED);
317 getNativeFrame(infrared_frame, (
unsigned char *)infrared_raw.bitmap);
320 getPointcloud(depth_frame, pointcloud_colvector);
323 std::lock_guard<std::mutex> lock(mutex);
325 pointcloud->width = depth_profile.width();
326 pointcloud->height = depth_profile.height();
327 pointcloud->points.resize(pointcloud_colvector.size());
328 for (
size_t i = 0; i < pointcloud_colvector.size(); i++) {
329 pointcloud->points[(size_t)i].x = pointcloud_colvector[i][0];
330 pointcloud->points[(size_t)i].y = pointcloud_colvector[i][1];
331 pointcloud->points[(size_t)i].z = pointcloud_colvector[i][2];
334 update_pointcloud =
true;
358 d2.
close(depth_color);
363 std::lock_guard<std::mutex> lock(mutex);
367 viewer_colvector_thread.join();
369 std::cout <<
"Acquisition1 - Mean time: " <<
vpMath::getMean(time_vector)
370 <<
" ms ; Median time: " <<
vpMath::getMedian(time_vector) <<
" ms" << std::endl;
372 config.disable_all_streams();
373 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 60);
374 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 60);
375 config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 60);
378 color_profile = profile.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>();
379 color.init((
unsigned int)color_profile.height(), (
unsigned int)color_profile.width());
381 depth_profile = profile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();
382 depth_color.init((
unsigned int)depth_profile.height(), (
unsigned int)depth_profile.width());
383 depth_raw.init((
unsigned int)depth_profile.height(), (
unsigned int)depth_profile.width());
385 infrared_profile = profile.get_stream(RS2_STREAM_INFRARED).as<rs2::video_stream_profile>();
386 infrared.init((
unsigned int)infrared_profile.height(), (
unsigned int)infrared_profile.width());
388 d1.
init(color, 0, 0,
"Color");
389 d2.
init(depth_color, color.getWidth(), 0,
"Depth");
390 d3.
init(infrared, 0, color.getHeight() + 100,
"Infrared");
394 ViewerWorker viewer(pcl_color, mutex);
395 std::thread viewer_thread(&ViewerWorker::run, &viewer);
398 std::cout <<
"\n" << std::endl;
399 std::cout <<
"Color intrinsics:\n" 402 std::cout <<
"Color intrinsics:\n" 405 std::cout <<
"Depth intrinsics:\n" 408 std::cout <<
"Depth intrinsics:\n" 411 std::cout <<
"Infrared intrinsics:\n" 414 std::cout <<
"Infrared intrinsics:\n" 418 std::cout <<
"depth_M_color:\n" << rs.
getTransformation(RS2_STREAM_COLOR, RS2_STREAM_DEPTH) << std::endl;
419 std::cout <<
"color_M_infrared:\n" << rs.
getTransformation(RS2_STREAM_INFRARED, RS2_STREAM_COLOR) << std::endl;
428 std::lock_guard<std::mutex> lock(mutex);
431 rs.
acquire((
unsigned char *)color.bitmap, (
unsigned char *)depth_raw.bitmap, NULL, pointcloud_color,
432 (
unsigned char *)infrared.bitmap);
434 rs.
acquire((
unsigned char *)color.bitmap, (
unsigned char *)depth_raw.bitmap, NULL, pointcloud,
435 (
unsigned char *)infrared.bitmap);
438 update_pointcloud =
true;
441 rs.
acquire((
unsigned char *)color.bitmap, (
unsigned char *)depth_raw.bitmap, NULL,
442 (
unsigned char *)infrared.bitmap);
464 std::lock_guard<std::mutex> lock(mutex);
468 viewer_thread.join();
472 d2.
close(depth_color);
474 std::cout <<
"Acquisition2 - Mean time: " <<
vpMath::getMean(time_vector)
475 <<
" ms ; Median time: " <<
vpMath::getMedian(time_vector) <<
" ms" << std::endl;
477 #if VISP_HAVE_OPENCV_VERSION >= 0x030000 479 config.disable_all_streams();
480 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_BGR8, 60);
481 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 60);
482 config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 60);
485 color_profile = profile.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>();
486 cv::Mat mat_color(color_profile.height(), color_profile.width(), CV_8UC3);
488 depth_profile = profile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();
489 cv::Mat mat_depth(depth_profile.height(), depth_profile.width(), CV_8UC3);
490 rs2::colorizer color_map;
492 infrared_profile = profile.get_stream(RS2_STREAM_INFRARED).as<rs2::video_stream_profile>();
493 cv::Mat mat_infrared(infrared_profile.height(), infrared_profile.width(), CV_8U);
500 auto data = pipe.wait_for_frames();
501 frame_to_mat(data.get_color_frame(), mat_color);
502 frame_to_mat(color_map(data.get_depth_frame()), mat_depth);
503 frame_to_mat(data.first(RS2_STREAM_INFRARED), mat_infrared);
505 cv::imshow(
"OpenCV color", mat_color);
506 cv::imshow(
"OpenCV depth", mat_depth);
507 cv::imshow(
"OpenCV infrared", mat_infrared);
510 if (cv::waitKey(10) == 27)
514 std::cout <<
"Acquisition3 - Mean time: " <<
vpMath::getMean(time_vector)
515 <<
" ms ; Median time: " <<
vpMath::getMedian(time_vector) <<
" ms" << std::endl;
524 #if !defined(VISP_HAVE_REALSENSE2) 525 std::cout <<
"Install librealsense2 to make this test work." << std::endl;
527 #if !defined(VISP_HAVE_CPP11_COMPATIBILITY) 528 std::cout <<
"Build ViSP with C++11 compiler flag (cmake -DUSE_CPP11=ON) " 529 "to make this test work" 532 #if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI) 533 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 void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
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)
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.
Implementation of column vector and the associated operations.
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion) const
void init(vpImage< unsigned char > &I, int winx=-1, int winy=-1, const std::string &title="")
vpHomogeneousMatrix getTransformation(const rs2_stream &from, const rs2_stream &to) const
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)