unit-tests-common.h
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2015 Intel Corporation. All Rights Reserved.
3 
4 #pragma once
5 #ifndef LIBREALSENSE_UNITTESTS_COMMON_H
6 #define LIBREALSENSE_UNITTESTS_COMMON_H
7 
8 #include "approx.h"
9 #include "../include/librealsense2/rs.hpp"
10 #include "../include/librealsense2/hpp/rs_context.hpp"
11 #include "../include/librealsense2/hpp/rs_internal.hpp"
12 #include <limits> // For std::numeric_limits
13 #include <cmath> // For std::sqrt
14 #include <cassert> // For assert
15 #include <thread> // For std::this_thread::sleep_for
16 #include <map>
17 #include <mutex>
18 #include <condition_variable>
19 #include <atomic>
20 #include <vector>
21 #include <fstream>
22 #include <array>
23 #include "../src/types.h"
24 
25 // noexcept is not accepted by Visual Studio 2013 yet, but noexcept(false) is require on throwing destructors on gcc and clang
26 // It is normally advisable not to throw in a destructor, however, this usage is safe for require_error/require_no_error because
27 // they will only ever be created as temporaries immediately before being passed to a C ABI function. All parameters and return
28 // types are vanilla C types, and thus nothrow-copyable, and the function itself cannot throw because it is a C ABI function.
29 // Therefore, when a temporary require_error/require_no_error is destructed immediately following one of these C ABI function
30 // calls, we should not have any exceptions in flight, and can freely throw (perhaps indirectly by calling Catch's REQUIRE()
31 // macro) to indicate postcondition violations.
32 #ifdef WIN32
33 #define NOEXCEPT_FALSE
34 #else
35 #define NOEXCEPT_FALSE noexcept(false)
36 #endif
37 
38 
39 
41 {
44  int width;
45  int height;
46  int fps;
47  int index;
48 
49  bool operator==(const rs2::video_stream_profile& other) const
50  {
51  return stream == other.stream_type() &&
52  format == other.format() &&
53  width == other.width() &&
54  height == other.height() &&
55  index == other.stream_index();
56  }
57 };
58 
59 struct profile
60 {
63  int width;
64  int height;
65  int index;
66  int fps;
67 
68  bool operator==(const profile& other) const
69  {
70  return stream == other.stream &&
71  (format == 0 || other.format == 0 || format == other.format) &&
72  (width == 0 || other.width == 0 || width == other.width) &&
73  (height == 0 || other.height == 0 || height == other.height) &&
74  (index == 0 || other.index == 0 || index == other.index);
75 
76  }
77  bool operator!=(const profile& other) const
78  {
79  return !(*this == other);
80  }
81  bool operator<(const profile& other) const
82  {
83  return stream < other.stream;
84  }
85 };
86 
87 inline std::ostream& operator <<(std::ostream& stream, const profile& cap)
88 {
89  stream << cap.stream << " " << cap.stream << " " << cap.format << " "
90  << cap.width << " " << cap.height << " " << cap.index << " " << cap.fps;
91  return stream;
92 }
93 
95 {
96  std::vector<profile> streams;
97  int fps;
98  bool sync;
99 };
100 
101 inline std::vector<profile> configure_all_supported_streams(rs2::sensor& sensor, int width = 640, int height = 480, int fps = 60)
102 {
103  std::vector<profile> all_profiles =
104  {
112  { RS2_STREAM_ACCEL, RS2_FORMAT_MOTION_XYZ32F, 1, 1, 0, 200},
113  { RS2_STREAM_GYRO, RS2_FORMAT_MOTION_XYZ32F, 1, 1, 0, 200},
114  };
115 
116  std::vector<profile> profiles;
117  std::vector<rs2::stream_profile> modes;
118  auto all_modes = sensor.get_stream_profiles();
119 
120  for (auto profile : all_profiles)
121  {
122  if (std::find_if(all_modes.begin(), all_modes.end(), [&](rs2::stream_profile p)
123  {
124  if (auto video = p.as<rs2::video_stream_profile>())
125  {
126  if (p.fps() == profile.fps &&
127  p.stream_index() == profile.index &&
128  p.stream_type() == profile.stream &&
129  p.format() == profile.format &&
130  video.width() == profile.width &&
131  video.height() == profile.height)
132  {
133  modes.push_back(p);
134  return true;
135  }
136  }
137  else
138  {
139  if (auto motion = p.as<rs2::motion_stream_profile>())
140  {
141  if (((profile.fps / (p.fps()+1)) <= 2.f) && // Approximate IMU rates. No need for being exact
142  p.stream_index() == profile.index &&
143  p.stream_type() == profile.stream &&
144  p.format() == profile.format)
145  {
146  modes.push_back(p);
147  return true;
148  }
149  }
150  else
151  return false;
152  }
153 
154  return false;
155  }) != all_modes.end())
156  {
157  profiles.push_back(profile);
158 
159  }
160  }
161  if (modes.size() > 0)
162  REQUIRE_NOTHROW(sensor.open(modes));
163  return profiles;
164 }
165 
166 inline std::pair<std::vector<rs2::sensor>, std::vector<profile>> configure_all_supported_streams(rs2::device& dev, int width = 640, int height = 480, int fps = 30)
167 {
168  std::vector<profile> profiles;
169  std::vector<rs2::sensor> sensors;
170  auto sens = dev.query_sensors();
171  for (auto s : sens)
172  {
174  profiles.insert(profiles.end(), res.begin(), res.end());
175  if (res.size() > 0)
176  {
177  sensors.push_back(s);
178  }
179  }
180 
181  return{ sensors, profiles };
182 }
183 
185  const std::string from = " ";
186  const std::string to = "__";
187  auto temp = text;
188  size_t start_pos = 0;
189  while ((start_pos = temp.find(from, start_pos)) != std::string::npos) {
190  temp.replace(start_pos, from.size(), to);
191  start_pos += to.size();
192  }
193  return temp;
194 }
195 
196 #define SECTION_FROM_TEST_NAME space_to_underscore(Catch::getCurrentContext().getResultCapture()->getCurrentTestName()).c_str()
197 
198 //inline long long current_time()
199 //{
200 // return (std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch()).count() % 10000);
201 //}
202 
206 {
209 
212 
215 
216  if (sen.supports(RS2_OPTION_EXPOSURE))
217  {
219  REQUIRE_NOTHROW(range = sen.get_option_range(RS2_OPTION_EXPOSURE)); // TODO: fails sometimes with "Element Not Found!"
220  //float val = (range.min + (range.def-range.min)/10.f); // TODO - generate new records using the modified exposure
221 
223  }
224 }
225 
227 {
228  for (auto&& s : dev.query_sensors())
230 }
231 
232 inline bool wait_for_reset(std::function<bool(void)> func, std::shared_ptr<rs2::device> dev)
233 {
234  if (func())
235  return true;
236 
237  WARN("Reset workaround");
238 
239  try {
240  dev->hardware_reset();
241  }
242  catch (...)
243  {
244  }
245  return func();
246 }
247 
248 inline bool is_usb3(const rs2::device& dev)
249 {
250  bool usb3_device = true;
251  try
252  {
254  // Device types "3.x" and also "" (for legacy playback records) will be recognized as USB3
255  usb3_device = (std::string::npos == usb_type.find("2."));
256  }
257  catch (...) // In case the feature not provided assume USB3 device
258  {
259  }
260 
261  return usb3_device;
262 }
263 
264 // Provides for Device PID , USB3/2 (true/false)
265 typedef std::pair<std::string, bool > dev_type;
266 
267 inline dev_type get_PID(rs2::device& dev)
268 {
269  dev_type designator{ "",true };
271  bool usb_descriptor = false;
272 
273  REQUIRE_NOTHROW(designator.first = dev.get_info(RS2_CAMERA_INFO_PRODUCT_ID));
275  if (usb_descriptor)
276  {
278  designator.second = (std::string::npos == usb_type.find("2."));
279  }
280 
281  return designator;
282 }
283 
285 {
286 public:
287  command_line_params(int argc, char * const argv[])
288  {
289  for (auto i = 0; i < argc; i++)
290  {
291  _params.push_back(argv[i]);
292  }
293  }
294 
295  char * const * get_argv() const { return _params.data(); }
296  char * get_argv(int i) const { return _params[i]; }
297  size_t get_argc() const { return _params.size(); }
298 
299  static command_line_params& instance(int argc = 0, char * const argv[] = 0)
300  {
301  static command_line_params params(argc, argv);
302  return params;
303  }
304 
305  bool _found_any_section = false;
306 private:
307 
308  std::vector<char*> _params;
309 };
310 
311 inline bool file_exists(const std::string& filename)
312 {
313  std::ifstream f(filename);
314  return f.good();
315 }
316 
317 inline bool make_context(const char* id, rs2::context* ctx, std::string min_api_version = "0.0.0")
318 {
320 
321  static std::map<std::string, int> _counters;
322 
323  _counters[id]++;
324 
325  auto argc = command_line_params::instance().get_argc();
326  auto argv = command_line_params::instance().get_argv();
327 
328 
329  std::string base_filename;
330  bool record = false;
331  bool playback = false;
332  for (auto i = 0u; i < argc; i++)
333  {
334  std::string param(argv[i]);
335  if (param == "into")
336  {
337  i++;
338  if (i < argc)
339  {
340  base_filename = argv[i];
341  record = true;
342  }
343  }
344  else if (param == "from")
345  {
346  i++;
347  if (i < argc)
348  {
349  base_filename = argv[i];
350  playback = true;
351  }
352  }
353  }
354 
355  std::stringstream ss;
356  ss << id << "." << _counters[id] << ".test";
357  auto section = ss.str();
358 
359 
360  try
361  {
362  if (record)
363  {
364  *ctx = rs2::recording_context(base_filename, section);
365  }
366  else if (playback)
367  {
368  *ctx = rs2::mock_context(base_filename, section, min_api_version);
369  }
371  return true;
372  }
373  catch (...)
374  {
375  return false;
376  }
377 
378 }
379 
380 // Can be passed to rs2_error ** parameters, requires that an error is indicated with the specific provided message
382 {
384  bool validate_error_message; // Messages content may vary , subject to backend selection
386 public:
387  require_error(std::string message, bool message_validation = true) : message(move(message)), validate_error_message(message_validation), err() {}
388  require_error(const require_error &) = delete;
390  {
391  assert(!std::uncaught_exception());
392  REQUIRE(err != nullptr);
393  if (validate_error_message)
394  {
395  REQUIRE(rs2_get_error_message(err) == std::string(message));
396  }
397  }
398  require_error & operator = (const require_error &) = delete;
399  operator rs2_error ** () { return &err; }
400 };
401 
402 // Can be passed to rs2_error ** parameters, requires that no error is indicated
404 {
406 public:
407  require_no_error() : err() {}
408  require_no_error(const require_error &) = delete;
410  {
411  assert(!std::uncaught_exception());
412  REQUIRE(rs2_get_error_message(err) == rs2_get_error_message(nullptr)); // Perform this check first. If an error WAS indicated, Catch will display it, making our debugging easier.
413  REQUIRE(err == nullptr);
414  }
415  require_no_error & operator = (const require_no_error &) = delete;
416  operator rs2_error ** () { return &err; }
417 };
418 
419 // Compute dot product of a and b
420 inline float dot_product(const float(&a)[3], const float(&b)[3])
421 {
422  return a[0] * b[0] + a[1] * b[1] + a[2] * b[2];
423 }
424 
425 // Compute length of v
426 inline float vector_length(const float(&v)[3])
427 {
428  return std::sqrt(dot_product(v, v));
429 }
430 
431 // Require that r = cross(a, b)
432 inline void require_cross_product(const float(&r)[3], const float(&a)[3], const float(&b)[3])
433 {
434  REQUIRE(r[0] == approx(a[1] * b[2] - a[2] * b[1]));
435  REQUIRE(r[1] == approx(a[2] * b[0] - a[0] * b[2]));
436  REQUIRE(r[2] == approx(a[0] * b[1] - a[1] * b[0]));
437 }
438 
439 // Require that vector is exactly the zero vector
440 inline void require_zero_vector(const float(&vector)[3])
441 {
442  for (int i = 1; i < 3; ++i) REQUIRE(vector[i] == 0.0f);
443 }
444 
445 // Require that a == transpose(b)
446 inline void require_transposed(const float(&a)[9], const float(&b)[9])
447 {
448  REQUIRE(a[0] == approx(b[0]));
449  REQUIRE(a[1] == approx(b[3]));
450  REQUIRE(a[2] == approx(b[6]));
451  REQUIRE(a[3] == approx(b[1]));
452  REQUIRE(a[4] == approx(b[4]));
453  REQUIRE(a[5] == approx(b[7]));
454  REQUIRE(a[6] == approx(b[2]));
455  REQUIRE(a[7] == approx(b[5]));
456  REQUIRE(a[8] == approx(b[8]));
457 }
458 
459 // Require that matrix is an orthonormal 3x3 matrix
460 inline void require_rotation_matrix(const float(&matrix)[9])
461 {
462  const float row0[] = { matrix[0], matrix[3], matrix[6] };
463  const float row1[] = { matrix[1], matrix[4], matrix[7] };
464  const float row2[] = { matrix[2], matrix[5], matrix[8] };
465  CAPTURE( full_precision( row0[0] ));
466  CAPTURE( full_precision( row0[1] ));
467  CAPTURE( full_precision( row0[2] ));
468  CAPTURE( full_precision( row1[0] ));
469  CAPTURE( full_precision( row1[1] ));
470  CAPTURE( full_precision( row1[2] ));
471  CAPTURE( full_precision( row2[0] ));
472  CAPTURE( full_precision( row2[1] ));
473  CAPTURE( full_precision( row2[2] ));
474  CHECK(dot_product(row0, row0) == approx(1.f));
475  CAPTURE( full_precision( dot_product( row1, row1 )));
476  CHECK( dot_product( row1, row1 ) == approx( 1.f ) ); // this line is problematic, and needs higher epsilon!!
477  CHECK_THAT(dot_product(row1, row1), approx_equals(1.f));
478  CHECK(dot_product(row2, row2) == approx(1.f));
479  CHECK(dot_product(row0, row1) == approx(0.f));
480  CHECK(dot_product(row1, row2) == approx(0.f));
481  CHECK(dot_product(row2, row0) == approx(0.f));
482  require_cross_product(row0, row1, row2);
483  require_cross_product(row0, row1, row2);
484  require_cross_product(row0, row1, row2);
485 }
486 
487 // Require that matrix is exactly the identity matrix
488 inline void require_identity_matrix(const float(&matrix)[9])
489 {
490  static const float identity_matrix_3x3[] = { 1,0,0, 0,1,0, 0,0,1 };
491  for (int i = 0; i < 9; ++i)
492  REQUIRE(matrix[i] == approx(identity_matrix_3x3[i]));
493 }
494 
498  std::chrono::high_resolution_clock::time_point start_time, end_time;
502 };
503 
505 {
506  std::array<std::pair<bool, rs2_metadata_type>, RS2_FRAME_METADATA_COUNT> md_attributes{};
507 };
508 
509 
511 {
512  double timestamp;
513  unsigned long long frame_number;
517  frame_metadata frame_md; // Metadata attributes
518 
519  internal_frame_additional_data(const double &ts, const unsigned long long frame_num, const rs2_timestamp_domain& ts_domain, const rs2_stream& strm, const rs2_format& fmt) :
520  timestamp(ts),
521  frame_number(frame_num),
522  timestamp_domain(ts_domain),
523  stream(strm),
524  format(fmt) {}
525 };
526 
527 inline void check_fps(double actual_fps, double configured_fps)
528 {
529  REQUIRE(actual_fps >= configured_fps * 0.9); // allow threshold of 10 percent
530 }
531 
532 // All streaming tests are bounded by time or number of frames, which comes first
533 const int max_capture_time_sec = 3; // Each streaming test configuration shall not exceed this threshold
534 const uint32_t max_frames_to_receive = 50; // Max frames to capture per streaming tests
535 
536 //inline void test_wait_for_frames(rs2_device * device, std::initializer_list<stream_mode>& modes, std::map<rs2_stream, test_duration>& duration_per_stream)
537 //{
538 // rs2_start_device(device, require_no_error());
539 // REQUIRE( rs2_is_device_streaming(device, require_no_error()) == 1 );
540 //
541 // rs2_wait_for_frames(device, require_no_error());
542 //
543 // int lowest_fps_mode = std::numeric_limits<int>::max();
544 // for(auto & mode : modes)
545 // {
546 // REQUIRE( rs2_is_stream_enabled(device, mode.stream, require_no_error()) == 1 );
547 // REQUIRE( rs2_get_frame_data(device, mode.stream, require_no_error()) != nullptr );
548 // REQUIRE( rs2_get_frame_timestamp(device, mode.stream, require_no_error()) >= 0 );
549 // if (mode.framerate < lowest_fps_mode) lowest_fps_mode = mode.framerate;
550 // }
551 //
552 // std::vector<unsigned long long> last_frame_number;
553 // std::vector<unsigned long long> number_of_frames;
554 // last_frame_number.resize(RS2_STREAM_COUNT);
555 // number_of_frames.resize(RS2_STREAM_COUNT);
556 //
557 // for (auto& elem : modes)
558 // {
559 // number_of_frames[elem.stream] = 0;
560 // last_frame_number[elem.stream] = 0;
561 // }
562 //
563 // const auto actual_frames_to_receive = std::min(max_frames_to_receive, (uint32_t)(max_capture_time_sec* lowest_fps_mode));
564 // const auto first_frame_to_capture = (actual_frames_to_receive*0.1); // Skip the first 10% of frames
565 // const auto frames_to_capture = (actual_frames_to_receive - first_frame_to_capture);
566 //
567 // for (auto i = 0u; i< actual_frames_to_receive; ++i)
568 // {
569 // rs2_wait_for_frames(device, require_no_error());
570 //
571 // if (i < first_frame_to_capture) continue; // Skip some frames at the beginning to stabilize the stream output
572 //
573 // for (auto & mode : modes)
574 // {
575 // if (rs2_get_frame_timestamp(device, mode.stream, require_no_error()) > 0)
576 // {
577 // REQUIRE( rs2_is_stream_enabled(device, mode.stream, require_no_error()) == 1);
578 // REQUIRE( rs2_get_frame_data(device, mode.stream, require_no_error()) != nullptr);
579 // REQUIRE( rs2_get_frame_timestamp(device, mode.stream, require_no_error()) >= 0);
580 //
581 // auto frame_number = rs2_get_frame_number(device, mode.stream, require_no_error());
582 // if (!duration_per_stream[mode.stream].is_end_time_initialized && last_frame_number[mode.stream] != frame_number)
583 // {
584 // last_frame_number[mode.stream] = frame_number;
585 // ++number_of_frames[mode.stream];
586 // }
587 //
588 // if (!duration_per_stream[mode.stream].is_start_time_initialized && number_of_frames[mode.stream] >= 1)
589 // {
590 // duration_per_stream[mode.stream].start_time = std::chrono::high_resolution_clock::now();
591 // duration_per_stream[mode.stream].is_start_time_initialized = true;
592 // }
593 //
594 // if (!duration_per_stream[mode.stream].is_end_time_initialized && (number_of_frames[mode.stream] > (0.9 * frames_to_capture))) // Requires additional work for streams with different fps
595 // {
596 // duration_per_stream[mode.stream].end_time = std::chrono::high_resolution_clock::now();
597 // auto duration = std::chrono::duration_cast<std::chrono::milliseconds>(duration_per_stream[mode.stream].end_time - duration_per_stream[mode.stream].start_time).count();
598 // auto fps = ((double)number_of_frames[mode.stream] / duration) * 1000.;
599 // //check_fps(fps, mode.framerate); // requires additional work to configure UVC controls in order to achieve the required fps
600 // duration_per_stream[mode.stream].is_end_time_initialized = true;
601 // }
602 // }
603 // }
604 // }
605 //
606 // rs2_stop_device(device, require_no_error());
607 // REQUIRE( rs2_is_device_streaming(device, require_no_error()) == 0 );
608 //}
609 
610 
611 static std::mutex m;
612 static std::mutex cb_mtx;
613 static std::condition_variable cv;
614 static std::atomic<bool> stop_streaming;
615 static int done;
616 struct user_data {
617  std::map<rs2_stream, test_duration> duration_per_stream;
618  std::map<rs2_stream, unsigned> number_of_frames_per_stream;
619 };
620 
621 
622 inline void frame_callback(rs2::device &dev, rs2::frame frame, void * user)
623 {
624  std::lock_guard<std::mutex> lock(cb_mtx);
625 
626  if (stop_streaming || (frame.get_timestamp() == 0)) return;
627 
628  auto data = (user_data*)user;
629  bool stop = true;
630 
631  auto stream_type = frame.get_profile().stream_type();
632 
633  for (auto& elem : data->number_of_frames_per_stream)
634  {
635  if (elem.second < data->duration_per_stream[stream_type].actual_frames_to_receive)
636  {
637  stop = false;
638  break;
639  }
640  }
641 
642 
643  if (stop)
644  {
645  stop_streaming = true;
646  {
647  std::lock_guard<std::mutex> lk(m);
648  done = true;
649  }
650  cv.notify_one();
651  return;
652  }
653 
654  if (data->duration_per_stream[stream_type].is_end_time_initialized) return;
655 
656  unsigned num_of_frames = 0;
657  num_of_frames = (++data->number_of_frames_per_stream[stream_type]);
658 
659  if (num_of_frames >= data->duration_per_stream[stream_type].actual_frames_to_receive)
660  {
661  if (!data->duration_per_stream[stream_type].is_end_time_initialized)
662  {
663  data->duration_per_stream[stream_type].end_time = std::chrono::high_resolution_clock::now();
664  data->duration_per_stream[stream_type].is_end_time_initialized = true;
665  }
666 
667  return;
668  }
669 
670  if ((num_of_frames == data->duration_per_stream[stream_type].first_frame_to_capture) && (!data->duration_per_stream[stream_type].is_start_time_initialized)) // Skip some frames at the beginning to stabilize the stream output
671  {
672  data->duration_per_stream[stream_type].start_time = std::chrono::high_resolution_clock::now();
673  data->duration_per_stream[stream_type].is_start_time_initialized = true;
674  }
675 
676  REQUIRE(frame.get_data() != nullptr);
677  REQUIRE(frame.get_timestamp() >= 0);
678 }
679 
680 //inline void test_frame_callback(device &device, std::initializer_list<stream_profile>& modes, std::map<rs2_stream, test_duration>& duration_per_stream)
681 //{
682 // done = false;
683 // stop_streaming = false;
684 // user_data data;
685 // data.duration_per_stream = duration_per_stream;
686 //
687 // for(auto & mode : modes)
688 // {
689 // data.number_of_frames_per_stream[mode.stream] = 0;
690 // data.duration_per_stream[mode.stream].is_start_time_initialized = false;
691 // data.duration_per_stream[mode.stream].is_end_time_initialized = false;
692 // data.duration_per_stream[mode.stream].actual_frames_to_receive = std::min(max_frames_to_receive, (uint32_t)(max_capture_time_sec* mode.fps));
693 // data.duration_per_stream[mode.stream].first_frame_to_capture = (uint32_t)(data.duration_per_stream[mode.stream].actual_frames_to_receive*0.1); // Skip the first 10% of frames
694 // data.duration_per_stream[mode.stream].frames_to_capture = data.duration_per_stream[mode.stream].actual_frames_to_receive - data.duration_per_stream[mode.stream].first_frame_to_capture;
695 // // device doesn't know which subdevice is providing which stream. could loop over all subdevices? no, because subdevices don't expose this information
696 // REQUIRE( rs2_is_stream_enabled(device, mode.stream, require_no_error()) == 1 );
697 // rs2_start(device, mode.stream, frame_callback, &data, require_no_error());
698 // }
699 //
700 // rs2_start_device(device, require_no_error());
701 // REQUIRE( rs2_is_device_streaming(device, require_no_error()) == 1 );
702 //
703 // {
704 // std::unique_lock<std::mutex> lk(m);
705 // cv.wait(lk, [&]{return done;});
706 // lk.unlock();
707 // }
708 //
709 // rs2_stop_device(device, require_no_error());
710 // REQUIRE( rs2_is_device_streaming(device, require_no_error()) == 0 );
711 //
712 // for(auto & mode : modes)
713 // {
714 // auto duration = std::chrono::duration_cast<std::chrono::milliseconds>(data.duration_per_stream[mode.stream].end_time - data.duration_per_stream[mode.stream].start_time).count();
715 // auto fps = ((float)data.number_of_frames_per_stream[mode.stream] / duration) * 1000.;
716 // //check_fps(fps, mode.framerate); / TODO is not suppuorted yet. See above message
717 // }
718 //}
719 
720 //inline void motion_callback(rs2_device * , rs2_motion_data, void *)
721 //{
722 //}
723 //
724 //inline void timestamp_callback(rs2_device * , rs2_timestamp_data, void *)
725 //{
726 //}
727 //
729 //inline void test_streaming(rs2_device * device, std::initializer_list<stream_profile> modes)
730 //{
731 // std::map<rs2_stream, test_duration> duration_per_stream;
732 // for(auto & mode : modes)
733 // {
734 // duration_per_stream.insert(std::pair<rs2_stream, test_duration>(mode.stream, test_duration()));
735 // rs2_enable_stream(device, mode.stream, mode.width, mode.height, mode.format, mode.framerate, require_no_error());
736 // REQUIRE( rs2_is_stream_enabled(device, mode.stream, require_no_error()) == 1 );
737 // }
738 //
739 // test_wait_for_frames(device, modes, duration_per_stream);
740 //
741 // test_frame_callback(device, modes, duration_per_stream);
742 //
743 // for(auto & mode : modes)
744 // {
745 // rs2_disable_stream(device, mode.stream, require_no_error());
746 // REQUIRE( rs2_is_stream_enabled(device, mode.stream, require_no_error()) == 0 );
747 // }
748 //}
749 
750 inline void test_option(rs2::sensor &device, rs2_option option, std::initializer_list<int> good_values, std::initializer_list<int> bad_values)
751 {
752  // Test reading the current value
753  float first_value;
754  REQUIRE_NOTHROW(first_value = device.get_option(option));
755 
756 
757  // check if first value is something sane (should be default?)
759  REQUIRE_NOTHROW(range = device.get_option_range(option));
760  REQUIRE(first_value >= range.min);
761  REQUIRE(first_value <= range.max);
762  CHECK(first_value == range.def);
763 
764  // Test setting good values, and that each value set can be subsequently get
765  for (auto value : good_values)
766  {
767  REQUIRE_NOTHROW(device.set_option(option, (float)value));
768  REQUIRE(device.get_option(option) == value);
769  }
770 
771  // Test setting bad values, and verify that they do not change the value of the option
772  float last_good_value;
773  REQUIRE_NOTHROW(last_good_value = device.get_option(option));
774  for (auto value : bad_values)
775  {
776  REQUIRE_THROWS_AS(device.set_option(option, (float)value), rs2::error);
777  REQUIRE(device.get_option(option) == last_good_value);
778  }
779 
780  // Test that we can reset the option to its original value
781  REQUIRE_NOTHROW(device.set_option(option, first_value));
782  REQUIRE(device.get_option(option) == first_value);
783 }
784 
786 {
787  auto sp = s.get_stream_profiles();
788  int width = 0, height = 0;
789  for (auto&& p : sp)
790  {
791  if (auto video = p.as<rs2::video_stream_profile>())
792  {
793  width = video.width();
794  height = video.height();
795  if ((res = get_res_type(width, height)))
796  return p;
797  }
798  }
799  std::stringstream ss;
800  ss << "stream profile for " << width << "," << height << " resolution is not supported!";
801  throw std::runtime_error(ss.str());
802 }
803 
804 inline std::shared_ptr<rs2::device> do_with_waiting_for_camera_connection(rs2::context ctx, std::shared_ptr<rs2::device> dev, std::string serial, std::function<void()> operation)
805 {
806  std::mutex m;
807  bool disconnected = false;
808  bool connected = false;
809  std::shared_ptr<rs2::device> result;
810  std::condition_variable cv;
811 
812  ctx.set_devices_changed_callback([&result, dev, &disconnected, &connected, &m, &cv, &serial](rs2::event_information info) mutable
813  {
814  if (info.was_removed(*dev))
815  {
816  std::unique_lock<std::mutex> lock(m);
817  disconnected = true;
818  cv.notify_all();
819  }
820  auto list = info.get_new_devices();
821  if (list.size() > 0)
822  {
823  for (auto cam : list)
824  {
825  if (serial == cam.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER))
826  {
827  std::unique_lock<std::mutex> lock(m);
828  connected = true;
829  result = std::make_shared<rs2::device>(cam);
830 
832  cv.notify_all();
833  break;
834  }
835  }
836  }
837  });
838 
839  operation();
840 
841  std::unique_lock<std::mutex> lock(m);
842  REQUIRE(wait_for_reset([&]() {
843  return cv.wait_for(lock, std::chrono::seconds(20), [&]() { return disconnected; });
844  }, dev));
845  REQUIRE(cv.wait_for(lock, std::chrono::seconds(20), [&]() { return connected; }));
846  REQUIRE(result);
847  return result;
848 }
849 
851 {
852  rs2::device dev = devices_list[0];
853  std::string serial;
855  //forcing hardware reset to simulate device disconnection
856  auto shared_dev = std::make_shared<rs2::device>(devices_list.front());
857  shared_dev = do_with_waiting_for_camera_connection(ctx, shared_dev, serial, [&]()
858  {
859  shared_dev->hardware_reset();
860  });
862  return depth_sensor;
863 }
864 
865 
867 {
873 };
874 
875 #ifdef _WIN32
876 #include <windows.h>
877 #include <wchar.h>
878 #include <KnownFolders.h>
879 #include <shlobj.h>
880 
882 {
884  if (f == temp_folder)
885  {
886  TCHAR buf[MAX_PATH];
887  if (GetTempPath(MAX_PATH, buf) != 0)
888  {
889  char str[1024];
890  wcstombs(str, buf, 1023);
891  res = str;
892  }
893  }
894  else
895  {
896  GUID folder;
897  switch (f)
898  {
899  case user_desktop: folder = FOLDERID_Desktop;
900  break;
901  case user_documents: folder = FOLDERID_Documents;
902  break;
903  case user_pictures: folder = FOLDERID_Pictures;
904  break;
905  case user_videos: folder = FOLDERID_Videos;
906  break;
907  default:
908  throw std::invalid_argument(std::string("Value of f (") + std::to_string(f) + std::string(") is not supported"));
909  }
910  PWSTR folder_path = NULL;
911  HRESULT hr = SHGetKnownFolderPath(folder, KF_FLAG_DEFAULT_PATH, NULL, &folder_path);
912  if (SUCCEEDED(hr))
913  {
914  char str[1024];
915  wcstombs(str, folder_path, 1023);
916  CoTaskMemFree(folder_path);
917  res = str;
918  }
919  }
920  return res;
921 }
922 #endif //_WIN32
923 
924 #if defined __linux__ || defined __APPLE__
925 #include <unistd.h>
926 #include <sys/types.h>
927 #include <pwd.h>
928 
930 {
933  {
934  const char* tmp_dir = getenv("TMPDIR");
935  res = tmp_dir ? tmp_dir : "/tmp/";
936  }
937  else
938  {
939  const char* home_dir = getenv("HOME");
940  if (!home_dir)
941  {
942  struct passwd* pw = getpwuid(getuid());
943  home_dir = (pw && pw->pw_dir) ? pw->pw_dir : "";
944  }
945  if (home_dir)
946  {
947  res = home_dir;
948  switch (f)
949  {
950  case user_desktop: res += "/Desktop/";
951  break;
952  case user_documents: res += "/Documents/";
953  break;
954  case user_pictures: res += "/Pictures/";
955  break;
956  case user_videos: res += "/Videos/";
957  break;
958  default:
959  throw std::invalid_argument(
960  std::string("Value of f (") + std::to_string(f) + std::string(") is not supported"));
961  }
962  }
963  }
964  return res;
965 }
966 #endif // defined __linux__ || defined __APPLE__
967 
968 #endif
static const textual_icon lock
Definition: model-views.h:218
uint32_t first_frame_to_capture
GLboolean GLboolean GLboolean b
require_error(std::string message, bool message_validation=true)
bool operator<(const profile &other) const
Approx approx(F f)
Definition: approx.h:106
rs2_stream stream
std::ostream & operator<<(std::ostream &stream, const profile &cap)
std::string space_to_underscore(const std::string &text)
static std::mutex cb_mtx
~require_no_error() NOEXCEPT_FALSE
std::vector< sensor > query_sensors() const
Definition: rs_device.hpp:25
uint32_t frames_to_capture
bool operator!=(const profile &other) const
rs2::stream_profile get_profile_by_resolution_type(rs2::sensor &s, res_type res)
const int max_capture_time_sec
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
Definition: rs_option.h:22
GLdouble s
device front() const
Definition: rs_device.hpp:719
GLuint GLenum matrix
Definition: glext.h:11553
GLfloat GLfloat p
Definition: glext.h:12687
bool was_removed(const rs2::device &dev) const
Definition: rs_context.hpp:23
std::vector< profile > configure_all_supported_streams(rs2::sensor &sensor, int width=640, int height=480, int fps=60)
#define approx_equals(D)
Definition: approx.h:144
#define CHECK_THAT(arg, matcher)
Definition: catch.hpp:17424
GLfloat value
#define REQUIRE_THROWS_AS(expr, exceptionType)
Definition: catch.hpp:17402
stream_profile get_profile() const
Definition: rs_frame.hpp:557
std::string message
std::string get_folder_path(special_folder f)
Definition: os.cpp:247
const void * get_data() const
Definition: rs_frame.hpp:545
internal_frame_additional_data(const double &ts, const unsigned long long frame_num, const rs2_timestamp_domain &ts_domain, const rs2_stream &strm, const rs2_format &fmt)
GLsizei const GLchar *const * string
std::map< rs2_stream, unsigned > number_of_frames_per_stream
void require_cross_product(const float(&r)[3], const float(&a)[3], const float(&b)[3])
GLuint GLuint stream
Definition: glext.h:1790
static const textual_icon stop
Definition: model-views.h:225
void require_zero_vector(const float(&vector)[3])
uint32_t actual_frames_to_receive
const uint32_t max_frames_to_receive
GLenum GLuint id
char * get_argv(int i) const
GLenum cap
Definition: glext.h:8882
GLboolean GLboolean GLboolean GLboolean a
GLenum GLuint GLenum GLsizei const GLchar * buf
static const textual_icon usb_type
Definition: model-views.h:249
def info(name, value, persistent=False)
Definition: test.py:301
GLdouble f
Definition: getopt.h:41
size_t get_argc() const
GLdouble GLdouble r
std::string full_precision(T const d)
Definition: approx.h:152
#define WARN(msg)
Definition: catch.hpp:17431
#define CAPTURE(...)
Definition: catch.hpp:17432
void frame_callback(rs2::device &dev, rs2::frame frame, void *user)
REQUIRE(n_callbacks==1)
unsigned int uint32_t
Definition: stdint.h:80
const char * rs2_get_error_message(const rs2_error *error)
Definition: rs.cpp:1259
char *const * get_argv() const
double get_timestamp() const
Definition: rs_frame.hpp:474
const char * get_info(rs2_camera_info info) const
Definition: rs_device.hpp:79
void require_rotation_matrix(const float(&matrix)[9])
GLint GLsizei GLsizei height
static std::condition_variable cv
void require_transposed(const float(&a)[9], const float(&b)[9])
static std::mutex m
bool wait_for_reset(std::function< bool(void)> func, std::shared_ptr< rs2::device > dev)
float vector_length(const float(&v)[3])
rs2::depth_sensor restart_first_device_and_return_depth_sensor(const rs2::context &ctx, const rs2::device_list &devices_list)
static int done
rs2_format
A stream&#39;s format identifies how binary data is encoded within a frame.
Definition: rs_sensor.h:59
GLenum const GLfloat * params
std::pair< std::string, bool > dev_type
int stream_index() const
Definition: rs_frame.hpp:34
void log_to_file(rs2_log_severity min_severity, const char *file_path=nullptr)
Definition: rs.hpp:26
bool supports(rs2_camera_info info) const
Definition: rs_sensor.hpp:125
device_list get_new_devices() const
Definition: rs_context.hpp:57
GLenum func
rs2_stream
Streams are different types of data provided by RealSense devices.
Definition: rs_sensor.h:42
std::vector< profile > streams
bool supports(rs2_camera_info info) const
Definition: rs_device.hpp:66
bool is_start_time_initialized
bool make_context(const char *id, rs2::context *ctx, std::string min_api_version="0.0.0")
float dot_product(const float(&a)[3], const float(&b)[3])
void require_identity_matrix(const float(&matrix)[9])
std::map< rs2_stream, test_duration > duration_per_stream
~require_error() NOEXCEPT_FALSE
rs2_format format() const
Definition: rs_frame.hpp:44
rs2_timestamp_domain timestamp_domain
bool operator==(const rs2::video_stream_profile &other) const
void check_fps(double actual_fps, double configured_fps)
dev_type get_PID(rs2::device &dev)
void test_option(rs2::sensor &device, rs2_option option, std::initializer_list< int > good_values, std::initializer_list< int > bad_values)
GLenum GLfloat param
special_folder
static std::atomic< bool > stop_streaming
static const FGuid GUID
typename::boost::move_detail::remove_reference< T >::type && move(T &&t) BOOST_NOEXCEPT
void open(const stream_profile &profile) const
Definition: rs_sensor.hpp:111
void set_devices_changed_callback(T callback)
Definition: rs_context.hpp:169
static command_line_params & instance(int argc=0, char *const argv[]=0)
std::shared_ptr< rs2::device > do_with_waiting_for_camera_connection(rs2::context ctx, std::shared_ptr< rs2::device > dev, std::string serial, std::function< void()> operation)
GLsizei range
REQUIRE_NOTHROW(rs2_log(RS2_LOG_SEVERITY_INFO,"Log message using rs2_log()", nullptr))
#define NULL
Definition: tinycthread.c:47
int i
void disable_sensitive_options_for(rs2::sensor &sen)
GLuint res
Definition: glext.h:8856
option_range get_option_range(rs2_option option) const
Definition: rs_options.hpp:84
std::vector< char * > _params
bool file_exists(const std::string &filename)
rs2_format format
bool is_usb3(const rs2::device &dev)
std::vector< stream_profile > get_stream_profiles() const
Definition: rs_sensor.hpp:219
bool operator==(const profile &other) const
rs2_stream stream_type() const
Definition: rs_frame.hpp:39
void set_option(rs2_option option, float value) const
Definition: rs_options.hpp:99
GLuint64EXT * result
Definition: glext.h:10921
float get_option(rs2_option option) const
Definition: rs_options.hpp:72
GLdouble v
res_type
Definition: src/types.h:1920
auto device
Definition: pyrs_net.cpp:17
#define CHECK(condition)
Definition: parser.hpp:150
command_line_params(int argc, char *const argv[])
GLint GLsizei width
res_type get_res_type(uint32_t width, uint32_t height)
Definition: src/types.h:1926
std::chrono::high_resolution_clock::time_point start_time
#define NOEXCEPT_FALSE
std::string to_string(T value)
rs2_timestamp_domain
Specifies the clock in relation to which the frame timestamp was measured.
Definition: rs_frame.h:19


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