rs-post-processing.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 "example.hpp" // Include short list of convenience functions for rendering
6 
7 #include <map>
8 #include <string>
9 #include <thread>
10 #include <atomic>
11 
12 #include <imgui.h>
13 #include "imgui_impl_glfw.h"
14 
19 {
23  bool is_int;
24  float value;
26 
27  bool render(const float3& location, bool enabled);
28  static bool is_all_integers(const rs2::option_range& range);
29 };
30 
35 {
36 public:
39  std::string filter_name; //Friendly name of the filter
40  rs2::filter& filter; //The filter in use
41  std::map<rs2_option, filter_slider_ui> supported_options; //maps from an option supported by the filter, to the corresponding slider
42  std::atomic_bool is_enabled; //A boolean controlled by the user that determines whether to apply the filter or not
43 };
44 
45 // Helper functions for rendering the UI
46 void render_ui(float w, float h, std::vector<filter_options>& filters);
47 // Helper function for getting data from the queues and updating the view
49 
50 int main(int argc, char * argv[]) try
51 {
52  // Create a simple OpenGL window for rendering:
53  window app(1280, 720, "RealSense Post Processing Example");
54  ImGui_ImplGlfw_Init(app, false);
55 
56  // Construct objects to manage view state
57  glfw_state original_view_orientation{};
58  glfw_state filtered_view_orientation{};
59 
60  // Declare pointcloud objects, for calculating pointclouds and texture mappings
61  rs2::pointcloud original_pc;
62  rs2::pointcloud filtered_pc;
63 
64  // Declare RealSense pipeline, encapsulating the actual device and sensors
67  // Use a configuration object to request only depth from the pipeline
69  // Start streaming with the above configuration
70  pipe.start(cfg);
71 
72  // Declare filters
73  rs2::decimation_filter dec_filter; // Decimation - reduces depth frame density
74  rs2::threshold_filter thr_filter; // Threshold - removes values outside recommended range
75  rs2::spatial_filter spat_filter; // Spatial - edge-preserving spatial smoothing
76  rs2::temporal_filter temp_filter; // Temporal - reduces temporal noise
77 
78  // Declare disparity transform from depth to disparity and vice versa
79  const std::string disparity_filter_name = "Disparity";
80  rs2::disparity_transform depth_to_disparity(true);
81  rs2::disparity_transform disparity_to_depth(false);
82 
83  // Initialize a vector that holds filters and their options
84  std::vector<filter_options> filters;
85 
86  // The following order of emplacement will dictate the orders in which filters are applied
87  filters.emplace_back("Decimate", dec_filter);
88  filters.emplace_back("Threshold", thr_filter);
89  filters.emplace_back(disparity_filter_name, depth_to_disparity);
90  filters.emplace_back("Spatial", spat_filter);
91  filters.emplace_back("Temporal", temp_filter);
92 
93  // Declaring two concurrent queues that will be used to enqueue and dequeue frames from different threads
94  rs2::frame_queue original_data;
95  rs2::frame_queue filtered_data;
96 
97  // Declare depth colorizer for pretty visualization of depth data
98  rs2::colorizer color_map;
99 
100  // Atomic boolean to allow thread safe way to stop the thread
101  std::atomic_bool stopped(false);
102 
103  // Create a thread for getting frames from the device and process them
104  // to prevent UI thread from blocking due to long computations.
105  std::thread processing_thread([&]() {
106  while (!stopped) //While application is running
107  {
108  rs2::frameset data = pipe.wait_for_frames(); // Wait for next set of frames from the camera
109  rs2::frame depth_frame = data.get_depth_frame(); //Take the depth frame from the frameset
110  if (!depth_frame) // Should not happen but if the pipeline is configured differently
111  return; // it might not provide depth and we don't want to crash
112 
113  rs2::frame filtered = depth_frame; // Does not copy the frame, only adds a reference
114 
115  /* Apply filters.
116  The implemented flow of the filters pipeline is in the following order:
117  1. apply decimation filter
118  2. apply threshold filter
119  3. transform the scene into disparity domain
120  4. apply spatial filter
121  5. apply temporal filter
122  6. revert the results back (if step Disparity filter was applied
123  to depth domain (each post processing block is optional and can be applied independantly).
124  */
125  bool revert_disparity = false;
126  for (auto&& filter : filters)
127  {
128  if (filter.is_enabled)
129  {
130  filtered = filter.filter.process(filtered);
131  if (filter.filter_name == disparity_filter_name)
132  {
133  revert_disparity = true;
134  }
135  }
136  }
137  if (revert_disparity)
138  {
139  filtered = disparity_to_depth.process(filtered);
140  }
141 
142  // Push filtered & original data to their respective queues
143  // Note, pushing to two different queues might cause the application to display
144  // original and filtered pointclouds from different depth frames
145  // To make sure they are synchronized you need to push them together or add some
146  // synchronization mechanisms
147  filtered_data.enqueue(filtered);
148  original_data.enqueue(depth_frame);
149  }
150  });
151 
152 
153  // Declare objects that will hold the calculated pointclouds and colored frames
154  // We save the last set of data to minimize flickering of the view
155  rs2::frame colored_depth;
156  rs2::frame colored_filtered;
157  rs2::points original_points;
158  rs2::points filtered_points;
159 
160 
161  // Save the time of last frame's arrival
162  auto last_time = std::chrono::high_resolution_clock::now();
163  // Maximum angle for the rotation of the pointcloud
164  const double max_angle = 15.0;
165  // We'll use rotation_velocity to rotate the pointcloud for a better view of the filters effects
166  float rotation_velocity = 0.3f;
167 
168  while (app)
169  {
170  float w = static_cast<float>(app.width());
171  float h = static_cast<float>(app.height());
172 
173  // Render the GUI
174  render_ui(w, h, filters);
175 
176  // Try to get new data from the queues and update the view with new texture
177  update_data(original_data, colored_depth, original_points, original_pc, original_view_orientation, color_map);
178  update_data(filtered_data, colored_filtered, filtered_points, filtered_pc, filtered_view_orientation, color_map);
179 
180  draw_text(10, 50, "Original");
181  draw_text(static_cast<int>(w / 2), 50, "Filtered");
182 
183  // Draw the pointclouds of the original and the filtered frames (if the are available already)
184  if (colored_depth && original_points)
185  {
186  glViewport(0, int(h) / 2, int(w) / 2, int(h) / 2);
187  draw_pointcloud(int(w) / 2.f, int(h) / 2.f, original_view_orientation, original_points);
188  }
189  if (colored_filtered && filtered_points)
190  {
191  glViewport(int(w) / 2, int(h) / 2, int(w) / 2, int(h) / 2);
192  draw_pointcloud(int(w) / 2.f, int(h) / 2.f, filtered_view_orientation, filtered_points);
193  }
194  // Update time of current frame's arrival
196 
197  // Time interval which must pass between movement of the pointcloud
198  const std::chrono::milliseconds rotation_delta(40);
199 
200  // In order to calibrate the velocity of the rotation to the actual displaying speed, rotate
201  // pointcloud only when enough time has passed between frames
202  if (curr - last_time > rotation_delta)
203  {
204  if (fabs(filtered_view_orientation.yaw) > max_angle)
205  {
206  rotation_velocity = -rotation_velocity;
207  }
208  original_view_orientation.yaw += rotation_velocity;
209  filtered_view_orientation.yaw += rotation_velocity;
210  last_time = curr;
211  }
212  }
213 
214  // Signal the processing thread to stop, and join
215  // (Not the safest way to join a thread, please wrap your threads in some RAII manner)
216  stopped = true;
217  processing_thread.join();
218 
219  return EXIT_SUCCESS;
220 }
221 catch (const rs2::error & e)
222 {
223  std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() << "):\n " << e.what() << std::endl;
224  return EXIT_FAILURE;
225 }
226 catch (const std::exception& e)
227 {
228  std::cerr << e.what() << std::endl;
229  return EXIT_FAILURE;
230 }
231 
233 {
234  rs2::frame f;
235  if (data.poll_for_frame(&f)) // Try to take the depth and points from the queue
236  {
237  points = pc.calculate(f); // Generate pointcloud from the depth data
238  colorized_depth = color_map.process(f); // Colorize the depth frame with a color map
239  pc.map_to(colorized_depth); // Map the colored depth to the point cloud
240  view.tex.upload(colorized_depth); // and upload the texture to the view (without this the view will be B&W)
241  }
242 }
243 
244 void render_ui(float w, float h, std::vector<filter_options>& filters)
245 {
246  // Flags for displaying ImGui window
247  static const int flags = ImGuiWindowFlags_NoCollapse
253 
255  ImGui::SetNextWindowSize({ w, h });
256  ImGui::Begin("app", nullptr, flags);
257 
258  // Using ImGui library to provide slide controllers for adjusting the filter options
259  const float offset_x = w / 4;
260  const int offset_from_checkbox = 120;
261  float offset_y = h / 2;
262  float elements_margin = 45;
263  for (auto& filter : filters)
264  {
265  // Draw a checkbox per filter to toggle if it should be applied
266  ImGui::SetCursorPos({ offset_x, offset_y });
267  ImGui::PushStyleColor(ImGuiCol_CheckMark, { 40 / 255.f, 170 / 255.f, 90 / 255.f, 1 });
268  bool tmp_value = filter.is_enabled;
269  ImGui::Checkbox(filter.filter_name.c_str(), &tmp_value);
270  filter.is_enabled = tmp_value;
272 
273  if (filter.supported_options.size() == 0)
274  {
275  offset_y += elements_margin;
276  }
277  // Draw a slider for each of the filter's options
278  for (auto& option_slider_pair : filter.supported_options)
279  {
280  filter_slider_ui& slider = option_slider_pair.second;
281  if (slider.render({ offset_x + offset_from_checkbox, offset_y, w / 4 }, filter.is_enabled))
282  {
283  filter.filter.set_option(option_slider_pair.first, slider.value);
284  }
285  offset_y += elements_margin;
286  }
287  }
288 
289  ImGui::End();
290  ImGui::Render();
291 }
292 
294 {
295  bool value_changed = false;
297  ImGui::PushStyleColor(ImGuiCol_SliderGrab, { 40 / 255.f, 170 / 255.f, 90 / 255.f, 1 });
298  ImGui::PushStyleColor(ImGuiCol_SliderGrabActive, { 20 / 255.f, 150 / 255.f, 70 / 255.f, 1 });
300  if (!enabled)
301  {
304  ImGui::PushStyleColor(ImGuiCol_Text, { 0.6f, 0.6f, 0.6f, 1 });
305  }
306 
307  ImGui::PushItemWidth(location.z);
308  ImGui::SetCursorPos({ location.x, location.y + 3 });
309  ImGui::TextUnformatted(label.c_str());
310  if (ImGui::IsItemHovered())
311  ImGui::SetTooltip("%s", description.c_str());
312 
313  ImGui::SetCursorPos({ location.x + 170, location.y });
314 
315  if (is_int)
316  {
317  int value_as_int = static_cast<int>(value);
318  value_changed = ImGui::SliderInt(("##" + name).c_str(), &value_as_int, static_cast<int>(range.min), static_cast<int>(range.max), "%.0f");
319  value = static_cast<float>(value_as_int);
320  }
321  else
322  {
323  value_changed = ImGui::SliderFloat(("##" + name).c_str(), &value, range.min, range.max, "%.3f", 1.0f);
324  }
325 
327 
328  if (!enabled)
329  {
331  }
334  return value_changed;
335 }
336 
341 {
342  const auto is_integer = [](float f)
343  {
344  return (fabs(fmod(f, 1)) < std::numeric_limits<float>::min());
345  };
346 
347  return is_integer(range.min) && is_integer(range.max) &&
348  is_integer(range.def) && is_integer(range.step);
349 }
350 
355  filter_name(name),
356  filter(flt),
357  is_enabled(true)
358 {
359  const std::array<rs2_option, 5> possible_filter_options = {
365  };
366 
367  //Go over each filter option and create a slider for it
368  for (rs2_option opt : possible_filter_options)
369  {
370  if (flt.supports(opt))
371  {
373  supported_options[opt].range = range;
374  supported_options[opt].value = range.def;
376  supported_options[opt].description = flt.get_option_description(opt);
377  std::string opt_name = flt.get_option_name(opt);
378  supported_options[opt].name = name + "_" + opt_name;
379  std::string prefix = "Filter ";
380  supported_options[opt].label = opt_name;
381  }
382  }
383 }
384 
386  filter_name(std::move(other.filter_name)),
387  filter(other.filter),
389  is_enabled(other.is_enabled.load())
390 {
391 }
IMGUI_API void PushStyleVar(ImGuiStyleVar idx, float val)
Definition: imgui.cpp:4650
frameset wait_for_frames(unsigned int timeout_ms=RS2_DEFAULT_TIMEOUT) const
float z
Definition: example.hpp:36
int main(int argc, char *argv[])
bool is_integer(float f)
Definition: rendering.h:1571
IMGUI_API void SetTooltip(const char *fmt,...) IM_PRINTFARGS(1)
Definition: imgui.cpp:3288
GLuint const GLchar * name
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
Definition: rs_option.h:22
filter_options(const std::string name, rs2::filter &filter)
IMGUI_API void SetCursorPos(const ImVec2 &local_pos)
Definition: imgui.cpp:5094
bool render(const float3 &location, bool enabled)
std::atomic_bool is_enabled
GLint location
std::map< rs2_option, filter_slider_ui > supported_options
std::enable_if< std::is_base_of< rs2::frame, T >::value, bool >::type poll_for_frame(T *output) const
GLfloat value
void enqueue(frame f) const
GLint GLint GLsizei GLsizei GLsizei depth
bool supports(rs2_camera_info info) const
void map_to(frame mapped)
GLdouble GLdouble GLdouble w
GLsizei const GLchar *const * string
rs2::option_range range
GLfloat GLfloat GLfloat GLfloat h
Definition: glext.h:1960
e
Definition: rmse.py:177
GLint GLint GLint GLint GLint GLint GLint GLbitfield GLenum filter
IMGUI_API bool SliderInt(const char *label, int *v, int v_min, int v_max, const char *display_format="%.0f", bool render_bg=false)
Definition: imgui.cpp:6687
depth_frame get_depth_frame() const
Definition: rs_frame.hpp:1006
const std::string & get_failed_args() const
Definition: rs_types.hpp:117
GLdouble f
rs2::frame process(rs2::frame frame) const override
rs2::filter & filter
IMGUI_API bool Begin(const char *name, bool *p_open=NULL, ImGuiWindowFlags flags=0)
Definition: imgui.cpp:3772
IMGUI_API void PopStyleVar(int count=1)
Definition: imgui.cpp:4675
IMGUI_API void TextUnformatted(const char *text, const char *text_end=NULL)
Definition: imgui.cpp:5276
const char * get_option_description(rs2_option option) const
Definition: rs_options.hpp:32
const char * get_option_name(rs2_option option) const
Definition: rs_options.hpp:45
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)
points calculate(frame depth) const
IMGUI_API void SetNextWindowSize(const ImVec2 &size, ImGuiSetCond cond=0)
Definition: imgui.cpp:4937
std::string filter_name
GLbitfield flags
GLenum GLenum GLsizei const GLuint GLboolean enabled
IMGUI_API void PushItemWidth(float item_width)
Definition: imgui.cpp:4486
IMGUI_API void End()
Definition: imgui.cpp:4330
float y
Definition: example.hpp:36
void enable_stream(rs2_stream stream_type, int stream_index, int width, int height, rs2_format format=RS2_FORMAT_ANY, int framerate=0)
#define glViewport
IMGUI_API void PushStyleColor(ImGuiCol idx, const ImVec4 &col)
Definition: imgui.cpp:4599
float height() const
Definition: example.hpp:628
static bool is_all_integers(const rs2::option_range &range)
void ImGui_ImplGlfw_NewFrame(float scale_factor)
IMGUI_API bool SliderFloat(const char *label, float *v, float v_min, float v_max, const char *display_format="%.3f", float power=1.0f, bool render_bg=false)
Definition: imgui.cpp:6570
float GrabRounding
Definition: imgui.h:767
void draw_pointcloud(float width, float height, glfw_state &app_state, rs2::points &points)
Definition: example.hpp:886
IMGUI_API void PopItemWidth()
Definition: imgui.cpp:4507
int min(int a, int b)
Definition: lz4s.c:73
GLuint GLsizei const GLchar * label
void draw_text(int x, int y, const char *text)
Definition: example.hpp:109
IMGUI_API bool Checkbox(const char *label, bool *v)
Definition: imgui.cpp:7269
typename::boost::move_detail::remove_reference< T >::type && move(T &&t) BOOST_NOEXCEPT
std::ostream & cerr()
GLsizei range
option_range get_option_range(rs2_option option) const
Definition: rs_options.hpp:84
IMGUI_API ImGuiStyle & GetStyle()
Definition: imgui.cpp:2019
pipeline_profile start()
texture tex
Definition: example.hpp:882
IMGUI_API bool IsItemHovered()
Definition: imgui.cpp:3200
const std::string & get_failed_function() const
Definition: rs_types.hpp:112
Definition: parser.hpp:150
GLdouble GLdouble GLint GLint const GLdouble * points
float x
Definition: example.hpp:36
IMGUI_API void Render()
Definition: imgui.cpp:2619
void render_ui(float w, float h, std::vector< filter_options > &filters)
IMGUI_API void PopStyleColor(int count=1)
Definition: imgui.cpp:4609
void update_data(rs2::frame_queue &data, rs2::frame &depth, rs2::points &points, rs2::pointcloud &pc, glfw_state &view, rs2::colorizer &color_map)


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