unit-tests-live.cpp
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 
5 // This set of tests is valid for any number and combination of RealSense cameras, including R200 and F200 //
7 
8 #include <cmath>
9 #include "unit-tests-common.h"
10 #include "../include/librealsense2/rs_advanced_mode.hpp"
13 #include <iostream>
14 #include <chrono>
15 #include <ctime>
16 #include <algorithm>
17 #include <librealsense2/rsutil.h>
18 
19 using namespace rs2;
20 
21 TEST_CASE("Sync sanity", "[live][mayfail]") {
22 
25  {
26  auto list = ctx.query_devices();
27  REQUIRE(list.size());
28 
29  auto dev = list[0];
31 
32  int fps = is_usb3(dev) ? 30 : 15; // In USB2 Mode the devices will switch to lower FPS rates
34 
35  auto profiles = configure_all_supported_streams(dev, 640, 480, fps);
36 
37  for (auto s : dev.query_sensors())
38  {
39  s.start(sync);
40  }
41 
42  for (auto i = 0; i < 30; i++)
43  {
44  auto frames = sync.wait_for_frames(500);
45  }
46 
47  std::vector<std::vector<double>> all_timestamps;
48  auto actual_fps = fps;
49 
50  for (auto i = 0; i < 200; i++)
51  {
52  auto frames = sync.wait_for_frames(5000);
53  REQUIRE(frames.size() > 0);
54 
55  std::vector<double> timestamps;
56  for (auto&& f : frames)
57  {
58  bool hw_timestamp_domain = false;
59  bool system_timestamp_domain = false;
60  bool global_timestamp_domain = false;
61 
62  if (f.supports_frame_metadata(RS2_FRAME_METADATA_ACTUAL_FPS))
63  {
64  auto val = static_cast<int>(f.get_frame_metadata(RS2_FRAME_METADATA_ACTUAL_FPS));
65  if (val < actual_fps)
66  actual_fps = val;
67  }
68  if (f.get_frame_timestamp_domain() == RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK)
69  {
70  hw_timestamp_domain = true;
71  }
72  if (f.get_frame_timestamp_domain() == RS2_TIMESTAMP_DOMAIN_SYSTEM_TIME)
73  {
74  system_timestamp_domain = true;
75  }
76  if (f.get_frame_timestamp_domain() == RS2_TIMESTAMP_DOMAIN_GLOBAL_TIME)
77  {
78  global_timestamp_domain = true;
79  }
80  CAPTURE(hw_timestamp_domain);
81  CAPTURE(system_timestamp_domain);
82  CAPTURE(global_timestamp_domain);
83  REQUIRE(int(hw_timestamp_domain) + int(system_timestamp_domain) + int(global_timestamp_domain) == 1);
84 
85  timestamps.push_back(f.get_timestamp());
86  }
87  all_timestamps.push_back(timestamps);
88  }
89 
90 
91  size_t num_of_partial_sync_sets = 0;
92  for (auto set_timestamps : all_timestamps)
93  {
94  if (set_timestamps.size() < profiles.second.size())
95  num_of_partial_sync_sets++;
96 
97  if (set_timestamps.size() <= 1)
98  continue;
99 
100  std::sort(set_timestamps.begin(), set_timestamps.end());
101  REQUIRE(set_timestamps[set_timestamps.size() - 1] - set_timestamps[0] <= (float)1000 / (float)actual_fps);
102  }
103 
104  CAPTURE(num_of_partial_sync_sets);
105  CAPTURE(all_timestamps.size());
106  // Require some coherent framesets, no KPI
107  REQUIRE((float(num_of_partial_sync_sets) / all_timestamps.size()) < 1.f);
108 
109  for (auto s : dev.query_sensors())
110  {
111  s.stop();
112  }
113  }
114 }
115 
116 TEST_CASE("Sync different fps", "[live][mayfail]") {
117 
119 
121  {
122  auto list = ctx.query_devices();
123  REQUIRE(list.size());
124  auto dev = list[0];
125 
126  list = ctx.query_devices();
127  REQUIRE(list.size());
128  dev = list[0];
129 
130  syncer syncer;
132 
133  auto sensors = dev.query_sensors();
134 
135  for (auto s : sensors)
136  {
137  if (s.supports(RS2_OPTION_EXPOSURE))
138  {
139  auto range = s.get_option_range(RS2_OPTION_EXPOSURE);
140  REQUIRE_NOTHROW(s.set_option(RS2_OPTION_EXPOSURE, range.min));
141  }
142 
143  }
144 
145  std::map<rs2_stream, rs2::sensor*> profiles_sensors;
146  std::map<rs2::sensor*, rs2_stream> sensors_profiles;
147 
148  int fps_step = is_usb3(dev) ? 30 : 15; // USB2 Mode
149 
150  std::vector<int> fps(sensors.size(), 0);
151 
152  // The heuristic for FPS selection need to be better explained and probably refactored
153  for (auto i = 0; i < fps.size(); i++)
154  {
155  fps[i] = (fps.size() - i - 1) * fps_step % 90 + fps_step;
156  }
157  std::vector<std::vector<rs2::sensor*>> streams_groups(fps.size());
158  for (auto i = 0; i < sensors.size(); i++)
159  {
160  auto profs = configure_all_supported_streams(sensors[i], 640, 480, fps[i]);
161  for (auto p : profs)
162  {
163  profiles_sensors[p.stream] = &sensors[i];
164  sensors_profiles[&sensors[i]] = p.stream;
165  }
166  if (profs.size() > 0)
167  sensors[i].start(syncer);
168  }
169 
170  for (auto i = 0; i < sensors.size(); i++)
171  {
172  for (auto j = 0; j < sensors.size(); j++)
173  {
174  if ((float)fps[j] / (float)fps[i] >= 1)
175  {
176  streams_groups[i].push_back(&sensors[j]);
177  }
178 
179  }
180  }
181 
182  std::vector<std::vector<rs2_stream>> frames_arrived;
183 
184  for (auto i = 0; i < 200; i++)
185  {
186  auto frames = syncer.wait_for_frames(5000);
187  REQUIRE(frames.size() > 0);
188  std::vector<rs2_stream> streams_arrived;
189  for (auto&& f : frames)
190  {
191  auto s = f.get_profile().stream_type();
192  streams_arrived.push_back(s);
193  }
194  frames_arrived.push_back(streams_arrived);
195  }
196 
197  std::vector<int> streams_groups_arrrived(streams_groups.size(), 0);
198 
199  for (auto streams : frames_arrived)
200  {
201  std::set<rs2::sensor*> sensors;
202 
203  for (auto s : streams)
204  {
205  sensors.insert(profiles_sensors[s]);
206  }
207  std::vector<rs2::sensor*> sensors_vec(sensors.size());
208  std::copy(sensors.begin(), sensors.end(), sensors_vec.begin());
209  auto it = std::find(streams_groups.begin(), streams_groups.end(), sensors_vec);
210  if (it != streams_groups.end())
211  {
212  auto ind = std::distance(streams_groups.begin(), it);
213  streams_groups_arrrived[ind]++;
214  }
215  }
216 
217 
218  for (auto i = 0; i < streams_groups_arrrived.size(); i++)
219  {
220  for (auto j = 0; j < streams_groups_arrrived.size(); j++)
221  {
222  REQUIRE(streams_groups_arrrived[j]);
223  auto num1 = streams_groups_arrrived[i];
224  auto num2 = streams_groups_arrrived[j];
225  CAPTURE(sensors_profiles[&sensors[i]]);
226  CAPTURE(num1);
227  CAPTURE(sensors_profiles[&sensors[j]]);
228  CAPTURE(num2);
229  REQUIRE((float)num1 / (float)num2 <= 5 * (float)fps[i] / (float)fps[j]);
230  }
231 
232  }
233  }
234 }
235 
236 bool get_mode(rs2::device& dev, stream_profile* profile, int mode_index = 0)
237 {
238  auto sensors = dev.query_sensors();
239  REQUIRE(sensors.size() > 0);
240 
241  for (auto i = 0; i < sensors.size(); i++)
242  {
243  auto modes = sensors[i].get_stream_profiles();
244  REQUIRE(modes.size() > 0);
245 
246  if (mode_index >= modes.size())
247  continue;
248 
249  *profile = modes[mode_index];
250  return true;
251  }
252  return false;
253 }
254 
255 TEST_CASE("Sync start stop", "[live][mayfail]") {
257 
259  {
260  auto list = ctx.query_devices();
261  REQUIRE(list.size() > 0);
262  auto dev = list[0];
264 
265  syncer sync;
266 
268  auto mode_index = 0;
269  bool usb3_device = is_usb3(dev);
270  int fps = usb3_device ? 30 : 15; // In USB2 Mode the devices will switch to lower FPS rates
271  int req_fps = usb3_device ? 60 : 30; // USB2 Mode has only a single resolution for 60 fps which is not sufficient to run the test
272 
273  do
274  {
275  REQUIRE(get_mode(dev, &mode, mode_index));
276  mode_index++;
277  } while (mode.fps() != req_fps);
278 
279  auto video = mode.as<rs2::video_stream_profile>();
280  auto res = configure_all_supported_streams(dev, video.width(), video.height(), mode.fps());
281 
282  for (auto s : res.first)
283  {
284  REQUIRE_NOTHROW(s.start(sync));
285  }
286 
287 
289  for (auto i = 0; i < 30; i++)
290  {
291  frames = sync.wait_for_frames(10000);
292  REQUIRE(frames.size() > 0);
293  }
294 
295  frameset old_frames;
296 
297  while (sync.poll_for_frames(&old_frames));
298 
299  stream_profile other_mode;
300  mode_index = 0;
301 
302  REQUIRE(get_mode(dev, &other_mode, mode_index));
303  auto other_video = other_mode.as<rs2::video_stream_profile>();
304  while ((other_video.height() == video.height() && other_video.width() == video.width()) || other_video.fps() != req_fps)
305  {
306  CAPTURE(mode_index);
307  CAPTURE(video.format());
308  CAPTURE(video.width());
309  CAPTURE(video.height());
310  CAPTURE(video.fps());
311  CAPTURE(other_video.format());
312  CAPTURE(other_video.width());
313  CAPTURE(other_video.height());
314  CAPTURE(other_video.fps());
315  REQUIRE(get_mode(dev, &other_mode, mode_index));
316  mode_index++;
317  other_video = other_mode.as<rs2::video_stream_profile>();
318  REQUIRE(other_video);
319  }
320 
321  for (auto s : res.first)
322  {
323  REQUIRE_NOTHROW(s.stop());
324  REQUIRE_NOTHROW(s.close());
325  }
326  res = configure_all_supported_streams(dev, other_video.width(), other_video.height(), other_mode.fps());
327 
328  for (auto s : res.first)
329  {
330  REQUIRE_NOTHROW(s.start(sync));
331  }
332 
333  for (auto i = 0; i < 10; i++)
334  frames = sync.wait_for_frames(10000);
335 
336  REQUIRE(frames.size() > 0);
337  auto f = frames[0];
338  auto image = f.as<rs2::video_frame>();
339  REQUIRE(image);
340 
341  REQUIRE(image.get_width() == other_video.width());
342 
343  REQUIRE(image.get_height() == other_video.height());
344  }
345 }
346 
347 TEST_CASE("Device metadata enumerates correctly", "[live]")
348 {
351  { // Require at least one device to be plugged in
352  std::vector<rs2::device> list;
353  REQUIRE_NOTHROW(list = ctx.query_devices());
354  REQUIRE(list.size() > 0);
355 
356  // For each device
357  for (auto&& dev : list)
358  {
359  SECTION("supported device metadata strings are nonempty, unsupported ones throw")
360  {
361  for (auto j = 0; j < RS2_CAMERA_INFO_COUNT; ++j) {
362  auto is_supported = false;
363  REQUIRE_NOTHROW(is_supported = dev.supports(rs2_camera_info(j)));
364  if (is_supported) REQUIRE(dev.get_info(rs2_camera_info(j)) != nullptr);
365  else REQUIRE_THROWS(dev.get_info(rs2_camera_info(j)));
366  }
367  }
368  }
369  }
370 }
371 
375 TEST_CASE("Start-Stop stream sequence", "[live][using_pipeline]")
376 {
377  // Require at least one device to be plugged in
379  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
380  {
381  std::vector<sensor> list;
382  REQUIRE_NOTHROW(list = ctx.query_all_sensors());
383  REQUIRE(list.size() > 0);
384 
385  pipeline pipe(ctx);
386  device dev;
387  // Configure all supported streams to run at 30 frames per second
388 
389  for (auto i = 0; i < 5; i++)
390  {
393  REQUIRE_NOTHROW(profile = cfg.resolve(pipe));
394  REQUIRE(profile);
395  REQUIRE_NOTHROW(dev = profile.get_device());
396  REQUIRE(dev);
398 
399  // Test sequence
400  REQUIRE_NOTHROW(pipe.start(cfg));
401 
402  REQUIRE_NOTHROW(pipe.stop());
403  }
404  }
405 }
406 
407 TEST_CASE("Start-Stop streaming - Sensors callbacks API", "[live][using_callbacks]")
408 {
411  {
412  for (auto i = 0; i < 5; i++)
413  {
414  std::vector<rs2::device> list;
415  REQUIRE_NOTHROW(list = ctx.query_devices());
416  REQUIRE(list.size());
417 
418  auto dev = list[0];
419  CAPTURE(dev.get_info(RS2_CAMERA_INFO_NAME));
421 
422  std::mutex m;
423  int fps = is_usb3(dev) ? 30 : 15; // In USB2 Mode the devices will switch to lower FPS rates
424  std::map<std::string, size_t> frames_per_stream{};
425 
426  auto profiles = configure_all_supported_streams(dev, 640, 480, fps);
427 
428  for (auto s : profiles.first)
429  {
430  REQUIRE_NOTHROW(s.start([&m, &frames_per_stream](rs2::frame f)
431  {
432  std::lock_guard<std::mutex> lock(m);
433  ++frames_per_stream[f.get_profile().stream_name()];
434  }));
435  }
436 
437  std::this_thread::sleep_for(std::chrono::seconds(1));
438  // Stop & flush all active sensors
439  for (auto s : profiles.first)
440  {
441  REQUIRE_NOTHROW(s.stop());
442  REQUIRE_NOTHROW(s.close());
443  }
444 
445  // Verify frames arrived for all the profiles specified
446  std::stringstream active_profiles, streams_arrived;
447  active_profiles << "Profiles requested : " << profiles.second.size() << std::endl;
448  for (auto& pf : profiles.second)
449  active_profiles << pf << std::endl;
450  streams_arrived << "Streams recorded : " << frames_per_stream.size() << std::endl;
451  for (auto& frec : frames_per_stream)
452  streams_arrived << frec.first << ": frames = " << frec.second << std::endl;
453 
454  CAPTURE(active_profiles.str().c_str());
455  CAPTURE(streams_arrived.str().c_str());
456  REQUIRE(profiles.second.size() == frames_per_stream.size());
457  }
458  }
459 }
460 
464 // This test is postponed for later review and refactoring
465 //TEST_CASE("Frame drops", "[live][using_pipeline]")
466 //{
467 // // Require at least one device to be plugged in
468 // rs2::context ctx;
469 // if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
470 // {
471 // std::vector<sensor> list;
472 // REQUIRE_NOTHROW(list = ctx.query_all_sensors());
473 // REQUIRE(list.size() > 0);
474 
475 // pipeline pipe(ctx);
476 // device dev;
477 // // Configure all supported streams to run at 30 frames per second
478 
479 // //std::this_thread::sleep_for(std::chrono::milliseconds(10000));
480 
481 // for (auto i = 0; i < 5; i++)
482 // {
483 // rs2::config cfg;
484 // rs2::pipeline_profile profile;
485 // REQUIRE_NOTHROW(profile = cfg.resolve(pipe));
486 // REQUIRE(profile);
487 // REQUIRE_NOTHROW(dev = profile.get_device());
488 // REQUIRE(dev);
489 // disable_sensitive_options_for(dev);
490 
491 // // Test sequence
492 // REQUIRE_NOTHROW(pipe.start(cfg));
493 
494 // unsigned long long current_depth_frame_number = 0;
495 // unsigned long long prev_depth_frame_number = 0;
496 // unsigned long long current_color_frame_number = 0;
497 // unsigned long long prev_color_frame_number = 0;
498 
499 // // Capture 30 frames to give autoexposure, etc. a chance to settle
500 // for (auto i = 0; i < 30; ++i)
501 // {
502 // auto frame = pipe.wait_for_frames();
503 // prev_depth_frame_number = frame.get_depth_frame().get_frame_number();
504 // prev_color_frame_number = frame.get_color_frame().get_frame_number();
505 // }
506 
507 // // Checking for frame drops on depth+color
508 // for (auto i = 0; i < 1000; ++i)
509 // {
510 // auto frame = pipe.wait_for_frames();
511 // current_depth_frame_number = frame.get_depth_frame().get_frame_number();
512 // current_color_frame_number = frame.get_color_frame().get_frame_number();
513 
514 // printf("User got %zd frames: depth %d, color %d\n", frame.size(), current_depth_frame_number, current_color_frame_number);
515 
516 // REQUIRE(current_depth_frame_number == (prev_depth_frame_number+1));
517 // REQUIRE(current_color_frame_number == (prev_color_frame_number + 1));
518 
519 // prev_depth_frame_number = current_depth_frame_number;
520 // prev_color_frame_number = current_color_frame_number;
521 // }
522 
523 // REQUIRE_NOTHROW(pipe.stop());
524 // }
525 // }
526 //}
527 
531 
532 TEST_CASE("No extrinsic transformation between a stream and itself", "[live]")
533 {
534  // Require at least one device to be plugged in
537  {
538  std::vector<sensor> list;
539  REQUIRE_NOTHROW(list = ctx.query_all_sensors());
540  const size_t device_count = list.size();
541  REQUIRE(device_count > 0);
542 
543  // For each device
544  for (auto&& snr : list)
545  {
546  std::vector<rs2::stream_profile> profs;
547  REQUIRE_NOTHROW(profs = snr.get_stream_profiles());
548  REQUIRE(profs.size()>0);
549 
550  rs2_extrinsics extrin;
551  try {
552  auto prof = profs[0];
553  extrin = prof.get_extrinsics_to(prof);
554  }
555  catch (error &e) {
556  // if device isn't calibrated, get_extrinsics must error out (according to old comment. Might not be true under new API)
557  WARN(e.what());
558  continue;
559  }
560 
561  require_identity_matrix(extrin.rotation);
562  require_zero_vector(extrin.translation);
563  }
564  }
565 }
566 
567 TEST_CASE("Extrinsic transformation between two streams is a rigid transform", "[live]")
568 {
569  // Require at least one device to be plugged in
572  {
573  std::vector<sensor> list;
574  REQUIRE_NOTHROW(list = ctx.query_all_sensors());
575  const size_t device_count = list.size();
576  REQUIRE(device_count > 0);
577 
578  // For each device
579  for (int i = 0; i < device_count; ++i)
580  {
581  auto dev = list[i];
582  auto adj_devices = ctx.get_sensor_parent(dev).query_sensors();
583 
584  //REQUIRE(dev != nullptr);
585 
586  // For every pair of streams
587  for (auto j = 0; j < adj_devices.size(); ++j)
588  {
589  for (size_t k = j + 1; k < adj_devices.size(); ++k)
590  {
591  std::vector<rs2::stream_profile> profs_a, profs_b;
592  REQUIRE_NOTHROW(profs_a = adj_devices[j].get_stream_profiles());
593  REQUIRE(profs_a.size()>0);
594 
595  REQUIRE_NOTHROW(profs_b = adj_devices[k].get_stream_profiles());
596  REQUIRE(profs_b.size()>0);
597 
598  // Extrinsics from A to B should have an orthonormal 3x3 rotation matrix and a translation vector of magnitude less than 10cm
599  rs2_extrinsics a_to_b;
600 
601  try {
602  a_to_b = profs_a[0].get_extrinsics_to(profs_b[0]);
603  }
604  catch (error &e) {
605  WARN(e.what());
606  continue;
607  }
608 
609  require_rotation_matrix(a_to_b.rotation);
610  REQUIRE(vector_length(a_to_b.translation) < 0.1f);
611 
612  // Extrinsics from B to A should be the inverse of extrinsics from A to B
613  rs2_extrinsics b_to_a;
614  REQUIRE_NOTHROW(b_to_a = profs_b[0].get_extrinsics_to(profs_a[0]));
615 
616  require_transposed(a_to_b.rotation, b_to_a.rotation);
617  REQUIRE(b_to_a.rotation[0] * a_to_b.translation[0] + b_to_a.rotation[3] * a_to_b.translation[1] + b_to_a.rotation[6] * a_to_b.translation[2] == approx(-b_to_a.translation[0]));
618  REQUIRE(b_to_a.rotation[1] * a_to_b.translation[0] + b_to_a.rotation[4] * a_to_b.translation[1] + b_to_a.rotation[7] * a_to_b.translation[2] == approx(-b_to_a.translation[1]));
619  REQUIRE(b_to_a.rotation[2] * a_to_b.translation[0] + b_to_a.rotation[5] * a_to_b.translation[1] + b_to_a.rotation[8] * a_to_b.translation[2] == approx(-b_to_a.translation[2]));
620  }
621  }
622  }
623  }
624 }
625 
626 TEST_CASE("Extrinsic transformations are transitive", "[live]")
627 {
628  // Require at least one device to be plugged in
631  {
632  std::vector<sensor> list;
633  REQUIRE_NOTHROW(list = ctx.query_all_sensors());
634  REQUIRE(list.size() > 0);
635 
636  // For each device
637  for (auto&& dev : list)
638  {
639  auto adj_devices = ctx.get_sensor_parent(dev).query_sensors();
640 
641  // For every set of subdevices
642  for (auto a = 0UL; a < adj_devices.size(); ++a)
643  {
644  for (auto b = 0UL; b < adj_devices.size(); ++b)
645  {
646  for (auto c = 0UL; c < adj_devices.size(); ++c)
647  {
648  std::vector<rs2::stream_profile> profs_a, profs_b, profs_c ;
649  REQUIRE_NOTHROW(profs_a = adj_devices[a].get_stream_profiles());
650  REQUIRE(profs_a.size()>0);
651 
652  REQUIRE_NOTHROW(profs_b = adj_devices[b].get_stream_profiles());
653  REQUIRE(profs_b.size()>0);
654 
655  REQUIRE_NOTHROW(profs_c = adj_devices[c].get_stream_profiles());
656  REQUIRE(profs_c.size()>0);
657 
658  // Require that the composition of a_to_b and b_to_c is equal to a_to_c
659  rs2_extrinsics a_to_b, b_to_c, a_to_c;
660 
661  try {
662  a_to_b = profs_a[0].get_extrinsics_to(profs_b[0]);
663  b_to_c = profs_b[0].get_extrinsics_to(profs_c[0]);
664  a_to_c = profs_a[0].get_extrinsics_to(profs_c[0]);
665  }
666  catch (error &e)
667  {
668  WARN(e.what());
669  continue;
670  }
671 
672  // a_to_c.rotation == a_to_b.rotation * b_to_c.rotation
673  auto&& epsilon = 0.0001;
674  REQUIRE(a_to_c.rotation[0] == approx((float)(a_to_b.rotation[0] * b_to_c.rotation[0] + a_to_b.rotation[3] * b_to_c.rotation[1] + a_to_b.rotation[6] * b_to_c.rotation[2])).epsilon(epsilon));
675  REQUIRE(a_to_c.rotation[2] == approx(a_to_b.rotation[2] * b_to_c.rotation[0] + a_to_b.rotation[5] * b_to_c.rotation[1] + a_to_b.rotation[8] * b_to_c.rotation[2]).epsilon(epsilon));
676  REQUIRE(a_to_c.rotation[1] == approx(a_to_b.rotation[1] * b_to_c.rotation[0] + a_to_b.rotation[4] * b_to_c.rotation[1] + a_to_b.rotation[7] * b_to_c.rotation[2]).epsilon(epsilon));
677  REQUIRE(a_to_c.rotation[3] == approx(a_to_b.rotation[0] * b_to_c.rotation[3] + a_to_b.rotation[3] * b_to_c.rotation[4] + a_to_b.rotation[6] * b_to_c.rotation[5]).epsilon(epsilon));
678  REQUIRE(a_to_c.rotation[4] == approx(a_to_b.rotation[1] * b_to_c.rotation[3] + a_to_b.rotation[4] * b_to_c.rotation[4] + a_to_b.rotation[7] * b_to_c.rotation[5]).epsilon(epsilon));
679  REQUIRE(a_to_c.rotation[5] == approx(a_to_b.rotation[2] * b_to_c.rotation[3] + a_to_b.rotation[5] * b_to_c.rotation[4] + a_to_b.rotation[8] * b_to_c.rotation[5]).epsilon(epsilon));
680  REQUIRE(a_to_c.rotation[6] == approx(a_to_b.rotation[0] * b_to_c.rotation[6] + a_to_b.rotation[3] * b_to_c.rotation[7] + a_to_b.rotation[6] * b_to_c.rotation[8]).epsilon(epsilon));
681  REQUIRE(a_to_c.rotation[7] == approx(a_to_b.rotation[1] * b_to_c.rotation[6] + a_to_b.rotation[4] * b_to_c.rotation[7] + a_to_b.rotation[7] * b_to_c.rotation[8]).epsilon(epsilon));
682  REQUIRE(a_to_c.rotation[8] == approx(a_to_b.rotation[2] * b_to_c.rotation[6] + a_to_b.rotation[5] * b_to_c.rotation[7] + a_to_b.rotation[8] * b_to_c.rotation[8]).epsilon(epsilon));
683 
684  // a_to_c.translation = a_to_b.transform(b_to_c.translation)
685  REQUIRE(a_to_c.translation[0] == approx(a_to_b.rotation[0] * b_to_c.translation[0] + a_to_b.rotation[3] * b_to_c.translation[1] + a_to_b.rotation[6] * b_to_c.translation[2] + a_to_b.translation[0]).epsilon(epsilon));
686  REQUIRE(a_to_c.translation[1] == approx(a_to_b.rotation[1] * b_to_c.translation[0] + a_to_b.rotation[4] * b_to_c.translation[1] + a_to_b.rotation[7] * b_to_c.translation[2] + a_to_b.translation[1]).epsilon(epsilon));
687  REQUIRE(a_to_c.translation[2] == approx(a_to_b.rotation[2] * b_to_c.translation[0] + a_to_b.rotation[5] * b_to_c.translation[1] + a_to_b.rotation[8] * b_to_c.translation[2] + a_to_b.translation[2]).epsilon(epsilon));
688  }
689  }
690  }
691  }
692  }
693 }
694 
695 TEST_CASE("Toggle Advanced Mode", "[live][AdvMd][mayfail]") {
696  for (int i = 0; i < 3; ++i)
697  {
700  {
701  device_list list;
702  REQUIRE_NOTHROW(list = ctx.query_devices());
703  REQUIRE(list.size() > 0);
704 
705  auto dev = std::make_shared<device>(list.front());
706 
708 
709  std::string serial;
710  REQUIRE_NOTHROW(serial = dev->get_info(RS2_CAMERA_INFO_SERIAL_NUMBER));
711 
712  if (dev->is<rs400::advanced_mode>())
713  {
714  auto advanced = dev->as<rs400::advanced_mode>();
715 
716  if (!advanced.is_enabled())
717  {
718  dev = do_with_waiting_for_camera_connection(ctx, dev, serial, [&]()
719  {
720  REQUIRE_NOTHROW(advanced.toggle_advanced_mode(true));
721  });
722  }
724  advanced = dev->as<rs400::advanced_mode>();
725 
726  REQUIRE(advanced.is_enabled());
727 
728  dev = do_with_waiting_for_camera_connection(ctx, dev, serial, [&]()
729  {
730  REQUIRE_NOTHROW(advanced.toggle_advanced_mode(false));
731  });
732  advanced = dev->as<rs400::advanced_mode>();
733  REQUIRE(!advanced.is_enabled());
734  }
735  }
736  }
737 }
738 
739 
740 TEST_CASE("Advanced Mode presets", "[live][AdvMd][mayfail]")
741 {
742  static const std::vector<res_type> resolutions = { low_resolution,
744  high_resolution };
745 
748  {
749  device_list list;
750  REQUIRE_NOTHROW(list = ctx.query_devices());
751  REQUIRE(list.size() > 0);
752 
753  auto dev = std::make_shared<device>(list.front());
754 
756 
757  std::string serial;
758  REQUIRE_NOTHROW(serial = dev->get_info(RS2_CAMERA_INFO_SERIAL_NUMBER));
759 
760  if (dev->is<rs400::advanced_mode>())
761  {
762  auto advanced = dev->as<rs400::advanced_mode>();
763 
764  if (!advanced.is_enabled())
765  {
766  dev = do_with_waiting_for_camera_connection(ctx, dev, serial, [&]()
767  {
768  REQUIRE_NOTHROW(advanced.toggle_advanced_mode(true));
769  });
770  }
772  advanced = dev->as<rs400::advanced_mode>();
773 
774  REQUIRE(advanced.is_enabled());
775  auto sensors = dev->query_sensors();
776 
777  sensor presets_sensor;
778  for (sensor& elem : sensors)
779  {
780  auto supports = false;
781  REQUIRE_NOTHROW(supports = elem.supports(RS2_OPTION_VISUAL_PRESET));
782  if (supports)
783  {
784  presets_sensor = elem;
785  break;
786  }
787  }
788 
789  for (auto& res : resolutions)
790  {
791  std::vector<rs2::stream_profile> sp = {get_profile_by_resolution_type(presets_sensor, res)};
792  if (presets_sensor.supports(RS2_OPTION_VISUAL_PRESET))
793  {
794  presets_sensor.open(sp);
795  presets_sensor.start([](rs2::frame) {});
796  for (auto i = 0; i < RS2_RS400_VISUAL_PRESET_COUNT; ++i)
797  {
798  auto preset = (rs2_rs400_visual_preset)i;
799  CAPTURE(res);
800  CAPTURE(preset);
801  try
802  {
803  presets_sensor.set_option(RS2_OPTION_VISUAL_PRESET, (float)preset);
804  }
805  catch (...)
806  {
807  // preset is not supported
808  continue;
809  }
810  float ret_preset;
811  REQUIRE_NOTHROW(ret_preset = presets_sensor.get_option(RS2_OPTION_VISUAL_PRESET));
812  REQUIRE(preset == (rs2_rs400_visual_preset)((int)ret_preset));
813  }
814  presets_sensor.stop();
815  presets_sensor.close();
816  }
817  }
818 
819  dev = do_with_waiting_for_camera_connection(ctx, dev, serial, [&]()
820  {
821  REQUIRE_NOTHROW(advanced.toggle_advanced_mode(false));
822  });
824  advanced = dev->as<rs400::advanced_mode>();
825  REQUIRE(!advanced.is_enabled());
826  }
827  }
828 }
829 
830 TEST_CASE("Advanced Mode JSON", "[live][AdvMd][mayfail]") {
833  {
834  device_list list;
835  REQUIRE_NOTHROW(list = ctx.query_devices());
836  REQUIRE(list.size() > 0);
837 
838 
839  auto dev = std::make_shared<device>(list.front());
840 
842 
843  std::string serial;
844  REQUIRE_NOTHROW(serial = dev->get_info(RS2_CAMERA_INFO_SERIAL_NUMBER));
845 
846  if (dev->is<rs400::advanced_mode>())
847  {
848  auto advanced = dev->as<rs400::advanced_mode>();
849 
850  if (!advanced.is_enabled())
851  {
852  dev = do_with_waiting_for_camera_connection(ctx, dev, serial, [&]()
853  {
854  REQUIRE_NOTHROW(advanced.toggle_advanced_mode(true));
855  });
856  }
857 
859  advanced = dev->as<rs400::advanced_mode>();
860  REQUIRE(advanced.is_enabled());
861 
862  auto sensors = dev->query_sensors();
863  sensor presets_sensor;
864  for (sensor& elem : sensors)
865  {
866  auto supports = false;
867  REQUIRE_NOTHROW(supports = elem.supports(RS2_OPTION_VISUAL_PRESET));
868  if (supports)
869  {
870  presets_sensor = elem;
871  break;
872  }
873  }
874 
875  std::string json1, json2;
876  REQUIRE_NOTHROW(json1 = advanced.serialize_json());
878  REQUIRE_NOTHROW(advanced.load_json(json1));
879  REQUIRE_NOTHROW(json2 = advanced.serialize_json());
880  REQUIRE(json1 == json2);
881 
882  dev = do_with_waiting_for_camera_connection(ctx, dev, serial, [&]()
883  {
884  REQUIRE_NOTHROW(advanced.toggle_advanced_mode(false));
885  });
887  advanced = dev->as<rs400::advanced_mode>();
888  REQUIRE(!advanced.is_enabled());
889  }
890  }
891 }
892 
893 TEST_CASE("Advanced Mode controls", "[live][AdvMd][mayfail]") {
896  {
897  device_list list;
898  REQUIRE_NOTHROW(list = ctx.query_devices());
899  REQUIRE(list.size() > 0);
900 
901  std::shared_ptr<device> dev = std::make_shared<device>(list.front());
902  if (dev->is<rs400::advanced_mode>())
903  {
905  auto info = dev->get_info(RS2_CAMERA_INFO_NAME);
906  CAPTURE(info);
907 
908  std::string serial;
909  REQUIRE_NOTHROW(serial = dev->get_info(RS2_CAMERA_INFO_SERIAL_NUMBER));
910 
911 
912  auto advanced = dev->as<rs400::advanced_mode>();
913  if (!advanced.is_enabled())
914  {
915 
916  dev = do_with_waiting_for_camera_connection(ctx, dev, serial, [&]()
917  {
918  REQUIRE_NOTHROW(advanced.toggle_advanced_mode(true));
919  });
920  }
921 
922 
923 
925  advanced = dev->as<rs400::advanced_mode>();
926  REQUIRE(advanced.is_enabled());
927 
928  {
929  STDepthControlGroup ctrl_curr{};
930  REQUIRE_NOTHROW(ctrl_curr = advanced.get_depth_control(0));
931  STDepthControlGroup ctrl_min{};
932  REQUIRE_NOTHROW(ctrl_min = advanced.get_depth_control(1));
933  STDepthControlGroup ctrl_max{};
934  REQUIRE_NOTHROW(ctrl_max = advanced.get_depth_control(2));
935  REQUIRE_NOTHROW(advanced.set_depth_control(ctrl_min));
936  REQUIRE_NOTHROW(ctrl_curr = advanced.get_depth_control(0));
937  REQUIRE(ctrl_curr == ctrl_min);
938  }
939 
940  {
941  STRsm ctrl_curr{};
942  REQUIRE_NOTHROW(ctrl_curr = advanced.get_rsm(0));
943  STRsm ctrl_min{};
944  REQUIRE_NOTHROW(ctrl_min = advanced.get_rsm(1));
945  STRsm ctrl_max{};
946  REQUIRE_NOTHROW(ctrl_max = advanced.get_rsm(2));
947  REQUIRE_NOTHROW(advanced.set_rsm(ctrl_min));
948  REQUIRE_NOTHROW(ctrl_curr = advanced.get_rsm(0));
949  REQUIRE(ctrl_curr == ctrl_min);
950  }
951 
952  {
953  STRauSupportVectorControl ctrl_curr{};
954  REQUIRE_NOTHROW(ctrl_curr = advanced.get_rau_support_vector_control(0));
955  STRauSupportVectorControl ctrl_min{};
956  REQUIRE_NOTHROW(ctrl_min = advanced.get_rau_support_vector_control(1));
957  STRauSupportVectorControl ctrl_max{};
958  REQUIRE_NOTHROW(ctrl_max = advanced.get_rau_support_vector_control(2));
959  REQUIRE_NOTHROW(advanced.set_rau_support_vector_control(ctrl_min));
960  REQUIRE_NOTHROW(ctrl_curr = advanced.get_rau_support_vector_control(0));
961  REQUIRE(ctrl_curr == ctrl_min);
962  }
963 
964  {
965  STColorControl ctrl_curr{};
966  REQUIRE_NOTHROW(ctrl_curr = advanced.get_color_control(0));
967  STColorControl ctrl_min{};
968  REQUIRE_NOTHROW(ctrl_min = advanced.get_color_control(1));
969  STColorControl ctrl_max{};
970  REQUIRE_NOTHROW(ctrl_max = advanced.get_color_control(2));
971  REQUIRE_NOTHROW(advanced.set_color_control(ctrl_min));
972  REQUIRE_NOTHROW(ctrl_curr = advanced.get_color_control(0));
973  REQUIRE(ctrl_curr == ctrl_min);
974  }
975 
976  {
977  STRauColorThresholdsControl ctrl_curr{};
978  REQUIRE_NOTHROW(ctrl_curr = advanced.get_rau_thresholds_control(0));
979  STRauColorThresholdsControl ctrl_min{};
980  REQUIRE_NOTHROW(ctrl_min = advanced.get_rau_thresholds_control(1));
981  STRauColorThresholdsControl ctrl_max{};
982  REQUIRE_NOTHROW(ctrl_max = advanced.get_rau_thresholds_control(2));
983  REQUIRE_NOTHROW(advanced.set_rau_thresholds_control(ctrl_min));
984  REQUIRE_NOTHROW(ctrl_curr = advanced.get_rau_thresholds_control(0));
985  REQUIRE(ctrl_curr == ctrl_min);
986  }
987 
988  {
989  STSloColorThresholdsControl ctrl_curr{};
990  REQUIRE_NOTHROW(ctrl_curr = advanced.get_slo_color_thresholds_control(0));
991  STSloColorThresholdsControl ctrl_min{};
992  REQUIRE_NOTHROW(ctrl_min = advanced.get_slo_color_thresholds_control(1));
993  STSloColorThresholdsControl ctrl_max{};
994  REQUIRE_NOTHROW(ctrl_max = advanced.get_slo_color_thresholds_control(2));
995  REQUIRE_NOTHROW(advanced.set_slo_color_thresholds_control(ctrl_min));
996  REQUIRE_NOTHROW(ctrl_curr = advanced.get_slo_color_thresholds_control(0));
997  REQUIRE(ctrl_curr == ctrl_min);
998  }
999 
1000  {
1001  STSloPenaltyControl ctrl_curr{};
1002  REQUIRE_NOTHROW(ctrl_curr = advanced.get_slo_penalty_control(0));
1003  STSloPenaltyControl ctrl_min{};
1004  REQUIRE_NOTHROW(ctrl_min = advanced.get_slo_penalty_control(1));
1005  STSloPenaltyControl ctrl_max{};
1006  REQUIRE_NOTHROW(ctrl_max = advanced.get_slo_penalty_control(2));
1007  REQUIRE_NOTHROW(advanced.set_slo_penalty_control(ctrl_min));
1008  REQUIRE_NOTHROW(ctrl_curr = advanced.get_slo_penalty_control(0));
1009  REQUIRE(ctrl_curr == ctrl_min);
1010  }
1011 
1012  {
1013  STHdad ctrl_curr1{};
1014  REQUIRE_NOTHROW(ctrl_curr1 = advanced.get_hdad(0));
1015  REQUIRE_NOTHROW(advanced.set_hdad(ctrl_curr1));
1016  STHdad ctrl_curr2{};
1017  REQUIRE_NOTHROW(ctrl_curr2 = advanced.get_hdad(0));
1018  REQUIRE(ctrl_curr1 == ctrl_curr2);
1019  }
1020 
1021  {
1022  STColorCorrection ctrl_curr{};
1023  REQUIRE_NOTHROW(ctrl_curr = advanced.get_color_correction(0));
1024  STColorCorrection ctrl_min{};
1025  REQUIRE_NOTHROW(ctrl_min = advanced.get_color_correction(1));
1026  STColorCorrection ctrl_max{};
1027  REQUIRE_NOTHROW(ctrl_max = advanced.get_color_correction(2));
1028  REQUIRE_NOTHROW(advanced.set_color_correction(ctrl_min));
1029  REQUIRE_NOTHROW(ctrl_curr = advanced.get_color_correction(0));
1030  REQUIRE(ctrl_curr == ctrl_min);
1031  }
1032 
1033  {
1034  STAEControl ctrl_curr1{};
1035  REQUIRE_NOTHROW(ctrl_curr1 = advanced.get_ae_control(0));
1036  REQUIRE_NOTHROW(advanced.set_ae_control(ctrl_curr1));
1037  STAEControl ctrl_curr2{};
1038  REQUIRE_NOTHROW(ctrl_curr2 = advanced.get_ae_control(0));
1039  REQUIRE(ctrl_curr1 == ctrl_curr2);
1040  }
1041 
1042  {
1043  STDepthTableControl ctrl_curr{};
1044  REQUIRE_NOTHROW(ctrl_curr = advanced.get_depth_table(0));
1045  STDepthTableControl ctrl_min{};
1046  REQUIRE_NOTHROW(ctrl_min = advanced.get_depth_table(1));
1047  STDepthTableControl ctrl_max{};
1048  REQUIRE_NOTHROW(ctrl_max = advanced.get_depth_table(2));
1049  REQUIRE_NOTHROW(advanced.set_depth_table(ctrl_min));
1050  REQUIRE_NOTHROW(ctrl_curr = advanced.get_depth_table(0));
1051  REQUIRE(ctrl_curr == ctrl_min);
1052  }
1053 
1054  {
1055  STCensusRadius ctrl_curr{};
1056  REQUIRE_NOTHROW(ctrl_curr = advanced.get_census(0));
1057  STCensusRadius ctrl_min{};
1058  REQUIRE_NOTHROW(ctrl_min = advanced.get_census(1));
1059  STCensusRadius ctrl_max{};
1060  REQUIRE_NOTHROW(ctrl_max = advanced.get_census(2));
1061  REQUIRE_NOTHROW(advanced.set_census(ctrl_min));
1062  REQUIRE_NOTHROW(ctrl_curr = advanced.get_census(0));
1063  REQUIRE(ctrl_curr == ctrl_min);
1064  }
1065 
1066 
1067  dev = do_with_waiting_for_camera_connection(ctx, dev, serial, [&]()
1068  {
1069  REQUIRE_NOTHROW(advanced.toggle_advanced_mode(false));
1070  });
1071 
1073  advanced = dev->as<rs400::advanced_mode>();
1074 
1075  REQUIRE(!advanced.is_enabled());
1076  }
1077  }
1078 }
1079 
1080 // the tests may incorrectly interpret changes to librealsense-core, namely default profiles selections
1081 TEST_CASE("Streaming modes sanity check", "[live][mayfail]")
1082 {
1083  // Require at least one device to be plugged in
1084  rs2::context ctx;
1086  {
1087  std::vector<sensor> list;
1088  REQUIRE_NOTHROW(list = ctx.query_all_sensors());
1089  REQUIRE(list.size() > 0);
1090 
1091  // For each device
1092  for (auto&& dev : list)
1093  {
1095 
1096  std::string PID;
1098 
1099  // make sure they provide at least one streaming mode
1100  std::vector<rs2::stream_profile> stream_profiles;
1101  REQUIRE_NOTHROW(stream_profiles = dev.get_stream_profiles());
1102  REQUIRE(stream_profiles.size() > 0);
1103 
1104  SECTION("check stream profile settings are sane")
1105  {
1106  // for each stream profile provided:
1107  for (auto profile : stream_profiles) {
1108 
1109  // require that the settings are sane
1112  REQUIRE(profile.fps() >= 2);
1113  REQUIRE(profile.fps() <= 300);
1114 
1115  // require that we can start streaming this mode
1116  REQUIRE_NOTHROW(dev.open({ profile }));
1117  // TODO: make callback confirm stream format/dimensions/framerate
1118  REQUIRE_NOTHROW(dev.start([](rs2::frame fref) {}));
1119 
1120  // Require that we can disable the stream afterwards
1121  REQUIRE_NOTHROW(dev.stop());
1122  REQUIRE_NOTHROW(dev.close());
1123  }
1124  }
1125  SECTION("check stream intrinsics are sane")
1126  {
1127  for (auto profile : stream_profiles)
1128  {
1129  if (auto video = profile.as<video_stream_profile>())
1130  {
1132  CAPTURE(video.stream_type());
1133  CAPTURE(video.format());
1134  CAPTURE(video.width());
1135  CAPTURE(video.height());
1136 
1137  bool calib_format = ((PID != "0AA5") &&
1138  (RS2_FORMAT_Y16 == video.format()) &&
1139  (RS2_STREAM_INFRARED == video.stream_type()));
1140  if (!calib_format) // intrinsics are not available for calibration formats
1141  {
1142  REQUIRE_NOTHROW(intrin = video.get_intrinsics());
1143 
1144  // Intrinsic width/height must match width/height of streaming mode we requested
1145  REQUIRE(intrin.width == video.width());
1146  REQUIRE(intrin.height == video.height());
1147 
1148  // Principal point must be within center 20% of image
1149  REQUIRE(intrin.ppx > video.width() * 0.4f);
1150  REQUIRE(intrin.ppx < video.width() * 0.6f);
1151  REQUIRE(intrin.ppy > video.height() * 0.4f);
1152  REQUIRE(intrin.ppy < video.height() * 0.6f);
1153 
1154  // Focal length must be non-negative (todo - Refine requirements based on known expected FOV)
1155  REQUIRE(intrin.fx > 0.0f);
1156  REQUIRE(intrin.fy > 0.0f);
1157  }
1158  else
1159  {
1160  REQUIRE_THROWS(intrin = video.get_intrinsics());
1161  }
1162  }
1163  }
1164  }
1165  }
1166  }
1167 }
1168 
1169 TEST_CASE("Motion profiles sanity", "[live]")
1170 {
1171  rs2::context ctx;
1173  {
1174  std::vector<sensor> list;
1175  REQUIRE_NOTHROW(list = ctx.query_all_sensors());
1176  REQUIRE(list.size() > 0);
1177 
1178  // For each device
1179  for (auto&& dev : list)
1180  {
1182 
1183  // make sure they provide at least one streaming mode
1184  std::vector<rs2::stream_profile> stream_profiles;
1185  REQUIRE_NOTHROW(stream_profiles = dev.get_stream_profiles());
1186  REQUIRE(stream_profiles.size() > 0);
1187 
1188  // for each stream profile provided:
1189  for (auto profile : stream_profiles)
1190  {
1191  SECTION("check motion intrisics") {
1192 
1193  auto stream = profile.stream_type();
1195 
1196  CAPTURE(stream);
1197 
1199  {
1200  auto motion = profile.as<motion_stream_profile>();
1201  REQUIRE_NOTHROW(mm_int = motion.get_motion_intrinsics());
1202 
1203  for (int j = 0; j < 3; j++)
1204  {
1205  auto scale = mm_int.data[j][j];
1206  CAPTURE(scale);
1207  // Make sure scale value is "sane"
1208  // We don't expect Motion Device to require adjustment of more then 20%
1209  REQUIRE(scale > 0.8);
1210  REQUIRE(scale < 1.2);
1211 
1212  auto bias = mm_int.data[0][3];
1213  CAPTURE(bias);
1214  // Make sure bias is "sane"
1215  REQUIRE(bias > -0.5);
1216  REQUIRE(bias < 0.5);
1217  }
1218  }
1219  }
1220  }
1221  }
1222  }
1223 }
1224 
1225 TEST_CASE("Check width and height of stream intrinsics", "[live][AdvMd]")
1226 {
1227  rs2::context ctx;
1229  {
1230  std::vector<device> devs;
1231  REQUIRE_NOTHROW(devs = ctx.query_devices());
1232 
1233  for (auto&& dev : devs)
1234  {
1235  auto shared_dev = std::make_shared<device>(dev);
1237  std::string serial;
1239  std::string PID;
1241  if (shared_dev->is<rs400::advanced_mode>())
1242  {
1243  auto advanced = shared_dev->as<rs400::advanced_mode>();
1244 
1245  if (advanced.is_enabled())
1246  {
1247  shared_dev = do_with_waiting_for_camera_connection(ctx, shared_dev, serial, [&]()
1248  {
1249  REQUIRE_NOTHROW(advanced.toggle_advanced_mode(false));
1250  });
1251  }
1252  disable_sensitive_options_for(*shared_dev);
1253  advanced = shared_dev->as<rs400::advanced_mode>();
1254 
1255  REQUIRE(advanced.is_enabled() == false);
1256  }
1257 
1258  std::vector<sensor> list;
1259  REQUIRE_NOTHROW(list = shared_dev->query_sensors());
1260  REQUIRE(list.size() > 0);
1261 
1262  for (auto&& dev : list)
1263  {
1265  auto module_name = dev.get_info(RS2_CAMERA_INFO_NAME);
1266  // TODO: if FE
1267  std::vector<rs2::stream_profile> stream_profiles;
1268  REQUIRE_NOTHROW(stream_profiles = dev.get_stream_profiles());
1269  REQUIRE(stream_profiles.size() > 0);
1270 
1271  // for each stream profile provided:
1272  int i=0;
1273  for (const auto& profile : stream_profiles)
1274  {
1275  i++;
1276  if (auto video = profile.as<video_stream_profile>())
1277  {
1279 
1280  CAPTURE(video.stream_type());
1281  CAPTURE(video.format());
1282  CAPTURE(video.width());
1283  CAPTURE(video.height());
1284 
1285  // Calibration formats does not provide intrinsic data, except for SR300
1286  bool calib_format = ((PID != "0AA5") &&
1287  (RS2_FORMAT_Y16 == video.format()) &&
1288  (RS2_STREAM_INFRARED == video.stream_type()));
1289  if (!calib_format)
1290  REQUIRE_NOTHROW(intrin = video.get_intrinsics());
1291  else
1292  REQUIRE_THROWS(intrin = video.get_intrinsics());
1293 
1294  // Intrinsic width/height must match width/height of streaming mode we requested
1295  REQUIRE(intrin.width == video.width());
1296  REQUIRE(intrin.height == video.height());
1297  }
1298  }
1299  }
1300  }
1301  }
1302 }
1303 
1304 std::vector<rs2::stream_profile> get_supported_streams(rs2::sensor sensor, std::vector<rs2::stream_profile> profiles) {
1305  std::set<std::pair<rs2_stream, int>> supported_streams;
1306  auto hint = supported_streams.begin();
1307  // get the set of supported stream+index pairs
1308  for (auto& profile : sensor.get_stream_profiles()) {
1309  hint = supported_streams.emplace_hint(hint, profile.stream_type(), profile.stream_index());
1310  }
1311 
1312  // all profiles
1313  std::map<std::pair<rs2_stream, int>, rs2::stream_profile> all_profiles;
1314  for (auto& profile : profiles) {
1315  all_profiles.emplace(std::make_pair(profile.stream_type(), profile.stream_index()), profile);
1316  }
1317 
1318  std::vector<rs2::stream_profile> output;
1319  for (auto pair : supported_streams) {
1320  auto it = all_profiles.find(pair);
1321  if (it != all_profiles.end()) output.push_back(it->second);
1322  }
1323  return output;
1324 }
1325 
1326 TEST_CASE("get_active_streams sanity check", "[live]")
1327 {
1328  rs2::context ctx;
1330  {
1331  // Require at least one device to be plugged in
1332  REQUIRE_NOTHROW(ctx.query_devices().size() > 0);
1333 
1334  // Get device and a stream profile for each stream type it supports
1335  rs2::pipeline pipe(ctx);
1336  rs2::config cfg;
1337  rs2::pipeline_profile pipe_profile;
1338  cfg.enable_all_streams();
1339  REQUIRE_NOTHROW(pipe_profile = cfg.resolve(pipe));
1340 
1341  rs2::device dev = pipe_profile.get_device();
1342  std::vector<rs2::stream_profile> streams = pipe_profile.get_streams();
1343 
1344  for (auto&& sensor : dev.query_sensors())
1345  {
1346  // find which streams are supported by this specific sensor
1347  auto profiles = get_supported_streams(sensor, streams);
1348  auto n_streams = profiles.size();
1349  // iterate over all possible sets of streams supported by the sensor
1350  for (size_t bits=(1 << n_streams)-1; bits>0; --bits) {
1351  std::vector<rs2::stream_profile> opened_profiles;
1352  for (int i = 0; i < n_streams; ++i) {
1353  if (bits&(1ULL << i)) opened_profiles.push_back(profiles[i]);
1354  }
1355  REQUIRE_NOTHROW(sensor.open(opened_profiles));
1356  std::vector<rs2::stream_profile> reported_profiles;
1357  REQUIRE_NOTHROW(reported_profiles = sensor.get_active_streams());
1358 
1359  REQUIRE(reported_profiles == opened_profiles);
1360  sensor.close();
1361  }
1362  }
1363  }
1364 }
1365 
1366 TEST_CASE("Check option API", "[live][options]")
1367 {
1368  // Require at least one device to be plugged in
1369  rs2::context ctx;
1371  {
1372  std::vector<sensor> list;
1373  REQUIRE_NOTHROW(list = ctx.query_all_sensors());
1374  REQUIRE(list.size() > 0);
1375 
1376  // for each device
1377  for (auto&& dev : list)
1378  {
1379 
1380  // for each option
1381  for (auto i = 0; i < RS2_OPTION_COUNT; ++i) {
1382  auto opt = rs2_option(i);
1383  bool is_opt_supported;
1384  REQUIRE_NOTHROW(is_opt_supported = dev.supports(opt));
1385 
1386 
1387  SECTION("Ranges are sane")
1388  {
1389  if (!is_opt_supported)
1390  {
1391  REQUIRE_THROWS_AS(dev.get_option_range(opt), error);
1392  }
1393  else
1394  {
1396  REQUIRE_NOTHROW(range = dev.get_option_range(opt));
1397 
1398  // a couple sanity checks
1399  REQUIRE(range.min < range.max);
1400  REQUIRE(range.min + range.step <= range.max);
1401  REQUIRE(range.step > 0);
1402  REQUIRE(range.def <= range.max);
1403  REQUIRE(range.min <= range.def);
1404 
1405  // TODO: check that range.def == range.min + k*range.step for some k?
1406  // TODO: some sort of bounds checking against constants?
1407  }
1408  }
1409  SECTION("get_option returns a legal value")
1410  {
1411  if (!is_opt_supported)
1412  {
1413  REQUIRE_THROWS_AS(dev.get_option(opt), error);
1414  }
1415  else
1416  {
1417  auto range = dev.get_option_range(opt);
1418  float value;
1419  REQUIRE_NOTHROW(value = dev.get_option(opt));
1420 
1421  // value in range. Do I need to account for epsilon in lt[e]/gt[e] comparisons?
1422  REQUIRE(value >= range.min);
1423  REQUIRE(value <= range.max);
1424 
1425  // value doesn't change between two gets (if no additional threads are calling set)
1426  REQUIRE(dev.get_option(opt) == approx(value));
1427 
1428  // REQUIRE(value == approx(range.def)); // Not sure if this is a reasonable check
1429  // TODO: make sure value == range.min + k*range.step for some k?
1430  }
1431  }
1432  SECTION("set opt doesn't like bad values") {
1433  if (!is_opt_supported)
1434  {
1435  REQUIRE_THROWS_AS(dev.set_option(opt, 1), error);
1436  }
1437  else
1438  {
1439  auto range = dev.get_option_range(opt);
1440 
1441  // minimum should work, as should maximum
1442  REQUIRE_NOTHROW(dev.set_option(opt, range.min));
1443  REQUIRE_NOTHROW(dev.set_option(opt, range.max));
1444 
1445  int n_steps = int((range.max - range.min) / range.step);
1446 
1447  // check a few arbitrary points along the scale
1448  REQUIRE_NOTHROW(dev.set_option(opt, range.min + (1 % n_steps)*range.step));
1449  REQUIRE_NOTHROW(dev.set_option(opt, range.min + (11 % n_steps)*range.step));
1450  REQUIRE_NOTHROW(dev.set_option(opt, range.min + (111 % n_steps)*range.step));
1451  REQUIRE_NOTHROW(dev.set_option(opt, range.min + (1111 % n_steps)*range.step));
1452 
1453  // below min and above max shouldn't work
1454  REQUIRE_THROWS_AS(dev.set_option(opt, range.min - range.step), error);
1455  REQUIRE_THROWS_AS(dev.set_option(opt, range.max + range.step), error);
1456 
1457  // make sure requesting value in the range, but not a legal step doesn't work
1458  // TODO: maybe something for range.step < 1 ?
1459  for (auto j = 1; j < range.step; j++) {
1460  CAPTURE(range.step);
1461  CAPTURE(j);
1462  REQUIRE_THROWS_AS(dev.set_option(opt, range.min + j), error);
1463  }
1464  }
1465  }
1466  SECTION("check get/set sequencing works as expected") {
1467  if (!is_opt_supported) continue;
1468  auto range = dev.get_option_range(opt);
1469 
1470  // setting a valid value lets you get that value back
1471  dev.set_option(opt, range.min);
1472  REQUIRE(dev.get_option(opt) == approx(range.min));
1473 
1474  // setting an invalid value returns the last set valid value.
1475  REQUIRE_THROWS(dev.set_option(opt, range.max + range.step));
1476  REQUIRE(dev.get_option(opt) == approx(range.min));
1477 
1478  dev.set_option(opt, range.max);
1479  REQUIRE_THROWS(dev.set_option(opt, range.min - range.step));
1480  REQUIRE(dev.get_option(opt) == approx(range.max));
1481 
1482  }
1483  SECTION("get_description returns a non-empty, non-null string") {
1484  if (!is_opt_supported) {
1485  REQUIRE_THROWS_AS(dev.get_option_description(opt), error);
1486  }
1487  else
1488  {
1489  REQUIRE(dev.get_option_description(opt) != nullptr);
1490  REQUIRE(std::string(dev.get_option_description(opt)) != std::string(""));
1491  }
1492  }
1493  // TODO: tests for get_option_value_description? possibly too open a function to have useful tests
1494  }
1495  }
1496  }
1497 }
1498 
1499 // List of controls coupled together, such as modifying one of them would impose changes(affect) other options if modified
1500 // The list is managed per-sensor/SKU
1502 {
1508 };
1509 
1511 
1512 const std::map<dev_type,dev_group> dev_map = {
1513  /* RS400/PSR*/ { { "0AD1", true }, e_d400},
1514  /* RS410/ASR*/ { { "0AD2", true }, e_d400 },
1515  { { "0AD2", false }, e_d400},
1516  /* RS415/ASRC*/ { { "0AD3", true }, e_d400},
1517  { { "0AD3", false }, e_d400},
1518  /* RS430/AWG*/ { { "0AD4", true }, e_d400},
1519  /* RS430_MM / AWGT*/{ { "0AD5", true }, e_d400},
1520  /* D4/USB2*/ { { "0AD6", false }, e_d400 },
1521  /* RS420/PWG*/ { { "0AF6", true }, e_d400},
1522  /* RS420_MM/PWGT*/ { { "0AFE", true }, e_d400},
1523  /* RS410_MM/ASRT*/ { { "0AFF", true }, e_d400},
1524  /* RS400_MM/PSR*/ { { "0B00", true }, e_d400},
1525  /* RS405/DS5U*/ { { "0B01", true }, e_d400},
1526  /* RS430_MMC/AWGTC*/{ { "0B03", true }, e_d400},
1527  /* RS435_RGB/AWGC*/ { { "0B07", true }, e_d400},
1528  { { "0B07", false }, e_d400},
1529  /* DS5U */ { { "0B0C", true }, e_d400},
1530  /* D435I */ { { "0B3A", true }, e_d400},
1531  /*SR300*/ { { "0AA5", true }, e_sr300 },
1532 };
1533 
1534 // Testing bundled depth controls
1535 const std::map<dev_group, std::vector<option_bundle> > auto_disabling_controls =
1536 {
1538  { RS2_STREAM_DEPTH, RS2_OPTION_GAIN, RS2_OPTION_ENABLE_AUTO_EXPOSURE, 1.f, 1.f } } }, // The value remain intact == the controls shall not affect each other
1539  //{ e_sr300, { { RS2_STREAM_DEPTH, TBD, TBD, 1.f, 0.f } } }, Provision for
1540 };
1541 
1542 // Verify that the bundled controls (Exposure<->Aut-Exposure) are in sync
1543 TEST_CASE("Auto-Disabling Controls", "[live][options]")
1544 {
1545  // Require at least one device to be plugged in
1546  rs2::context ctx;
1548  {
1549  std::vector<rs2::device> list;
1550  REQUIRE_NOTHROW(list = ctx.query_devices());
1551  REQUIRE(list.size() > 0);
1552 
1553  // for each sensor
1554  for (auto&& dev : list)
1555  {
1557  dev_type PID = get_PID(dev);
1558  CAPTURE(PID.first);
1559  CAPTURE(PID.second);
1560  auto dev_grp{ e_unresolved_grp };
1561  REQUIRE_NOTHROW(dev_grp = dev_map.at(PID));
1562 
1563  for (auto&& snr : dev.query_sensors())
1564  {
1565  // The test will apply to depth sensor only. In future may be extended for additional type of sensors
1566  if (snr.is<depth_sensor>())
1567  {
1568  auto entry = auto_disabling_controls.find(dev_grp);
1569  if (auto_disabling_controls.end() == entry)
1570  {
1571  WARN("Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ? " USB3" : " USB2"));
1572  }
1573  else
1574  {
1575  auto test_patterns = auto_disabling_controls.at(dev_grp);
1576  REQUIRE(test_patterns.size() > 0);
1577 
1578  for (auto i = 0; i < test_patterns.size(); ++i)
1579  {
1580  if (test_patterns[i].sensor_type != RS2_STREAM_DEPTH)
1581  continue;
1582 
1583  auto orig_opt = test_patterns[i].master_option;
1584  auto tgt_opt = test_patterns[i].slave_option;
1585  bool opt_orig_supported{};
1586  bool opt_tgt_supported{};
1587  REQUIRE_NOTHROW(opt_orig_supported = snr.supports(orig_opt));
1588  REQUIRE_NOTHROW(opt_tgt_supported = snr.supports(tgt_opt));
1589 
1590  if (opt_orig_supported && opt_tgt_supported)
1591  {
1592  rs2::option_range master_range,slave_range;
1593  REQUIRE_NOTHROW(master_range = snr.get_option_range(orig_opt));
1594  REQUIRE_NOTHROW(slave_range = snr.get_option_range(tgt_opt));
1595 
1596  // Switch the receiving options into the responding state
1597  auto slave_cur_val = snr.get_option(tgt_opt);
1598  if (slave_cur_val != test_patterns[i].slave_val_before)
1599  {
1600  REQUIRE_NOTHROW(snr.set_option(tgt_opt, test_patterns[i].slave_val_before));
1601  //std::this_thread::sleep_for(std::chrono::milliseconds(500));
1602  REQUIRE(snr.get_option(tgt_opt) == test_patterns[i].slave_val_before);
1603  }
1604 
1605  // Modify the originating control and verify that the target control has been modified as well
1606  // Modifying gain while in auto exposure throws an exception.
1607  try
1608  {
1609  (snr.set_option(orig_opt, master_range.def));
1610  }
1611  catch (...)
1612  {
1613  continue;
1614  }
1615  REQUIRE(snr.get_option(tgt_opt) == test_patterns[i].slave_val_after);
1616  }
1617  }
1618  }
1619  }
1620  }
1621  } // for (auto&& dev : list)
1622  }
1623 }
1624 
1627 TEST_CASE("Multiple devices", "[live][multicam][!mayfail]")
1628 {
1629  rs2::context ctx;
1631  {
1632  // Require at least one device to be plugged in
1633  std::vector<sensor> list;
1634  REQUIRE_NOTHROW(list = ctx.query_all_sensors());
1635  REQUIRE(list.size() > 0);
1636 
1637  SECTION("subdevices on a single device")
1638  {
1639  for (auto & dev : list)
1640  {
1642 
1643  SECTION("opening the same subdevice multiple times")
1644  {
1645  auto modes = dev.get_stream_profiles();
1646  REQUIRE(modes.size() > 0);
1647  CAPTURE(modes.front().stream_type());
1648  REQUIRE_NOTHROW(dev.open(modes.front()));
1649 
1650  SECTION("same mode")
1651  {
1652  // selected, but not streaming
1653  REQUIRE_THROWS_AS(dev.open({ modes.front() }), error);
1654 
1655  // streaming
1656  REQUIRE_NOTHROW(dev.start([](rs2::frame fref) {}));
1657  REQUIRE_THROWS_AS(dev.open({ modes.front() }), error);
1658  }
1659 
1660  SECTION("different modes")
1661  {
1662  if (modes.size() == 1)
1663  {
1664  WARN("device " << dev.get_info(RS2_CAMERA_INFO_NAME) << " S/N: " << dev.get_info(
1665  RS2_CAMERA_INFO_SERIAL_NUMBER) << " w/ FW v" << dev.get_info(
1667  WARN("subdevice has only 1 supported streaming mode. Skipping Same Subdevice, different modes test.");
1668  }
1669  else
1670  {
1671  // selected, but not streaming
1672  REQUIRE_THROWS_AS(dev.open({ modes[1] }), error);
1673 
1674  // streaming
1675  REQUIRE_NOTHROW(dev.start([](rs2::frame fref) {}));
1676  REQUIRE_THROWS_AS(dev.open({ modes[1] }), error);
1677  }
1678  }
1679 
1680  REQUIRE_NOTHROW(dev.stop());
1681  }
1682  // TODO: Move
1683  SECTION("opening different subdevices") {
1684  for (auto&& subdevice1 : ctx.get_sensor_parent(dev).query_sensors())
1685  {
1686  disable_sensitive_options_for(subdevice1);
1687  for (auto&& subdevice2 : ctx.get_sensor_parent(dev).query_sensors())
1688  {
1689  disable_sensitive_options_for(subdevice2);
1690 
1691  if (subdevice1 == subdevice2)
1692  continue;
1693 
1694  // get first lock
1695  REQUIRE_NOTHROW(subdevice1.open(subdevice1.get_stream_profiles().front()));
1696 
1697  // selected, but not streaming
1698  {
1699  auto profile = subdevice2.get_stream_profiles().front();
1700 
1701  CAPTURE(profile.stream_type());
1702  CAPTURE(profile.format());
1703  CAPTURE(profile.fps());
1704  auto vid_p = profile.as<rs2::video_stream_profile>();
1705  CAPTURE(vid_p.width());
1706  CAPTURE(vid_p.height());
1707 
1708  REQUIRE_NOTHROW(subdevice2.open(subdevice2.get_stream_profiles().front()));
1709  REQUIRE_NOTHROW(subdevice2.start([](rs2::frame fref) {}));
1710  REQUIRE_NOTHROW(subdevice2.stop());
1711  REQUIRE_NOTHROW(subdevice2.close());
1712  }
1713 
1714  // streaming
1715  {
1716  REQUIRE_NOTHROW(subdevice1.start([](rs2::frame fref) {}));
1717  REQUIRE_NOTHROW(subdevice2.open(subdevice2.get_stream_profiles().front()));
1718  REQUIRE_NOTHROW(subdevice2.start([](rs2::frame fref) {}));
1719  // stop streaming in opposite order just to be sure that works too
1720  REQUIRE_NOTHROW(subdevice1.stop());
1721  REQUIRE_NOTHROW(subdevice2.stop());
1722  REQUIRE_NOTHROW(subdevice2.close());
1723  }
1724 
1725  REQUIRE_NOTHROW(subdevice1.close());
1726  }
1727  }
1728  }
1729  }
1730  }
1731  SECTION("multiple devices")
1732  {
1733  if (list.size() == 1)
1734  {
1735  WARN("Only one device connected. Skipping multi-device test");
1736  }
1737  else
1738  {
1739  for (auto & dev1 : list)
1740  {
1742  for (auto & dev2 : list)
1743  {
1744  // couldn't think of a better way to compare the two...
1745  if (dev1 == dev2)
1746  continue;
1747 
1749 
1750  auto dev1_profiles = dev1.get_stream_profiles();
1751  auto dev2_profiles = dev2.get_stream_profiles();
1752 
1753  if (!dev1_profiles.size() || !dev2_profiles.size())
1754  continue;
1755 
1756  auto dev1_profile = dev1_profiles.front();
1757  auto dev2_profile = dev2_profiles.front();
1758 
1759  CAPTURE(dev1_profile.stream_type());
1760  CAPTURE(dev1_profile.format());
1761  CAPTURE(dev1_profile.fps());
1762  auto vid_p1 = dev1_profile.as<rs2::video_stream_profile>();
1763  CAPTURE(vid_p1.width());
1764  CAPTURE(vid_p1.height());
1765 
1766  CAPTURE(dev2_profile.stream_type());
1767  CAPTURE(dev2_profile.format());
1768  CAPTURE(dev2_profile.fps());
1769  auto vid_p2 = dev2_profile.as<rs2::video_stream_profile>();
1770  CAPTURE(vid_p2.width());
1771  CAPTURE(vid_p2.height());
1772 
1773  REQUIRE_NOTHROW(dev1.open(dev1_profile));
1774  REQUIRE_NOTHROW(dev2.open(dev2_profile));
1775 
1776  REQUIRE_NOTHROW(dev1.start([](rs2::frame fref) {}));
1777  REQUIRE_NOTHROW(dev2.start([](rs2::frame fref) {}));
1778  REQUIRE_NOTHROW(dev1.stop());
1779  REQUIRE_NOTHROW(dev2.stop());
1780 
1781  REQUIRE_NOTHROW(dev1.close());
1782  REQUIRE_NOTHROW(dev2.close());
1783  }
1784  }
1785  }
1786  }
1787  }
1788 }
1789 
1790 // On Windows 10 RS2 there is an unusual behaviour that may fail this test:
1791 // When trying to enable the second instance of Source Reader, instead of failing, the Media Foundation allows it
1792 // and sends an HR to the first Source Reader instead (something about the application being preempted)
1793 TEST_CASE("Multiple applications", "[live][multicam][!mayfail]")
1794 {
1795  rs2::context ctx1;
1797  {
1798  // Require at least one device to be plugged in
1799  std::vector<sensor> list1;
1800  REQUIRE_NOTHROW(list1 = ctx1.query_all_sensors());
1801  REQUIRE(list1.size() > 0);
1802 
1803  rs2::context ctx2;
1804  REQUIRE(make_context("two_contexts", &ctx2));
1805  std::vector<sensor> list2;
1806  REQUIRE_NOTHROW(list2 = ctx2.query_all_sensors());
1807  REQUIRE(list2.size() == list1.size());
1808  SECTION("subdevices on a single device")
1809  {
1810  for (auto&& dev1 : list1)
1811  {
1813  for (auto&& dev2 : list2)
1814  {
1816 
1817  if (dev1 == dev2)
1818  {
1819  bool skip_section = false;
1820 #ifdef _WIN32
1821  skip_section = true;
1822 #endif
1823  if (!skip_section)
1824  {
1825  SECTION("same subdevice") {
1826  // get modes
1827  std::vector<rs2::stream_profile> modes1, modes2;
1828  REQUIRE_NOTHROW(modes1 = dev1.get_stream_profiles());
1829  REQUIRE_NOTHROW(modes2 = dev2.get_stream_profiles());
1830  REQUIRE(modes1.size() > 0);
1831  REQUIRE(modes1.size() == modes2.size());
1832  // require that the lists are the same (disregarding order)
1833  for (auto profile : modes1) {
1834  REQUIRE(std::any_of(begin(modes2), end(modes2), [&profile](const rs2::stream_profile & p)
1835  {
1836  return profile == p;
1837  }));
1838  }
1839 
1840  // grab first lock
1841  CAPTURE(modes1.front().stream_name());
1842  REQUIRE_NOTHROW(dev1.open(modes1.front()));
1843 
1844  SECTION("same mode")
1845  {
1846  // selected, but not streaming
1847  REQUIRE_THROWS_AS(dev2.open({ modes1.front() }), error);
1848 
1849  // streaming
1850  REQUIRE_NOTHROW(dev1.start([](rs2::frame fref) {}));
1851  REQUIRE_THROWS_AS(dev2.open({ modes1.front() }), error);
1852  }
1853  SECTION("different modes")
1854  {
1855  if (modes1.size() == 1)
1856  {
1857  WARN("device " << dev1.get_info(RS2_CAMERA_INFO_NAME) << " S/N: " << dev1.get_info(
1858  RS2_CAMERA_INFO_SERIAL_NUMBER) << " w/ FW v" << dev1.get_info(
1860  WARN("Device has only 1 supported streaming mode. Skipping Same Subdevice, different modes test.");
1861  }
1862  else
1863  {
1864  // selected, but not streaming
1865  REQUIRE_THROWS_AS(dev2.open({ modes1[1] }), error);
1866 
1867  // streaming
1868  REQUIRE_NOTHROW(dev1.start([](rs2::frame fref) {}));
1869  REQUIRE_THROWS_AS(dev2.open({ modes1[1] }), error);
1870  }
1871  }
1872  REQUIRE_NOTHROW(dev1.stop());
1873  }
1874  }
1875  }
1876  else
1877  {
1878  SECTION("different subdevice")
1879  {
1880  // get first lock
1881  REQUIRE_NOTHROW(dev1.open(dev1.get_stream_profiles().front()));
1882 
1883  // selected, but not streaming
1884  {
1885  CAPTURE(dev2.get_stream_profiles().front().stream_type());
1886  REQUIRE_NOTHROW(dev2.open(dev2.get_stream_profiles().front()));
1887  REQUIRE_NOTHROW(dev2.start([](rs2::frame fref) {}));
1888  REQUIRE_NOTHROW(dev2.stop());
1889  REQUIRE_NOTHROW(dev2.close());
1890  }
1891 
1892  // streaming
1893  {
1894  REQUIRE_NOTHROW(dev1.start([](rs2::frame fref) {}));
1895  REQUIRE_NOTHROW(dev2.open(dev2.get_stream_profiles().front()));
1896  REQUIRE_NOTHROW(dev2.start([](rs2::frame fref) {}));
1897  // stop streaming in opposite order just to be sure that works too
1898  REQUIRE_NOTHROW(dev1.stop());
1899  REQUIRE_NOTHROW(dev2.stop());
1900 
1901  REQUIRE_NOTHROW(dev1.close());
1902  REQUIRE_NOTHROW(dev2.close());
1903  }
1904  }
1905  }
1906  }
1907  }
1908  }
1909  SECTION("subdevices on separate devices")
1910  {
1911  if (list1.size() == 1)
1912  {
1913  WARN("Only one device connected. Skipping multi-device test");
1914  }
1915  else
1916  {
1917  for (auto & dev1 : list1)
1918  {
1920  for (auto & dev2 : list2)
1921  {
1923 
1924  if (dev1 == dev2)
1925  continue;
1926 
1927  // get modes
1928  std::vector<rs2::stream_profile> modes1, modes2;
1929  REQUIRE_NOTHROW(modes1 = dev1.get_stream_profiles());
1930  REQUIRE_NOTHROW(modes2 = dev2.get_stream_profiles());
1931  REQUIRE(modes1.size() > 0);
1932  REQUIRE(modes2.size() > 0);
1933 
1934  // grab first lock
1935  CAPTURE(modes1.front().stream_type());
1936  CAPTURE(dev1.get_info(RS2_CAMERA_INFO_NAME));
1937  CAPTURE(dev1.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER));
1938  CAPTURE(dev2.get_info(RS2_CAMERA_INFO_NAME));
1939  CAPTURE(dev2.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER));
1940  REQUIRE_NOTHROW(dev1.open(modes1.front()));
1941 
1942  // try to acquire second lock
1943 
1944  // selected, but not streaming
1945  {
1946  REQUIRE_NOTHROW(dev2.open({ modes2.front() }));
1947  REQUIRE_NOTHROW(dev2.start([](rs2::frame fref) {}));
1948  REQUIRE_NOTHROW(dev2.stop());
1949  REQUIRE_NOTHROW(dev2.close());
1950  }
1951 
1952  // streaming
1953  {
1954  REQUIRE_NOTHROW(dev1.start([](rs2::frame fref) {}));
1955  REQUIRE_NOTHROW(dev2.open({ modes2.front() }));
1956  REQUIRE_NOTHROW(dev2.start([](rs2::frame fref) {}));
1957  // stop streaming in opposite order just to be sure that works too
1958  REQUIRE_NOTHROW(dev1.stop());
1959  REQUIRE_NOTHROW(dev2.stop());
1960  REQUIRE_NOTHROW(dev2.close());
1961  }
1962 
1963  REQUIRE_NOTHROW(dev1.close());
1964  }
1965  }
1966  }
1967  }
1968  }
1969 }
1970 
1971 
1972 //
1974 void metadata_verification(const std::vector<internal_frame_additional_data>& data)
1975 {
1976  // Heuristics that we use to verify metadata
1977  // Metadata sanity
1978  // Frame numbers and timestamps increase monotonically
1979  // Sensor timestamp should be less or equal to frame timestamp
1980  // Exposure time and gain values are greater than zero
1981  // Sensor framerate is bounded to >0 and < 200 fps for uvc streams
1982  int64_t last_val[3] = { -1, -1, -1 };
1983 
1984  for (size_t i = 0; i < data.size(); i++)
1985  {
1986 
1987  // Check that Frame/Sensor timetamps, frame number rise monotonically
1989  {
1990  if (data[i].frame_md.md_attributes[j].first)
1991  {
1992  int64_t value = data[i].frame_md.md_attributes[j].second;
1993  CAPTURE(value);
1994  CAPTURE(last_val[j]);
1995 
1996  REQUIRE((value > last_val[j]));
1997  if (RS2_FRAME_METADATA_FRAME_COUNTER == j && last_val[j] >= 0) // In addition, there shall be no frame number gaps
1998  {
1999  REQUIRE((1 == (value - last_val[j])));
2000  }
2001 
2002  last_val[j] = data[i].frame_md.md_attributes[j].second;
2003  }
2004  }
2005 
2006  // Metadata below must have a non negative value
2007  auto md = data[i].frame_md.md_attributes[RS2_FRAME_METADATA_ACTUAL_EXPOSURE];
2008  if (md.first) REQUIRE(md.second >= 0);
2009  md = data[i].frame_md.md_attributes[RS2_FRAME_METADATA_GAIN_LEVEL];
2010  if (md.first) REQUIRE(md.second >= 0);
2011  md = data[i].frame_md.md_attributes[RS2_FRAME_METADATA_TIME_OF_ARRIVAL];
2012  if (md.first) REQUIRE(md.second >= 0);
2013  md = data[i].frame_md.md_attributes[RS2_FRAME_METADATA_BACKEND_TIMESTAMP];
2014  if (md.first) REQUIRE(md.second >= 0);
2015  md = data[i].frame_md.md_attributes[RS2_FRAME_METADATA_ACTUAL_FPS];
2016  if (md.first) REQUIRE(md.second >= 0);
2017  md = data[i].frame_md.md_attributes[RS2_FRAME_METADATA_POWER_LINE_FREQUENCY];
2018  if (md.first) REQUIRE(md.second >= 0);
2019 
2020  // Metadata below must have a boolean value
2021  md = data[i].frame_md.md_attributes[RS2_FRAME_METADATA_AUTO_EXPOSURE];
2022  if (md.first) REQUIRE((md.second == 0 || md.second == 1));
2023  md = data[i].frame_md.md_attributes[RS2_FRAME_METADATA_FRAME_LASER_POWER_MODE];
2024  if (md.first) REQUIRE((md.second == 0 || md.second == 1));
2025  md = data[i].frame_md.md_attributes[RS2_FRAME_METADATA_AUTO_WHITE_BALANCE_TEMPERATURE];
2026  if (md.first) REQUIRE((md.second == 0 || md.second == 1));
2027  md = data[i].frame_md.md_attributes[RS2_FRAME_METADATA_BACKLIGHT_COMPENSATION];
2028  if (md.first) REQUIRE((md.second == 0 || md.second == 1));
2029  md = data[i].frame_md.md_attributes[RS2_FRAME_METADATA_LOW_LIGHT_COMPENSATION];
2030  if (md.first) REQUIRE((md.second == 0 || md.second == 1));
2031  }
2032 }
2033 
2034 
2037 {
2038  std::vector<uint8_t> raw_data(24, 0);
2039  raw_data[0] = 0x14;
2040  raw_data[2] = 0xab;
2041  raw_data[3] = 0xcd;
2042  raw_data[4] = 0x4d;
2043  raw_data[8] = num;
2044  if (auto debug = dev.as<debug_protocol>())
2045  debug.send_and_receive_raw_data(raw_data);
2046 }
2047 
2048 
2049 
2050 TEST_CASE("Error handling sanity", "[live][!mayfail]") {
2051 
2052  //Require at least one device to be plugged in
2053  rs2::context ctx;
2055  {
2056  std::vector<sensor> list;
2057  REQUIRE_NOTHROW(list = ctx.query_all_sensors());
2058  REQUIRE(list.size() > 0);
2059 
2060  std::string notification_description;
2062  std::condition_variable cv;
2063  std::mutex m;
2064 
2065  // An exempt of possible error values - note that the full list is available to Librealsenes core
2066  const std::map< uint8_t, std::string> error_report = {
2067  { 0, "Success" },
2068  { 1, "Laser hot - power reduce" },
2069  { 2, "Laser hot - disabled" },
2070  { 3, "Flag B - laser disabled" },
2071  };
2072 
2073  //enable error polling
2074  for (auto && subdevice : list) {
2075 
2076  if (subdevice.supports(RS2_OPTION_ERROR_POLLING_ENABLED))
2077  {
2078  disable_sensitive_options_for(subdevice);
2079 
2080  subdevice.set_notifications_callback([&](rs2::notification n)
2081  {
2082  std::unique_lock<std::mutex> lock(m);
2083 
2084  notification_description = n.get_description();
2085  severity = n.get_severity();
2086  cv.notify_one();
2087  });
2088 
2089  REQUIRE_NOTHROW(subdevice.set_option(RS2_OPTION_ERROR_POLLING_ENABLED, 1));
2090 
2091  // The first entry with success value cannot be emulated
2092  for (auto i = 1; i < error_report.size(); i++)
2093  {
2094  trigger_error(ctx.get_sensor_parent(subdevice), i);
2095  std::unique_lock<std::mutex> lock(m);
2096  CAPTURE(i);
2097  CAPTURE(error_report.at(i));
2098  CAPTURE(severity);
2099  auto pred = [&]() {
2100  return notification_description.compare(error_report.at(i)) == 0
2101  && severity == RS2_LOG_SEVERITY_ERROR;
2102  };
2103  REQUIRE(cv.wait_for(lock, std::chrono::seconds(10), pred));
2104 
2105  }
2106  REQUIRE_NOTHROW(subdevice.set_option(RS2_OPTION_ERROR_POLLING_ENABLED, 0));
2107  }
2108  }
2109  }
2110 }
2111 
2112 std::vector<uint32_t> split(const std::string &s, char delim) {
2113  std::stringstream ss(s);
2114  std::string item;
2115  std::vector<uint32_t> tokens;
2116  while (std::getline(ss, item, delim)) {
2117  tokens.push_back(std::stoi(item, nullptr));
2118  }
2119  return tokens;
2120 }
2121 
2122 bool is_fw_version_newer(rs2::sensor& subdevice, const uint32_t other_fw[4])
2123 {
2124  std::string fw_version_str;
2125  REQUIRE_NOTHROW(fw_version_str = subdevice.get_info(RS2_CAMERA_INFO_FIRMWARE_VERSION));
2126  auto fw = split(fw_version_str, '.');
2127  if (fw[0] > other_fw[0])
2128  return true;
2129  if (fw[0] == other_fw[0] && fw[1] > other_fw[1])
2130  return true;
2131  if (fw[0] == other_fw[0] && fw[1] == other_fw[1] && fw[2] > other_fw[2])
2132  return true;
2133  if (fw[0] == other_fw[0] && fw[1] == other_fw[1] && fw[2] == other_fw[2] && fw[3] > other_fw[3])
2134  return true;
2135  if (fw[0] == other_fw[0] && fw[1] == other_fw[1] && fw[2] == other_fw[2] && fw[3] == other_fw[3])
2136  return true;
2137  return false;
2138 }
2139 
2140 
2141 TEST_CASE("Auto disabling control behavior", "[live]") {
2142  //Require at least one device to be plugged in
2143  rs2::context ctx;
2145  {
2146  std::vector<sensor> list;
2147  REQUIRE_NOTHROW(list = ctx.query_all_sensors());
2148  REQUIRE(list.size() > 0);
2149 
2150  for (auto && subdevice : list)
2151  {
2152  disable_sensitive_options_for(subdevice);
2153  auto info = subdevice.get_info(RS2_CAMERA_INFO_NAME);
2154  CAPTURE(info);
2155 
2157  float val{};
2158  if (subdevice.supports(RS2_OPTION_ENABLE_AUTO_EXPOSURE))
2159  {
2160  SECTION("Disable auto exposure when setting a value")
2161  {
2162  REQUIRE_NOTHROW(subdevice.set_option(RS2_OPTION_ENABLE_AUTO_EXPOSURE, 1));
2163  REQUIRE_NOTHROW(range = subdevice.get_option_range(RS2_OPTION_EXPOSURE));
2164  REQUIRE_NOTHROW(subdevice.set_option(RS2_OPTION_EXPOSURE, range.max));
2165  CAPTURE(range.max);
2166  REQUIRE_NOTHROW(val = subdevice.get_option(RS2_OPTION_ENABLE_AUTO_EXPOSURE));
2167  REQUIRE(val == 0);
2168  }
2169  }
2170 
2171  if (subdevice.supports(RS2_OPTION_EMITTER_ENABLED))
2172  {
2173  SECTION("Disable emitter when setting a value")
2174  {
2175  for (auto elem : { 0.f, 2.f })
2176  {
2177  CAPTURE(elem);
2178  REQUIRE_NOTHROW(subdevice.set_option(RS2_OPTION_EMITTER_ENABLED, elem));
2179  REQUIRE_NOTHROW(range = subdevice.get_option_range(RS2_OPTION_LASER_POWER));
2180  REQUIRE_NOTHROW(subdevice.set_option(RS2_OPTION_LASER_POWER, range.max));
2181  CAPTURE(range.max);
2182  REQUIRE_NOTHROW(val = subdevice.get_option(RS2_OPTION_EMITTER_ENABLED));
2183  REQUIRE(val == 1);
2184  //0 - on, 1- off, 2 - deprecated for fw later than 5.9.11.0
2185  //check if the fw version supports elem = 2
2186  const uint32_t MIN_FW_VER[4] = { 5, 9, 11, 0 };
2187  if (is_fw_version_newer(subdevice, MIN_FW_VER)) break;
2188  }
2189  }
2190  }
2191 
2192  if (subdevice.supports(RS2_OPTION_ENABLE_AUTO_WHITE_BALANCE)) // TODO: Add auto-disabling to SR300 options
2193  {
2194  SECTION("Disable white balance when setting a value")
2195  {
2196  if (subdevice.supports(RS2_OPTION_ENABLE_AUTO_WHITE_BALANCE) && subdevice.supports(RS2_OPTION_WHITE_BALANCE))
2197  {
2198 
2199  REQUIRE_NOTHROW(subdevice.set_option(RS2_OPTION_ENABLE_AUTO_WHITE_BALANCE, 1));
2200  REQUIRE_NOTHROW(range = subdevice.get_option_range(RS2_OPTION_WHITE_BALANCE));
2201  REQUIRE_NOTHROW(subdevice.set_option(RS2_OPTION_WHITE_BALANCE, range.max));
2202  CAPTURE(range.max);
2203  REQUIRE_NOTHROW(val = subdevice.get_option(RS2_OPTION_ENABLE_AUTO_WHITE_BALANCE));
2204  REQUIRE(val == 0);
2205  }
2206  }
2207  }
2208  }
2209  }
2210 }
2211 
2212 
2213 std::pair<std::shared_ptr<rs2::device>, std::weak_ptr<rs2::device>> make_device(device_list& list)
2214 {
2215  REQUIRE(list.size() > 0);
2216 
2217  std::shared_ptr<rs2::device> dev;
2218  REQUIRE_NOTHROW(dev = std::make_shared<rs2::device>(list[0]));
2219  std::weak_ptr<rs2::device> weak_dev(dev);
2220 
2222 
2223  return std::pair<std::shared_ptr<rs2::device>, std::weak_ptr<rs2::device>>(dev, weak_dev);
2224 }
2225 
2226 void reset_device(std::shared_ptr<rs2::device>& strong, std::weak_ptr<rs2::device>& weak, device_list& list, const rs2::device& new_dev)
2227 {
2228  strong.reset();
2229  weak.reset();
2230  list = nullptr;
2231  strong = std::make_shared<rs2::device>(new_dev);
2232  weak = strong;
2234 }
2235 
2236 TEST_CASE("Disconnect events works", "[live]") {
2237 
2238  rs2::context ctx;
2240  {
2241  device_list list;
2242  REQUIRE_NOTHROW(list = ctx.query_devices());
2243 
2244  auto dev = make_device(list);
2245  auto dev_strong = dev.first;
2246  auto dev_weak = dev.second;
2247 
2248 
2249  auto disconnected = false;
2250  auto connected = false;
2251 
2252  std::string serial;
2253 
2254  REQUIRE_NOTHROW(serial = dev_strong->get_info(RS2_CAMERA_INFO_SERIAL_NUMBER));
2255 
2256  std::condition_variable cv;
2257  std::mutex m;
2258 
2259  //Setting up devices change callback to notify the test about device disconnection
2261  {
2262  auto&& strong = dev_weak.lock();
2263  {
2264  if (strong)
2265  {
2266  if (info.was_removed(*strong))
2267  {
2268  std::unique_lock<std::mutex> lock(m);
2269  disconnected = true;
2270  cv.notify_one();
2271  }
2272 
2273 
2274  for (auto d : info.get_new_devices())
2275  {
2276  for (auto&& s : d.query_sensors())
2277  disable_sensitive_options_for(s);
2278 
2279  if (serial == d.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER))
2280  {
2281  try
2282  {
2283  std::unique_lock<std::mutex> lock(m);
2284  connected = true;
2285  cv.notify_one();
2286  break;
2287  }
2288  catch (...)
2289  {
2290 
2291  }
2292  }
2293  }
2294  }
2295 
2296  }}));
2297 
2298  //forcing hardware reset to simulate device disconnection
2299  do_with_waiting_for_camera_connection(ctx, dev_strong, serial, [&]()
2300  {
2301  dev_strong->hardware_reset();
2302  });
2303 
2304  //Check that after the library reported device disconnection, operations on old device object will return error
2305  REQUIRE_THROWS(dev_strong->query_sensors().front().close());
2306  }
2307 }
2308 
2309 TEST_CASE("Connect events works", "[live]") {
2310 
2311 
2312  rs2::context ctx;
2314  {
2315  device_list list;
2316  REQUIRE_NOTHROW(list = ctx.query_devices());
2317 
2318  auto dev = make_device(list);
2319  auto dev_strong = dev.first;
2320  auto dev_weak = dev.second;
2321 
2322  std::string serial;
2323 
2324  REQUIRE_NOTHROW(serial = dev_strong->get_info(RS2_CAMERA_INFO_SERIAL_NUMBER));
2325 
2326  auto disconnected = false;
2327  auto connected = false;
2328  std::condition_variable cv;
2329  std::mutex m;
2330 
2331  //Setting up devices change callback to notify the test about device disconnection and connection
2333  {
2334  auto&& strong = dev_weak.lock();
2335  {
2336  if (strong)
2337  {
2338  if (info.was_removed(*strong))
2339  {
2340  std::unique_lock<std::mutex> lock(m);
2341  disconnected = true;
2342  cv.notify_one();
2343  }
2344 
2345 
2346  for (auto d : info.get_new_devices())
2347  {
2348  if (serial == d.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER))
2349  {
2350  try
2351  {
2352  std::unique_lock<std::mutex> lock(m);
2353 
2354  reset_device(dev_strong, dev_weak, list, d);
2355 
2356  connected = true;
2357  cv.notify_one();
2358  break;
2359  }
2360  catch (...)
2361  {
2362 
2363  }
2364  }
2365  }
2366  }
2367 
2368  }}));
2369 
2370  //forcing hardware reset to simulate device disconnection
2371  do_with_waiting_for_camera_connection(ctx, dev_strong, serial, [&]()
2372  {
2373  dev_strong->hardware_reset();
2374  });
2375  }
2376 }
2377 
2378 std::shared_ptr<std::function<void(rs2::frame fref)>> check_stream_sanity(const context& ctx, const sensor& sub, int num_of_frames, bool infinite = false)
2379 {
2380  std::shared_ptr<std::condition_variable> cv = std::make_shared<std::condition_variable>();
2381  std::shared_ptr<std::mutex> m = std::make_shared<std::mutex>();
2382  std::shared_ptr<std::map<rs2_stream, int>> streams_frames = std::make_shared<std::map<rs2_stream, int>>();
2383 
2384  std::shared_ptr<std::function<void(rs2::frame fref)>> func;
2385 
2386  std::vector<rs2::stream_profile> modes;
2387  REQUIRE_NOTHROW(modes = sub.get_stream_profiles());
2388 
2389  auto streaming = false;
2390 
2391  for (auto p : modes)
2392  {
2393  if (auto video = p.as<video_stream_profile>())
2394  {
2395  if (video.width() == 640 && video.height() == 480 && video.fps() == 60 && video.format())
2396  {
2397  if ((video.stream_type() == RS2_STREAM_DEPTH && video.format() == RS2_FORMAT_Z16) ||
2398  (video.stream_type() == RS2_STREAM_FISHEYE && video.format() == RS2_FORMAT_RAW8))
2399  {
2400  streaming = true;
2401  (*streams_frames)[p.stream_type()] = 0;
2402 
2403  REQUIRE_NOTHROW(sub.open(p));
2404 
2405  func = std::make_shared< std::function<void(frame fref)>>([num_of_frames, m, streams_frames, cv](frame fref) mutable
2406  {
2407  std::unique_lock<std::mutex> lock(*m);
2408  auto stream = fref.get_profile().stream_type();
2409  streams_frames->at(stream)++;
2410  if (streams_frames->at(stream) >= num_of_frames)
2411  cv->notify_one();
2412 
2413  });
2414  REQUIRE_NOTHROW(sub.start(*func));
2415  }
2416  }
2417  }
2418  }
2419 
2420 
2421  std::unique_lock<std::mutex> lock(*m);
2422  cv->wait_for(lock, std::chrono::seconds(30), [&]
2423  {
2424  for (auto f : (*streams_frames))
2425  {
2426  if (f.second < num_of_frames)
2427  return false;
2428  }
2429  return true;
2430  });
2431 
2432  if (!infinite && streaming)
2433  {
2434  REQUIRE_NOTHROW(sub.stop());
2435  REQUIRE_NOTHROW(sub.close());
2436 
2437  }
2438 
2439  return func;
2440 }
2441 
2442 TEST_CASE("Connect Disconnect events while streaming", "[live]") {
2443  rs2::context ctx;
2445  {
2446  device_list list;
2447  REQUIRE_NOTHROW(list = ctx.query_devices());
2448 
2449  std::string serial;
2450 
2451  auto dev = make_device(list);
2452  auto dev_strong = dev.first;
2453  auto dev_weak = dev.second;
2454 
2455 
2456  REQUIRE_NOTHROW(serial = dev_strong->get_info(RS2_CAMERA_INFO_SERIAL_NUMBER));
2457 
2458 
2459  auto disconnected = false;
2460  auto connected = false;
2461  std::condition_variable cv;
2462  std::mutex m;
2463 
2464  //Setting up devices change callback to notify the test about device disconnection and connection
2466  {
2467  auto&& strong = dev_weak.lock();
2468  {
2469  if (strong)
2470  {
2471  if (info.was_removed(*strong))
2472  {
2473  std::unique_lock<std::mutex> lock(m);
2474  disconnected = true;
2475  cv.notify_one();
2476  }
2477 
2478 
2479  for (auto d : info.get_new_devices())
2480  {
2481  if (serial == d.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER))
2482  {
2483  try
2484  {
2485  std::unique_lock<std::mutex> lock(m);
2486 
2487  reset_device(dev_strong, dev_weak, list, d);
2488 
2489  connected = true;
2490  cv.notify_one();
2491  break;
2492  }
2493  catch (...)
2494  {
2495 
2496  }
2497  }
2498  }
2499  }
2500 
2501  }}));
2502 
2503  for (auto&& s : dev_strong->query_sensors())
2504  auto func = check_stream_sanity(ctx, s, 1, true);
2505 
2506  for (auto i = 0; i < 3; i++)
2507  {
2508  //forcing hardware reset to simulate device disconnection
2509  dev_strong = do_with_waiting_for_camera_connection(ctx, dev_strong, serial, [&]()
2510  {
2511  dev_strong->hardware_reset();
2512  });
2513 
2514  for (auto&& s : dev_strong->query_sensors())
2515  auto func = check_stream_sanity(ctx, s, 10);
2516 
2517  disconnected = connected = false;
2518  }
2519 
2520  }
2521 }
2522 
2524 {
2525  for (auto d : ctx.get_sensor_parent(dev).query_sensors())
2526  {
2527  for (auto i = 0; i < RS2_OPTION_COUNT; i++)
2528  {
2529  if (d.supports((rs2_option)i))
2530  REQUIRE_NOTHROW(d.get_option((rs2_option)i));
2531  }
2532  }
2533 }
2534 //
2535 TEST_CASE("Connect Disconnect events while controls", "[live]")
2536 {
2537  rs2::context ctx;
2539  {
2540  device_list list;
2541  REQUIRE_NOTHROW(list = ctx.query_devices());
2542 
2543  auto dev = make_device(list);
2544  auto dev_strong = dev.first;
2545  auto dev_weak = dev.second;
2546 
2547  std::string serial;
2548 
2549  REQUIRE_NOTHROW(serial = dev_strong->get_info(RS2_CAMERA_INFO_SERIAL_NUMBER));
2550 
2551 
2552  auto disconnected = false;
2553  auto connected = false;
2554  std::condition_variable cv;
2555  std::mutex m;
2556 
2557  //Setting up devices change callback to notify the test about device disconnection and connection
2559  {
2560  auto&& strong = dev_weak.lock();
2561  {
2562  if (strong)
2563  {
2564  if (info.was_removed(*strong))
2565  {
2566  std::unique_lock<std::mutex> lock(m);
2567  disconnected = true;
2568  cv.notify_one();
2569  }
2570 
2571  for (auto d : info.get_new_devices())
2572  {
2573  if (serial == d.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER))
2574  {
2575  try
2576  {
2577  std::unique_lock<std::mutex> lock(m);
2578 
2579  reset_device(dev_strong, dev_weak, list, d);
2580  connected = true;
2581  cv.notify_one();
2582  break;
2583  }
2584  catch (...)
2585  {
2586 
2587  }
2588  }
2589  }
2590  }
2591 
2592  }}));
2593 
2594  //forcing hardware reset to simulate device disconnection
2595  dev_strong = do_with_waiting_for_camera_connection(ctx, dev_strong, serial, [&]()
2596  {
2597  dev_strong->hardware_reset();
2598  });
2599 
2600  for (auto&& s : dev_strong->query_sensors())
2601  check_controls_sanity(ctx, s);
2602  }
2603 
2604 }
2605 
2606 TEST_CASE("Basic device_hub flow", "[live][!mayfail]") {
2607 
2608  rs2::context ctx;
2609 
2610  std::shared_ptr<rs2::device> dev;
2611 
2613  {
2614  device_hub hub(ctx);
2615  REQUIRE_NOTHROW(dev = std::make_shared<rs2::device>(hub.wait_for_device()));
2616 
2617  std::weak_ptr<rs2::device> weak(dev);
2618 
2620 
2621  dev->hardware_reset();
2622  int i = 300;
2623  while (i > 0 && hub.is_connected(*dev))
2624  {
2625  std::this_thread::sleep_for(std::chrono::milliseconds(10));
2626  --i;
2627  }
2628  /*if (i == 0)
2629  {
2630  WARN("Reset workaround");
2631  dev->hardware_reset();
2632  while (hub.is_connected(*dev))
2633  std::this_thread::sleep_for(std::chrono::milliseconds(10));
2634  }*/
2635 
2636  // Don't exit the test in unknown state
2638  }
2639 }
2640 
2641 
2642 struct stream_format
2643 {
2644  rs2_stream stream_type;
2645  int width;
2646  int height;
2647  int fps;
2649  int index;
2650 };
2651 
2652 TEST_CASE("Auto-complete feature works", "[offline][util::config][using_pipeline]") {
2653  // dummy device can provide the following profiles:
2654  rs2::context ctx;
2655 
2656  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
2657  {
2658  struct Test {
2659  std::vector<stream_format> given; // We give these profiles to the config class
2660  std::vector<stream_format> expected; // pool of profiles the config class can return. Leave empty if auto-completer is expected to fail
2661  };
2662  std::vector<Test> tests = {
2663  // Test 0 (Depth always has RS2_FORMAT_Z16)
2664  { { { RS2_STREAM_DEPTH , 0, 0, 0, RS2_FORMAT_ANY, 0 } }, // given
2665  { { RS2_STREAM_DEPTH , 0, 0, 0, RS2_FORMAT_Z16, 0 } } }, // expected
2666  // Test 1 (IR always has RS2_FORMAT_Y8)
2667  { { { RS2_STREAM_INFRARED, 0, 0, 0, RS2_FORMAT_ANY, 1 } }, // given
2668  { { RS2_STREAM_INFRARED, 0, 0, 0, RS2_FORMAT_Y8 , 1 } } }, // expected
2669  // Test 2 (No 200 fps depth)
2670  { { { RS2_STREAM_DEPTH , 0, 0, 200, RS2_FORMAT_ANY, -1 } }, // given
2671  { } }, // expected
2672  // Test 3 (Can request 60 fps IR)
2673  { { { RS2_STREAM_INFRARED, 0, 0, 60, RS2_FORMAT_ANY, 1 } }, // given
2674  { { RS2_STREAM_INFRARED, 0, 0, 60, RS2_FORMAT_ANY, 1 } } }, // expected
2675  // Test 4 (requesting IR@200fps + depth fails
2676  { { { RS2_STREAM_INFRARED, 0, 0, 200, RS2_FORMAT_ANY, 1 }, { RS2_STREAM_DEPTH , 0, 0, 0, RS2_FORMAT_ANY, -1 } }, // given
2677  { } }, // expected
2678  // Test 5 (Can't do 640x480@110fps a)
2679  { { { RS2_STREAM_INFRARED, 640, 480, 110, RS2_FORMAT_ANY, -1 } }, // given
2680  { } }, // expected
2681  // Test 6 (Can't do 640x480@110fps b)
2682  { { { RS2_STREAM_DEPTH , 640, 480, 0, RS2_FORMAT_ANY, -1 }, { RS2_STREAM_INFRARED, 0, 0, 110, RS2_FORMAT_ANY, 1 } }, // given
2683  { } }, // expected
2684  // Test 7 (Pull extra details from second stream a)
2685  { { { RS2_STREAM_DEPTH , 640, 480, 0, RS2_FORMAT_ANY, -1 }, { RS2_STREAM_INFRARED, 0, 0, 30, RS2_FORMAT_ANY, 1 } }, // given
2686  { { RS2_STREAM_DEPTH , 640, 480, 30, RS2_FORMAT_ANY, 0 }, { RS2_STREAM_INFRARED, 640, 480, 30, RS2_FORMAT_ANY, 1 } } }, // expected
2687  // Test 8 (Pull extra details from second stream b) [IR also supports 200, could fail if that gets selected]
2688  { { { RS2_STREAM_INFRARED, 640, 480, 0, RS2_FORMAT_ANY, 1 }, { RS2_STREAM_DEPTH , 0, 0, 0, RS2_FORMAT_ANY , 0 } }, // given
2689  { { RS2_STREAM_INFRARED, 640, 480, 10, RS2_FORMAT_ANY, 1 }, { RS2_STREAM_INFRARED, 640, 480, 30, RS2_FORMAT_ANY , 1 }, // expected - options for IR stream
2690  { RS2_STREAM_DEPTH , 640, 480, 10, RS2_FORMAT_ANY, 0 }, { RS2_STREAM_DEPTH , 640, 480, 30, RS2_FORMAT_ANY , 0 } } } // expected - options for depth stream
2691 
2692  };
2693 
2694  pipeline pipe(ctx);
2695  rs2::config cfg;
2696  for (int i = 0; i < tests.size(); ++i)
2697  {
2698  cfg.disable_all_streams();
2699  for (auto & profile : tests[i].given) {
2701  }
2702 
2703  CAPTURE(i);
2704  if (tests[i].expected.size() == 0) {
2705  REQUIRE_THROWS_AS(pipe.start(cfg), std::runtime_error);
2706  }
2707  else
2708  {
2709  rs2::pipeline_profile pipe_profile;
2710  REQUIRE_NOTHROW(pipe_profile = pipe.start(cfg));
2711  //REQUIRE()s are in here
2712  REQUIRE(pipe_profile);
2713  REQUIRE_NOTHROW(pipe.stop());
2714  }
2715  }
2716  }
2717 }
2718 
2719 
2720 //TODO: make it work
2721 //TEST_CASE("Sync connect disconnect", "[live]") {
2722 // rs2::context ctx;
2723 //
2724 // if (make_context(SECTION_FROM_TEST_NAME, &ctx))
2725 // {
2726 // auto list = ctx.query_devices();
2727 // REQUIRE(list.size());
2728 // pipeline pipe(ctx);
2729 // auto dev = pipe.get_device();
2730 //
2731 // disable_sensitive_options_for(dev);
2732 //
2733 //
2734 // auto profiles = configure_all_supported_streams(dev, dev);
2735 //
2736 //
2737 // pipe.start();
2738 //
2739 // std::string serial;
2740 // REQUIRE_NOTHROW(serial = dev.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER));
2741 //
2742 // auto disconnected = false;
2743 // auto connected = false;
2744 // std::condition_variable cv;
2745 // std::mutex m;
2746 //
2747 // //Setting up devices change callback to notify the test about device disconnection and connection
2748 // REQUIRE_NOTHROW(ctx.set_devices_changed_callback([&](event_information& info) mutable
2749 // {
2750 // std::unique_lock<std::mutex> lock(m);
2751 // if (info.was_removed(dev))
2752 // {
2753 //
2754 // try {
2755 // pipe.stop();
2756 // pipe.disable_all();
2757 // dev = nullptr;
2758 // }
2759 // catch (...) {};
2760 // disconnected = true;
2761 // cv.notify_one();
2762 // }
2763 //
2764 // auto devs = info.get_new_devices();
2765 // if (devs.size() > 0)
2766 // {
2767 // dev = pipe.get_device();
2768 // std::string new_serial;
2769 // REQUIRE_NOTHROW(new_serial = dev.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER));
2770 // if (serial == new_serial)
2771 // {
2772 // disable_sensitive_options_for(dev);
2773 //
2774 // auto profiles = configure_all_supported_streams(dev, pipe);
2775 //
2776 // pipe.start();
2777 //
2778 // connected = true;
2779 // cv.notify_one();
2780 // }
2781 // }
2782 //
2783 // }));
2784 //
2785 //
2786 // for (auto i = 0; i < 5; i++)
2787 // {
2788 // auto frames = pipe.wait_for_frames(10000);
2789 // REQUIRE(frames.size() > 0);
2790 // }
2791 //
2792 // {
2793 // std::unique_lock<std::mutex> lock(m);
2794 // disconnected = connected = false;
2795 // auto shared_dev = std::make_shared<rs2::device>(dev);
2796 // dev.hardware_reset();
2797 //
2798 // REQUIRE(wait_for_reset([&]() {
2799 // return cv.wait_for(lock, std::chrono::seconds(20), [&]() {return disconnected; });
2800 // }, shared_dev));
2801 // REQUIRE(cv.wait_for(lock, std::chrono::seconds(20), [&]() {return connected; }));
2802 // }
2803 //
2804 // for (auto i = 0; i < 5; i++)
2805 // {
2806 // auto frames = pipe.wait_for_frames(10000);
2807 // REQUIRE(frames.size() > 0);
2808 //
2809 // }
2810 // }
2811 //}
2812 
2813 
2814 void validate(std::vector<std::vector<stream_profile>> frames, std::vector<std::vector<double>> timestamps, device_profiles requests, int actual_fps)
2815 {
2816  REQUIRE(frames.size() > 0);
2817 
2818  int successful = 0;
2819 
2820  auto gap = (float)1000 / (float)actual_fps;
2821 
2822  auto ts = 0;
2823 
2824  std::vector<profile> actual_streams_arrived;
2825  for (auto i = 0; i < frames.size(); i++)
2826  {
2827  auto frame = frames[i];
2828  auto ts = timestamps[i];
2829  if (frame.size() == 0)
2830  {
2831  CAPTURE(frame.size());
2832  continue;
2833  }
2834 
2835  std::vector<profile> stream_arrived;
2836 
2837  for (auto f : frame)
2838  {
2839  auto image = f.as<rs2::video_stream_profile>();
2840 
2841  stream_arrived.push_back({ image.stream_type(), image.format(), image.width(), image.height() });
2842  REQUIRE(image.fps());
2843  }
2844 
2845  std::sort(ts.begin(), ts.end());
2846 
2847  if (ts[ts.size() - 1] - ts[0] > (float)gap / (float)2)
2848  {
2849  CAPTURE(gap);
2850  CAPTURE((float)gap / (float)2);
2851  CAPTURE(ts[ts.size() - 1]);
2852  CAPTURE(ts[0]);
2853  CAPTURE(ts[ts.size() - 1] - ts[0]);
2854  continue;
2855  }
2856 
2857  for (auto& str : stream_arrived)
2858  actual_streams_arrived.push_back(str);
2859 
2860  if (stream_arrived.size() != requests.streams.size())
2861  continue;
2862 
2863  std::sort(stream_arrived.begin(), stream_arrived.end());
2864  std::sort(requests.streams.begin(), requests.streams.end());
2865 
2866  auto equals = true;
2867  for (auto i = 0; i < requests.streams.size(); i++)
2868  {
2869  if (stream_arrived[i] != requests.streams[i])
2870  {
2871  equals = false;
2872  break;
2873  }
2874 
2875  }
2876  if (!equals)
2877  continue;
2878 
2879  successful++;
2880 
2881  }
2882 
2883  std::stringstream ss;
2884  ss << "Requested profiles : " << std::endl;
2885  for (auto profile : requests.streams)
2886  {
2887  ss << STRINGIFY(profile.stream) << " = " << profile.stream << std::endl;
2888  ss << STRINGIFY(profile.format) << " = " << profile.format << std::endl;
2889  ss << STRINGIFY(profile.width) << " = " << profile.width << std::endl;
2890  ss << STRINGIFY(profile.height) << " = " << profile.height << std::endl;
2891  ss << STRINGIFY(profile.index) << " = " << profile.index << std::endl;
2892  }
2893  CAPTURE(ss.str());
2894  CAPTURE(requests.fps);
2895  CAPTURE(requests.sync);
2896 
2897  ss.str("");
2898  ss << "\n\nReceived profiles : " << std::endl;
2899  std::sort(actual_streams_arrived.begin(), actual_streams_arrived.end());
2900  auto last = std::unique(actual_streams_arrived.begin(), actual_streams_arrived.end());
2901  actual_streams_arrived.erase(last, actual_streams_arrived.end());
2902 
2903  for (auto profile : actual_streams_arrived)
2904  {
2905  ss << STRINGIFY(profile.stream) << " = " << profile.stream << std::endl;
2906  ss << STRINGIFY(profile.format) << " = " << profile.format << std::endl;
2907  ss << STRINGIFY(profile.width) << " = " << profile.width << std::endl;
2908  ss << STRINGIFY(profile.height) << " = " << profile.height << std::endl;
2909  ss << STRINGIFY(profile.index) << " = " << profile.index << std::endl;
2910  }
2911  CAPTURE(ss.str());
2912 
2913  REQUIRE(successful > 0);
2914 }
2915 
2916 static const std::map< dev_type, device_profiles> pipeline_default_configurations = {
2917 /* RS400/PSR*/ { { "0AD1", true} ,{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 1280, 720, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 1280, 720, 1 } }, 30, true}},
2918 /* RS410/ASR*/ { { "0AD2", true } ,{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 1280, 720, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 1280, 720, 1 } }, 30, true }},
2919 /* D410/USB2*/ { { "0AD2", false },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 640, 480, 1 } }, 15, true } },
2920 /* RS415/ASRC*/ { { "0AD3", true } ,{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 1280, 720, 0 },{ RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30, true }},
2921 /* D415/USB2*/ { { "0AD3", false },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },{ RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 640, 480, 0 } }, 15, true } },
2922 /* RS430/AWG*/ { { "0AD4", true } ,{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 1280, 720, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_Y8, 1280, 720, 1 } }, 30, true }},
2923 /* RS430_MM/AWGT*/ { { "0AD5", true } ,{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 1280, 720, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_Y8, 1280, 720, 1 } }, 30, true }},
2924 /* RS420/PWG*/ { { "0AF6", true } ,{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 1280, 720, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_Y8, 1280, 720, 1 } }, 30, true }},
2925 /* RS420_MM/PWGT*/ { { "0AFE", true } ,{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 1280, 720, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_Y8, 1280, 720, 1 } }, 30, true }},
2926 /* RS410_MM/ASRT*/ { { "0AFF", true } ,{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 1280, 720, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 1280, 720, 1 } }, 30, true } },
2927 /* RS400_MM/PSR*/ { { "0B00", true } ,{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 1280, 720, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 1280, 720, 1 } }, 30, true } },
2928 /* RS430_MM_RGB/AWGTC*/ { { "0B01", true } ,{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 1280, 720, 0 },{ RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30, true }},
2929 /* RS405/D460/DS5U*/ { { "0B03", true } ,{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 1280, 720, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 1280, 720, 1 } }, 30, true }},
2930 /* RS435_RGB/AWGC*/ { { "0B07", true } ,{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 1280, 720, 0 },{ RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30, true }},
2931 /* D435/USB2*/ { { "0B07", false },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },{ RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 640, 480, 0 } }, 15, true } },
2932 // TODO - IMU data profiles are pending FW timestamp fix
2933 /* D435I/USB3*/ { { "0B3A", true } ,{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 1280, 720, 0 },{ RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30, true } },
2934 /* SR300*/ { { "0AA5", true } ,{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },{ RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 1920, 1080, 0 } }, 30, true } },
2935 };
2936 
2937 TEST_CASE("Pipeline wait_for_frames", "[live][pipeline][using_pipeline][!mayfail]") {
2938 
2939  rs2::context ctx;
2940 
2941  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
2942  {
2943  rs2::device dev;
2944  rs2::pipeline pipe(ctx);
2945  rs2::config cfg;
2947  REQUIRE_NOTHROW(profile = cfg.resolve(pipe));
2948  REQUIRE(profile);
2949  REQUIRE_NOTHROW(dev = profile.get_device());
2950  REQUIRE(dev);
2952  dev_type PID = get_PID(dev);
2953  CAPTURE(PID.first);
2954  CAPTURE(PID.second);
2955 
2957  {
2958  WARN("Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ? " USB3" : " USB2"));
2959  }
2960  else
2961  {
2962  REQUIRE(pipeline_default_configurations.at(PID).streams.size() > 0);
2963 
2964  REQUIRE_NOTHROW(pipe.start(cfg));
2965 
2966  std::vector<std::vector<stream_profile>> frames;
2967  std::vector<std::vector<double>> timestamps;
2968 
2969  for (auto i = 0; i < 30; i++)
2970  REQUIRE_NOTHROW(pipe.wait_for_frames(10000));
2971 
2972  auto actual_fps = pipeline_default_configurations.at(PID).fps;
2973 
2974  while (frames.size() < 100)
2975  {
2976  frameset frame;
2977  REQUIRE_NOTHROW(frame = pipe.wait_for_frames(10000));
2978  std::vector<stream_profile> frames_set;
2979  std::vector<double> ts;
2980 
2981  for (auto f : frame)
2982  {
2983  if (f.supports_frame_metadata(RS2_FRAME_METADATA_ACTUAL_FPS))
2984  {
2985  auto val = static_cast<int>(f.get_frame_metadata(RS2_FRAME_METADATA_ACTUAL_FPS));
2986  if (val < actual_fps)
2987  actual_fps = val;
2988  }
2989  frames_set.push_back(f.get_profile());
2990  ts.push_back(f.get_timestamp());
2991  }
2992  frames.push_back(frames_set);
2993  timestamps.push_back(ts);
2994  }
2995 
2996 
2997  REQUIRE_NOTHROW(pipe.stop());
2998  validate(frames, timestamps, pipeline_default_configurations.at(PID), actual_fps);
2999  }
3000  }
3001 }
3002 
3003 TEST_CASE("Pipeline poll_for_frames", "[live][pipeline][using_pipeline][!mayfail]")
3004 {
3005  rs2::context ctx;
3006 
3007  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
3008  {
3009  auto list = ctx.query_devices();
3010  REQUIRE(list.size());
3011  rs2::device dev;
3012  rs2::pipeline pipe(ctx);
3013  rs2::config cfg;
3015  REQUIRE_NOTHROW(profile = cfg.resolve(pipe));
3016  REQUIRE(profile);
3017  REQUIRE_NOTHROW(dev = profile.get_device());
3018  REQUIRE(dev);
3020  dev_type PID = get_PID(dev);
3021  CAPTURE(PID.first);
3022  CAPTURE(PID.second);
3023 
3025  {
3026  WARN("Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ? " USB3" : " USB2"));
3027  }
3028  else
3029  {
3030  REQUIRE(pipeline_default_configurations.at(PID).streams.size() > 0);
3031 
3032  REQUIRE_NOTHROW(pipe.start(cfg));
3033 
3034  std::vector<std::vector<stream_profile>> frames;
3035  std::vector<std::vector<double>> timestamps;
3036 
3037  for (auto i = 0; i < 30; i++)
3038  REQUIRE_NOTHROW(pipe.wait_for_frames(5000));
3039 
3040  auto actual_fps = pipeline_default_configurations.at(PID).fps;
3041  while (frames.size() < 100)
3042  {
3043  frameset frame;
3044  if (pipe.poll_for_frames(&frame))
3045  {
3046  std::vector<stream_profile> frames_set;
3047  std::vector<double> ts;
3048  for (auto f : frame)
3049  {
3050  if (f.supports_frame_metadata(RS2_FRAME_METADATA_ACTUAL_FPS))
3051  {
3052  auto val = static_cast<int>(f.get_frame_metadata(RS2_FRAME_METADATA_ACTUAL_FPS));
3053  if (val < actual_fps)
3054  actual_fps = val;
3055  }
3056  frames_set.push_back(f.get_profile());
3057  ts.push_back(f.get_timestamp());
3058  }
3059  frames.push_back(frames_set);
3060  timestamps.push_back(ts);
3061  }
3062  }
3063 
3064  REQUIRE_NOTHROW(pipe.stop());
3065  validate(frames, timestamps, pipeline_default_configurations.at(PID), actual_fps);
3066  }
3067 
3068  }
3069 }
3070 
3071 static const std::map<dev_type, device_profiles> pipeline_custom_configurations = {
3072  /* RS400/PSR*/ { {"0AD1", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 640, 480, 1 } }, 30, true } },
3073  /* RS410/ASR*/ { {"0AD2", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 640, 480, 1 } }, 30, true } },
3074  /* D410/USB2*/ { {"0AD2", false },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 480, 270, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 480, 270, 1 } }, 30, true } },
3075  /* RS415/ASRC*/ { {"0AD3", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },{ RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30, true } },
3076  /* D415/USB2*/ { {"0AD3", false },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 480, 270, 0 },{ RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 424, 240, 0 } }, 30, true } },
3077  /* RS430/AWG*/ { {"0AD4", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_Y8, 640, 480, 1 } }, 30, true } },
3078  /* RS430_MM/AWGT*/ { {"0AD5", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_Y8, 640, 480, 1 } }, 30, true } },
3079  /* RS420/PWG*/ { {"0AF6", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_Y8, 640, 480, 1 } }, 30, true } },
3080  /* RS420_MM/PWGT*/ { {"0AFE", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_Y8, 640, 480, 1 } }, 30, true } },
3081  /* RS410_MM/ASRT*/ { {"0AFF", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 640, 480, 1 } }, 30, true } },
3082  /* RS400_MM/PSR*/ { {"0B00", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 640, 480, 1 } }, 30, true } },
3083  /* RS430_MC/AWGTC*/ { {"0B01", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },{ RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30, true } },
3084  /* RS405/D460/DS5U*/{ {"0B03", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 640, 480, 0 } }, 30, true } },
3085  /* RS435_RGB/AWGC*/ { {"0B07", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },{ RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30, true } },
3086  /* D435/USB2*/ { {"0B07", false },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 480, 270, 0 },{ RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 424, 240, 0 } }, 30, true } },
3087 
3088  /* SR300*/ { {"0AA5", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 240, 0 },
3089  { RS2_STREAM_INFRARED, RS2_FORMAT_Y8, 640, 240, 1 },
3090  { RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 640, 480, 0 } }, 30, true } },
3091 
3092  /* SR300*/ { {"0AA5", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },
3093  { RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 1920, 1080, 0 } }, 30, true } },
3094 };
3095 
3096 TEST_CASE("Pipeline enable stream", "[live][pipeline][using_pipeline]") {
3097 
3098  auto dev_requests = pipeline_custom_configurations;
3099 
3100  rs2::context ctx;
3101  if (!make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
3102  return;
3103 
3104  auto list = ctx.query_devices();
3105  REQUIRE(list.size());
3106 
3107  rs2::device dev;
3108  rs2::pipeline pipe(ctx);
3109  rs2::config cfg;
3111  REQUIRE_NOTHROW(profile = cfg.resolve(pipe));
3112  REQUIRE(profile);
3113  REQUIRE_NOTHROW(dev = profile.get_device());
3114  REQUIRE(dev);
3116  dev_type PID = get_PID(dev);
3117  CAPTURE(PID.first);
3118  CAPTURE(PID.second);
3119 
3120  if (dev_requests.end() == dev_requests.find(PID))
3121  {
3122  WARN("Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ? " USB3" : " USB2"));
3123  }
3124  else
3125  {
3126  REQUIRE(dev_requests[PID].streams.size() > 0);
3127 
3128  for (auto req : pipeline_custom_configurations.at(PID).streams)
3129  REQUIRE_NOTHROW(cfg.enable_stream(req.stream, req.index, req.width, req.height, req.format, dev_requests[PID].fps));
3130 
3131  REQUIRE_NOTHROW(profile = pipe.start(cfg));
3132  REQUIRE(profile);
3134  std::vector<std::vector<stream_profile>> frames;
3135  std::vector<std::vector<double>> timestamps;
3136 
3137  for (auto i = 0; i < 30; i++)
3138  REQUIRE_NOTHROW(pipe.wait_for_frames(5000));
3139 
3140  auto actual_fps = dev_requests[PID].fps;
3141 
3142  while (frames.size() < 100)
3143  {
3144  frameset frame;
3145  REQUIRE_NOTHROW(frame = pipe.wait_for_frames(5000));
3146  std::vector<stream_profile> frames_set;
3147  std::vector<double> ts;
3148 
3149  for (auto f : frame)
3150  {
3151  if (f.supports_frame_metadata(RS2_FRAME_METADATA_ACTUAL_FPS))
3152  {
3153  auto val = static_cast<int>(f.get_frame_metadata(RS2_FRAME_METADATA_ACTUAL_FPS));
3154  if (val < actual_fps)
3155  actual_fps = val;
3156  }
3157  frames_set.push_back(f.get_profile());
3158  ts.push_back(f.get_timestamp());
3159  }
3160  frames.push_back(frames_set);
3161  timestamps.push_back(ts);
3162  }
3163 
3164  REQUIRE_NOTHROW(pipe.stop());
3165  validate(frames, timestamps, dev_requests[PID], actual_fps);
3166  }
3167 }
3168 
3169 static const std::map<dev_type, device_profiles> pipeline_autocomplete_configurations = {
3170  /* RS400/PSR*/ { {"0AD1", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_ANY, 0, 0, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_ANY, 0, 0, 1 } }, 30, true } },
3171  /* RS410/ASR*/ { {"0AD2", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_ANY, 0, 0, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_ANY, 0, 0, 1 } }, 30, true } },
3172  /* D410/USB2*/ { {"0AD2", false },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 0, 0, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 0, 0, 0 } }, 15, true } },
3173  // FW issues render streaming Depth:HD + Color:FHD as not feasible. Applies for AWGC and ASRC
3174  /* AWGC/ASRC should be invoked with 30 fps in order to avoid selecting FullHD for Color sensor at least with FW 5.9.6*/
3175  /* RS415/ASRC*/ { {"0AD3", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_ANY, 0, 0, 0 }/*,{ RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 0, 0, 0 }*/ }, 30, true } },
3176  /* D415/USB2*/ { {"0AD3", false },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 0, 0, 0 },{ RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 0, 0, 0 } }, 60, true } },
3177  /* RS430/AWG*/ { {"0AD4", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_ANY, 0, 0, 0 } }, 30, true } },
3178  /* RS430_MM/AWGT*/ { {"0AD5", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_ANY, 0, 0, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_ANY, 0, 0, 1 } }, 30, true } },
3179  /* RS420/PWG*/ { {"0AF6", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_ANY, 0, 0, 0 } }, 30, true } },
3180  /* RS420_MM/PWGT*/ { {"0AFE", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 0, 0, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 0, 0, 0 } }, 30, true } },
3181  /* RS410_MM/ASRT*/ { {"0AFF", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 0, 0, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 0, 0, 0 } }, 30, true } },
3182  /* RS400_MM/PSR*/ { {"0B00", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 0, 0, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 0, 0, 0 } }, 30, true } },
3183  /* RS430_MM_RGB/AWGTC*/{ {"0B01", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 0, 0, 0 },{ RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 0, 0, 0 } }, 30, true } },
3184  /* RS405/DS5U*/ { {"0B03", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 0, 0, 0 },{ RS2_STREAM_INFRARED, RS2_FORMAT_ANY, 0, 0, 1 } }, 30, true } },
3185  /* RS435_RGB/AWGC*/ { {"0B07", true },{ { /*{ RS2_STREAM_DEPTH, RS2_FORMAT_ANY, 0, 0, 0 },*/{ RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 0, 0, 0 } }, 30, true } },
3186  /* D435/USB2*/ { {"0B07", false },{ { /*{ RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 0, 0, 0 },*/{ RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 0, 0, 0 } }, 60, true } },
3187 
3188  /* SR300*/ { {"0AA5", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_ANY, 0, 0, 0 },
3189  { RS2_STREAM_INFRARED, RS2_FORMAT_ANY, 0, 0, 1 },
3190  { RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 0, 0, 0 } }, 30, true } },
3191 };
3192 
3193 TEST_CASE("Pipeline enable stream auto complete", "[live][pipeline][using_pipeline]")
3194 {
3196 
3197  rs2::context ctx;
3198 
3199  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
3200  {
3201  auto list = ctx.query_devices();
3202  REQUIRE(list.size());
3203 
3204  rs2::device dev;
3205  rs2::pipeline pipe(ctx);
3206  rs2::config cfg;
3208  REQUIRE_NOTHROW(profile = cfg.resolve(pipe));
3209  REQUIRE(profile);
3210  REQUIRE_NOTHROW(dev = profile.get_device());
3211  REQUIRE(dev);
3213  dev_type PID = get_PID(dev);
3214  CAPTURE(PID.first);
3215  CAPTURE(PID.second);
3216 
3217  if (configurations.end() == configurations.find(PID))
3218  {
3219  WARN("Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ? " USB3" : " USB2"));
3220  }
3221  else
3222  {
3223  REQUIRE(configurations[PID].streams.size() > 0);
3224 
3225  for (auto req : configurations[PID].streams)
3226  REQUIRE_NOTHROW(cfg.enable_stream(req.stream, req.index, req.width, req.height, req.format, configurations[PID].fps));
3227 
3228  REQUIRE_NOTHROW(profile = pipe.start(cfg));
3229  REQUIRE(profile);
3230  REQUIRE(profile.get_device());
3232 
3233  std::vector<std::vector<stream_profile>> frames;
3234  std::vector<std::vector<double>> timestamps;
3235 
3236  for (auto i = 0; i < 30; i++)
3237  REQUIRE_NOTHROW(pipe.wait_for_frames(5000));
3238 
3239  auto actual_fps = configurations[PID].fps;
3240 
3241  while (frames.size() < 100)
3242  {
3243  frameset frame;
3244  REQUIRE_NOTHROW(frame = pipe.wait_for_frames(5000));
3245  std::vector<stream_profile> frames_set;
3246  std::vector<double> ts;
3247  for (auto f : frame)
3248  {
3249  if (f.supports_frame_metadata(RS2_FRAME_METADATA_ACTUAL_FPS))
3250  {
3251  auto val = static_cast<int>(f.get_frame_metadata(RS2_FRAME_METADATA_ACTUAL_FPS));
3252  if (val < actual_fps)
3253  actual_fps = val;
3254  }
3255  frames_set.push_back(f.get_profile());
3256  ts.push_back(f.get_timestamp());
3257  }
3258  frames.push_back(frames_set);
3259  timestamps.push_back(ts);
3260  }
3261 
3262  REQUIRE_NOTHROW(pipe.stop());
3263  validate(frames, timestamps, configurations[PID], actual_fps);
3264  }
3265  }
3266 }
3267 
3268 TEST_CASE("Pipeline disable_all", "[live][pipeline][using_pipeline][!mayfail]") {
3269 
3270  auto not_default_configurations = pipeline_custom_configurations;
3271  auto default_configurations = pipeline_default_configurations;
3272 
3273  rs2::context ctx;
3274 
3275  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
3276  {
3277  auto list = ctx.query_devices();
3278  REQUIRE(list.size());
3279 
3280  rs2::device dev;
3281  rs2::pipeline pipe(ctx);
3282  rs2::config cfg;
3284  REQUIRE_NOTHROW(profile = cfg.resolve(pipe));
3285  REQUIRE(profile);
3286  REQUIRE_NOTHROW(dev = profile.get_device());
3287  REQUIRE(dev);
3289  dev_type PID = get_PID(dev);
3290  CAPTURE(PID.first);
3291  CAPTURE(PID.second);
3292 
3293  if ((not_default_configurations.end() == not_default_configurations.find(PID)) || ((default_configurations.find(PID) == default_configurations.end())))
3294  {
3295  WARN("Skipping test - the Device-Under-Test profile is not defined properly for PID " << PID.first << (PID.second ? " USB3" : " USB2"));
3296  }
3297  else
3298  {
3299  REQUIRE(not_default_configurations[PID].streams.size() > 0);
3300 
3301  for (auto req : not_default_configurations[PID].streams)
3302  REQUIRE_NOTHROW(cfg.enable_stream(req.stream, req.index, req.width, req.height, req.format, not_default_configurations[PID].fps));
3303 
3305 
3306  REQUIRE_NOTHROW(profile = pipe.start(cfg));
3307  REQUIRE(profile);
3309 
3310 
3311  std::vector<std::vector<stream_profile>> frames;
3312  std::vector<std::vector<double>> timestamps;
3313 
3314  for (auto i = 0; i < 30; i++)
3315  REQUIRE_NOTHROW(pipe.wait_for_frames(5000));
3316 
3317  auto actual_fps = default_configurations[PID].fps;
3318 
3319  while (frames.size() < 100)
3320  {
3321  frameset frame;
3322  REQUIRE_NOTHROW(frame = pipe.wait_for_frames(5000));
3323  std::vector<stream_profile> frames_set;
3324  std::vector<double> ts;
3325  for (auto f : frame)
3326  {
3327  if (f.supports_frame_metadata(RS2_FRAME_METADATA_ACTUAL_FPS))
3328  {
3329  auto val = static_cast<int>(f.get_frame_metadata(RS2_FRAME_METADATA_ACTUAL_FPS));
3330  if (val < actual_fps)
3331  actual_fps = val;
3332  }
3333  frames_set.push_back(f.get_profile());
3334  ts.push_back(f.get_timestamp());
3335  }
3336  frames.push_back(frames_set);
3337  timestamps.push_back(ts);
3338  }
3339 
3340  REQUIRE_NOTHROW(pipe.stop());
3341  validate(frames, timestamps, default_configurations[PID], actual_fps);
3342  }
3343  }
3344 }
3345 
3346 TEST_CASE("Pipeline disable stream", "[live][pipeline][using_pipeline]") {
3347 
3349 
3350  rs2::context ctx;
3351 
3352  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
3353  {
3354  auto list = ctx.query_devices();
3355  REQUIRE(list.size());
3356 
3357  rs2::device dev;
3358  rs2::pipeline pipe(ctx);
3359  rs2::config cfg;
3361  REQUIRE_NOTHROW(profile = cfg.resolve(pipe));
3362  REQUIRE(profile);
3363  REQUIRE_NOTHROW(dev = profile.get_device());
3364  REQUIRE(dev);
3366  dev_type PID = get_PID(dev);
3367  CAPTURE(PID.first);
3368  CAPTURE(PID.second);
3369 
3370  if (configurations.end() == configurations.find(PID))
3371  {
3372  WARN("Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ? " USB3" : " USB2"));
3373  }
3374  else
3375  {
3376  REQUIRE(configurations[PID].streams.size() > 0);
3377 
3378  for (auto req : configurations[PID].streams)
3379  REQUIRE_NOTHROW(cfg.enable_stream(req.stream, req.index, req.width, req.height, req.format, configurations[PID].fps));
3380 
3381  auto stream_to_be_removed = configurations[PID].streams[configurations[PID].streams.size() - 1].stream;
3382  REQUIRE_NOTHROW(cfg.disable_stream(stream_to_be_removed));
3383 
3384  auto& streams = configurations[PID].streams;
3385  streams.erase(streams.end() - 1);
3386 
3387  REQUIRE_NOTHROW(profile = pipe.start(cfg));
3388  REQUIRE(profile);
3390 
3391  std::vector<std::vector<stream_profile>> frames;
3392  std::vector<std::vector<double>> timestamps;
3393 
3394  for (auto i = 0; i < 30; i++)
3395  REQUIRE_NOTHROW(pipe.wait_for_frames(5000));
3396 
3397  auto actual_fps = configurations[PID].fps;
3398  while (frames.size() < 100)
3399  {
3400  frameset frame;
3401  REQUIRE_NOTHROW(frame = pipe.wait_for_frames(5000));
3402  std::vector<stream_profile> frames_set;
3403  std::vector<double> ts;
3404  for (auto f : frame)
3405  {
3406  if (f.supports_frame_metadata(RS2_FRAME_METADATA_ACTUAL_FPS))
3407  {
3408  auto val = static_cast<int>(f.get_frame_metadata(RS2_FRAME_METADATA_ACTUAL_FPS));
3409  if (val < actual_fps)
3410  actual_fps = val;
3411  }
3412  frames_set.push_back(f.get_profile());
3413  ts.push_back(f.get_timestamp());
3414  }
3415  frames.push_back(frames_set);
3416  timestamps.push_back(ts);
3417  }
3418 
3419  REQUIRE_NOTHROW(pipe.stop());
3420  validate(frames, timestamps, configurations[PID], actual_fps);
3421  }
3422  }
3423 }
3424 // The test relies on default profiles that may alter
3425 TEST_CASE("Pipeline with specific device", "[live][pipeline][using_pipeline]")
3426 {
3427 
3428  rs2::context ctx;
3429 
3430  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
3431  {
3432  auto list = ctx.query_devices();
3433  REQUIRE(list.size());
3434 
3435  rs2::device dev;
3436  REQUIRE_NOTHROW(dev = list[0]);
3438  std::string serial, serial1, serial2;
3439  REQUIRE_NOTHROW(serial = dev.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER));
3440 
3441  rs2::pipeline pipe(ctx);
3442  rs2::config cfg;
3443  REQUIRE_NOTHROW(cfg.enable_device(serial));
3445  REQUIRE_NOTHROW(profile = cfg.resolve(pipe));
3446  REQUIRE(profile);
3447  REQUIRE_NOTHROW(dev = profile.get_device());
3448  REQUIRE(dev);
3450  REQUIRE_NOTHROW(serial1 = dev.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER));
3451  CAPTURE(serial);
3452  CAPTURE(serial1);
3453  REQUIRE(serial1 == serial);
3454 
3455  REQUIRE_NOTHROW(profile = pipe.start(cfg));
3456  REQUIRE(profile);
3457  REQUIRE_NOTHROW(dev = profile.get_device());
3458  REQUIRE_NOTHROW(serial2 = dev.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER));
3459  CAPTURE(serial);
3460  CAPTURE(serial2);
3461  REQUIRE(serial2 == serial);
3462  REQUIRE_NOTHROW(pipe.stop());
3463 
3464  }
3465 }
3466 
3467 bool operator==(std::vector<profile> streams1, std::vector<profile> streams2)
3468 {
3469  if (streams1.size() != streams2.size())
3470  return false;
3471 
3472  std::sort(streams1.begin(), streams1.end());
3473  std::sort(streams2.begin(), streams2.end());
3474 
3475  auto equals = true;
3476  for (auto i = 0; i < streams1.size(); i++)
3477  {
3478  if (streams1[i] != streams2[i])
3479  {
3480  equals = false;
3481  break;
3482  }
3483  }
3484  return equals;
3485 }
3486 
3487 TEST_CASE("Pipeline start stop", "[live][pipeline][using_pipeline]") {
3488 
3490 
3491  rs2::context ctx;
3492 
3493  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
3494  {
3495  auto list = ctx.query_devices();
3496  REQUIRE(list.size());
3497 
3498  rs2::device dev;
3499  rs2::pipeline pipe(ctx);
3500  rs2::config cfg;
3501  rs2::pipeline_profile pipe_profile;
3502  REQUIRE_NOTHROW(pipe_profile = cfg.resolve(pipe));
3503  REQUIRE(pipe_profile);
3504  REQUIRE_NOTHROW(dev = pipe_profile.get_device());
3505  REQUIRE(dev);
3507  dev_type PID = get_PID(dev);
3508  CAPTURE(PID.first);
3509  CAPTURE(PID.second);
3510 
3511  if (configurations.end() == configurations.find(PID))
3512  {
3513  WARN("Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ? " USB3" : " USB2"));
3514  }
3515  else
3516  {
3517  REQUIRE(configurations[PID].streams.size() > 0);
3518 
3519  for (auto req : configurations[PID].streams)
3520  REQUIRE_NOTHROW(cfg.enable_stream(req.stream, req.index, req.width, req.height, req.format, configurations[PID].fps));
3521 
3522  auto& streams = configurations[PID].streams;
3523 
3524  REQUIRE_NOTHROW(pipe.start(cfg));
3525 
3526  std::vector<device_profiles> frames;
3527 
3528  for (auto i = 0; i < 10; i++)
3529  REQUIRE_NOTHROW(pipe.wait_for_frames(5000));
3530 
3531 
3532  REQUIRE_NOTHROW(pipe.stop());
3533  REQUIRE_NOTHROW(pipe.start(cfg));
3534 
3535  for (auto i = 0; i < 20; i++)
3536  REQUIRE_NOTHROW(pipe.wait_for_frames(5000));
3537 
3538  std::vector<profile> profiles;
3539  auto equals = 0;
3540  for (auto i = 0; i < 30; i++)
3541  {
3542  frameset frame;
3543  REQUIRE_NOTHROW(frame = pipe.wait_for_frames(5000));
3544  REQUIRE(frame.size() > 0);
3545 
3546  for (auto f : frame)
3547  {
3548  auto profile = f.get_profile();
3549  auto video_profile = profile.as<video_stream_profile>();
3550 
3551  profiles.push_back({ profile.stream_type(),
3552  profile.format(),
3553  video_profile.width(),
3554  video_profile.height(),
3555  video_profile.stream_index() });
3556 
3557  }
3558  if (profiles == streams)
3559  equals++;
3560  profiles.clear();
3561  }
3562 
3563  REQUIRE_NOTHROW(pipe.stop());
3564  REQUIRE(equals > 1);
3565  }
3566  }
3567 }
3568 
3569 static const std::map<dev_type, device_profiles> pipeline_configurations_for_extrinsic = {
3570  /* D400/PSR*/ { {"0AD1", true},{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },
3571  { RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 640, 480, 0 } }, 30, true } },
3572  /* D410/ASR*/ { {"0AD2", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },
3573  { RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 640, 480, 0 } }, 30, true } },
3574  /* D410/USB2*/ { {"0AD2", false },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 480, 270, 0 },
3575  { RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 480, 270, 0 } }, 30, true } },
3576  /* D415/ASRC*/ { {"0AD3", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },
3577  { RS2_STREAM_INFRARED, RS2_FORMAT_Y8, 640, 480, 1 } ,
3578  { RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 1920, 1080, 0 } }, 30, true } },
3579  /* D415/USB2*/ { {"0AD3", false },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 480, 270, 0 },
3580  { RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 424, 240, 0 } }, 30, true } },
3581  /* RS430/AWG*/ { {"0AD4", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },
3582  { RS2_STREAM_INFRARED, RS2_FORMAT_Y8, 640, 480, 1 } }, 30, true } },
3583  /* RS430_MM/AWGT*/ { {"0AD5", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },
3584  { RS2_STREAM_INFRARED, RS2_FORMAT_Y8, 640, 480, 1 } }, 30, true } },
3585  /* RS420/PWG*/ { {"0AF6", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },
3586  { RS2_STREAM_INFRARED, RS2_FORMAT_Y8, 640, 480, 1 } }, 30, true } },
3587  /* RS420_MM/PWGT*/ { {"0AFE", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },
3588  { RS2_STREAM_INFRARED, RS2_FORMAT_Y8, 640, 480, 1 } }, 30, true } },
3589  /* RS410_MM/ASRT*/ { {"0AFF", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },
3590  { RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 640, 480, 0 } }, 30, true } },
3591  /* RS400_MM/PSR*/ { {"0B00", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },
3592  { RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 640, 480, 0 } }, 30, true } },
3593  /* RS430_MM_RGB/AWGTC*/{ {"0B01", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },
3594  { RS2_STREAM_INFRARED, RS2_FORMAT_Y8, 640, 480, 1 } ,
3595  { RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 1920, 1080, 0 } }, 30, true } },
3596  /* RS405/DS5U*/ { {"0B03", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },
3597  { RS2_STREAM_INFRARED, RS2_FORMAT_RGB8, 640, 480, 0 } }, 30, true } },
3598  /* RS435_RGB/AWGC*/ { {"0B07", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },
3599  { RS2_STREAM_INFRARED, RS2_FORMAT_Y8, 640, 480, 1 } ,
3600  { RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 1920, 1080, 0 } }, 30, true } },
3601  /* D435/USB2*/ { {"0B07", false },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 480, 270, 0 },
3602  { RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 424, 240, 0 } }, 30, true } },
3603 
3604  /* SR300*/ { {"0AA5", true },{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 240, 0 },
3605  { RS2_STREAM_INFRARED, RS2_FORMAT_Y8, 640, 240, 1 },
3606  { RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 640, 480, 0 } }, 30, true } },
3607  };
3608 
3609 TEST_CASE("Pipeline get selection", "[live][pipeline][using_pipeline]") {
3610  rs2::context ctx;
3612 
3613  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
3614  {
3615  auto list = ctx.query_devices();
3616  REQUIRE(list.size());
3617 
3618  rs2::device dev;
3619  rs2::pipeline pipe(ctx);
3620  rs2::config cfg;
3621  rs2::pipeline_profile pipe_profile;
3622  REQUIRE_NOTHROW(pipe_profile = cfg.resolve(pipe));
3623  REQUIRE(pipe_profile);
3624  REQUIRE_NOTHROW(dev = pipe_profile.get_device());
3625  REQUIRE(dev);
3627  dev_type PID = get_PID(dev);
3628  CAPTURE(PID.first);
3629  CAPTURE(PID.second);
3630 
3631  if (configurations.end() == configurations.find(PID))
3632  {
3633  WARN("Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ? " USB3" : " USB2"));
3634  }
3635  else
3636  {
3637  REQUIRE(configurations[PID].streams.size() > 0);
3638 
3639  for (auto req : configurations[PID].streams)
3640  REQUIRE_NOTHROW(cfg.enable_stream(req.stream, req.index, req.width, req.height, req.format, configurations[PID].fps));
3641 
3642  REQUIRE_NOTHROW(pipe.start(cfg));
3643  std::vector<stream_profile> profiles;
3644  REQUIRE_NOTHROW(pipe_profile = pipe.get_active_profile());
3645  REQUIRE(pipe_profile);
3646  REQUIRE_NOTHROW(profiles = pipe_profile.get_streams());
3647 
3648  auto streams = configurations[PID].streams;
3649  std::vector<profile> pipe_streams;
3650  for (auto s : profiles)
3651  {
3653  auto video = s.as<video_stream_profile>();
3654 
3655  pipe_streams.push_back({ video.stream_type(), video.format(), video.width(), video.height(), video.stream_index() });
3656  }
3657  REQUIRE(pipe_streams.size() == streams.size());
3658 
3659  std::sort(pipe_streams.begin(), pipe_streams.end());
3660  std::sort(streams.begin(), streams.end());
3661 
3662  for (auto i = 0; i < pipe_streams.size(); i++)
3663  {
3664  REQUIRE(pipe_streams[i] == streams[i]);
3665  }
3666  }
3667  }
3668 }
3669 
3670 TEST_CASE("Per-frame metadata sanity check", "[live][!mayfail]") {
3671  //Require at least one device to be plugged in
3672  rs2::context ctx;
3674  {
3675  std::vector<sensor> list;
3676  REQUIRE_NOTHROW(list = ctx.query_all_sensors());
3677  REQUIRE(list.size() > 0);
3678 
3679  const int frames_before_start_measure = 10;
3680  const int frames_for_fps_measure = 50;
3681  const double msec_to_sec = 0.001;
3682  const int num_of_profiles_for_each_subdevice = 2;
3683  const float max_diff_between_real_and_metadata_fps = 1.0f;
3684 
3685  for (auto && subdevice : list) {
3686  std::vector<rs2::stream_profile> modes;
3687  REQUIRE_NOTHROW(modes = subdevice.get_stream_profiles());
3688 
3689  REQUIRE(modes.size() > 0);
3690  CAPTURE(subdevice.get_info(RS2_CAMERA_INFO_NAME));
3691 
3692  //the test will be done only on sub set of profile for each sub device
3693  for (int i = 0; i < modes.size(); i += static_cast<int>(std::ceil((float)modes.size() / (float)num_of_profiles_for_each_subdevice)))
3694  {
3695  // Full-HD is often times too heavy for the build machine to handle
3696  if (auto video_profile = modes[i].as<video_stream_profile>())
3697  {
3698  if (video_profile.width() == 1920 && video_profile.height() == 1080 && video_profile.fps() == 60)
3699  {
3700  continue; // Disabling for now
3701  }
3702  }
3703  // GPIO Requires external triggers to produce events
3704  if (RS2_STREAM_GPIO == modes[i].stream_type())
3705  continue; // Disabling for now
3706 
3707  CAPTURE(modes[i].format());
3708  CAPTURE(modes[i].fps());
3709  CAPTURE(modes[i].stream_type());
3710  CAPTURE(modes[i].stream_index());
3711  if (auto video = modes[i].as<video_stream_profile>())
3712  {
3713  CAPTURE(video.width());
3714  CAPTURE(video.height());
3715  }
3716 
3717  std::vector<internal_frame_additional_data> frames_additional_data;
3718  auto frames = 0;
3719  double start;
3720  std::condition_variable cv;
3721  std::mutex m;
3722  auto first = true;
3723 
3724  REQUIRE_NOTHROW(subdevice.open({ modes[i] }));
3725  disable_sensitive_options_for(subdevice);
3726 
3727  REQUIRE_NOTHROW(subdevice.start([&](rs2::frame f)
3728  {
3729  if (frames_additional_data.size() >= frames_for_fps_measure)
3730  {
3731  cv.notify_one();
3732  }
3733 
3734  if ((frames >= frames_before_start_measure) && (frames_additional_data.size() < frames_for_fps_measure))
3735  {
3736  if (first)
3737  {
3738  start = internal::get_time();
3739  }
3740  first = false;
3741 
3743  f.get_frame_number(),
3745  f.get_profile().stream_type(),
3746  f.get_profile().format() };
3747 
3748  // Store frame metadata attributes, verify API behavior correctness
3750  {
3751  CAPTURE(i);
3752  bool supported = false;
3754  if (supported)
3755  {
3758  data.frame_md.md_attributes[i] = std::make_pair(true, val);
3759  }
3760  else
3761  {
3762 
3764  data.frame_md.md_attributes[i].first = false;
3765  }
3766  }
3767 
3768 
3769  std::unique_lock<std::mutex> lock(m);
3770  frames_additional_data.push_back(data);
3771  }
3772  frames++;
3773  }));
3774 
3775 
3776  CAPTURE(frames_additional_data.size());
3777  CAPTURE(frames_for_fps_measure);
3778 
3779  std::unique_lock<std::mutex> lock(m);
3780  cv.wait_for(lock, std::chrono::seconds(15), [&] {return ((frames_additional_data.size() >= frames_for_fps_measure)); });
3781 
3782  auto end = internal::get_time();
3783  REQUIRE_NOTHROW(subdevice.stop());
3784  REQUIRE_NOTHROW(subdevice.close());
3785 
3786  lock.unlock();
3787 
3788  auto seconds = (end - start)*msec_to_sec;
3789 
3790  CAPTURE(start);
3791  CAPTURE(end);
3792  CAPTURE(seconds);
3793 
3794  REQUIRE(seconds > 0);
3795 
3796  if (frames_additional_data.size())
3797  {
3798  auto actual_fps = (double)frames_additional_data.size() / (double)seconds;
3799  double metadata_seconds = frames_additional_data[frames_additional_data.size() - 1].timestamp - frames_additional_data[0].timestamp;
3800  metadata_seconds *= msec_to_sec;
3801  CAPTURE(frames_additional_data[frames_additional_data.size() - 1].timestamp);
3802  CAPTURE(frames_additional_data[0].timestamp);
3803 
3804  if (metadata_seconds <= 0)
3805  {
3806  std::cout << "Start metadata " << std::fixed << frames_additional_data[0].timestamp << "\n";
3807  std::cout << "End metadata " << std::fixed << frames_additional_data[frames_additional_data.size() - 1].timestamp << "\n";
3808  }
3809  REQUIRE(metadata_seconds > 0);
3810 
3811  auto metadata_frames = frames_additional_data[frames_additional_data.size() - 1].frame_number - frames_additional_data[0].frame_number;
3812  auto metadata_fps = (double)metadata_frames / (double)metadata_seconds;
3813 
3814  for (auto i = 0; i < frames_additional_data.size() - 1; i++)
3815  {
3816  CAPTURE(i);
3817  CAPTURE(frames_additional_data[i].timestamp_domain);
3818  CAPTURE(frames_additional_data[i + 1].timestamp_domain);
3819  REQUIRE((frames_additional_data[i].timestamp_domain == frames_additional_data[i + 1].timestamp_domain));
3820 
3821  CAPTURE(frames_additional_data[i].frame_number);
3822  CAPTURE(frames_additional_data[i + 1].frame_number);
3823 
3824  REQUIRE((frames_additional_data[i].frame_number < frames_additional_data[i + 1].frame_number));
3825  }
3826 
3827  CAPTURE(metadata_frames);
3828  CAPTURE(metadata_seconds);
3829  CAPTURE(metadata_fps);
3830  CAPTURE(frames_additional_data.size());
3832 
3833  //it the diff in percentage between metadata fps and actual fps is bigger than max_diff_between_real_and_metadata_fps
3834  //the test will fail
3835  REQUIRE(std::fabs(metadata_fps / actual_fps - 1) < max_diff_between_real_and_metadata_fps);
3836 
3837  // Verify per-frame metadata attributes
3838  metadata_verification(frames_additional_data);
3839  }
3840  }
3841  }
3842  }
3843 }
3844 
3845 TEST_CASE("color sensor API", "[live][options]")
3846 {
3847  rs2::context ctx;
3848  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.17.1"))
3849  {
3850  rs2::device dev;
3851  rs2::pipeline pipe(ctx);
3852  rs2::config cfg;
3854  REQUIRE_NOTHROW(profile = cfg.resolve(pipe));
3855  REQUIRE(profile);
3856  REQUIRE_NOTHROW(dev = profile.get_device());
3857  REQUIRE(dev);
3858  dev_type PID = get_PID(dev);
3859  if (!librealsense::val_in_range(PID.first, { std::string("0AA5"),
3860  std::string("0B48"),
3861  std::string("0AD3"),
3862  std::string("0AD4"),
3863  std::string("0AD5"),
3864  std::string("0B01"),
3865  std::string("0B07"),
3866  std::string("0B3A"),
3867  std::string("0B3D") }))
3868  {
3869  WARN("Skipping test - no motion sensor is device type: " << PID.first << (PID.second ? " USB3" : " USB2"));
3870  return;
3871  }
3872  auto sensor = profile.get_device().first<rs2::color_sensor>();
3874  std::cout << "depth sensor: " << librealsense::get_string(RS2_EXTENSION_DEPTH_SENSOR) << "\n";
3875  std::cout << "color sensor: " << librealsense::get_string(RS2_EXTENSION_COLOR_SENSOR) << "\n";
3876  std::cout << "motion sensor: " << librealsense::get_string(RS2_EXTENSION_MOTION_SENSOR) << "\n";
3877  std::cout << "fisheye sensor: " << librealsense::get_string(RS2_EXTENSION_FISHEYE_SENSOR) << "\n";
3882  REQUIRE(module_name.size() > 0);
3883  }
3884 }
3885 
3886 TEST_CASE("motion sensor API", "[live][options]")
3887 {
3888  rs2::context ctx;
3889  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.17.1"))
3890  {
3891  rs2::device dev;
3892  rs2::pipeline pipe(ctx);
3893  rs2::config cfg;
3895  REQUIRE_NOTHROW(profile = cfg.resolve(pipe));
3896  REQUIRE(profile);
3897  REQUIRE_NOTHROW(dev = profile.get_device());
3898  REQUIRE(dev);
3899  dev_type PID = get_PID(dev);
3900  if (!librealsense::val_in_range(PID.first, { std::string("0AD5"),
3901  std::string("0AFE"),
3902  std::string("0AFF"),
3903  std::string("0B00"),
3904  std::string("0B01"),
3905  std::string("0B3A"),
3906  std::string("0B3D")}))
3907  {
3908  WARN("Skipping test - no motion sensor is device type: " << PID.first << (PID.second ? " USB3" : " USB2"));
3909  return;
3910  }
3911  auto sensor = profile.get_device().first<rs2::motion_sensor>();
3915  REQUIRE(module_name.size() > 0);
3916  }
3917 }
3918 
3919 TEST_CASE("fisheye sensor API", "[live][options]")
3920 {
3921  rs2::context ctx;
3922  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.17.1"))
3923  {
3924  rs2::device dev;
3925  rs2::pipeline pipe(ctx);
3926  rs2::config cfg;
3928  REQUIRE_NOTHROW(profile = cfg.resolve(pipe));
3929  REQUIRE(profile);
3930  REQUIRE_NOTHROW(dev = profile.get_device());
3931  REQUIRE(dev);
3932 
3933  dev_type PID = get_PID(dev);
3934  if (!librealsense::val_in_range(PID.first, { std::string("0AD5"),
3935  std::string("0AFE"),
3936  std::string("0AFF"),
3937  std::string("0B00"),
3938  std::string("0B01") }))
3939  {
3940  WARN("Skipping test - no fisheye sensor is device type: " << PID.first << (PID.second ? " USB3" : " USB2"));
3941  return;
3942  }
3943  auto sensor = profile.get_device().first<rs2::fisheye_sensor>();
3947  REQUIRE(module_name.size() > 0);
3948  }
3949 }
3950 
3951 // FW Sub-presets API
3952 TEST_CASE("Alternating Emitter", "[live][options]")
3953 {
3954  rs2::context ctx;
3955  //log_to_console(RS2_LOG_SEVERITY_DEBUG);
3956 
3957  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.17.1"))
3958  {
3959  rs2::device dev;
3960  rs2::pipeline pipe(ctx);
3961  rs2::config cfg;
3963  REQUIRE_NOTHROW(profile = cfg.resolve(pipe));
3964  REQUIRE(profile);
3965  REQUIRE_NOTHROW(dev = profile.get_device());
3966  REQUIRE(dev);
3968  dev_type PID = get_PID(dev);
3969  CAPTURE(PID.first);
3970  const size_t record_frames = 60;
3971 
3972  // D400 Global Shutter only models
3973  if (!librealsense::val_in_range(PID.first, { std::string("0B3A"),std::string("0B07") }))
3974  {
3975  WARN("Skipping test - the Alternating Emitter feature is not supported for device type: " << PID.first << (PID.second ? " USB3" : " USB2"));
3976  }
3977  else
3978  {
3979  auto depth_sensor = profile.get_device().first<rs2::depth_sensor>();
3982 
3983  GIVEN("Success scenario"){
3984 
3989 
3990  WHEN("Sequence - idle - flickering on/off")
3991  {
3992  THEN("Stress test succeed")
3993  {
3994  for (int i=0 ;i<30; i++)
3995  {
3996  //std::cout << "iteration " << i << " off";
3997  // Revert to original state
4002  //std::cout << " - on\n";
4007  }
4008 
4009  // Revert
4014  }
4015  }
4016 
4017  WHEN("Sequence=[idle->:laser_on->: emitter_toggle_on->:streaming]") {
4018 
4019  REQUIRE(false==static_cast<bool>(depth_sensor.get_option(RS2_OPTION_EMITTER_ON_OFF)));
4022  THEN("The emitter is alternating on/off") {
4023 
4024  std::vector<int> emitter_state;
4025  emitter_state.reserve(record_frames);
4026 
4027  REQUIRE_NOTHROW(pipe.start(cfg));
4028  REQUIRE(true ==static_cast<bool>(depth_sensor.get_option(RS2_OPTION_EMITTER_ON_OFF)));
4029 
4030  // Warmup - the very first depth frames may not include the alternating pattern
4031  frameset fs;
4032  for (int i=0; i<10; )
4033  {
4034  REQUIRE_NOTHROW(fs = pipe.wait_for_frames());
4035  if (auto f = fs.get_depth_frame())
4036  i++;
4037  }
4038 
4039  bool even=true;
4040  while (emitter_state.size() < record_frames)
4041  {
4042  size_t last_fn = 0;
4043  REQUIRE_NOTHROW(fs = pipe.wait_for_frames());
4044 
4045  if (auto f = fs.get_depth_frame())
4046  {
4047  if (((bool(f.get_frame_number()%2)) != even) && f.supports_frame_metadata(RS2_FRAME_METADATA_FRAME_LASER_POWER_MODE))
4048  {
4049  even = !even; // Alternating odd/even frame number is sufficient to avoid duplicates
4050  auto val = static_cast<int>(f.get_frame_metadata(RS2_FRAME_METADATA_FRAME_LASER_POWER_MODE));
4051  emitter_state.push_back(val);
4052  }
4053  }
4054  }
4055 
4056  // Reject Laser off command while subpreset is active
4059 
4060  // Allow Laser off command when subpreset is removed
4063  REQUIRE(false==static_cast<bool>(depth_sensor.get_option(RS2_OPTION_EMITTER_ON_OFF)));
4065 
4066  // Re-enable alternating emitter to test stream stop scenario
4069 
4072 
4073  REQUIRE_NOTHROW(pipe.stop());
4074  REQUIRE(false ==static_cast<bool>(depth_sensor.get_option(RS2_OPTION_EMITTER_ON_OFF)));
4075  std::stringstream emitter_results;
4076  std::copy(emitter_state.begin(), emitter_state.end(), std::ostream_iterator<int>(emitter_results));
4077  CAPTURE(emitter_results.str().c_str());
4078 
4079  // Verify that the laser state is constantly alternating
4080  REQUIRE(std::adjacent_find(emitter_state.begin(), emitter_state.end()) == emitter_state.end());
4081  }
4082  }
4083 
4084  WHEN("Sequence=[idle->:streaming-:laser_on->: emitter_toggle_on]") {
4085 
4086  THEN("The emitter is alternating on/off") {
4087 
4088  std::vector<int> emitter_state;
4089  emitter_state.reserve(record_frames);
4090 
4091  REQUIRE_NOTHROW(pipe.start(cfg));
4094  REQUIRE(true ==static_cast<bool>(depth_sensor.get_option(RS2_OPTION_EMITTER_ON_OFF)));
4095 
4096  // Warmup - the very first depth frames may not include the alternating pattern
4097  frameset fs;
4098  for (int i=0; i<10; )
4099  {
4100  REQUIRE_NOTHROW(fs = pipe.wait_for_frames());
4101  if (auto f = fs.get_depth_frame())
4102  i++;
4103  }
4104 
4105  bool even=true;
4106  while (emitter_state.size() < record_frames)
4107  {
4108  size_t last_fn = 0;
4109  REQUIRE_NOTHROW(fs = pipe.wait_for_frames());
4110 
4111  if (auto f = fs.get_depth_frame())
4112  {
4113  if (((bool(f.get_frame_number()%2) != even)) && f.supports_frame_metadata(RS2_FRAME_METADATA_FRAME_LASER_POWER_MODE))
4114  {
4115  even = !even;
4116  auto val = static_cast<int>(f.get_frame_metadata(RS2_FRAME_METADATA_FRAME_LASER_POWER_MODE));
4117  emitter_state.push_back(val);
4118  }
4119  }
4120  }
4121  REQUIRE_NOTHROW(pipe.stop());
4122 
4123  REQUIRE(false ==static_cast<bool>(depth_sensor.get_option(RS2_OPTION_EMITTER_ON_OFF)));
4124  std::stringstream emitter_results;
4125  std::copy(emitter_state.begin(), emitter_state.end(), std::ostream_iterator<int>(emitter_results));
4126  CAPTURE(emitter_results.str().c_str());
4127 
4128  // Verify that the laser state is constantly alternating
4129  REQUIRE(std::adjacent_find(emitter_state.begin(), emitter_state.end()) == emitter_state.end());
4130  }
4131  }
4132  }
4133 
4134  GIVEN("Negative scenario"){
4135 
4142 
4143  WHEN("Sequence=[idle->:laser_off->: emitter_toggle_on]") {
4144  THEN ("Cannot set alternating emitter when laser is set off") {
4146  }
4147  }
4148 
4149  WHEN("Sequence=[idle->:laser_on->:emitter_toggle_on->:laser_off]") {
4150  THEN ("Cannot turn_off laser while the alternating emitter option is on") {
4154  }
4155  }
4156  }
4157 
4158  // Revert to original state
4163  }
4164  }
4165 }
4166 
4167 // the tests may incorrectly interpret changes to librealsense-core, namely default profiles selections
4168 TEST_CASE("All suggested profiles can be opened", "[live][!mayfail]") {
4169 
4170  //Require at least one device to be plugged in
4171  rs2::context ctx;
4173  {
4174 
4175  const int num_of_profiles_for_each_subdevice = 2;
4176 
4177  std::vector<sensor> list;
4178  REQUIRE_NOTHROW(list = ctx.query_all_sensors());
4179  REQUIRE(list.size() > 0);
4180 
4181  for (auto && subdevice : list) {
4182 
4183  disable_sensitive_options_for(subdevice);
4184 
4185  std::vector<rs2::stream_profile> modes;
4186  REQUIRE_NOTHROW(modes = subdevice.get_stream_profiles());
4187 
4188  REQUIRE(modes.size() > 0);
4189  //the test will be done only on sub set of profile for each sub device
4190  for (auto i = 0UL; i < modes.size(); i += (int)std::ceil((float)modes.size() / (float)num_of_profiles_for_each_subdevice)) {
4191  //CAPTURE(rs2_subdevice(subdevice));
4192  CAPTURE(modes[i].format());
4193  CAPTURE(modes[i].fps());
4194  CAPTURE(modes[i].stream_type());
4195  REQUIRE_NOTHROW(subdevice.open({ modes[i] }));
4196  REQUIRE_NOTHROW(subdevice.start([](rs2::frame fref) {}));
4197  REQUIRE_NOTHROW(subdevice.stop());
4198  REQUIRE_NOTHROW(subdevice.close());
4199  }
4200  }
4201  }
4202 }
4203 
4204 TEST_CASE("Pipeline config enable resolve start flow", "[live][pipeline][using_pipeline]") {
4205  rs2::context ctx;
4206 
4207  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
4208  {
4209  auto list = ctx.query_devices();
4210  REQUIRE(list.size());
4211 
4212  rs2::device dev;
4213  rs2::pipeline pipe(ctx);
4214  rs2::config cfg;
4216  REQUIRE_NOTHROW(profile = cfg.resolve(pipe));
4217  REQUIRE(profile);
4218  REQUIRE_NOTHROW(dev = profile.get_device());
4219  REQUIRE(dev);
4221  REQUIRE_NOTHROW(profile = cfg.resolve(pipe));
4222  REQUIRE(profile);
4223  REQUIRE_NOTHROW(dev = profile.get_device());
4224  REQUIRE(dev);
4225 
4226  REQUIRE_NOTHROW(profile = cfg.resolve(pipe));
4227  REQUIRE(profile);
4228  REQUIRE_NOTHROW(dev = profile.get_device());
4229  REQUIRE(dev);
4230 
4232  REQUIRE_NOTHROW(pipe.start(cfg));
4233 
4234  REQUIRE_NOTHROW(profile = pipe.get_active_profile());
4236  CAPTURE(depth_profile.stream_index());
4237  CAPTURE(depth_profile.stream_type());
4238  CAPTURE(depth_profile.format());
4239  CAPTURE(depth_profile.fps());
4240  CAPTURE(depth_profile.width());
4241  CAPTURE(depth_profile.height());
4242  std::vector<device_profiles> frames;
4243 
4244 
4245  uint32_t timeout = is_usb3(dev) ? 500 : 2000; // for USB2 it takes longer to produce frames
4246 
4247  for (auto i = 0; i < 5; i++)
4248  REQUIRE_NOTHROW(pipe.wait_for_frames(timeout));
4249 
4250  REQUIRE_NOTHROW(pipe.stop());
4251  REQUIRE_NOTHROW(pipe.start(cfg));
4252 
4253  for (auto i = 0; i < 5; i++)
4254  REQUIRE_NOTHROW(pipe.wait_for_frames(timeout));
4255 
4257 
4259  REQUIRE_NOTHROW(profile = cfg.resolve(pipe));
4260  REQUIRE(profile);
4261  REQUIRE_NOTHROW(dev = profile.get_device());
4262  REQUIRE(dev);
4263 
4265  REQUIRE_NOTHROW(profile = cfg.resolve(pipe));
4266  REQUIRE(profile);
4267  REQUIRE_NOTHROW(dev = profile.get_device());
4268  REQUIRE(dev);
4269  }
4270 }
4271 
4272 TEST_CASE("Pipeline - multicam scenario with specific devices", "[live][multicam][pipeline][using_pipeline]") {
4273  rs2::context ctx;
4274 
4275  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
4276  {
4277 
4278  auto list = ctx.query_devices();
4279  int realsense_devices_count = 0;
4280  rs2::device d;
4281  for (auto&& dev : list)
4282  {
4283  if (dev.supports(RS2_CAMERA_INFO_NAME))
4284  {
4286  if (name != "Platform Camera")
4287  {
4288  realsense_devices_count++;
4289  d = dev;
4290  }
4291  }
4292  }
4293  if (realsense_devices_count < 2)
4294  {
4295  WARN("Skipping test! This test requires multiple RealSense devices connected");
4296  return;
4297  }
4298 
4300  //After getting the device, find a serial and a profile it can use
4301  std::string required_serial;
4303  stream_profile required_profile;
4304  //find the a video profile of some sensor
4305  for (auto&& sensor : d.query_sensors())
4306  {
4307  for (auto&& profile : sensor.get_stream_profiles())
4308  {
4309  auto vid_profile = profile.as<video_stream_profile>();
4310  if (vid_profile)
4311  {
4312  required_profile = vid_profile;
4313  break;
4314  }
4315  }
4316  if (required_profile)
4317  break;
4318  }
4319  REQUIRE(required_profile);
4320  CAPTURE(required_profile);
4321  auto vid_profile = required_profile.as<video_stream_profile>();
4322 
4323  rs2::device dev;
4324  rs2::pipeline pipe(ctx);
4325  rs2::config cfg;
4326 
4327  //Using the config object to request the serial and stream that we found above
4328  REQUIRE_NOTHROW(cfg.enable_device(required_serial));
4329  REQUIRE_NOTHROW(cfg.enable_stream(vid_profile.stream_type(), vid_profile.stream_index(), vid_profile.width(), vid_profile.height(), vid_profile.format(), vid_profile.fps()));
4330 
4331  //Testing that config.resolve() returns the right data
4332  rs2::pipeline_profile resolved_profile;
4333  REQUIRE_NOTHROW(resolved_profile = cfg.resolve(pipe));
4334  REQUIRE(resolved_profile);
4335  rs2::pipeline_profile resolved_profile_from_start;
4336  REQUIRE_NOTHROW(resolved_profile_from_start = pipe.start(cfg));
4337  REQUIRE(resolved_profile_from_start);
4338 
4339  REQUIRE_NOTHROW(dev = resolved_profile.get_device());
4340  REQUIRE(dev);
4341  rs2::device dev_from_start;
4342  REQUIRE_NOTHROW(dev_from_start = resolved_profile_from_start.get_device());
4343  REQUIRE(dev_from_start);
4344 
4345  //Compare serial number
4346  std::string actual_serial;
4347  std::string actual_serial_from_start;
4348  REQUIRE_NOTHROW(actual_serial = dev.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER));
4349  REQUIRE_NOTHROW(actual_serial_from_start = dev_from_start.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER));
4350  REQUIRE(actual_serial == required_serial);
4351  REQUIRE(actual_serial == actual_serial_from_start);
4352 
4353  //Compare Stream
4354  std::vector<rs2::stream_profile> actual_streams;
4355  REQUIRE_NOTHROW(actual_streams = resolved_profile.get_streams());
4356  REQUIRE(actual_streams.size() == 1);
4357  REQUIRE(actual_streams[0] == required_profile);
4358  std::vector<rs2::stream_profile> actual_streams_from_start;
4359  REQUIRE_NOTHROW(actual_streams_from_start = resolved_profile_from_start.get_streams());
4360  REQUIRE(actual_streams_from_start.size() == 1);
4361  REQUIRE(actual_streams_from_start[0] == required_profile);
4362 
4363  pipe.stop();
4364 
4365  //Using the config object to request the serial and stream that we found above, and test the pipeline.start() returns the right data
4366  rs2::device started_dev;
4367  rs2::pipeline_profile strarted_profile;
4368  cfg = rs2::config(); //Clean previous config
4369 
4370  //Using the config object to request the serial and stream that we found above
4371  REQUIRE_NOTHROW(cfg.enable_device(required_serial));
4372  REQUIRE_NOTHROW(cfg.enable_stream(vid_profile.stream_type(), vid_profile.stream_index(), vid_profile.width(), vid_profile.height(), vid_profile.format(), vid_profile.fps()));
4373 
4374  //Testing that pipeline.start(cfg) returns the right data
4375  REQUIRE_NOTHROW(strarted_profile = pipe.start(cfg));
4376  REQUIRE(strarted_profile);
4377  REQUIRE_NOTHROW(started_dev = strarted_profile.get_device());
4378  REQUIRE(started_dev);
4379 
4380  //Compare serial number
4381  std::string started_serial;
4382  REQUIRE_NOTHROW(started_serial = started_dev.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER));
4383  REQUIRE(started_serial == required_serial);
4384 
4385  //Compare Stream
4386  std::vector<rs2::stream_profile> started_streams;
4387  REQUIRE_NOTHROW(started_streams = strarted_profile.get_streams());
4388  REQUIRE(started_streams.size() == 1);
4389  REQUIRE(started_streams[0] == required_profile);
4390  pipe.stop();
4391  }
4392 }
4393 
4394 TEST_CASE("Empty Pipeline Profile", "[live][pipeline][using_pipeline]") {
4395  rs2::context ctx;
4396 
4397  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
4398  {
4400  rs2::pipeline_profile prof;
4401  REQUIRE_FALSE(prof);
4402  rs2::device dev;
4403  CHECK_THROWS(dev = prof.get_device());
4404  REQUIRE(!dev);
4405  for (int i = 0; i < (int)RS2_STREAM_COUNT; i++)
4406  {
4407  rs2_stream stream = static_cast<rs2_stream>(i);
4408  CAPTURE(stream);
4410  CHECK_THROWS(sp = prof.get_stream(stream));
4411  REQUIRE(!sp);
4412  }
4413  std::vector<rs2::stream_profile> spv;
4414  CHECK_THROWS(spv = prof.get_streams());
4415  REQUIRE(spv.size() == 0);
4416  }
4417 }
4418 
4420 {
4421  rs2::device d1 = profile1.get_device();
4422  rs2::device d2 = profile2.get_device();
4423 
4424  REQUIRE(d1.get().get());
4425  REQUIRE(d2.get().get());
4426  std::string serial1, serial2;
4429  if (serial1 != serial2)
4430  {
4431  throw std::runtime_error(serial1 + " is different than " + serial2);
4432  }
4433 
4434  std::string name1, name2;
4437  if (name1 != name2)
4438  {
4439  throw std::runtime_error(name1 + " is different than " + name2);
4440  }
4441 
4442  auto streams1 = profile1.get_streams();
4443  auto streams2 = profile2.get_streams();
4444  if (streams1.size() != streams2.size())
4445  {
4446  throw std::runtime_error(std::string("Profiles contain different number of streams ") + std::to_string(streams1.size()) + " vs " + std::to_string(streams2.size()));
4447  }
4448 
4449  auto streams1_and_2_equals = true;
4450  for (auto&& s : streams1)
4451  {
4452  auto it = std::find_if(streams2.begin(), streams2.end(), [&s](const stream_profile& sp) {
4453  return
4454  s.format() == sp.format() &&
4455  s.fps() == sp.fps() &&
4456  s.is_default() == sp.is_default() &&
4457  s.stream_index() == sp.stream_index() &&
4458  s.stream_type() == sp.stream_type() &&
4459  s.stream_name() == sp.stream_name();
4460  });
4461  if (it == streams2.end())
4462  {
4463  streams1_and_2_equals = false;
4464  }
4465  }
4466 
4467  if (!streams1_and_2_equals)
4468  {
4469  throw std::runtime_error(std::string("Profiles contain different streams"));
4470  }
4471 }
4472 TEST_CASE("Pipeline empty Config", "[live][pipeline][using_pipeline]") {
4473  rs2::context ctx;
4474 
4475  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
4476  {
4478  //Empty config
4479  rs2::pipeline p(ctx);
4480  rs2::config c1;
4481  REQUIRE(c1.get().get() != nullptr);
4482  bool can_resolve = false;
4483  REQUIRE_NOTHROW(can_resolve = c1.can_resolve(p));
4484  REQUIRE(true == can_resolve);
4485  REQUIRE_THROWS(c1.resolve(nullptr));
4487  REQUIRE_NOTHROW(profile = c1.resolve(p));
4488  REQUIRE(true == profile);
4489  }
4490 }
4491 
4492 TEST_CASE("Pipeline 2 Configs", "[live][pipeline][using_pipeline]") {
4493  rs2::context ctx;
4494 
4495  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
4496  {
4497  rs2::pipeline p(ctx);
4498  rs2::config c1;
4499  rs2::config c2;
4500  bool can_resolve1 = false;
4501  bool can_resolve2 = false;
4502  REQUIRE_NOTHROW(can_resolve1 = c1.can_resolve(p));
4503  REQUIRE_NOTHROW(can_resolve2 = c2.can_resolve(p));
4504  REQUIRE(can_resolve1);
4505  REQUIRE(can_resolve2);
4506  rs2::pipeline_profile profile1;
4507  rs2::pipeline_profile profile2;
4508 
4509  REQUIRE_NOTHROW(profile1 = c1.resolve(p));
4510  REQUIRE(profile1);
4511  REQUIRE_NOTHROW(profile2 = c2.resolve(p));
4512  REQUIRE(profile2);
4513 
4514  REQUIRE_NOTHROW(require_pipeline_profile_same(profile1, profile2));
4515  }
4516 }
4517 
4518 TEST_CASE("Pipeline start after resolve uses the same profile", "[live][pipeline][using_pipeline]") {
4519  rs2::context ctx;
4520 
4521  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
4522  {
4523  rs2::pipeline pipe(ctx);
4524  rs2::config cfg;
4526  rs2::pipeline_profile profile_from_cfg;
4527  REQUIRE_NOTHROW(profile_from_cfg = cfg.resolve(pipe));
4528  REQUIRE(profile_from_cfg);
4529  rs2::pipeline_profile profile_from_start;
4530  REQUIRE_NOTHROW(profile_from_start = pipe.start(cfg));
4531  REQUIRE(profile_from_start);
4532  REQUIRE_NOTHROW(require_pipeline_profile_same(profile_from_cfg, profile_from_start));
4533 
4534  }
4535 }
4536 
4537 TEST_CASE("Pipeline start ignores previous config if it was changed", "[live][pipeline][using_pipeline][!mayfail]") {
4538  rs2::context ctx;
4539  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
4540  {
4541  rs2::pipeline pipe(ctx);
4542  rs2::config cfg;
4543  rs2::pipeline_profile profile_from_cfg;
4544  REQUIRE_NOTHROW(profile_from_cfg = cfg.resolve(pipe));
4545  REQUIRE(profile_from_cfg);
4546  cfg.enable_stream(RS2_STREAM_INFRARED, RS2_FORMAT_ANY, 60); //enable a single stream (unlikely to be the default one)
4547  rs2::pipeline_profile profile_from_start;
4548  REQUIRE_NOTHROW(profile_from_start = pipe.start(cfg));
4549  REQUIRE(profile_from_start);
4550  REQUIRE_THROWS(require_pipeline_profile_same(profile_from_cfg, profile_from_start));
4551  }
4552 }
4553 
4554 TEST_CASE("Pipeline Config disable all is a nop with empty config", "[live][pipeline][using_pipeline]") {
4555  rs2::context ctx;
4556 
4557  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
4558  {
4559  rs2::pipeline p(ctx);
4560  rs2::config c1;
4561  c1.disable_all_streams();
4562  rs2::config c2;
4563  rs2::pipeline_profile profile1;
4564  rs2::pipeline_profile profile2;
4565 
4566  REQUIRE_NOTHROW(profile1 = c1.resolve(p));
4567  REQUIRE(profile1);
4568  REQUIRE_NOTHROW(profile2 = c2.resolve(p));
4569  REQUIRE(profile2);
4570  REQUIRE_NOTHROW(require_pipeline_profile_same(profile1, profile2));
4571  }
4572 }
4573 TEST_CASE("Pipeline Config disable each stream is nop on empty config", "[live][pipeline][using_pipeline]") {
4574  rs2::context ctx;
4575 
4576  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
4577  {
4578  rs2::pipeline p(ctx);
4579  rs2::config c1;
4580  for (int i = 0; i < (int)RS2_STREAM_COUNT; i++)
4581  {
4582  REQUIRE_NOTHROW(c1.disable_stream(static_cast<rs2_stream>(i)));
4583  }
4584  rs2::config c2;
4585  rs2::pipeline_profile profile1;
4586  rs2::pipeline_profile profile2;
4587 
4588  REQUIRE_NOTHROW(profile1 = c1.resolve(p));
4589  REQUIRE(profile1);
4590  REQUIRE_NOTHROW(profile2 = c2.resolve(p));
4591  REQUIRE(profile2);
4592  REQUIRE_NOTHROW(require_pipeline_profile_same(profile1, profile2));
4593  }
4594 }
4595 //
4596 //TEST_CASE("Pipeline record and playback", "[live][pipeline][using_pipeline][!mayfail]") {
4597 // rs2::context ctx;
4598 //
4599 // if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
4600 // {
4601 // const std::string filename = get_folder_path(special_folder::temp_folder) + "test_file.bag";
4602 // //Scoping the below code to make sure no one holds the device
4603 // {
4604 // rs2::pipeline p(ctx);
4605 // rs2::config cfg;
4606 // REQUIRE_NOTHROW(cfg.enable_record_to_file(filename));
4607 // rs2::pipeline_profile profile;
4608 // REQUIRE_NOTHROW(profile = cfg.resolve(p));
4609 // REQUIRE(profile);
4610 // auto dev = profile.get_device();
4611 // REQUIRE(dev);
4612 // disable_sensitive_options_for(dev);
4613 // REQUIRE_NOTHROW(p.start(cfg));
4614 // std::this_thread::sleep_for(std::chrono::seconds(5));
4615 // rs2::frameset frames;
4616 // REQUIRE_NOTHROW(frames = p.wait_for_frames(200));
4617 // REQUIRE(frames);
4618 // REQUIRE(frames.size() > 0);
4619 // REQUIRE_NOTHROW(p.stop());
4620 // }
4621 // //Scoping the above code to make sure no one holds the device
4622 // REQUIRE(file_exists(filename));
4623 //
4624 // {
4625 // rs2::pipeline p(ctx);
4626 // rs2::config cfg;
4627 // rs2::pipeline_profile profile;
4628 // REQUIRE_NOTHROW(cfg.enable_device_from_file(filename));
4629 // REQUIRE_NOTHROW(profile = cfg.resolve(p));
4630 // REQUIRE(profile);
4631 // REQUIRE_NOTHROW(p.start(cfg));
4632 // std::this_thread::sleep_for(std::chrono::seconds(5));
4633 // rs2::frameset frames;
4634 // REQUIRE_NOTHROW(frames = p.wait_for_frames(200));
4635 // REQUIRE(frames);
4636 // REQUIRE_NOTHROW(p.stop());
4637 // }
4638 // }
4639 //}
4640 
4641 
4642 TEST_CASE("Pipeline enable bad configuration", "[pipeline][using_pipeline]")
4643 {
4644  rs2::context ctx;
4645  if (!make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
4646  return;
4647 
4648  pipeline pipe(ctx);
4649  rs2::config cfg;
4650 
4652  REQUIRE_THROWS(pipe.start(cfg));
4653 }
4654 
4655 TEST_CASE("Pipeline stream enable hierarchy", "[pipeline]")
4656 {
4657  rs2::context ctx;
4658  if (!make_context(SECTION_FROM_TEST_NAME, &ctx, "2.13.0"))
4659  return;
4660 
4661  pipeline pipe(ctx);
4662  rs2::config cfg;
4663  std::vector<stream_profile> default_streams = pipe.start(cfg).get_streams();
4664  pipe.stop();
4665 
4666  cfg.enable_all_streams();
4667  std::vector<stream_profile> all_streams = pipe.start(cfg).get_streams();
4668  pipe.stop();
4669 
4670  cfg.disable_all_streams();
4672  std::vector<stream_profile> wildcards_streams = pipe.start(cfg).get_streams();
4673  pipe.stop();
4674 
4675  for (auto d : default_streams)
4676  {
4677  auto it = std::find(begin(all_streams), end(all_streams), d);
4678  REQUIRE(it != std::end(all_streams));
4679  }
4680  for (auto w : wildcards_streams)
4681  {
4682  auto it = std::find(begin(all_streams), end(all_streams), w);
4683  REQUIRE(it != std::end(all_streams));
4684  }
4685 }
4686 
4687 TEST_CASE("Pipeline stream with callback", "[live][pipeline][using_pipeline][!mayfail]")
4688 {
4689  rs2::context ctx;
4690 
4692  return;
4693 
4694  rs2::pipeline pipe(ctx);
4696 
4697  auto callback = [&](const rs2::frame& f)
4698  {
4699  q.enqueue(f);
4700  };
4701 
4702  // Stream with callback
4703  pipe.start(callback);
4705  rs2::frameset frame_from_queue;
4706  REQUIRE_THROWS(pipe.poll_for_frames(&frame_from_queue));
4707  REQUIRE_THROWS(pipe.try_wait_for_frames(&frame_from_queue));
4708 
4709  rs2::frame frame_from_callback = q.wait_for_frame();
4710  pipe.stop();
4711 
4712  REQUIRE(frame_from_callback);
4713  REQUIRE(frame_from_queue == false);
4714 
4715  frame_from_callback = rs2::frame();
4716  frame_from_queue = rs2::frameset();
4717 
4718  // Stream without callback
4719  pipe.start();
4721  REQUIRE_NOTHROW(pipe.poll_for_frames(&frame_from_queue));
4722  REQUIRE_NOTHROW(pipe.try_wait_for_frames(&frame_from_queue));
4723 
4724  pipe.stop();
4725 
4726  REQUIRE(frame_from_callback == false);
4727  REQUIRE(frame_from_queue);
4728 }
4729 
4730 TEST_CASE("Syncer sanity with software-device device", "[live][software-device][!mayfail]") {
4731  rs2::context ctx;
4733  {
4734 
4735  const int W = 640;
4736  const int H = 480;
4737  const int BPP = 2;
4738  std::shared_ptr<software_device> dev = std::move(std::make_shared<software_device>());
4739  auto s = dev->add_sensor("software_sensor");
4740 
4741  rs2_intrinsics intrinsics{ W, H, 0, 0, 0, 0, RS2_DISTORTION_NONE ,{ 0,0,0,0,0 } };
4742 
4743  s.add_video_stream({ RS2_STREAM_DEPTH, 0, 0, W, H, 60, BPP, RS2_FORMAT_Z16, intrinsics });
4744  s.add_video_stream({ RS2_STREAM_INFRARED, 1, 1, W, H,60, BPP, RS2_FORMAT_Y8, intrinsics });
4745  dev->create_matcher(RS2_MATCHER_DI);
4746 
4747  frame_queue q;
4748 
4749  auto profiles = s.get_stream_profiles();
4750  auto depth = profiles[0];
4751  auto ir = profiles[1];
4752 
4753  syncer sync;
4754  s.open(profiles);
4755  s.start(sync);
4756 
4757  std::vector<uint8_t> pixels(W * H * BPP, 0);
4758  std::weak_ptr<rs2::software_device> weak_dev(dev);
4759 
4760  std::thread t([&s, weak_dev, pixels, depth, ir]() mutable {
4761 
4762  auto shared_dev = weak_dev.lock();
4763  if (shared_dev == nullptr)
4764  return;
4765  s.on_video_frame({ pixels.data(), [](void*) {}, 0,0,0, RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, 7, depth });
4766  s.on_video_frame({ pixels.data(), [](void*) {}, 0,0,0, RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, 5, ir });
4767 
4768  s.on_video_frame({ pixels.data(), [](void*) {},0,0, 0, RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, 8, depth });
4769  s.on_video_frame({ pixels.data(), [](void*) {},0,0, 0, RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, 6, ir });
4770 
4771  s.on_video_frame({ pixels.data(), [](void*) {},0,0, 0, RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, 8, ir });
4772  });
4773  t.detach();
4774 
4775  std::vector<std::vector<std::pair<rs2_stream, uint64_t>>> expected =
4776  {
4777  { { RS2_STREAM_DEPTH , 7}},
4778  { { RS2_STREAM_INFRARED , 5 } },
4779  { { RS2_STREAM_INFRARED , 6 } },
4780  { { RS2_STREAM_DEPTH , 8 },{ RS2_STREAM_INFRARED , 8 } }
4781  };
4782 
4783  std::vector<std::vector<std::pair<rs2_stream, uint64_t>>> results;
4784 
4785  for (auto i = 0UL; i < expected.size(); i++)
4786  {
4787  frameset fs;
4788  REQUIRE_NOTHROW(fs = sync.wait_for_frames(5000));
4789  std::vector < std::pair<rs2_stream, uint64_t>> curr;
4790 
4791  for (auto f : fs)
4792  {
4793  curr.push_back({ f.get_profile().stream_type(), f.get_frame_number() });
4794  }
4795  results.push_back(curr);
4796  }
4797 
4798  CAPTURE(results.size());
4799  CAPTURE(expected.size());
4800  REQUIRE(results.size() == expected.size());
4801 
4802  for (size_t i = 0; i < expected.size(); i++)
4803  {
4804  auto exp = expected[i];
4805  auto curr = results[i];
4806  CAPTURE(i);
4807  CAPTURE(exp.size());
4808  CAPTURE(curr.size());
4809  REQUIRE(exp.size() == curr.size());
4810 
4811  for (size_t j = 0; j < exp.size(); j++)
4812  {
4813  CAPTURE(j);
4814  CAPTURE(exp[j].first);
4815  CAPTURE(exp[j].second);
4816  CAPTURE(curr[j].first);
4817  CAPTURE(curr[j].second);
4818  REQUIRE(std::find(curr.begin(), curr.end(), exp[j]) != curr.end());
4819  }
4820  }
4821  }
4822 }
4823 
4824 TEST_CASE("Syncer clean_inactive_streams by frame number with software-device device", "[live][software-device]") {
4825  rs2::context ctx;
4827  {
4829  const int W = 640;
4830  const int H = 480;
4831  const int BPP = 2;
4832 
4833  std::shared_ptr<software_device> dev = std::make_shared<software_device>();
4834  auto s = dev->add_sensor("software_sensor");
4835 
4836  rs2_intrinsics intrinsics{ W, H, 0, 0, 0, 0, RS2_DISTORTION_NONE ,{ 0,0,0,0,0 } };
4837  s.add_video_stream({ RS2_STREAM_DEPTH, 0, 0, W, H, 60, BPP, RS2_FORMAT_Z16, intrinsics });
4838  s.add_video_stream({ RS2_STREAM_INFRARED, 1, 1, W, H,60, BPP, RS2_FORMAT_Y8, intrinsics });
4839  dev->create_matcher(RS2_MATCHER_DI);
4840  frame_queue q;
4841 
4842  auto profiles = s.get_stream_profiles();
4843  auto depth = profiles[0];
4844  auto ir = profiles[1];
4845 
4846  syncer sync(10);
4847  s.open(profiles);
4848  s.start(sync);
4849 
4850  std::vector<uint8_t> pixels(W * H * BPP, 0);
4851  std::weak_ptr<rs2::software_device> weak_dev(dev);
4852  std::thread t([s, weak_dev, pixels, depth, ir]() mutable {
4853  auto shared_dev = weak_dev.lock();
4854  if (shared_dev == nullptr)
4855  return;
4856  s.on_video_frame({ pixels.data(), [](void*) {}, 0,0,0, RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, 1, depth });
4857  s.on_video_frame({ pixels.data(), [](void*) {}, 0,0, 0, RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, 1, ir });
4858 
4859  s.on_video_frame({ pixels.data(), [](void*) {}, 0,0,0, RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, 3, depth });
4860 
4861  s.on_video_frame({ pixels.data(), [](void*) {}, 0,0, 0, RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, 4, depth });
4862 
4863  s.on_video_frame({ pixels.data(), [](void*) {},0,0, 0, RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, 5, depth });
4864 
4865  s.on_video_frame({ pixels.data(), [](void*) {}, 0,0,0, RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, 6, depth });
4866 
4867  s.on_video_frame({ pixels.data(), [](void*) {}, 0, 0, 0, RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, 7, depth });
4868  });
4869 
4870  t.detach();
4871 
4872  std::vector<std::vector<std::pair<rs2_stream, uint64_t>>> expected =
4873  {
4874  { { RS2_STREAM_DEPTH , 1 } },
4875  { { RS2_STREAM_INFRARED , 1 } },
4876  { { RS2_STREAM_DEPTH , 3 } },
4877  { { RS2_STREAM_DEPTH , 4 } },
4878  { { RS2_STREAM_DEPTH , 5 } },
4879  { { RS2_STREAM_DEPTH , 6 } },
4880  { { RS2_STREAM_DEPTH , 7 } },
4881  };
4882 
4883  std::vector<std::vector<std::pair<rs2_stream, uint64_t>>> results;
4884 
4885  for (auto i = 0UL; i < expected.size(); i++)
4886  {
4887  frameset fs;
4888  CAPTURE(i);
4889  REQUIRE_NOTHROW(fs = sync.wait_for_frames(5000));
4890  std::vector < std::pair<rs2_stream, uint64_t>> curr;
4891 
4892  for (auto f : fs)
4893  {
4894  curr.push_back({ f.get_profile().stream_type(), f.get_frame_number() });
4895  }
4896  results.push_back(curr);
4897  }
4898 
4899  CAPTURE(results.size());
4900  CAPTURE(expected.size());
4901  REQUIRE(results.size() == expected.size());
4902 
4903  for (size_t i = 0; i < expected.size(); i++)
4904  {
4905  auto exp = expected[i];
4906  auto curr = results[i];
4907  CAPTURE(i);
4908  CAPTURE(exp.size());
4909  CAPTURE(curr.size());
4910  REQUIRE(exp.size() == exp.size());
4911 
4912  for (size_t j = 0; j < exp.size(); j++)
4913  {
4914  CAPTURE(j);
4915  CAPTURE(exp[j].first);
4916  CAPTURE(exp[j].second);
4917  CAPTURE(curr[j].first);
4918  CAPTURE(curr[j].second);
4919  REQUIRE(std::find(curr.begin(), curr.end(), exp[j]) != curr.end());
4920  }
4921  }
4922  }
4923 }
4924 
4925 TEST_CASE("Unit transform test", "[live][software-device]") {
4926  rs2::context ctx;
4927 
4929  return;
4930 
4932  const int W = 640;
4933  const int H = 480;
4934  const int BPP = 2;
4935  int expected_frames = 1;
4936  int fps = 60;
4937  float depth_unit = 1.5;
4938  units_transform ut;
4939  rs2_intrinsics intrinsics{ W, H, 0, 0, 0, 0, RS2_DISTORTION_NONE ,{ 0,0,0,0,0 } };
4940 
4941  std::shared_ptr<software_device> dev = std::make_shared<software_device>();
4942  auto s = dev->add_sensor("software_sensor");
4943  s.add_read_only_option(RS2_OPTION_DEPTH_UNITS, depth_unit);
4944  s.add_video_stream({ RS2_STREAM_DEPTH, 0, 0, W, H, fps, BPP, RS2_FORMAT_Z16, intrinsics });
4945 
4946  auto profiles = s.get_stream_profiles();
4947  auto depth = profiles[0];
4948 
4949  syncer sync;
4950  s.open(profiles);
4951  s.start(sync);
4952 
4953  std::vector<uint16_t> pixels(W * H, 0);
4954  for (int i = 0; i < W * H; i++) {
4955  pixels[i] = i % 10;
4956  }
4957 
4958  std::weak_ptr<rs2::software_device> weak_dev(dev);
4959  std::thread t([s, weak_dev, &pixels, depth, expected_frames]() mutable {
4960  auto shared_dev = weak_dev.lock();
4961  if (shared_dev == nullptr)
4962  return;
4963  for (int i = 1; i <= expected_frames; i++)
4964  s.on_video_frame({ pixels.data(), [](void*) {}, 0,0,rs2_time_t(i * 100), RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, i, depth });
4965  });
4966  t.detach();
4967 
4968  for (auto i = 0; i < expected_frames; i++)
4969  {
4970  frame f;
4971  REQUIRE_NOTHROW(f = sync.wait_for_frames(5000));
4972 
4973  auto f_format = f.get_profile().format();
4974  REQUIRE(RS2_FORMAT_Z16 == f_format);
4975 
4976  auto depth_distance = ut.process(f);
4977  auto depth_distance_format = depth_distance.get_profile().format();
4978  REQUIRE(RS2_FORMAT_DISTANCE == depth_distance_format);
4979 
4980  auto frame_data = reinterpret_cast<const uint16_t*>(f.get_data());
4981  auto depth_distance_data = reinterpret_cast<const float*>(depth_distance.get_data());
4982 
4983  for (size_t i = 0; i < W*H; i++)
4984  {
4985  auto frame_data_units_transformed = (frame_data[i] * depth_unit);
4986  REQUIRE(depth_distance_data[i] == frame_data_units_transformed);
4987  }
4988  }
4989 }
4990 
4991 #define ADD_ENUM_TEST_CASE(rs2_enum_type, RS2_ENUM_COUNT) \
4992 TEST_CASE(#rs2_enum_type " enum test", "[live]") { \
4993  int last_item_index = static_cast<int>(RS2_ENUM_COUNT); \
4994  for (int i = 0; i < last_item_index; i++) \
4995  { \
4996  rs2_enum_type enum_value = static_cast<rs2_enum_type>(i); \
4997  std::string str; \
4998  REQUIRE_NOTHROW(str = rs2_enum_type##_to_string(enum_value)); \
4999  REQUIRE(str.empty() == false); \
5000  std::string error = "Unknown enum value passed to " #rs2_enum_type "_to_string"; \
5001  error += " (Value: " + std::to_string(i) + ")"; \
5002  error += "\nDid you add a new value but forgot to add it to:\n" \
5003  " librealsense::get_string(" #rs2_enum_type ") ?"; \
5004  CAPTURE(error); \
5005  REQUIRE(str != "UNKNOWN"); \
5006  } \
5007  /* Test for false positive*/ \
5008  for (int i = last_item_index; i < last_item_index + 1; i++) \
5009  { \
5010  rs2_enum_type enum_value = static_cast<rs2_enum_type>(i); \
5011  std::string str; \
5012  REQUIRE_NOTHROW(str = rs2_enum_type##_to_string(enum_value)); \
5013  REQUIRE(str == "UNKNOWN"); \
5014  } \
5015 }
5016 
5031 
5032 void dev_changed(rs2_device_list* removed_devs, rs2_device_list* added_devs, void* ptr) {}
5033 TEST_CASE("C API Compilation", "[live]") {
5034  rs2_error* e;
5036  REQUIRE(e != nullptr);
5037 }
5038 
5039 
5040 
5041 TEST_CASE("Syncer try wait for frames", "[live][software-device]") {
5042  rs2::context ctx;
5044  {
5045  std::shared_ptr<software_device> dev = std::move(std::make_shared<software_device>());
5046  auto s = dev->add_sensor("software_sensor");
5047 
5048  const int W = 640, H = 480, BPP = 2;
5049  rs2_intrinsics intrinsics{ W, H, 0, 0, 0, 0, RS2_DISTORTION_NONE ,{ 0,0,0,0,0 } };
5050  s.add_video_stream({ RS2_STREAM_DEPTH, 0, 0, W, H, 60, BPP, RS2_FORMAT_Z16, intrinsics });
5051  s.add_video_stream({ RS2_STREAM_INFRARED, 1, 1, W, H,60, BPP, RS2_FORMAT_Y8, intrinsics });
5052  dev->create_matcher(RS2_MATCHER_DI);
5053 
5054  auto profiles = s.get_stream_profiles();
5055  syncer sync;
5056  s.open(profiles);
5057  s.start(sync);
5058 
5059  std::vector<uint8_t> pixels(W * H * BPP, 0);
5060  std::weak_ptr<rs2::software_device> weak_dev(dev);
5061 
5062  auto depth = profiles[0];
5063  auto ir = profiles[1];
5064  std::thread t([&s, weak_dev, pixels, depth, ir]() mutable {
5065 
5066  auto shared_dev = weak_dev.lock();
5067  if (shared_dev == nullptr)
5068  return;
5069  s.on_video_frame({ pixels.data(), [](void*) {}, 0,0,0, RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, 7, depth });
5070  s.on_video_frame({ pixels.data(), [](void*) {}, 0,0,0, RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, 5, ir });
5071 
5072  s.on_video_frame({ pixels.data(), [](void*) {},0,0, 0, RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, 8, depth });
5073  s.on_video_frame({ pixels.data(), [](void*) {},0,0, 0, RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, 6, ir });
5074 
5075  s.on_video_frame({ pixels.data(), [](void*) {},0,0, 0, RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, 8, ir });
5076  });
5077  t.detach();
5078 
5079  std::vector<std::vector<std::pair<rs2_stream, uint64_t>>> expected =
5080  {
5081  { { RS2_STREAM_DEPTH , 7 } },
5082  { { RS2_STREAM_INFRARED , 5 } },
5083  { { RS2_STREAM_INFRARED , 6 } },
5084  { { RS2_STREAM_DEPTH , 8 },{ RS2_STREAM_INFRARED , 8 } }
5085  };
5086 
5087  std::vector<std::vector<std::pair<rs2_stream, uint64_t>>> results;
5088  for (auto i = 0UL; i < expected.size(); i++)
5089  {
5090  frameset fs;
5091  REQUIRE(sync.try_wait_for_frames(&fs, 5000));
5092  std::vector < std::pair<rs2_stream, uint64_t>> curr;
5093 
5094  for (auto f : fs)
5095  {
5096  curr.push_back({ f.get_profile().stream_type(), f.get_frame_number() });
5097  }
5098  results.push_back(curr);
5099  }
5100 
5101  CAPTURE(results.size());
5102  CAPTURE(expected.size());
5103  REQUIRE(results.size() == expected.size());
5104 
5105  for (size_t i = 0; i < expected.size(); i++)
5106  {
5107  auto exp = expected[i];
5108  auto curr = results[i];
5109  CAPTURE(exp.size());
5110  CAPTURE(curr.size());
5111  REQUIRE(exp.size() == curr.size());
5112 
5113  for (size_t j = 0; j < exp.size(); j++)
5114  {
5115  CAPTURE(exp[j].first);
5116  CAPTURE(exp[j].second);
5117  REQUIRE(std::find(curr.begin(), curr.end(), exp[j]) != curr.end());
5118  }
5119  }
5120  }
5121 }
5122 
5123 TEST_CASE("Test Motion Module Extension", "[software-device][using_pipeline][projection]") {
5124  rs2::context ctx;
5126  return;
5128  const std::string filename = folder_name + "D435i_Depth_and_IMU.bag";
5129  REQUIRE(file_exists(filename));
5130  auto dev = ctx.load_device(filename);
5131  dev.set_real_time(false);
5132 
5133  syncer sync;
5134  std::vector<sensor> sensors = dev.query_sensors();
5135  for (auto s : sensors)
5136  {
5137  REQUIRE((std::string(s.get_info(RS2_CAMERA_INFO_NAME)) == "Stereo Module") == (s.is<rs2::depth_sensor>()));
5138  REQUIRE((std::string(s.get_info(RS2_CAMERA_INFO_NAME)) == "RGB Camera") == (s.is<rs2::color_sensor>()));
5139  REQUIRE((std::string(s.get_info(RS2_CAMERA_INFO_NAME)) == "Motion Module") == (s.is<rs2::motion_sensor>()));
5140  }
5141 }
5142 
5143 // Marked as MayFail due to DSO-11753. TODO -revisit once resolved
5144 TEST_CASE("Projection from recording", "[software-device][using_pipeline][projection][!mayfail]") {
5145  rs2::context ctx;
5147  return;
5149  const std::string filename = folder_name + "single_depth_color_640x480.bag";
5150  REQUIRE(file_exists(filename));
5151  auto dev = ctx.load_device(filename);
5152  dev.set_real_time(false);
5153 
5154  syncer sync;
5155  std::vector<sensor> sensors = dev.query_sensors();
5156  REQUIRE(sensors.size() == 2);
5157  for (auto s : sensors)
5158  {
5159  REQUIRE_NOTHROW(s.open(s.get_stream_profiles().front()));
5160  REQUIRE_NOTHROW(s.start(sync));
5161  }
5162 
5163  rs2::frame depth;
5166 
5167  while (!depth_profile || !color_profile)
5168  {
5169  frameset frames = sync.wait_for_frames();
5170  REQUIRE(frames.size() > 0);
5171  if (frames.size() == 1)
5172  {
5173  if (frames.get_profile().stream_type() == RS2_STREAM_DEPTH)
5174  {
5175  depth = frames.get_depth_frame();
5176  depth_profile = depth.get_profile();
5177  }
5178  else
5179  {
5180  color_profile = frames.get_color_frame().get_profile();
5181  }
5182  }
5183  else
5184  {
5185  depth = frames.get_depth_frame();
5186  depth_profile = depth.get_profile();
5187  color_profile = frames.get_color_frame().get_profile();
5188  }
5189  }
5190 
5191  auto depth_intrin = depth_profile.as<rs2::video_stream_profile>().get_intrinsics();
5192  auto color_intrin = color_profile.as<rs2::video_stream_profile>().get_intrinsics();
5193  auto depth_extrin_to_color = depth_profile.as<rs2::video_stream_profile>().get_extrinsics_to(color_profile);
5194  auto color_extrin_to_depth = color_profile.as<rs2::video_stream_profile>().get_extrinsics_to(depth_profile);
5195 
5196  float depth_scale = 0;
5197  for (auto s : sensors)
5198  {
5199  auto depth_sensor = s.is<rs2::depth_sensor>();
5200  if (s.is<rs2::depth_sensor>())
5201  {
5202  REQUIRE_NOTHROW(depth_scale = s.as<rs2::depth_sensor>().get_depth_scale());
5203  }
5204  REQUIRE((std::string(s.get_info(RS2_CAMERA_INFO_NAME)) == "Stereo Module") == (s.is<rs2::depth_sensor>()));
5205  REQUIRE((std::string(s.get_info(RS2_CAMERA_INFO_NAME)) == "RGB Camera") == (s.is<rs2::color_sensor>()));
5206  }
5207 
5208  int count = 0;
5209  for (float i = 0; i < depth_intrin.width; i++)
5210  {
5211  for (float j = 0; j < depth_intrin.height; j++)
5212  {
5213  float depth_pixel[2] = { i, j };
5214  auto udist = depth.as<rs2::depth_frame>().get_distance(static_cast<int>(depth_pixel[0]+0.5f), static_cast<int>(depth_pixel[1]+0.5f));
5215  if (udist == 0) continue;
5216 
5217  float from_pixel[2] = { 0 }, to_pixel[2] = { 0 }, point[3] = { 0 }, other_point[3] = { 0 };
5218  rs2_deproject_pixel_to_point(point, &depth_intrin, depth_pixel, udist);
5219  rs2_transform_point_to_point(other_point, &depth_extrin_to_color, point);
5220  rs2_project_point_to_pixel(from_pixel, &color_intrin, other_point);
5221 
5222  // Search along a projected beam from 0.1m to 10 meter
5223  rs2_project_color_pixel_to_depth_pixel(to_pixel, reinterpret_cast<const uint16_t*>(depth.get_data()), depth_scale, 0.1f, 10,
5224  &depth_intrin, &color_intrin,
5225  &color_extrin_to_depth, &depth_extrin_to_color, from_pixel);
5226 
5227  float dist = sqrt(pow((depth_pixel[1] - to_pixel[1]), 2) + pow((depth_pixel[0] - to_pixel[0]), 2));
5228  if (dist > 1)
5229  count++;
5230  if (dist > 2)
5231  {
5232  WARN("Projecting color->depth, distance > 2 pixels. Origin: ["
5233  << depth_pixel[0] << "," << depth_pixel[1] <<"], Projected << "
5234  << to_pixel[0] << "," << to_pixel[1] << "]");
5235  }
5236  }
5237  }
5238  const double MAX_ERROR_PERCENTAGE = 0.1;
5239  CAPTURE(count);
5240  REQUIRE(count * 100 / (depth_intrin.width * depth_intrin.height) < MAX_ERROR_PERCENTAGE);
5241 }
5242 
5243 TEST_CASE("software-device pose stream", "[software-device]")
5244 {
5246 
5247  auto sensor = dev.add_sensor("Pose"); // Define single sensor
5249  auto stream_profile = sensor.add_pose_stream(stream);
5250 
5251  rs2::syncer sync;
5252 
5254  sensor.start(sync);
5255 
5256  rs2_software_pose_frame::pose_frame_info info = { { 1, 1, 1 },{ 2, 2, 2 },{ 3, 3, 3 },{ 4, 4 ,4 ,4 },{ 5, 5, 5 },{ 6, 6 ,6 }, 0, 0 };
5258  sensor.on_pose_frame(frame);
5259 
5260  rs2::frameset fset = sync.wait_for_frames();
5262  REQUIRE(pose);
5263  REQUIRE(((memcmp(frame.data, pose.get_data(), sizeof(rs2_software_pose_frame::pose_frame_info)) == 0) &&
5264  frame.frame_number == pose.get_frame_number() &&
5265  frame.domain == pose.get_frame_timestamp_domain() &&
5266  frame.timestamp == pose.get_timestamp()));
5267 
5268 }
5269 
5270 TEST_CASE("software-device motion stream", "[software-device]")
5271 {
5273 
5274  auto sensor = dev.add_sensor("Motion"); // Define single sensor
5275  rs2_motion_device_intrinsic intrinsics = { { 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1 },{ 2, 2, 2 },{ 3, 3 ,3 } };
5276  rs2_motion_stream stream = { RS2_STREAM_ACCEL, 0, 0, 200, RS2_FORMAT_MOTION_RAW, intrinsics };
5277  auto stream_profile = sensor.add_motion_stream(stream);
5278 
5279  rs2::syncer sync;
5280 
5282  sensor.start(sync);
5283 
5284  float data[3] = { 1, 1, 1 };
5286  sensor.on_motion_frame(frame);
5287 
5288  rs2::frameset fset = sync.wait_for_frames();
5290  REQUIRE(motion);
5291  REQUIRE(((memcmp(frame.data, motion.get_data(), sizeof(float) * 3) == 0) &&
5292  frame.frame_number == motion.get_frame_number() &&
5293  frame.domain == motion.get_frame_timestamp_domain() &&
5294  frame.timestamp == motion.get_timestamp()));
5295 
5296 }
5297 
5298 TEST_CASE("Record software-device", "[software-device][record][!mayfail]")
5299 {
5300  const int W = 640;
5301  const int H = 480;
5302  const int BPP = 2;
5303 
5305  const std::string filename = folder_name + "recording.bag";
5306 
5307  //Software device, streams and frames definition
5309 
5310  auto sensor = dev.add_sensor("Synthetic");
5311  rs2_intrinsics depth_intrinsics = { W, H, (float)W / 2, H / 2, (float)W, (float)H,
5312  RS2_DISTORTION_BROWN_CONRADY ,{ 0,0,0,0,0 } };
5313  rs2_video_stream video_stream = { RS2_STREAM_DEPTH, 0, 0, W, H, 60, BPP, RS2_FORMAT_Z16, depth_intrinsics };
5314  auto depth_stream_profile = sensor.add_video_stream(video_stream);
5315 
5316  rs2_motion_device_intrinsic motion_intrinsics = { { 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1 },{ 2, 2, 2 },{ 3, 3 ,3 } };
5317  rs2_motion_stream motion_stream = { RS2_STREAM_ACCEL, 0, 1, 200, RS2_FORMAT_MOTION_RAW, motion_intrinsics };
5318  auto motion_stream_profile = sensor.add_motion_stream(motion_stream);
5319 
5320  rs2_pose_stream pose_stream = { RS2_STREAM_POSE, 0, 2, 200, RS2_FORMAT_6DOF };
5321  auto pose_stream_profile = sensor.add_pose_stream(pose_stream);
5322 
5323  rs2::syncer sync;
5324  std::vector<stream_profile> stream_profiles;
5325  stream_profiles.push_back(depth_stream_profile);
5326  stream_profiles.push_back(motion_stream_profile);
5327  stream_profiles.push_back(pose_stream_profile);
5328 
5329  std::vector<uint8_t> pixels(W * H * BPP, 100);
5330  rs2_software_video_frame video_frame = { pixels.data(), [](void*) {},W*BPP, BPP, 10000, RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, 0, depth_stream_profile };
5331  float motion_data[3] = { 1, 1, 1 };
5333  rs2_software_pose_frame::pose_frame_info pose_info = { { 1, 1, 1 },{ 2, 2, 2 },{ 3, 3, 3 },{ 4, 4 ,4 ,4 },{ 5, 5, 5 },{ 6, 6 ,6 }, 0, 0 };
5335 
5336  //Record software device
5337  {
5338  recorder recorder(filename, dev);
5339  sensor.open(stream_profiles);
5340  sensor.start(sync);
5341  sensor.on_video_frame(video_frame);
5342  sensor.on_motion_frame(motion_frame);
5343  sensor.on_pose_frame(pose_frame);
5344  }
5345 
5346  //Playback software device
5347  rs2::context ctx;
5348 
5350  return;
5351  auto player_dev = ctx.load_device(filename);
5352  player_dev.set_real_time(false);
5353  syncer player_sync;
5354  auto s = player_dev.query_sensors()[0];
5355  REQUIRE_NOTHROW(s.open(s.get_stream_profiles()));
5356  REQUIRE_NOTHROW(s.start(player_sync));
5357  rs2::frameset fset;
5358  rs2::frame recorded_depth, recorded_accel, recorded_pose;
5359  while (player_sync.try_wait_for_frames(&fset))
5360  {
5361  if (fset.first_or_default(RS2_STREAM_DEPTH))
5362  recorded_depth = fset.first_or_default(RS2_STREAM_DEPTH);
5363  if (fset.first_or_default(RS2_STREAM_ACCEL))
5364  recorded_accel = fset.first_or_default(RS2_STREAM_ACCEL);
5365  if (fset.first_or_default(RS2_STREAM_POSE))
5366  recorded_pose = fset.first_or_default(RS2_STREAM_POSE);
5367  }
5368 
5369  REQUIRE(recorded_depth);
5370  REQUIRE(recorded_accel);
5371  REQUIRE(recorded_pose);
5372 
5373  //Compare input frames with recorded frames
5374  REQUIRE(((memcmp(video_frame.pixels, recorded_depth.get_data(), W * H * BPP) == 0) &&
5375  video_frame.frame_number == recorded_depth.get_frame_number() &&
5376  video_frame.domain == recorded_depth.get_frame_timestamp_domain() &&
5377  video_frame.timestamp == recorded_depth.get_timestamp()));
5378 
5379  REQUIRE(((memcmp(motion_frame.data, recorded_accel.get_data(), sizeof(float) * 3) == 0) &&
5380  motion_frame.frame_number == recorded_accel.get_frame_number() &&
5381  motion_frame.domain == recorded_accel.get_frame_timestamp_domain() &&
5382  motion_frame.timestamp == recorded_accel.get_timestamp()));
5383 
5384  REQUIRE(((memcmp(pose_frame.data, recorded_pose.get_data(), sizeof(rs2_software_pose_frame::pose_frame_info)) == 0) &&
5385  pose_frame.frame_number == recorded_pose.get_frame_number() &&
5386  pose_frame.domain == recorded_pose.get_frame_timestamp_domain() &&
5387  pose_frame.timestamp == recorded_pose.get_timestamp()));
5388 }
5389 
5391 {
5394  REQUIRE(strcmp(first.get_info(RS2_CAMERA_INFO_NAME), second.get_info(RS2_CAMERA_INFO_NAME)) == 0);
5395 
5396  auto first_options = first.get_supported_options();
5397  auto second_options = second.get_supported_options();
5398 
5399  REQUIRE(first_options.size() == second_options.size());
5400 
5401  REQUIRE(first_options == second_options);
5402 
5403  for (auto i = 0UL;i < first_options.size();i++)
5404  {
5405  auto opt = static_cast<rs2_option>(first_options[i]);
5406  CAPTURE(opt);
5407  CAPTURE(first.get_option(opt));
5408  CAPTURE(second.get_option(opt));
5409  REQUIRE(first.get_option(opt) == second.get_option(opt));
5410  }
5411 }
5412 
5413 void compare(std::vector<filter> first, std::vector<std::shared_ptr<filter>> second)
5414 {
5415  REQUIRE(first.size() == second.size());
5416 
5417  for (size_t i = 0;i < first.size();i++)
5418  {
5419  compare(first[i], (*second[i]));
5420  }
5421 }
5422 
5423 TEST_CASE("Sensor get recommended filters", "[live][!mayfail]") {
5424  //Require at least one device to be plugged in
5425  rs2::context ctx;
5426 
5427  enum sensors
5428  {
5429  depth,
5430  depth_stereo,
5431  color
5432  };
5433 
5434  std::map<sensors, std::vector<std::shared_ptr<filter>>> sensors_to_filters;
5435 
5436  auto dec_color = std::make_shared<decimation_filter>();
5437  dec_color->set_option(RS2_OPTION_STREAM_FILTER, RS2_STREAM_COLOR);
5438  dec_color->set_option(RS2_OPTION_STREAM_FORMAT_FILTER, RS2_FORMAT_ANY);
5439 
5440  sensors_to_filters[color] = {
5441  dec_color
5442  };
5443 
5444  auto huff_decoder = std::make_shared<depth_huffman_decoder>();
5445  auto dec_depth = std::make_shared<decimation_filter>();
5446  dec_depth->set_option(RS2_OPTION_STREAM_FILTER, RS2_STREAM_DEPTH);
5447  dec_depth->set_option(RS2_OPTION_STREAM_FORMAT_FILTER, RS2_FORMAT_Z16);
5448 
5449  auto threshold = std::make_shared<threshold_filter>(0.1f, 4.f);
5450  auto spatial = std::make_shared<spatial_filter>();
5451  auto temporal = std::make_shared<temporal_filter>();
5452  auto hole_filling = std::make_shared<hole_filling_filter>();
5453 
5454  sensors_to_filters[depth] = {
5455  dec_depth,
5456  threshold,
5457  spatial,
5458  temporal,
5459  hole_filling
5460  };
5461 
5462  auto depth2disparity = std::make_shared<disparity_transform>(true);
5463  auto disparity2depth = std::make_shared<disparity_transform>(false);
5464 
5465  sensors_to_filters[depth_stereo] = {
5466  huff_decoder,
5467  dec_depth,
5468  threshold,
5469  depth2disparity,
5470  spatial,
5471  temporal,
5472  hole_filling,
5473  disparity2depth
5474  };
5475 
5477  {
5478  std::vector<sensor> sensors;
5479  REQUIRE_NOTHROW(sensors = ctx.query_all_sensors());
5480  REQUIRE(sensors.size() > 0);
5481 
5482  for (auto sensor : sensors)
5483  {
5486  if (sensor.is<depth_stereo_sensor>())
5487  {
5488  compare(processing_blocks, sensors_to_filters[depth_stereo]);
5489  }
5490  else if (sensor.is<depth_sensor>())
5491  {
5492  compare(processing_blocks, sensors_to_filters[depth]);
5493  }
5494  else if (std::find_if(stream_profiles.begin(), stream_profiles.end(), [](stream_profile profile) { return profile.stream_type() == RS2_STREAM_COLOR;}) != stream_profiles.end())
5495  {
5496  compare(processing_blocks, sensors_to_filters[color]);
5497  }
5498  }
5499  }
5500 }
5501 
5502 TEST_CASE("L500 zero order sanity", "[live]") {
5503  //Require at least one device to be plugged in
5504  rs2::context ctx;
5505  const int RETRIES = 30;
5506 
5508  {
5509  std::vector<sensor> sensors;
5510  REQUIRE_NOTHROW(sensors = ctx.query_all_sensors());
5511  REQUIRE(sensors.size() > 0);
5512 
5513  for (auto sensor : sensors)
5514  {
5516  auto zo = std::find_if(processing_blocks.begin(), processing_blocks.end(), [](filter f)
5517  {
5518  return f.is<zero_order_invalidation>();
5519  });
5520 
5521  if(zo != processing_blocks.end())
5522  {
5523  rs2::config c;
5527 
5528  rs2::pipeline p;
5529  p.start(c);
5530  rs2::frame frame;
5531 
5532  std::map<rs2_stream, bool> stream_arrived;
5533  stream_arrived[RS2_STREAM_DEPTH] = false;
5534  stream_arrived[RS2_STREAM_INFRARED] = false;
5535  stream_arrived[RS2_STREAM_CONFIDENCE] = false;
5536 
5537  for (auto i = 0;i < RETRIES;i++)
5538  {
5539  REQUIRE_NOTHROW(frame = p.wait_for_frames(15000));
5540  auto res = zo->process(frame);
5541  if (res.is<rs2::frameset>())
5542  {
5543  auto set = res.as<rs2::frameset>();
5544  REQUIRE(set.size() == stream_arrived.size()); // depth, ir, confidance
5545  for (auto&& f : set)
5546  {
5547  stream_arrived[f.get_profile().stream_type()] = true;
5548  }
5549  auto stream_missing = std::find_if(stream_arrived.begin(), stream_arrived.end(), [](std::pair< rs2_stream, bool> item)
5550  {
5551  return !item.second;
5552  });
5553 
5554  REQUIRE(stream_missing == stream_arrived.end());
5555  }
5556  }
5557  }
5558  }
5559  }
5560 }
5561 
5562 TEST_CASE("Positional_Sensors_API", "[live]")
5563 {
5564  rs2::context ctx;
5565 
5566  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.18.1"))
5567  {
5569  rs2::device dev;
5570  rs2::pipeline pipe(ctx);
5571  rs2::config cfg;
5573  REQUIRE_NOTHROW(profile = cfg.resolve(pipe));
5574  REQUIRE(profile);
5575  REQUIRE_NOTHROW(dev = profile.get_device());
5576  REQUIRE(dev);
5578  dev_type PID = get_PID(dev);
5579  CAPTURE(PID.first);
5580 
5581  // T265 Only
5582  if (!librealsense::val_in_range(PID.first, { std::string("0B37")}))
5583  {
5584  WARN("Skipping test - Applicable for Positional Tracking sensors only. Current device type: " << PID.first << (PID.second ? " USB3" : " USB2"));
5585  }
5586  else
5587  {
5588  CAPTURE(dev);
5589  REQUIRE(dev.is<rs2::tm2>());
5591  auto pose_snr = dev.first<rs2::pose_sensor>();
5592  CAPTURE(pose_snr);
5593  REQUIRE(pose_snr);
5594 
5595  WHEN("Sequence - Streaming.")
5596  {
5597  THEN("Export/Import must Fail")
5598  {
5600  REQUIRE_NOTHROW(pf = pipe.start(cfg));
5601  rs2::device d = pf.get_device();
5602  REQUIRE(d);
5603  auto pose_snr = d.first<rs2::pose_sensor>();
5604  CAPTURE(pose_snr);
5605  REQUIRE(pose_snr);
5606 
5607  WARN("T2xx Collecting frames started");
5609  // The frames are required to generate some initial localization map
5610  for (auto i = 0; i < 200; i++)
5611  {
5612  REQUIRE_NOTHROW(frames = pipe.wait_for_frames());
5613  REQUIRE(frames.size() > 0);
5614  }
5615 
5616  std::vector<uint8_t> results{}, vnv{};
5617  WARN("T2xx export map");
5618  REQUIRE_THROWS(results = pose_snr.export_localization_map());
5619  CAPTURE(results.size());
5620  REQUIRE(0 == results.size());
5621  WARN("T2xx import map");
5622  REQUIRE_THROWS(pose_snr.import_localization_map({ 0, 1, 2, 3, 4 }));
5623  REQUIRE_NOTHROW(pipe.stop());
5624  WARN("T2xx import/export during streaming finished");
5625  }
5626  }
5627 
5628  WHEN("Sequence - idle.")
5629  {
5630  THEN("Export/Import Success")
5631  {
5632  std::vector<uint8_t> results, vnv;
5633  REQUIRE_NOTHROW(results = pose_snr.export_localization_map());
5634  CAPTURE(results.size());
5635  REQUIRE(results.size());
5636 
5637  bool ret = false;
5638  REQUIRE_NOTHROW(ret = pose_snr.import_localization_map(results));
5639  CAPTURE(ret);
5640  REQUIRE(ret);
5641  REQUIRE_NOTHROW(vnv = pose_snr.export_localization_map());
5642  CAPTURE(vnv.size());
5643  REQUIRE(vnv.size());
5644  REQUIRE(vnv == results);
5645  }
5646  }
5647 
5648  WHEN("Sequence - Streaming.")
5649  {
5650  THEN("Set/Get Static node functionality")
5651  {
5653  REQUIRE_NOTHROW(pf = pipe.start(cfg));
5654  rs2::device d = pf.get_device();
5655  REQUIRE(d);
5656  auto pose_snr = d.first<rs2::pose_sensor>();
5657  CAPTURE(pose_snr);
5658  REQUIRE(pose_snr);
5659 
5661  // The frames are required to get pose with sufficient confidence for static node marker
5662  for (auto i = 0; i < 100; i++)
5663  {
5664  REQUIRE_NOTHROW(frames = pipe.wait_for_frames());
5665  REQUIRE(frames.size() > 0);
5666  }
5667 
5668  rs2_vector init_pose{}, test_pose{ 1,2,3 }, vnv_pose{};
5669  rs2_quaternion init_or{}, test_or{ 4,5,6,7 }, vnv_or{};
5670  auto res = 0;
5671  REQUIRE_NOTHROW(res = pose_snr.set_static_node("wp1", test_pose, test_or));
5672  CAPTURE(res);
5673  REQUIRE(res != 0);
5674  std::this_thread::sleep_for(std::chrono::milliseconds(500));
5675  REQUIRE_NOTHROW(res = pose_snr.get_static_node("wp1", vnv_pose, vnv_or));
5676  CAPTURE(vnv_pose);
5677  CAPTURE(vnv_or);
5678  CAPTURE(res);
5679  REQUIRE(test_pose.x == approx(vnv_pose.x));
5680  REQUIRE(test_pose.y == approx(vnv_pose.y));
5681  REQUIRE(test_pose.z == approx(vnv_pose.z));
5682  REQUIRE(test_or.x == approx(vnv_or.x));
5683  REQUIRE(test_or.y == approx(vnv_or.y));
5684  REQUIRE(test_or.z == approx(vnv_or.z));
5685  REQUIRE(test_or.w == approx(vnv_or.w));
5686 
5687  REQUIRE_NOTHROW(res = pose_snr.remove_static_node("wp1"));
5688  REQUIRE_NOTHROW(!(res = pose_snr.remove_static_node("wp1")));
5689 
5690  REQUIRE_NOTHROW(pipe.stop());
5691  }
5692  }
5693  }
5694  }
5695 }
5696 
5697 TEST_CASE("Wheel_Odometry_API", "[live]")
5698 {
5699  rs2::context ctx;
5700 
5701  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.18.1"))
5702  {
5704  rs2::device dev;
5705  rs2::pipeline pipe(ctx);
5706  rs2::config cfg;
5708  REQUIRE_NOTHROW(profile = cfg.resolve(pipe));
5709  REQUIRE(profile);
5710  REQUIRE_NOTHROW(dev = profile.get_device());
5711  REQUIRE(dev);
5712  dev_type PID = get_PID(dev);
5713  CAPTURE(PID.first);
5714 
5715  // T265 Only
5716  if (!librealsense::val_in_range(PID.first, { std::string("0B37")}))
5717  {
5718  WARN("Skipping test - Applicable for Positional Tracking sensors only. Current device type: " << PID.first << (PID.second ? " USB3" : " USB2"));
5719  }
5720  else
5721  {
5722  CAPTURE(dev);
5723  REQUIRE(dev.is<rs2::tm2>());
5724  auto wheel_odom_snr = dev.first<rs2::wheel_odometer>();
5725  CAPTURE(wheel_odom_snr);
5726  REQUIRE(wheel_odom_snr);
5727 
5728  WHEN("Sequence - idle.")
5729  {
5730  THEN("Load wheel odometry calibration")
5731  {
5732  std::ifstream calibrationFile("calibration_odometry.json");
5733  REQUIRE(calibrationFile);
5734  {
5735  const std::string json_str((std::istreambuf_iterator<char>(calibrationFile)),
5736  std::istreambuf_iterator<char>());
5737  const std::vector<uint8_t> wo_calib(json_str.begin(), json_str.end());
5738  bool b;
5739  REQUIRE_NOTHROW(b = wheel_odom_snr.load_wheel_odometery_config(wo_calib));
5740  REQUIRE(b);
5741  }
5742  }
5743  }
5744 
5745  WHEN("Sequence - Streaming.")
5746  {
5747  THEN("Send wheel odometry data")
5748  {
5750  REQUIRE_NOTHROW(pf = pipe.start(cfg));
5751  rs2::device d = pf.get_device();
5752  REQUIRE(d);
5753  auto wo_snr = d.first<rs2::wheel_odometer>();
5754  CAPTURE(wo_snr);
5755  REQUIRE(wo_snr);
5756 
5757  bool b;
5758  float norm_max = 0;
5759  WARN("T2xx Collecting frames started - Keep device static");
5761  for (int i = 0; i < 100; i++)
5762  {
5763  REQUIRE_NOTHROW(frames = pipe.wait_for_frames());
5764  REQUIRE(frames.size() > 0);
5765  auto f = frames.first_or_default(RS2_STREAM_POSE);
5766  auto pose_data = f.as<rs2::pose_frame>().get_pose_data();
5767  float norm = sqrt(pose_data.translation.x*pose_data.translation.x + pose_data.translation.y*pose_data.translation.y
5768  + pose_data.translation.z*pose_data.translation.z);
5769  if (norm > norm_max) norm_max = norm;
5770 
5771  REQUIRE_NOTHROW(b = wo_snr.send_wheel_odometry(0, 0, { 1,0,0 }));
5772  REQUIRE(b);
5773  }
5774  Approx approx_norm(0);
5775  approx_norm.epsilon(0.005); // 0.5cm threshold
5776  REQUIRE_FALSE(norm_max == approx_norm);
5777  REQUIRE_NOTHROW(pipe.stop());
5778  }
5779  }
5780  }
5781  }
5782 }
5783 
5784 
5785 TEST_CASE("get_sensor_from_frame", "[live][using_pipeline][!mayfail]")
5786 {
5787  // Require at least one device to be plugged in
5788  rs2::context ctx;
5789  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.22.0"))
5790  {
5791  std::vector<sensor> list;
5792  REQUIRE_NOTHROW(list = ctx.query_all_sensors());
5793  REQUIRE(list.size() > 0);
5794 
5795  pipeline pipe(ctx);
5796  device dev;
5797  // Configure all supported streams to run at 30 frames per second
5798 
5799  rs2::config cfg;
5801  REQUIRE_NOTHROW(profile = cfg.resolve(pipe));
5802  REQUIRE(profile);
5803  REQUIRE_NOTHROW(dev = profile.get_device());
5804  REQUIRE(dev);
5806 
5807  // Test sequence
5808  REQUIRE_NOTHROW(pipe.start(cfg));
5809  std::string dev_serial_no = dev.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER);
5810  for (auto i = 0; i < 5; i++)
5811  {
5812  rs2::frameset data = pipe.wait_for_frames(); // Wait for next set of frames from the camera
5813  for (auto&& frame : data)
5814  {
5815  std::string frame_serial_no = sensor_from_frame(frame)->get_info(RS2_CAMERA_INFO_SERIAL_NUMBER);
5816  REQUIRE(dev_serial_no == frame_serial_no);
5817  // TODO: Add additinal sensor attribiutions checks.
5818  }
5819  }
5820  REQUIRE_NOTHROW(pipe.stop());
5821  }
5822 }
5823 
5824 TEST_CASE("l500_presets_set_preset", "[live]")
5825 {
5827  // Require at least one device to be plugged in
5828  rs2::context ctx;
5829  if (make_context(SECTION_FROM_TEST_NAME, &ctx, "2.31.0"))
5830  {
5831  std::vector<sensor> list;
5832  REQUIRE_NOTHROW(list = ctx.query_all_sensors());
5833  REQUIRE(list.size() > 0);
5834 
5835  sensor ds;
5836 
5837  for (auto&& s : list)
5838  {
5839  if (s.is < rs2::depth_sensor>())
5840  {
5841  ds = s.as < rs2::depth_sensor>();
5842  break;
5843  }
5844  }
5845 
5846  REQUIRE(ds);
5847 
5848  for (auto&& option : _hw_controls)
5849  {
5850  REQUIRE(ds.supports(option));
5851  }
5852  REQUIRE(ds.supports(RS2_OPTION_SENSOR_MODE));
5853 
5854  auto presets = ds.get_option_range(RS2_OPTION_VISUAL_PRESET);
5855  REQUIRE(presets.min == RS2_L500_VISUAL_PRESET_CUSTOM);
5856  REQUIRE(presets.max == RS2_L500_VISUAL_PRESET_COUNT - 1);
5857  REQUIRE(presets.step == 1);
5858  REQUIRE(presets.def == RS2_L500_VISUAL_PRESET_DEFAULT);
5859 
5860  std::map< rs2_option, option_range> options_range;
5861 
5862  for (auto&& option : _hw_controls)
5863  {
5865  {
5866  options_range[option] = ds.get_option_range(option);
5867  }
5868  }
5869 
5870  std::map<int, int> expected_ambient_per_preset =
5871  {
5874  {RS2_L500_VISUAL_PRESET_MAX_RANGE, RS2_DIGITAL_GAIN_HIGH},
5875  {RS2_L500_VISUAL_PRESET_SHORT_RANGE, RS2_DIGITAL_GAIN_LOW}
5876  };
5877 
5878  std::map<int, int> expected_laser_power_per_preset =
5879  {
5882  };
5883 
5884  std::map< float, float> apd_per_ambient;
5885  for (auto i : expected_ambient_per_preset)
5886  {
5887  std::vector<int> resolutions{ RS2_SENSOR_MODE_XGA, RS2_SENSOR_MODE_VGA };
5888  for (auto res : resolutions)
5889  {
5890  ds.set_option(RS2_OPTION_SENSOR_MODE, (float)res);
5891  ds.set_option(RS2_OPTION_VISUAL_PRESET, (float)i.first);
5892  CAPTURE(ds.get_option(RS2_OPTION_DIGITAL_GAIN));
5893  REQUIRE(ds.get_option(RS2_OPTION_DIGITAL_GAIN) == i.second);
5894  apd_per_ambient[ds.get_option(RS2_OPTION_DIGITAL_GAIN)] = ds.get_option(RS2_OPTION_AVALANCHE_PHOTO_DIODE);
5895  auto expected_laser_power = expected_laser_power_per_preset.find(i.first);
5896  if (expected_laser_power != expected_laser_power_per_preset.end())
5897  {
5898  CAPTURE(ds.get_option(RS2_OPTION_LASER_POWER));
5899  REQUIRE(ds.get_option(RS2_OPTION_LASER_POWER) == expected_laser_power->second);
5900  }
5901 
5902  }
5903  }
5904 
5905  CAPTURE(apd_per_ambient[RS2_SENSOR_MODE_XGA]);
5906  CAPTURE(apd_per_ambient[RS2_SENSOR_MODE_VGA]);
5907  REQUIRE(apd_per_ambient[RS2_SENSOR_MODE_XGA] != apd_per_ambient[RS2_SENSOR_MODE_VGA]);
5908  for (auto&& opt : options_range)
5909  {
5910  ds.set_option(opt.first, opt.second.min);
5911  CAPTURE(ds.get_option(RS2_OPTION_VISUAL_PRESET));
5914  }
5915 
5916  }
5917 }
static const textual_icon lock
Definition: model-views.h:218
rs2_camera_info
Read-only strings that can be queried from the device. Not all information attributes are available o...
Definition: rs_sensor.h:22
frameset wait_for_frames(unsigned int timeout_ms=RS2_DEFAULT_TIMEOUT) const
static void rs2_transform_point_to_point(float to_point[3], const struct rs2_extrinsics *extrin, const float from_point[3])
Definition: rsutil.h:168
GLuint GLuint end
GLboolean GLboolean GLboolean b
Approx approx(F f)
Definition: approx.h:106
bool is_connected(const device &dev) const
Definition: rs_context.hpp:256
bool try_wait_for_frames(frameset *fs, unsigned int timeout_ms=5000) const
rs2_exception_type
Exception types are the different categories of errors that RealSense API might return.
Definition: rs_types.h:30
float get_depth_scale() const
Definition: rs_sensor.hpp:471
GLenum GLuint GLenum severity
rs2_stream stream
const char * get_string(rs2_rs400_visual_preset value)
GLuint const GLchar * name
std::vector< sensor > query_all_sensors() const
Generate a flat list of all available sensors from all RealSense devices.
Definition: rs_context.hpp:142
std::vector< sensor > query_sensors() const
Definition: rs_device.hpp:25
static const std::map< dev_type, device_profiles > pipeline_default_configurations
const std::shared_ptr< rs2_device > & get() const
Definition: rs_device.hpp:116
rs2::stream_profile get_profile_by_resolution_type(rs2::sensor &s, res_type res)
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
Definition: rs_option.h:22
bool operator==(const plane &lhs, const plane &rhs)
Definition: rendering.h:134
GLdouble s
device front() const
Definition: rs_device.hpp:719
std::shared_ptr< std::function< void(rs2::frame fref)> > check_stream_sanity(const context &ctx, const sensor &sub, int num_of_frames, bool infinite=false)
std::vector< stream_profile > get_active_streams() const
Definition: rs_sensor.hpp:246
TEST_CASE("Sync sanity","[live][mayfail]")
GLfloat GLfloat p
Definition: glext.h:12687
const GLfloat * m
Definition: glext.h:6814
std::vector< uint32_t > split(const std::string &s, char delim)
device get_sensor_parent(const sensor &s) const
Definition: rs_context.hpp:154
rs2_distortion
Distortion model: defines how pixel coordinates should be mapped to sensor coordinates.
Definition: rs_types.h:45
float translation[3]
Definition: rs_sensor.h:99
GLenum GLenum GLenum GLenum GLenum scale
Definition: glext.h:10806
#define WHEN(desc)
Definition: catch.hpp:17487
rs2_metadata_type get_frame_metadata(rs2_frame_metadata_value frame_metadata) const
Definition: rs_frame.hpp:497
rs2_sr300_visual_preset
For SR300 devices: provides optimized settings (presets) for specific types of usage.
Definition: rs_option.h:119
bool val_in_range(const T &val, const std::initializer_list< T > &list)
Definition: src/types.h:174
std::vector< profile > configure_all_supported_streams(rs2::sensor &sensor, int width=640, int height=480, int fps=60)
playback load_device(const std::string &file)
Definition: rs_context.hpp:184
std::vector< filter > get_recommended_filters() const
Definition: rs_sensor.hpp:273
GLfloat value
#define REQUIRE_THROWS_AS(expr, exceptionType)
Definition: catch.hpp:17402
stream_profile get_profile() const
Definition: rs_frame.hpp:557
device_list query_devices() const
Definition: rs_context.hpp:112
void enqueue(frame f) const
rs2_log_severity get_severity() const
Definition: rs_sensor.hpp:64
static const std::map< dev_type, device_profiles > pipeline_autocomplete_configurations
All the parameters required to define a video stream.
Definition: rs_internal.h:41
Approx & epsilon(T const &newEpsilon)
Definition: catch.hpp:3147
All the parameters required to define a pose frame.
Definition: rs_internal.h:100
frame wait_for_frame(unsigned int timeout_ms=5000) const
std::string get_folder_path(special_folder f)
Definition: os.cpp:247
uint32_t size() const
Definition: rs_device.hpp:711
rs2_intrinsics intrin
bool try_wait_for_frames(frameset *f, unsigned int timeout_ms=RS2_DEFAULT_TIMEOUT) const
GLint GLint GLsizei GLsizei GLsizei depth
void dev_changed(rs2_device_list *removed_devs, rs2_device_list *added_devs, void *ptr)
const void * get_data() const
Definition: rs_frame.hpp:545
bool supports_frame_metadata(rs2_frame_metadata_value frame_metadata) const
Definition: rs_frame.hpp:509
unsigned short uint16_t
Definition: stdint.h:79
Definition: cah-model.h:10
dictionary frame_data
Definition: t265_stereo.py:80
GLdouble GLdouble GLdouble w
GLsizei const GLchar *const * string
d
Definition: rmse.py:171
std::string get_description() const
Definition: rs_sensor.hpp:46
void enable_device(const std::string &serial)
software_sensor add_sensor(std::string name)
GLuint entry
Definition: glext.h:10991
GLuint GLuint stream
Definition: glext.h:1790
rs2_timestamp_domain domain
Definition: rs_internal.h:94
GLdouble n
Definition: glext.h:1966
bool get_mode(rs2::device &dev, stream_profile *profile, int mode_index=0)
e
Definition: rmse.py:177
GLsizei GLsizei GLfloat distance
Definition: glext.h:10563
rs2_stream sensor_type
point
Definition: rmse.py:166
std::vector< rs2::stream_profile > get_supported_streams(rs2::sensor sensor, std::vector< rs2::stream_profile > profiles)
rs2_timestamp_domain domain
Definition: rs_internal.h:116
void require_zero_vector(const float(&vector)[3])
void sort(sort_type m_sort_type, const std::string &in, const std::string &out)
GLuint num
Definition: glext.h:5648
static const std::map< dev_type, device_profiles > pipeline_custom_configurations
::realsense_legacy_msgs::pose_< std::allocator< void > > pose
Definition: pose.h:88
float rotation[9]
Definition: rs_sensor.h:98
GLenum GLenum GLsizei void * image
frameset wait_for_frames(unsigned int timeout_ms=5000) const
GLuint index
#define STRINGIFY(arg)
Definition: rs.h:31
depth_frame get_depth_frame() const
Definition: rs_frame.hpp:1006
frame first_or_default(rs2_stream s, rs2_format f=RS2_FORMAT_ANY) const
Definition: rs_frame.hpp:978
GLdouble t
GLboolean GLboolean GLboolean GLboolean a
GLuint GLfloat * val
const int H
video_frame get_color_frame() const
Definition: rs_frame.hpp:1015
def info(name, value, persistent=False)
Definition: test.py:301
Quaternion used to represent rotation.
Definition: rs_types.h:135
std::vector< rs2_option > get_supported_options()
Definition: rs_options.hpp:119
not_this_one begin(...)
GLdouble f
bool poll_for_frames(frameset *f) const
GLenum mode
const int W
GLfloat bias
Definition: glext.h:7937
GLuint GLenum option
Definition: glext.h:5923
Definition: getopt.h:41
dictionary streams
Definition: t265_stereo.py:140
GLsizeiptr size
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 trigger_error(const rs2::device &dev, int num)
std::shared_ptr< rs2_config > get() const
std::ostream & cout()
const GLubyte * c
Definition: glext.h:12690
bool is() const
Definition: rs_device.hpp:122
static const std::map< dev_type, device_profiles > pipeline_configurations_for_extrinsic
#define SECTION(...)
Definition: catch.hpp:17438
#define WARN(msg)
Definition: catch.hpp:17431
#define CAPTURE(...)
Definition: catch.hpp:17432
REQUIRE(n_callbacks==1)
All the parameters required to define a pose stream.
Definition: rs_internal.h:66
void disable_all_streams()
std::pair< std::shared_ptr< rs2::device >, std::weak_ptr< rs2::device > > make_device(device_list &list)
unsigned int uint32_t
Definition: stdint.h:80
double get_timestamp() const
Definition: rs_frame.hpp:474
#define GIVEN(desc)
Definition: catch.hpp:17485
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
GLenum GLint GLenum GLsizei GLsizei GLsizei GLint GLsizei const void * bits
Definition: glext.h:6898
static std::condition_variable cv
GLint GLint GLsizei GLint GLenum format
#define REQUIRE_THROWS(...)
Definition: catch.hpp:17401
void require_transposed(const float(&a)[9], const float(&b)[9])
rs2_playback_status
#define SECTION_FROM_TEST_NAME
stream_profile get_stream(rs2_stream stream_type, int stream_index=-1) const
Definition: rs_pipeline.hpp:60
def find(dir, mask)
Definition: file.py:25
def callback(frame)
Definition: t265_stereo.py:91
void disable_stream(rs2_stream stream, int index=-1)
float vector_length(const float(&v)[3])
GLuint start
GLint j
All the parameters required to define a motion stream.
Definition: rs_internal.h:55
rs2_format
A stream&#39;s format identifies how binary data is encoded within a frame.
Definition: rs_sensor.h:59
GLint first
#define CHECK_THROWS(...)
Definition: catch.hpp:17415
std::pair< std::string, bool > dev_type
void enable_all_streams()
GLint GLint GLsizei GLint GLenum GLenum const void * pixels
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
void enable_stream(rs2_stream stream_type, int stream_index, int width, int height, rs2_format format=RS2_FORMAT_ANY, int framerate=0)
std::vector< std::pair< stream_profile, frame_callback > > configurations
Definition: recorder.h:485
bool can_resolve(std::shared_ptr< rs2_pipeline > p) const
std::vector< std::shared_ptr< stream_profile_interface >> stream_profiles
Definition: streaming.h:165
dictionary intrinsics
Definition: t265_stereo.py:142
GLenum func
rs2_stream
Streams are different types of data provided by RealSense devices.
Definition: rs_sensor.h:42
std::vector< profile > streams
device get_device() const
Definition: rs_pipeline.hpp:83
bool poll_for_frames(frameset *fs) const
bool make_context(const char *id, rs2::context *ctx, std::string min_api_version="0.0.0")
void require_identity_matrix(const float(&matrix)[9])
#define ADD_ENUM_TEST_CASE(rs2_enum_type, RS2_ENUM_COUNT)
#define THEN(desc)
Definition: catch.hpp:17489
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented...
Definition: rs_sensor.h:96
void log_to_console(rs2_log_severity min_severity)
Definition: rs.hpp:19
rs2_format format() const
Definition: rs_frame.hpp:44
3D vector in Euclidean coordinate space
Definition: rs_types.h:129
bool is_fw_version_newer(rs2::sensor &subdevice, const uint32_t other_fw[4])
rs2_option slave_option
static void rs2_project_point_to_pixel(float pixel[2], const struct rs2_intrinsics *intrin, const float point[3])
Definition: rsutil.h:19
GLdouble GLdouble GLdouble q
pipeline_profile resolve(std::shared_ptr< rs2_pipeline > p) const
std::vector< stream_profile > get_streams() const
Definition: rs_pipeline.hpp:29
dev_type get_PID(rs2::device &dev)
rs2_extension
Specifies advanced interfaces (capabilities) objects may implement.
Definition: rs_types.h:166
rs2_notification_category
Category of the librealsense notification.
Definition: rs_types.h:17
GLbitfield GLuint64 timeout
static auto it
const char * get_info(rs2_camera_info info) const
long long rs2_metadata_type
Definition: rs_types.h:301
rs2_timestamp_domain get_frame_timestamp_domain() const
Definition: rs_frame.hpp:485
signed __int64 int64_t
Definition: stdint.h:89
void set_real_time(bool real_time) const
void require_pipeline_profile_same(const rs2::pipeline_profile &profile1, const rs2::pipeline_profile &profile2)
GLint GLsizei count
All the parameters required to define a motion frame.
Definition: rs_internal.h:89
rs2_rs400_visual_preset
For RS400 devices: provides optimized settings (presets) for specific types of usage.
Definition: rs_option.h:137
rs2_timestamp_domain domain
Definition: rs_internal.h:83
bool is() const
Definition: rs_sensor.hpp:326
void metadata_verification(const std::vector< internal_frame_additional_data > &data)
typename::boost::move_detail::remove_reference< T >::type && move(T &&t) BOOST_NOEXCEPT
Video stream intrinsics.
Definition: rs_types.h:58
void open(const stream_profile &profile) const
Definition: rs_sensor.hpp:111
::realsense_legacy_msgs::motion_intrinsics_< std::allocator< void > > motion_intrinsics
void set_devices_changed_callback(T callback)
Definition: rs_context.hpp:169
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)
T first() const
Definition: rs_device.hpp:52
void rs2_set_devices_changed_callback(const rs2_context *context, rs2_devices_changed_callback_ptr callback, void *user, rs2_error **error)
Definition: rs.cpp:787
int stoi(const std::string &value)
#define REQUIRE_FALSE(...)
Definition: catch.hpp:17399
GLsizei range
Motion device intrinsics: scale, bias, and variances.
Definition: rs_types.h:103
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
void close() const
Definition: rs_sensor.hpp:173
std::array< float, 3 > color
Definition: model-views.h:449
const char * get_info(rs2_camera_info info) const
Definition: rs_sensor.hpp:138
void reset_device(std::shared_ptr< rs2::device > &strong, std::weak_ptr< rs2::device > &weak, device_list &list, const rs2::device &new_dev)
All the parameters required to define a video frame.
Definition: rs_internal.h:76
bool file_exists(const std::string &filename)
rs2_format format
void check_controls_sanity(const context &ctx, const sensor &dev)
pipeline_profile get_active_profile() const
pipeline_profile start()
static void rs2_project_color_pixel_to_depth_pixel(float to_pixel[2], const uint16_t *data, float depth_scale, float depth_min, float depth_max, const struct rs2_intrinsics *depth_intrin, const struct rs2_intrinsics *color_intrin, const struct rs2_extrinsics *color_to_depth, const struct rs2_extrinsics *depth_to_color, const float from_pixel[2])
Definition: rsutil.h:212
void validate(std::vector< std::vector< stream_profile >> frames, std::vector< std::vector< double >> timestamps, device_profiles requests, int actual_fps)
double rs2_time_t
Definition: rs_types.h:300
GLboolean * data
unsigned long long get_frame_number() const
Definition: rs_frame.hpp:521
device wait_for_device() const
Definition: rs_context.hpp:240
bool is_usb3(const rs2::device &dev)
rs2_log_severity
Severity of the librealsense logger.
Definition: rs_types.h:153
std::vector< stream_profile > get_stream_profiles() const
Definition: rs_sensor.hpp:219
size_t size() const
Definition: rs_frame.hpp:1097
rs2_stream stream_type() const
Definition: rs_frame.hpp:39
void set_option(rs2_option option, float value) const
Definition: rs_options.hpp:99
const std::map< dev_type, dev_group > dev_map
float get_option(rs2_option option) const
Definition: rs_options.hpp:72
rs2_option master_option
double get_time()
Definition: rs_internal.hpp:62
int fps() const
Definition: rs_frame.hpp:49
std::shared_ptr< sensor > sensor_from_frame(frame f)
Definition: rs_sensor.hpp:357
const std::map< dev_group, std::vector< option_bundle > > auto_disabling_controls
Definition: parser.hpp:150
rs2_frame_metadata_value
Per-Frame-Metadata is the set of read-only properties that might be exposed for each individual frame...
Definition: rs_frame.h:29
const int BPP
void start(T callback) const
Definition: rs_sensor.hpp:185
GLint GLsizei width
void copy(void *dst, void const *src, size_t size)
Definition: types.cpp:836
void stop() const
Definition: rs_sensor.hpp:195
T as() const
Definition: rs_device.hpp:129
void compare(filter first, filter second)
T as() const
Definition: rs_frame.hpp:580
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