rs-hdr.cpp
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2020 Intel Corporation. All Rights Reserved.
3 
4 #include <librealsense2/rs.hpp> // Include RealSense Cross Platform API
5 #include "example-imgui.hpp" // Include short list of convenience functions for rendering
6 #include <iostream>
7 
8 
9 // HDR Example demonstrates how to use the HDR feature - only for D400 product line devices
10 int main() try
11 {
12 
14  rs2::device_list devices_list = ctx.query_devices();
15  size_t device_count = devices_list.size();
16  if (!device_count)
17  {
18  std::cout << "No device detected. Is it plugged in?\n";
19  return EXIT_SUCCESS;
20  }
21 
23  bool device_found = false;
24  for (auto&& dev : devices_list)
25  {
26  // finding a device of D400 product line for working with HDR feature
27  if (dev.supports(RS2_CAMERA_INFO_PRODUCT_LINE) &&
28  std::string(dev.get_info(RS2_CAMERA_INFO_PRODUCT_LINE)) == "D400")
29  {
30  device = dev;
31  device_found = true;
32  break;
33  }
34  }
35 
36  if (!device_found)
37  {
38  std::cout << "No device from D400 product line detected. Is it plugged in?\n";
39  return EXIT_SUCCESS;
40  }
41 
42  rs2::depth_sensor depth_sensor = device.query_sensors().front();
43 
44  // disable auto exposure before sending HDR configuration
47 
48  // setting the HDR sequence size to 2 frames
49  if (depth_sensor.supports(RS2_OPTION_SEQUENCE_SIZE))
50  depth_sensor.set_option(RS2_OPTION_SEQUENCE_SIZE, 2);
51  else
52  {
53  std::cout << "Firmware and/or SDK versions must be updated for the HDR feature to be supported.\n";
54  return EXIT_SUCCESS;
55  }
56 
57  // configuring id for this hdr config (value must be in range [0,3])
58  depth_sensor.set_option(RS2_OPTION_SEQUENCE_NAME, 0);
59 
60  // configuration for the first HDR sequence ID
61  depth_sensor.set_option(RS2_OPTION_SEQUENCE_ID, 1);
62  depth_sensor.set_option(RS2_OPTION_EXPOSURE, 8000); // setting exposure to 8000, so sequence 1 will be set to high exposure
63  depth_sensor.set_option(RS2_OPTION_GAIN, 25); // setting gain to 25, so sequence 1 will be set to high gain
64 
65  // configuration for the second HDR sequence ID
66  depth_sensor.set_option(RS2_OPTION_SEQUENCE_ID, 2);
67  depth_sensor.set_option(RS2_OPTION_EXPOSURE, 18); // setting exposure to 18, so sequence 2 will be set to low exposure
68  depth_sensor.set_option(RS2_OPTION_GAIN, 16); // setting gain to 16, so sequence 2 will be set to low gain
69 
70  // turning ON the HDR with the above configuration
71  depth_sensor.set_option(RS2_OPTION_HDR_ENABLED, 1);
72 
73  // Declare depth colorizer for pretty visualization of depth data
74  rs2::colorizer color_map;
75 
76  // Declare RealSense pipeline, encapsulating the actual device and sensors
78 
79  // Start streaming with depth and infrared configuration
80  // The HDR merging algorithm can work with both depth and infrared,or only with depth,
81  // but the resulting stream is better when both depth and infrared are used.
85  pipe.start(cfg);
86 
87  // initializing the merging filter
88  rs2::hdr_merge merging_filter;
89 
90  // initializing the frameset
92 
93  // flag used to see the original stream or the merged one
94  int frames_without_hdr_metadata_params = 0;
95 
96  // init parameters to set view's window
97  unsigned width = 1280;
98  unsigned height = 720;
99  std::string title = "RealSense HDR Example";
100  unsigned tiles_in_row = 4;
101  unsigned tiles_in_col = 2;
102 
103  // init view window
104  window app(width, height, title.c_str(), tiles_in_row, tiles_in_col);
105 
106  // init ImGui with app (window object)
107  ImGui_ImplGlfw_Init(app, false);
108 
109  // init hdr_widgets object
110  // hdr_widgets holds the sliders, the text boxes and the frames_map
111  hdr_widgets hdr_widgets(depth_sensor);
112 
113  while (app) // application is still alive
114  {
115  data = pipe.wait_for_frames(); // Wait for next set of frames from the camera
116 
117  auto frame = data.get_depth_frame();
118 
119  if (!frame.supports_frame_metadata(RS2_FRAME_METADATA_SEQUENCE_SIZE) ||
120  !frame.supports_frame_metadata(RS2_FRAME_METADATA_SEQUENCE_ID))
121  {
122  ++frames_without_hdr_metadata_params;
123  if (frames_without_hdr_metadata_params > 20)
124  {
125  std::cout << "Firmware and/or SDK versions must be updated for the HDR feature to be supported.\n";
126  return EXIT_SUCCESS;
127  }
128  app.show(data.apply_filter(color_map));
129  continue;
130  }
131 
132  // merging the frames from the different HDR sequence IDs
133  auto merged_frame = merging_filter.process(data).apply_filter(color_map); // Find and colorize the depth data;
134 
135  //get frames data
136  auto hdr_seq_size = frame.get_frame_metadata(RS2_FRAME_METADATA_SEQUENCE_SIZE);
137  auto hdr_seq_id = frame.get_frame_metadata(RS2_FRAME_METADATA_SEQUENCE_ID);
138 
139  //get frames
140  auto infrared_frame = data.get_infrared_frame();
141  auto depth_frame = data.get_depth_frame().apply_filter(color_map);
142  auto hdr_frame = merged_frame.as<rs2::frameset>().get_depth_frame().apply_filter(color_map);
143 
144  //update frames in frames map in hdr_widgets
145  hdr_widgets.update_frames_map(infrared_frame, depth_frame, hdr_frame, hdr_seq_id, hdr_seq_size);
146 
147  //render hdr widgets sliders and text boxes
148  hdr_widgets.render_widgets();
149 
150  //the show method, when applied on frame map, break it to frames and upload each frame into its specific tile
151  app.show(hdr_widgets.get_frames_map());
152 
153  }
154 
155  return EXIT_SUCCESS;
156 }
157 catch (const rs2::error& e)
158 {
159  std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() << "):\n " << e.what() << std::endl;
160  return EXIT_FAILURE;
161 }
162 catch (const std::exception& e)
163 {
164  std::cerr << e.what() << std::endl;
165  return EXIT_FAILURE;
166 }
frame apply_filter(filter_interface &filter)
Definition: rs_frame.hpp:593
frameset wait_for_frames(unsigned int timeout_ms=RS2_DEFAULT_TIMEOUT) const
void render_widgets()
std::vector< sensor > query_sensors() const
Definition: rs_device.hpp:25
rs2_metadata_type get_frame_metadata(rs2_frame_metadata_value frame_metadata) const
Definition: rs_frame.hpp:497
device_list query_devices() const
Definition: rs_context.hpp:112
uint32_t size() const
Definition: rs_device.hpp:711
void update_frames_map(const rs2::video_frame &infrared_frame, const rs2::frame &depth_frame, const rs2::frame &hdr_frame, rs2_metadata_type hdr_seq_id, rs2_metadata_type hdr_seq_size)
GLsizei const GLchar *const * string
e
Definition: rmse.py:177
depth_frame get_depth_frame() const
Definition: rs_frame.hpp:1006
const std::string & get_failed_args() const
Definition: rs_types.hpp:117
rs2::frame process(rs2::frame frame) const override
std::ostream & cout()
int main()
Definition: rs-hdr.cpp:10
bool ImGui_ImplGlfw_Init(GLFWwindow *window, bool install_callbacks)
frames_mosaic & get_frames_map()
GLint GLsizei GLsizei height
bool supports(rs2_camera_info info) const
Definition: rs_sensor.hpp:125
void enable_stream(rs2_stream stream_type, int stream_index, int width, int height, rs2_format format=RS2_FORMAT_ANY, int framerate=0)
std::ostream & cerr()
video_frame get_infrared_frame(const size_t index=0) const
Definition: rs_frame.hpp:1032
pipeline_profile start()
GLboolean * data
void set_option(rs2_option option, float value) const
Definition: rs_options.hpp:99
float get_option(rs2_option option) const
Definition: rs_options.hpp:72
auto device
Definition: pyrs_net.cpp:17
const std::string & get_failed_function() const
Definition: rs_types.hpp:112
GLint GLsizei width
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