rs-align-advanced.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>
5 #include "example-imgui.hpp"
6 
7 #include <sstream>
8 #include <iostream>
9 #include <fstream>
10 #include <algorithm>
11 #include <cstring>
12 
13 void render_slider(rect location, float& clipping_dist);
14 void remove_background(rs2::video_frame& other, const rs2::depth_frame& depth_frame, float depth_scale, float clipping_dist);
16 rs2_stream find_stream_to_align(const std::vector<rs2::stream_profile>& streams);
17 bool profile_changed(const std::vector<rs2::stream_profile>& current, const std::vector<rs2::stream_profile>& prev);
18 
19 int main(int argc, char * argv[]) try
20 {
21  // Create and initialize GUI related objects
22  window app(1280, 720, "RealSense Align (Advanced) Example"); // Simple window handling
23  ImGui_ImplGlfw_Init(app, false); // ImGui library intializition
24  rs2::colorizer c; // Helper to colorize depth images
25  texture renderer; // Helper for renderig images
26 
27  // Create a pipeline to easily configure and start the camera
29  //Calling pipeline's start() without any additional parameters will start the first device
30  // with its default streams.
31  //The start function returns the pipeline profile which the pipeline used to start the device
33 
34  // Each depth camera might have different units for depth pixels, so we get it here
35  // Using the pipeline's profile, we can retrieve the device that the pipeline uses
36  float depth_scale = get_depth_scale(profile.get_device());
37 
38  //Pipeline could choose a device that does not have a color stream
39  //If there is no color stream, choose to align depth to another stream
41 
42  // Create a rs2::align object.
43  // rs2::align allows us to perform alignment of depth frames to others frames
44  //The "align_to" is the stream type to which we plan to align depth frames.
45  rs2::align align(align_to);
46 
47  // Define a variable for controlling the distance to clip
48  float depth_clipping_distance = 1.f;
49 
50  while (app) // Application still alive?
51  {
52  // Using the align object, we block the application until a frameset is available
53  rs2::frameset frameset = pipe.wait_for_frames();
54 
55  // rs2::pipeline::wait_for_frames() can replace the device it uses in case of device error or disconnection.
56  // Since rs2::align is aligning depth to some other stream, we need to make sure that the stream was not changed
57  // after the call to wait_for_frames();
59  {
60  //If the profile was changed, update the align object, and also get the new device's depth scale
61  profile = pipe.get_active_profile();
62  align_to = find_stream_to_align(profile.get_streams());
63  align = rs2::align(align_to);
64  depth_scale = get_depth_scale(profile.get_device());
65  }
66 
67  //Get processed aligned frame
68  auto processed = align.process(frameset);
69 
70  // Trying to get both other and aligned depth frames
71  rs2::video_frame other_frame = processed.first(align_to);
72  rs2::depth_frame aligned_depth_frame = processed.get_depth_frame();
73 
74  //If one of them is unavailable, continue iteration
75  if (!aligned_depth_frame || !other_frame)
76  {
77  continue;
78  }
79  // Passing both frames to remove_background so it will "strip" the background
80  // NOTE: in this example, we alter the buffer of the other frame, instead of copying it and altering the copy
81  // This behavior is not recommended in real application since the other frame could be used elsewhere
82  remove_background(other_frame, aligned_depth_frame, depth_scale, depth_clipping_distance);
83 
84  // Taking dimensions of the window for rendering purposes
85  float w = static_cast<float>(app.width());
86  float h = static_cast<float>(app.height());
87 
88  // At this point, "other_frame" is an altered frame, stripped form its background
89  // Calculating the position to place the frame in the window
90  rect altered_other_frame_rect{ 0, 0, w, h };
91  altered_other_frame_rect = altered_other_frame_rect.adjust_ratio({ static_cast<float>(other_frame.get_width()),static_cast<float>(other_frame.get_height()) });
92 
93  // Render aligned image
94  renderer.render(other_frame, altered_other_frame_rect);
95 
96  // The example also renders the depth frame, as a picture-in-picture
97  // Calculating the position to place the depth frame in the window
98  rect pip_stream{ 0, 0, w / 5, h / 5 };
99  pip_stream = pip_stream.adjust_ratio({ static_cast<float>(aligned_depth_frame.get_width()),static_cast<float>(aligned_depth_frame.get_height()) });
100  pip_stream.x = altered_other_frame_rect.x + altered_other_frame_rect.w - pip_stream.w - (std::max(w, h) / 25);
101  pip_stream.y = altered_other_frame_rect.y + (std::max(w, h) / 25);
102 
103  // Render depth (as picture in pipcture)
104  renderer.upload(c.process(aligned_depth_frame));
105  renderer.show(pip_stream);
106 
107  // Using ImGui library to provide a slide controller to select the depth clipping distance
109  render_slider({ 5.f, 0, w, h }, depth_clipping_distance);
110  ImGui::Render();
111 
112  }
113  return EXIT_SUCCESS;
114 }
115 catch (const rs2::error & e)
116 {
117  std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() << "):\n " << e.what() << std::endl;
118  return EXIT_FAILURE;
119 }
120 catch (const std::exception & e)
121 {
122  std::cerr << e.what() << std::endl;
123  return EXIT_FAILURE;
124 }
125 
127 {
128  // Go over the device's sensors
129  for (rs2::sensor& sensor : dev.query_sensors())
130  {
131  // Check if the sensor if a depth sensor
133  {
134  return dpt.get_depth_scale();
135  }
136  }
137  throw std::runtime_error("Device does not have a depth sensor");
138 }
139 
140 void render_slider(rect location, float& clipping_dist)
141 {
142  // Some trickery to display the control nicely
143  static const int flags = ImGuiWindowFlags_NoCollapse
149  const int pixels_to_buttom_of_stream_text = 25;
150  const float slider_window_width = 30;
151 
152  ImGui::SetNextWindowPos({ location.x, location.y + pixels_to_buttom_of_stream_text });
153  ImGui::SetNextWindowSize({ slider_window_width + 20, location.h - (pixels_to_buttom_of_stream_text * 2) });
154 
155  //Render the vertical slider
156  ImGui::Begin("slider", nullptr, flags);
157  ImGui::PushStyleColor(ImGuiCol_FrameBg, ImColor(215.f / 255, 215.0f / 255, 215.0f / 255));
158  ImGui::PushStyleColor(ImGuiCol_SliderGrab, ImColor(215.f / 255, 215.0f / 255, 215.0f / 255));
159  ImGui::PushStyleColor(ImGuiCol_SliderGrabActive, ImColor(215.f / 255, 215.0f / 255, 215.0f / 255));
160  auto slider_size = ImVec2(slider_window_width / 2, location.h - (pixels_to_buttom_of_stream_text * 2) - 20);
161  ImGui::VSliderFloat("", slider_size, &clipping_dist, 0.0f, 6.0f, "", 1.0f, true);
162  if (ImGui::IsItemHovered())
163  ImGui::SetTooltip("Depth Clipping Distance: %.3f", clipping_dist);
165 
166  //Display bars next to slider
167  float bars_dist = (slider_size.y / 6.0f);
168  for (int i = 0; i <= 6; i++)
169  {
170  ImGui::SetCursorPos({ slider_size.x, i * bars_dist });
171  std::string bar_text = "- " + std::to_string(6-i) + "m";
172  ImGui::Text("%s", bar_text.c_str());
173  }
174  ImGui::End();
175 }
176 
177 void remove_background(rs2::video_frame& other_frame, const rs2::depth_frame& depth_frame, float depth_scale, float clipping_dist)
178 {
179  const uint16_t* p_depth_frame = reinterpret_cast<const uint16_t*>(depth_frame.get_data());
180  uint8_t* p_other_frame = reinterpret_cast<uint8_t*>(const_cast<void*>(other_frame.get_data()));
181 
182  int width = other_frame.get_width();
183  int height = other_frame.get_height();
184  int other_bpp = other_frame.get_bytes_per_pixel();
185 
186  #pragma omp parallel for schedule(dynamic) //Using OpenMP to try to parallelise the loop
187  for (int y = 0; y < height; y++)
188  {
189  auto depth_pixel_index = y * width;
190  for (int x = 0; x < width; x++, ++depth_pixel_index)
191  {
192  // Get the depth value of the current pixel
193  auto pixels_distance = depth_scale * p_depth_frame[depth_pixel_index];
194 
195  // Check if the depth value is invalid (<=0) or greater than the threashold
196  if (pixels_distance <= 0.f || pixels_distance > clipping_dist)
197  {
198  // Calculate the offset in other frame's buffer to current pixel
199  auto offset = depth_pixel_index * other_bpp;
200 
201  // Set pixel to "background" color (0x999999)
202  std::memset(&p_other_frame[offset], 0x99, other_bpp);
203  }
204  }
205  }
206 }
207 
208 rs2_stream find_stream_to_align(const std::vector<rs2::stream_profile>& streams)
209 {
210  //Given a vector of streams, we try to find a depth stream and another stream to align depth with.
211  //We prioritize color streams to make the view look better.
212  //If color is not available, we take another stream that (other than depth)
214  bool depth_stream_found = false;
215  bool color_stream_found = false;
216  for (rs2::stream_profile sp : streams)
217  {
218  rs2_stream profile_stream = sp.stream_type();
219  if (profile_stream != RS2_STREAM_DEPTH)
220  {
221  if (!color_stream_found) //Prefer color
222  align_to = profile_stream;
223 
224  if (profile_stream == RS2_STREAM_COLOR)
225  {
226  color_stream_found = true;
227  }
228  }
229  else
230  {
231  depth_stream_found = true;
232  }
233  }
234 
235  if(!depth_stream_found)
236  throw std::runtime_error("No Depth stream available");
237 
238  if (align_to == RS2_STREAM_ANY)
239  throw std::runtime_error("No stream found to align with Depth");
240 
241  return align_to;
242 }
243 
244 bool profile_changed(const std::vector<rs2::stream_profile>& current, const std::vector<rs2::stream_profile>& prev)
245 {
246  for (auto&& sp : prev)
247  {
248  //If previous profile is in current (maybe just added another)
249  auto itr = std::find_if(std::begin(current), std::end(current), [&sp](const rs2::stream_profile& current_sp) { return sp.unique_id() == current_sp.unique_id(); });
250  if (itr == std::end(current)) //If it previous stream wasn't found in current
251  {
252  return true;
253  }
254  }
255  return false;
256 }
frameset wait_for_frames(unsigned int timeout_ms=RS2_DEFAULT_TIMEOUT) const
GLuint GLuint end
GLint y
float h
Definition: example.hpp:73
void render(const rs2::frame &frame, const rect &rect, float alpha=1.f)
Definition: example.hpp:471
IMGUI_API void SetTooltip(const char *fmt,...) IM_PRINTFARGS(1)
Definition: imgui.cpp:3288
std::vector< sensor > query_sensors() const
Definition: rs_device.hpp:25
IMGUI_API void SetCursorPos(const ImVec2 &local_pos)
Definition: imgui.cpp:5094
Definition: imgui.h:88
GLint location
IMGUI_API void SetNextWindowPos(const ImVec2 &pos, ImGuiSetCond cond=0)
Definition: imgui.cpp:4923
int get_bytes_per_pixel() const
Definition: rs_frame.hpp:707
void remove_background(rs2::video_frame &other, const rs2::depth_frame &depth_frame, float depth_scale, float clipping_dist)
const void * get_data() const
Definition: rs_frame.hpp:545
unsigned short uint16_t
Definition: stdint.h:79
GLdouble GLdouble GLdouble w
GLsizei const GLchar *const * string
rect adjust_ratio(float2 size) const
Definition: example.hpp:76
GLfloat GLfloat GLfloat GLfloat h
Definition: glext.h:1960
unsigned char uint8_t
Definition: stdint.h:78
e
Definition: rmse.py:177
void render_slider(rect location, float &clipping_dist)
The texture class.
Definition: example.hpp:402
const std::string & get_failed_args() const
Definition: rs_types.hpp:117
not_this_one begin(...)
GLdouble f
rs2::frame process(rs2::frame frame) const override
IMGUI_API bool Begin(const char *name, bool *p_open=NULL, ImGuiWindowFlags flags=0)
Definition: imgui.cpp:3772
dictionary streams
Definition: t265_stereo.py:140
const GLubyte * c
Definition: glext.h:12690
GLdouble x
float width() const
Definition: example.hpp:627
void upload(const rs2::video_frame &frame)
Definition: example.hpp:406
bool ImGui_ImplGlfw_Init(GLFWwindow *window, bool install_callbacks)
GLint GLsizei GLsizei height
IMGUI_API void SetNextWindowSize(const ImVec2 &size, ImGuiSetCond cond=0)
Definition: imgui.cpp:4937
GLbitfield flags
IMGUI_API void Text(const char *fmt,...) IM_PRINTFARGS(1)
Definition: imgui.cpp:5223
float get_depth_scale(rs2::device dev)
IMGUI_API void End()
Definition: imgui.cpp:4330
rs2_stream
Streams are different types of data provided by RealSense devices.
Definition: rs_sensor.h:42
device get_device() const
Definition: rs_pipeline.hpp:83
IMGUI_API void PushStyleColor(ImGuiCol idx, const ImVec4 &col)
Definition: imgui.cpp:4599
float height() const
Definition: example.hpp:628
rs2_stream find_stream_to_align(const std::vector< rs2::stream_profile > &streams)
Definition: example.hpp:70
void ImGui_ImplGlfw_NewFrame(float scale_factor)
std::vector< stream_profile > get_streams() const
Definition: rs_pipeline.hpp:29
void show(const rect &r, float alpha=1.f) const
Definition: example.hpp:448
int get_height() const
Definition: rs_frame.hpp:671
bool profile_changed(const std::vector< rs2::stream_profile > &current, const std::vector< rs2::stream_profile > &prev)
int main(int argc, char *argv[])
std::ostream & cerr()
int i
int unique_id() const
Definition: rs_frame.hpp:54
pipeline_profile get_active_profile() const
pipeline_profile start()
IMGUI_API bool VSliderFloat(const char *label, const ImVec2 &size, float *v, float v_min, float v_max, const char *display_format="%.3f", float power=1.0f, bool render_bg=false)
Definition: imgui.cpp:6633
float x
Definition: example.hpp:72
int get_width() const
Definition: rs_frame.hpp:659
IMGUI_API bool IsItemHovered()
Definition: imgui.cpp:3200
const std::string & get_failed_function() const
Definition: rs_types.hpp:112
GLint GLsizei width
IMGUI_API void Render()
Definition: imgui.cpp:2619
GLintptr offset
IMGUI_API void PopStyleColor(int count=1)
Definition: imgui.cpp:4609
float y
Definition: example.hpp:72
std::string to_string(T value)


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