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_SR300(
vpRealSense &rs,
const std::map<rs::stream, bool> &enables,
143 const std::map<rs::stream, vpRealSense::vpRsStreamParams> ¶ms,
const std::string &title,
144 const bool depth_color_visualization =
false,
const rs::stream &color_stream = rs::stream::color,
145 const rs::stream &depth_stream = rs::stream::depth,
bool display_pcl =
false,
bool pcl_color =
false)
147 std::cout << std::endl;
149 std::map<rs::stream, bool>::const_iterator it_enable;
150 std::map<rs::stream, vpRealSense::vpRsStreamParams>::const_iterator it_param;
152 for (it_enable = enables.begin(), it_param = params.begin(); it_enable != enables.end(); ++it_enable) {
155 if (it_enable->second) {
156 it_param = params.find(it_enable->first);
158 if (it_param != params.end()) {
174 bool direct_infrared_conversion =
false;
175 for (it_enable = enables.begin(); it_enable != enables.end(); ++it_enable) {
176 if (it_enable->second) {
177 switch (it_enable->first) {
178 case rs::stream::color:
183 case rs::stream::depth:
190 case rs::stream::infrared:
195 it_param = params.find(it_enable->first);
196 if (it_param != params.end()) {
197 direct_infrared_conversion = it_param->second.m_streamFormat == rs::format::y8;
207 #if defined(VISP_HAVE_X11) 209 #elif defined(VISP_HAVE_GDI) 213 for (it_enable = enables.begin(); it_enable != enables.end(); ++it_enable) {
214 if (it_enable->second) {
215 switch (it_enable->first) {
216 case rs::stream::color:
217 dc.
init(I_color, 0, 0,
"Color frame");
220 case rs::stream::depth:
221 if (depth_color_visualization) {
222 dd.
init(I_depth_color, (
int)I_color.
getWidth() + 80, 0,
"Depth frame");
224 dd.
init(I_depth, (
int)I_color.
getWidth() + 80, 0,
"Depth frame");
228 case rs::stream::infrared:
238 if (rs.
getHandler()->is_stream_enabled(rs::stream::infrared)) {
239 std::cout <<
"direct_infrared_conversion=" << direct_infrared_conversion << std::endl;
244 ViewerWorker viewer(pcl_color, mutex);
245 std::thread viewer_thread;
248 viewer_thread = std::thread(&ViewerWorker::run, &viewer);
255 std::vector<double> time_vector;
262 std::lock_guard<std::mutex> lock(mutex);
264 if (direct_infrared_conversion) {
266 rs.
acquire((
unsigned char *)I_color.
bitmap, (
unsigned char *)depth.
bitmap, NULL, pointcloud_color,
267 (
unsigned char *)I_infrared.
bitmap, NULL, color_stream, depth_stream);
269 rs.
acquire((
unsigned char *)I_color.
bitmap, (
unsigned char *)depth.
bitmap, NULL, pointcloud,
270 (
unsigned char *)I_infrared.
bitmap, NULL, color_stream, depth_stream);
274 rs.
acquire((
unsigned char *)I_color.
bitmap, (
unsigned char *)depth.
bitmap, NULL, pointcloud_color,
275 (
unsigned char *)infrared.
bitmap, NULL, color_stream, depth_stream);
277 rs.
acquire((
unsigned char *)I_color.
bitmap, (
unsigned char *)depth.
bitmap, NULL, pointcloud,
278 (
unsigned char *)infrared.
bitmap, NULL, color_stream, depth_stream);
284 update_pointcloud =
true;
287 if (direct_infrared_conversion) {
289 (
unsigned char *)I_infrared.
bitmap, NULL, color_stream, depth_stream);
292 (
unsigned char *)infrared.
bitmap, NULL, color_stream, depth_stream);
297 if (depth_color_visualization) {
304 if (depth_color_visualization) {
312 if (depth_color_visualization) {
334 std::lock_guard<std::mutex> lock(mutex);
338 viewer_thread.join();
343 <<
" ms ; Median time: " <<
vpMath::getMedian(time_vector) <<
" ms" << std::endl;
350 int main(
int argc,
char *argv[])
357 if (rs_get_device_name((
const rs_device *)rs.
getHandler(),
nullptr) != std::string(
"Intel RealSense SR300")) {
358 std::cout <<
"This test file is used to test the Intel RealSense SR300 only." << std::endl;
362 std::cout <<
"API version: " << rs_get_api_version(
nullptr) << std::endl;
363 std::cout <<
"Firmware: " << rs_get_device_firmware_version((
const rs_device *)rs.
getHandler(),
nullptr)
365 std::cout <<
"RealSense sensor characteristics: \n" << rs << std::endl;
369 std::map<rs::stream, bool> enables;
370 std::map<rs::stream, vpRealSense::vpRsStreamParams> params;
372 enables[rs::stream::color] =
false;
373 enables[rs::stream::depth] =
true;
374 enables[rs::stream::infrared] =
false;
378 test_SR300(rs, enables, params,
"SR300_DEPTH_Z16_640x240_110FPS");
380 enables[rs::stream::color] =
true;
381 enables[rs::stream::depth] =
false;
382 enables[rs::stream::infrared] =
false;
386 test_SR300(rs, enables, params,
"SR300_COLOR_RGBA8_1920x1080_30FPS");
388 enables[rs::stream::color] =
false;
389 enables[rs::stream::depth] =
false;
390 enables[rs::stream::infrared] =
true;
394 test_SR300(rs, enables, params,
"SR300_INFRARED_Y16_640x480_200FPS");
396 enables[rs::stream::color] =
false;
397 enables[rs::stream::depth] =
true;
398 enables[rs::stream::infrared] =
false;
402 test_SR300(rs, enables, params,
"SR300_DEPTH_Z16_640x480_60FPS",
true);
404 enables[rs::stream::color] =
false;
405 enables[rs::stream::depth] =
true;
406 enables[rs::stream::infrared] =
true;
411 test_SR300(rs, enables, params,
"SR300_DEPTH_Z16_640x480_60FPS + SR300_INFRARED_Y8_640x480_60FPS",
true);
413 #if (!defined(__APPLE__) && !defined(__MACH__)) // Not OSX, since viewer->spinOnce (10); produces a 416 enables[rs::stream::color] =
true;
417 enables[rs::stream::depth] =
true;
418 enables[rs::stream::infrared] =
true;
427 rs::stream color_stream = argc > 1 ? (rs::stream)atoi(argv[1]) : rs::stream::color;
428 std::cout <<
"\ncolor_stream: " << color_stream << std::endl;
430 rs::stream depth_stream = argc > 2 ? (rs::stream)atoi(argv[2]) : rs::stream::depth;
431 std::cout <<
"depth_stream: " << depth_stream << std::endl;
433 test_SR300(rs, enables, params,
434 "SR300_COLOR_RGBA8_640x480_60FPS + " 435 "SR300_DEPTH_Z16_640x480_60FPS + " 436 "SR300_INFRARED_Y8_640x480_60FPS",
437 true, color_stream, depth_stream,
true,
true);
441 enables[rs::stream::color] =
true;
442 enables[rs::stream::depth] =
true;
443 enables[rs::stream::infrared] =
false;
448 test_SR300(rs, enables, params,
449 "SR300_COLOR_ALIGNED_TO_DEPTH_RGBA8_640x480_30FPS + " 450 "SR300_DEPTH_Z16_640x480_30FPS",
451 true, rs::stream::color_aligned_to_depth);
454 test_SR300(rs, enables, params,
455 "SR300_COLOR_RGBA8_640x480_30FPS + " 456 "SR300_DEPTH_ALIGNED_TO_COLOR_Z16_640x480_30FPS",
457 true, rs::stream::color, rs::stream::depth_aligned_to_color);
459 #if VISP_HAVE_OPENCV_VERSION >= 0x020409 467 cv::Mat color_mat(480, 640, CV_8UC3);
468 cv::Mat infrared_mat(480, 640, CV_8U);
472 rs.
acquire(color_mat.data, NULL, NULL, infrared_mat.data);
474 cv::imshow(
"Color mat", color_mat);
475 cv::imshow(
"Infrared mat", infrared_mat);
476 char c = cv::waitKey(1);
488 std::cerr <<
"RealSense error " << e.
what() << std::endl;
489 }
catch (
const rs::error &e) {
490 std::cerr <<
"RealSense error calling " << e.get_failed_function() <<
"(" << e.get_failed_args()
491 <<
"): " << e.what() << std::endl;
492 }
catch (
const std::exception &e) {
493 std::cerr << e.what() << std::endl;
502 #if !defined(VISP_HAVE_REALSENSE) 503 std::cout <<
"Install librealsense to make this test work." << std::endl;
505 #if !defined(VISP_HAVE_CPP11_COMPATIBILITY) 506 std::cout <<
"Build ViSP with C++11 compiler flag (cmake -DUSE_CPP11=ON) " 507 "to make this test work." 510 #if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI) 511 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)