rs-imshow.cpp
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2017 Intel Corporation. All Rights Reserved.
3 
4 #include <librealsense2/rs.hpp> // Include RealSense Cross Platform API
5 #include <opencv2/opencv.hpp> // Include OpenCV API
6 
7 int main(int argc, char * argv[]) try
8 {
9  // Declare depth colorizer for pretty visualization of depth data
10  rs2::colorizer color_map;
11 
12  // Declare RealSense pipeline, encapsulating the actual device and sensors
14  // Start streaming with default recommended configuration
15  pipe.start();
16 
17  using namespace cv;
18  const auto window_name = "Display Image";
19  namedWindow(window_name, WINDOW_AUTOSIZE);
20 
21  while (waitKey(1) < 0 && getWindowProperty(window_name, WND_PROP_AUTOSIZE) >= 0)
22  {
23  rs2::frameset data = pipe.wait_for_frames(); // Wait for next set of frames from the camera
24  rs2::frame depth = data.get_depth_frame().apply_filter(color_map);
25 
26  // Query frame size (width and height)
27  const int w = depth.as<rs2::video_frame>().get_width();
28  const int h = depth.as<rs2::video_frame>().get_height();
29 
30  // Create OpenCV matrix of size (w,h) from the colorized depth data
31  Mat image(Size(w, h), CV_8UC3, (void*)depth.get_data(), Mat::AUTO_STEP);
32 
33  // Update the window with new data
34  imshow(window_name, image);
35  }
36 
37  return EXIT_SUCCESS;
38 }
39 catch (const rs2::error & e)
40 {
41  std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() << "):\n " << e.what() << std::endl;
42  return EXIT_FAILURE;
43 }
44 catch (const std::exception& e)
45 {
46  std::cerr << e.what() << std::endl;
47  return EXIT_FAILURE;
48 }
49 
50 
51 
frame apply_filter(filter_interface &filter)
Definition: rs_frame.hpp:593
frameset wait_for_frames(unsigned int timeout_ms=RS2_DEFAULT_TIMEOUT) const
GLint GLint GLsizei GLsizei GLsizei depth
const void * get_data() const
Definition: rs_frame.hpp:545
GLdouble GLdouble GLdouble w
GLfloat GLfloat GLfloat GLfloat h
Definition: glext.h:1960
e
Definition: rmse.py:177
GLenum GLenum GLsizei void * image
depth_frame get_depth_frame() const
Definition: rs_frame.hpp:1006
const std::string & get_failed_args() const
Definition: rs_types.hpp:117
std::ostream & cerr()
int main(int argc, char *argv[])
Definition: rs-imshow.cpp:7
pipeline_profile start()
const std::string & get_failed_function() const
Definition: rs_types.hpp:112
Definition: parser.hpp:150
T as() const
Definition: rs_frame.hpp:580


librealsense2
Author(s): Sergey Dorodnicov , Doron Hirshberg , Mark Horn , Reagan Lopez , Itay Carpis
autogenerated on Mon May 3 2021 02:47:40