rs-measure.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 <librealsense2/rsutil.h>
6 #include "example.hpp" // Include short list of convenience functions for rendering
7 
8 // This example will require several standard data-structures and algorithms:
9 #define _USE_MATH_DEFINES
10 #include <math.h>
11 #include <queue>
12 #include <unordered_set>
13 #include <map>
14 #include <thread>
15 #include <atomic>
16 #include <mutex>
17 
18 using pixel = std::pair<int, int>;
19 
20 // Distance 3D is used to calculate real 3D distance between two pixels
21 float dist_3d(const rs2::depth_frame& frame, pixel u, pixel v);
22 
23 // Toggle helper class will be used to render the two buttons
24 // controlling the edges of our ruler
25 struct toggle
26 {
27  toggle() : x(0.f), y(0.f) {}
28  toggle(float xl, float yl)
29  : x(std::min(std::max(xl, 0.f), 1.f)),
30  y(std::min(std::max(yl, 0.f), 1.f))
31  {}
32 
33  // Move from [0,1] space to pixel space of specific frame
35  {
36  int px = static_cast<int>(x * frm.get_width());
37  int py = static_cast<int>(y * frm.get_height());
38  return{ px, py };
39  }
40 
41  void render(const window& app)
42  {
43  glColor4f(0.f, 0.0f, 0.0f, 0.2f);
44  render_circle(app, 10);
45  render_circle(app, 8);
46  glColor4f(1.f, 0.9f, 1.0f, 1.f);
47  render_circle(app, 6);
48  }
49 
50  void render_circle(const window& app, float r)
51  {
52  const float segments = 16;
54  for (auto i = 0; i <= segments; i++)
55  {
56  auto t = 2 * PI_FL * float(i) / segments;
57 
58  glVertex2f(x * app.width() + cos(t) * r,
59  y * app.height() + sin(t) * r);
60 
61  glVertex2f(x * app.width(),
62  y * app.height());
63  }
64  glEnd();
65  }
66 
67  // This helper function is used to find the button
68  // closest to the mouse cursor
69  // Since we are only comparing this distance, sqrt can be safely skipped
70  float dist_2d(const toggle& other) const
71  {
72  return static_cast<float>(pow(x - other.x, 2) + pow(y - other.y, 2));
73  }
74 
75  float x;
76  float y;
77  bool selected = false;
78 };
79 
80 // Application state shared between the main-thread and GLFW events
81 struct state
82 {
83  bool mouse_down = false;
86 };
87 
88 // Helper function to register to UI events
89 void register_glfw_callbacks(window& app, state& app_state);
90 
91 // Distance rendering functions:
92 
93 // Simple distance is the classic pythagorean distance between 3D points
94 // This distance ignores the topology of the object and can cut both through
95 // air and through solid
97  const state& s,
98  const window& app);
99 
100 int main(int argc, char * argv[]) try
101 {
102  // OpenGL textures for the color and depth frames
104 
105  // Colorizer is used to visualize depth data
106  rs2::colorizer color_map;
107  // Use black to white color map
108  color_map.set_option(RS2_OPTION_COLOR_SCHEME, 2.f);
109  // Decimation filter reduces the amount of data (while preserving best samples)
111  // If the demo is too slow, make sure you run in Release (-DCMAKE_BUILD_TYPE=Release)
112  // but you can also increase the following parameter to decimate depth more (reducing quality)
114  // Define transformations from and to Disparity domain
115  rs2::disparity_transform depth2disparity;
116  rs2::disparity_transform disparity2depth(false);
117  // Define spatial filter (edge-preserving)
118  rs2::spatial_filter spat;
119  // Enable hole-filling
120  // Hole filling is an agressive heuristic and it gets the depth wrong many times
121  // However, this demo is not built to handle holes
122  // (the shortest-path will always prefer to "cut" through the holes since they have zero 3D distance)
123  spat.set_option(RS2_OPTION_HOLES_FILL, 5); // 5 = fill all the zero pixels
124  // Define temporal filter
126  // Spatially align all streams to depth viewport
127  // We do this because:
128  // a. Usually depth has wider FOV, and we only really need depth for this demo
129  // b. We don't want to introduce new holes
131 
132  // Declare RealSense pipeline, encapsulating the actual device and sensors
134 
136  cfg.enable_stream(RS2_STREAM_DEPTH); // Enable default depth
137  // For the color stream, set format to RGBA
138  // To allow blending of the color frame on top of the depth frame
140  auto profile = pipe.start(cfg);
141 
142  auto sensor = profile.get_device().first<rs2::depth_sensor>();
143 
144  // Set the device to High Accuracy preset of the D400 stereoscopic cameras
146  {
148  }
149 
150  auto stream = profile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();
151 
152  // Create a simple OpenGL window for rendering:
153  window app(stream.width(), stream.height(), "RealSense Measure Example");
154 
155  // Define application state and position the ruler buttons
156  state app_state;
157  app_state.ruler_start = { 0.45f, 0.5f };
158  app_state.ruler_end = { 0.55f, 0.5f };
159  register_glfw_callbacks(app, app_state);
160 
161  // After initial post-processing, frames will flow into this queue:
162  rs2::frame_queue postprocessed_frames;
163 
164  // Alive boolean will signal the worker threads to finish-up
165  std::atomic_bool alive{ true };
166 
167  // Video-processing thread will fetch frames from the camera,
168  // apply post-processing and send the result to the main thread for rendering
169  // It recieves synchronized (but not spatially aligned) pairs
170  // and outputs synchronized and aligned pairs
171  std::thread video_processing_thread([&]() {
172  while (alive)
173  {
174  // Fetch frames from the pipeline and send them for processing
176  if (pipe.poll_for_frames(&data))
177  {
178  // First make the frames spatially aligned
179  data = data.apply_filter(align_to);
180 
181  // Decimation will reduce the resultion of the depth image,
182  // closing small holes and speeding-up the algorithm
183  data = data.apply_filter(dec);
184 
185  // To make sure far-away objects are filtered proportionally
186  // we try to switch to disparity domain
187  data = data.apply_filter(depth2disparity);
188 
189  // Apply spatial filtering
190  data = data.apply_filter(spat);
191 
192  // Apply temporal filtering
193  data = data.apply_filter(temp);
194 
195  // If we are in disparity domain, switch back to depth
196  data = data.apply_filter(disparity2depth);
197 
199  data = data.apply_filter(color_map);
200 
201  // Send resulting frames for visualization in the main thread
202  postprocessed_frames.enqueue(data);
203  }
204  }
205  });
206 
207  rs2::frameset current_frameset;
208  while(app) // Application still alive?
209  {
210  // Fetch the latest available post-processed frameset
211  postprocessed_frames.poll_for_frame(&current_frameset);
212 
213  if (current_frameset)
214  {
215  auto depth = current_frameset.get_depth_frame();
216  auto color = current_frameset.get_color_frame();
217  auto colorized_depth = current_frameset.first(RS2_STREAM_DEPTH, RS2_FORMAT_RGB8);
218 
220  // Use the Alpha channel for blending
222 
223  // First render the colorized depth image
224  depth_image.render(colorized_depth, { 0, 0, app.width(), app.height() });
225 
226  // Render the color frame (since we have selected RGBA format
227  // pixels out of FOV will appear transparent)
228  color_image.render(color, { 0, 0, app.width(), app.height() });
229 
230  // Render the simple pythagorean distance
231  render_simple_distance(depth, app_state, app);
232 
233  // Render the ruler
234  app_state.ruler_start.render(app);
235  app_state.ruler_end.render(app);
236 
237  glColor3f(1.f, 1.f, 1.f);
239  }
240  }
241 
242  // Signal threads to finish and wait until they do
243  alive = false;
244  video_processing_thread.join();
245 
246  return EXIT_SUCCESS;
247 }
248 catch (const rs2::error & e)
249 {
250  std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() << "):\n " << e.what() << std::endl;
251  return EXIT_FAILURE;
252 }
253 catch (const std::exception& e)
254 {
255  std::cerr << e.what() << std::endl;
256  return EXIT_FAILURE;
257 }
258 
259 float dist_3d(const rs2::depth_frame& frame, pixel u, pixel v)
260 {
261  float upixel[2]; // From pixel
262  float upoint[3]; // From point (in 3D)
263 
264  float vpixel[2]; // To pixel
265  float vpoint[3]; // To point (in 3D)
266 
267  // Copy pixels into the arrays (to match rsutil signatures)
268  upixel[0] = static_cast<float>(u.first);
269  upixel[1] = static_cast<float>(u.second);
270  vpixel[0] = static_cast<float>(v.first);
271  vpixel[1] = static_cast<float>(v.second);
272 
273  // Query the frame for distance
274  // Note: this can be optimized
275  // It is not recommended to issue an API call for each pixel
276  // (since the compiler can't inline these)
277  // However, in this example it is not one of the bottlenecks
278  auto udist = frame.get_distance(static_cast<int>(upixel[0]), static_cast<int>(upixel[1]));
279  auto vdist = frame.get_distance(static_cast<int>(vpixel[0]), static_cast<int>(vpixel[1]));
280 
281  // Deproject from pixel to point in 3D
282  rs2_intrinsics intr = frame.get_profile().as<rs2::video_stream_profile>().get_intrinsics(); // Calibration data
283  rs2_deproject_pixel_to_point(upoint, &intr, upixel, udist);
284  rs2_deproject_pixel_to_point(vpoint, &intr, vpixel, vdist);
285 
286  // Calculate euclidean distance between the two points
287  return sqrt(pow(upoint[0] - vpoint[0], 2.f) +
288  pow(upoint[1] - vpoint[1], 2.f) +
289  pow(upoint[2] - vpoint[2], 2.f));
290 }
291 
292 void draw_line(float x0, float y0, float x1, float y1, int width)
293 {
295  glLineStipple(1, 0x00ff);
297  glLineWidth(static_cast<float>(width));
299  glVertex2f(x0, y0);
300  glVertex2f(x1, y1);
301  glEnd();
302  glPopAttrib();
303 }
304 
306  const state& s,
307  const window& app)
308 {
309  pixel center;
310 
311  glColor4f(0.f, 0.0f, 0.0f, 0.2f);
312  draw_line(s.ruler_start.x * app.width(),
313  s.ruler_start.y * app.height(),
314  s.ruler_end.x * app.width(),
315  s.ruler_end.y * app.height(), 9);
316 
317  glColor4f(0.f, 0.0f, 0.0f, 0.3f);
318  draw_line(s.ruler_start.x * app.width(),
319  s.ruler_start.y * app.height(),
320  s.ruler_end.x * app.width(),
321  s.ruler_end.y * app.height(), 7);
322 
323  glColor4f(1.f, 1.0f, 1.0f, 1.f);
324  draw_line(s.ruler_start.x * app.width(),
325  s.ruler_start.y * app.height(),
326  s.ruler_end.x * app.width(),
327  s.ruler_end.y * app.height(), 3);
328 
329  auto from_pixel = s.ruler_start.get_pixel(depth);
330  auto to_pixel = s.ruler_end.get_pixel(depth);
331  float air_dist = dist_3d(depth, from_pixel, to_pixel);
332 
333  center.first = (from_pixel.first + to_pixel.first) / 2;
334  center.second = (from_pixel.second + to_pixel.second) / 2;
335 
336  std::stringstream ss;
337  ss << int(air_dist * 100) << " cm";
338  auto str = ss.str();
339  auto x = (float(center.first) / depth.get_width()) * app.width() + 15;
340  auto y = (float(center.second) / depth.get_height()) * app.height() + 15;
341 
342  auto w = stb_easy_font_width((char*)str.c_str());
343 
344  // Draw dark background for the text label
345  glColor4f(0.f, 0.f, 0.f, 0.4f);
347  glVertex2f(x - 3, y - 10);
348  glVertex2f(x + w + 2, y - 10);
349  glVertex2f(x + w + 2, y + 2);
350  glVertex2f(x + w + 2, y + 2);
351  glVertex2f(x - 3, y + 2);
352  glVertex2f(x - 3, y - 10);
353  glEnd();
354 
355  // Draw white text label
356  glColor4f(1.f, 1.f, 1.f, 1.f);
357  draw_text(static_cast<int>(x), static_cast<int>(y), str.c_str());
358 }
359 
360 // Implement drag & drop behavior for the buttons:
361 void register_glfw_callbacks(window& app, state& app_state)
362 {
363  app.on_left_mouse = [&](bool pressed)
364  {
365  app_state.mouse_down = pressed;
366  };
367 
368  app.on_mouse_move = [&](double x, double y)
369  {
370  toggle cursor{ float(x) / app.width(), float(y) / app.height() };
371  std::vector<toggle*> toggles{
372  &app_state.ruler_start,
373  &app_state.ruler_end };
374 
375  if (app_state.mouse_down)
376  {
377  toggle* best = toggles.front();
378  for (auto&& t : toggles)
379  {
380  if (t->dist_2d(cursor) < best->dist_2d(cursor))
381  {
382  best = t;
383  }
384  }
385  best->selected = true;
386  }
387  else
388  {
389  for (auto&& t : toggles) t->selected = false;
390  }
391 
392  for (auto&& t : toggles)
393  {
394  if (t->selected) *t = cursor;
395  }
396  };
397 }
398 
float dist_3d(const rs2::depth_frame &frame, pixel u, pixel v)
Definition: rs-measure.cpp:259
frame apply_filter(filter_interface &filter)
Definition: rs_frame.hpp:593
std::function< void(bool)> on_left_mouse
Definition: example.hpp:501
bool mouse_down
Definition: rs-measure.cpp:83
GLint y
#define glLineStipple
void render(const rs2::frame &frame, const rect &rect, float alpha=1.f)
Definition: example.hpp:471
GLdouble s
void render_circle(const window &app, float r)
Definition: rs-measure.cpp:50
#define GL_TRIANGLE_STRIP
#define glBegin
GLuint color
std::enable_if< std::is_base_of< rs2::frame, T >::value, bool >::type poll_for_frame(T *output) const
stream_profile get_profile() const
Definition: rs_frame.hpp:557
void enqueue(frame f) const
#define glPushAttrib
GLint GLint GLsizei GLsizei GLsizei depth
pixel get_pixel(rs2::depth_frame frm) const
Definition: rs-measure.cpp:34
void draw_line(float x0, float y0, float x1, float y1, int width)
Definition: rs-measure.cpp:292
GLdouble GLdouble GLdouble w
#define GL_BLEND
GLuint GLuint stream
Definition: glext.h:1790
#define glColor4f
#define GL_SRC_ALPHA
e
Definition: rmse.py:177
#define glEnable
The texture class.
Definition: example.hpp:402
#define PI_FL
Definition: example.hpp:25
GLdouble t
#define GL_LINE_STIPPLE
const std::string & get_failed_args() const
Definition: rs_types.hpp:117
GLdouble f
toggle ruler_end
Definition: rs-measure.cpp:85
bool poll_for_frames(frameset *f) const
float y
Definition: rs-measure.cpp:76
static void rs2_deproject_pixel_to_point(float point[3], const struct rs2_intrinsics *intrin, const float pixel[2], float depth)
Definition: rsutil.h:83
void render(const window &app)
Definition: rs-measure.cpp:41
GLdouble GLdouble r
void register_glfw_callbacks(window &app, state &app_state)
Definition: rs-measure.cpp:361
GLdouble x
float width() const
Definition: example.hpp:627
#define glLineWidth
GLuint GLfloat x0
Definition: glext.h:9721
toggle ruler_start
Definition: rs-measure.cpp:84
float dist_2d(const toggle &other) const
Definition: rs-measure.cpp:70
#define glEnd
#define GL_ENABLE_BIT
void enable_stream(rs2_stream stream_type, int stream_index, int width, int height, rs2_format format=RS2_FORMAT_ANY, int framerate=0)
#define GL_ONE_MINUS_SRC_ALPHA
float height() const
Definition: example.hpp:628
GLuint GLfloat GLfloat GLfloat x1
Definition: glext.h:9721
float get_distance(int x, int y) const
Definition: rs_frame.hpp:833
#define glColor3f
static int stb_easy_font_width(char *text)
int get_height() const
Definition: rs_frame.hpp:671
int min(int a, int b)
Definition: lz4s.c:73
#define glPopAttrib
void draw_text(int x, int y, const char *text)
Definition: example.hpp:109
GLuint GLfloat GLfloat y0
Definition: glext.h:9721
Video stream intrinsics.
Definition: rs_types.h:58
std::ostream & cerr()
#define GL_LINE_STRIP
int main(int argc, char *argv[])
Definition: rs-measure.cpp:100
bool selected
Definition: rs-measure.cpp:77
GLuint segments
Definition: glext.h:9587
toggle(float xl, float yl)
Definition: rs-measure.cpp:28
int i
#define glVertex2f
float x
Definition: rs-measure.cpp:75
pipeline_profile start()
#define glBlendFunc
std::function< void(double, double)> on_mouse_move
Definition: example.hpp:503
GLboolean * data
void set_option(rs2_option option, float value) const
Definition: rs_options.hpp:99
GLdouble v
int get_width() const
Definition: rs_frame.hpp:659
GLdouble y1
const std::string & get_failed_function() const
Definition: rs_types.hpp:112
void render_simple_distance(const rs2::depth_frame &depth, const state &s, const window &app)
Definition: rs-measure.cpp:305
GLint GLsizei width
#define GL_TRIANGLES
#define glDisable


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