10 #include "../include/librealsense2/rs_advanced_mode.hpp" 37 for (
auto s : dev.query_sensors())
42 for (
auto i = 0;
i < 30;
i++)
47 std::vector<std::vector<double>> all_timestamps;
50 for (
auto i = 0;
i < 200;
i++)
55 std::vector<double> timestamps;
58 bool hw_timestamp_domain =
false;
59 bool system_timestamp_domain =
false;
60 bool global_timestamp_domain =
false;
70 hw_timestamp_domain =
true;
74 system_timestamp_domain =
true;
78 global_timestamp_domain =
true;
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);
85 timestamps.push_back(
f.get_timestamp());
87 all_timestamps.push_back(timestamps);
91 size_t num_of_partial_sync_sets = 0;
92 for (
auto set_timestamps : all_timestamps)
94 if (set_timestamps.size() <
profiles.second.size())
95 num_of_partial_sync_sets++;
97 if (set_timestamps.size() <= 1)
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);
104 CAPTURE(num_of_partial_sync_sets);
105 CAPTURE(all_timestamps.size());
107 REQUIRE((
float(num_of_partial_sync_sets) / all_timestamps.size()) < 1.
f);
109 for (
auto s : dev.query_sensors())
133 auto sensors = dev.query_sensors();
135 for (
auto s : sensors)
145 std::map<rs2_stream, rs2::sensor*> profiles_sensors;
146 std::map<rs2::sensor*, rs2_stream> sensors_profiles;
148 int fps_step =
is_usb3(dev) ? 30 : 15;
150 std::vector<int>
fps(sensors.size(), 0);
153 for (
auto i = 0;
i <
fps.size();
i++)
155 fps[
i] = (
fps.size() -
i - 1) * fps_step % 90 + fps_step;
157 std::vector<std::vector<rs2::sensor*>> streams_groups(
fps.size());
158 for (
auto i = 0;
i < sensors.size();
i++)
163 profiles_sensors[
p.stream] = &sensors[
i];
164 sensors_profiles[&sensors[
i]] =
p.stream;
166 if (profs.size() > 0)
167 sensors[i].
start(syncer);
170 for (
auto i = 0;
i < sensors.size();
i++)
172 for (
auto j = 0;
j < sensors.size();
j++)
174 if ((
float)
fps[
j] / (float)
fps[
i] >= 1)
176 streams_groups[
i].push_back(&sensors[
j]);
182 std::vector<std::vector<rs2_stream>> frames_arrived;
184 for (
auto i = 0;
i < 200;
i++)
188 std::vector<rs2_stream> streams_arrived;
191 auto s =
f.get_profile().stream_type();
192 streams_arrived.push_back(
s);
194 frames_arrived.push_back(streams_arrived);
197 std::vector<int> streams_groups_arrrived(streams_groups.size(), 0);
199 for (
auto streams : frames_arrived)
201 std::set<rs2::sensor*> sensors;
205 sensors.insert(profiles_sensors[
s]);
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())
213 streams_groups_arrrived[
ind]++;
218 for (
auto i = 0;
i < streams_groups_arrrived.size();
i++)
220 for (
auto j = 0;
j < streams_groups_arrrived.size();
j++)
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]]);
227 CAPTURE(sensors_profiles[&sensors[j]]);
229 REQUIRE((
float)num1 / (
float)num2 <= 5 * (
float)
fps[i] / (
float)
fps[j]);
241 for (
auto i = 0;
i < sensors.size();
i++)
243 auto modes = sensors[
i].get_stream_profiles();
246 if (mode_index >= modes.size())
249 *profile = modes[mode_index];
269 bool usb3_device =
is_usb3(dev);
270 int fps = usb3_device ? 30 : 15;
271 int req_fps = usb3_device ? 60 : 30;
277 }
while (mode.
fps() != req_fps);
282 for (
auto s : res.first)
289 for (
auto i = 0;
i < 30;
i++)
304 while ((other_video.height() == video.height() && other_video.width() == video.width()) || other_video.fps() != req_fps)
321 for (
auto s : res.first)
328 for (
auto s : res.first)
333 for (
auto i = 0;
i < 10;
i++)
347 TEST_CASE(
"Device metadata enumerates correctly",
"[live]")
352 std::vector<rs2::device> list;
357 for (
auto&&
dev : list)
359 SECTION(
"supported device metadata strings are nonempty, unsupported ones throw")
362 auto is_supported =
false;
375 TEST_CASE(
"Start-Stop stream sequence",
"[live][using_pipeline]")
381 std::vector<sensor> list;
389 for (
auto i = 0;
i < 5;
i++)
407 TEST_CASE(
"Start-Stop streaming - Sensors callbacks API",
"[live][using_callbacks]")
412 for (
auto i = 0;
i < 5;
i++)
414 std::vector<rs2::device> list;
424 std::map<std::string, size_t> frames_per_stream{};
432 std::lock_guard<std::mutex> lock(m);
433 ++frames_per_stream[f.get_profile().stream_name()];
437 std::this_thread::sleep_for(std::chrono::seconds(1));
446 std::stringstream active_profiles, streams_arrived;
447 active_profiles <<
"Profiles requested : " <<
profiles.second.size() << std::endl;
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;
454 CAPTURE(active_profiles.str().c_str());
455 CAPTURE(streams_arrived.str().c_str());
532 TEST_CASE(
"No extrinsic transformation between a stream and itself",
"[live]")
538 std::vector<sensor> list;
540 const size_t device_count = list.size();
544 for (
auto&& snr : list)
546 std::vector<rs2::stream_profile> profs;
552 auto prof = profs[0];
553 extrin = prof.get_extrinsics_to(prof);
567 TEST_CASE(
"Extrinsic transformation between two streams is a rigid transform",
"[live]")
573 std::vector<sensor> list;
575 const size_t device_count = list.size();
579 for (
int i = 0;
i < device_count; ++
i)
587 for (
auto j = 0;
j < adj_devices.size(); ++
j)
589 for (
size_t k =
j + 1; k < adj_devices.size(); ++k)
591 std::vector<rs2::stream_profile> profs_a, profs_b;
602 a_to_b = profs_a[0].get_extrinsics_to(profs_b[0]);
626 TEST_CASE(
"Extrinsic transformations are transitive",
"[live]")
632 std::vector<sensor> list;
637 for (
auto&&
dev : list)
642 for (
auto a = 0UL;
a < adj_devices.size(); ++
a)
644 for (
auto b = 0UL;
b < adj_devices.size(); ++
b)
646 for (
auto c = 0UL;
c < adj_devices.size(); ++
c)
648 std::vector<rs2::stream_profile> profs_a, profs_b, profs_c ;
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]);
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));
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));
695 TEST_CASE(
"Toggle Advanced Mode",
"[live][AdvMd][mayfail]") {
696 for (
int i = 0;
i < 3; ++
i)
705 auto dev = std::make_shared<device>(list.
front());
716 if (!advanced.is_enabled())
726 REQUIRE(advanced.is_enabled());
733 REQUIRE(!advanced.is_enabled());
740 TEST_CASE(
"Advanced Mode presets",
"[live][AdvMd][mayfail]")
742 static const std::vector<res_type> resolutions = {
low_resolution,
753 auto dev = std::make_shared<device>(list.
front());
764 if (!advanced.is_enabled())
774 REQUIRE(advanced.is_enabled());
775 auto sensors = dev->query_sensors();
778 for (
sensor& elem : sensors)
780 auto supports =
false;
784 presets_sensor = elem;
789 for (
auto&
res : resolutions)
794 presets_sensor.
open(sp);
814 presets_sensor.
stop();
815 presets_sensor.
close();
825 REQUIRE(!advanced.is_enabled());
830 TEST_CASE(
"Advanced Mode JSON",
"[live][AdvMd][mayfail]") {
839 auto dev = std::make_shared<device>(list.
front());
850 if (!advanced.is_enabled())
860 REQUIRE(advanced.is_enabled());
862 auto sensors = dev->query_sensors();
864 for (
sensor& elem : sensors)
866 auto supports =
false;
870 presets_sensor = elem;
888 REQUIRE(!advanced.is_enabled());
893 TEST_CASE(
"Advanced Mode controls",
"[live][AdvMd][mayfail]") {
901 std::shared_ptr<device>
dev = std::make_shared<device>(list.
front());
913 if (!advanced.is_enabled())
926 REQUIRE(advanced.is_enabled());
937 REQUIRE(ctrl_curr == ctrl_min);
949 REQUIRE(ctrl_curr == ctrl_min);
954 REQUIRE_NOTHROW(ctrl_curr = advanced.get_rau_support_vector_control(0));
956 REQUIRE_NOTHROW(ctrl_min = advanced.get_rau_support_vector_control(1));
958 REQUIRE_NOTHROW(ctrl_max = advanced.get_rau_support_vector_control(2));
960 REQUIRE_NOTHROW(ctrl_curr = advanced.get_rau_support_vector_control(0));
961 REQUIRE(ctrl_curr == ctrl_min);
973 REQUIRE(ctrl_curr == ctrl_min);
985 REQUIRE(ctrl_curr == ctrl_min);
990 REQUIRE_NOTHROW(ctrl_curr = advanced.get_slo_color_thresholds_control(0));
992 REQUIRE_NOTHROW(ctrl_min = advanced.get_slo_color_thresholds_control(1));
994 REQUIRE_NOTHROW(ctrl_max = advanced.get_slo_color_thresholds_control(2));
996 REQUIRE_NOTHROW(ctrl_curr = advanced.get_slo_color_thresholds_control(0));
997 REQUIRE(ctrl_curr == ctrl_min);
1009 REQUIRE(ctrl_curr == ctrl_min);
1018 REQUIRE(ctrl_curr1 == ctrl_curr2);
1030 REQUIRE(ctrl_curr == ctrl_min);
1039 REQUIRE(ctrl_curr1 == ctrl_curr2);
1051 REQUIRE(ctrl_curr == ctrl_min);
1063 REQUIRE(ctrl_curr == ctrl_min);
1075 REQUIRE(!advanced.is_enabled());
1081 TEST_CASE(
"Streaming modes sanity check",
"[live][mayfail]")
1087 std::vector<sensor> list;
1092 for (
auto&&
dev : list)
1102 REQUIRE(stream_profiles.size() > 0);
1104 SECTION(
"check stream profile settings are sane")
1107 for (
auto profile : stream_profiles) {
1125 SECTION(
"check stream intrinsics are sane")
1127 for (
auto profile : stream_profiles)
1137 bool calib_format = ((PID !=
"0AA5") &&
1174 std::vector<sensor> list;
1179 for (
auto&&
dev : list)
1186 REQUIRE(stream_profiles.size() > 0);
1189 for (
auto profile : stream_profiles)
1191 SECTION(
"check motion intrisics") {
1203 for (
int j = 0;
j < 3;
j++)
1225 TEST_CASE(
"Check width and height of stream intrinsics",
"[live][AdvMd]")
1230 std::vector<device> devs;
1233 for (
auto&&
dev : devs)
1235 auto shared_dev = std::make_shared<device>(
dev);
1245 if (advanced.is_enabled())
1255 REQUIRE(advanced.is_enabled() ==
false);
1258 std::vector<sensor> list;
1262 for (
auto&&
dev : list)
1269 REQUIRE(stream_profiles.size() > 0);
1273 for (
const auto&
profile : stream_profiles)
1286 bool calib_format = ((PID !=
"0AA5") &&
1305 std::set<std::pair<rs2_stream, int>> supported_streams;
1306 auto hint = supported_streams.begin();
1309 hint = supported_streams.emplace_hint(hint,
profile.stream_type(),
profile.stream_index());
1314 for (
auto&
profile : profiles) {
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);
1344 for (
auto&&
sensor : dev.query_sensors())
1351 std::vector<rs2::stream_profile> opened_profiles;
1352 for (
int i = 0;
i < n_streams; ++
i) {
1356 std::vector<rs2::stream_profile> reported_profiles;
1359 REQUIRE(reported_profiles == opened_profiles);
1372 std::vector<sensor> list;
1377 for (
auto&&
dev : list)
1383 bool is_opt_supported;
1389 if (!is_opt_supported)
1409 SECTION(
"get_option returns a legal value")
1411 if (!is_opt_supported)
1417 auto range =
dev.get_option_range(opt);
1432 SECTION(
"set opt doesn't like bad values") {
1433 if (!is_opt_supported)
1439 auto range =
dev.get_option_range(opt);
1459 for (
auto j = 1;
j <
range.step;
j++) {
1466 SECTION(
"check get/set sequencing works as expected") {
1467 if (!is_opt_supported)
continue;
1468 auto range =
dev.get_option_range(opt);
1483 SECTION(
"get_description returns a non-empty, non-null string") {
1484 if (!is_opt_supported) {
1489 REQUIRE(
dev.get_option_description(opt) !=
nullptr);
1513 { {
"0AD1",
true },
e_d400},
1514 { {
"0AD2",
true },
e_d400 },
1515 { {
"0AD2",
false },
e_d400},
1516 { {
"0AD3",
true },
e_d400},
1517 { {
"0AD3",
false },
e_d400},
1518 { {
"0AD4",
true },
e_d400},
1519 { {
"0AD5",
true },
e_d400},
1520 { {
"0AD6",
false },
e_d400 },
1521 { {
"0AF6",
true },
e_d400},
1522 { {
"0AFE",
true },
e_d400},
1523 { {
"0AFF",
true },
e_d400},
1524 { {
"0B00",
true },
e_d400},
1525 { {
"0B01",
true },
e_d400},
1526 { {
"0B03",
true },
e_d400},
1527 { {
"0B07",
true },
e_d400},
1528 { {
"0B07",
false },
e_d400},
1529 { {
"0B0C",
true },
e_d400},
1530 { {
"0B3A",
true },
e_d400},
1531 { {
"0AA5",
true },
e_sr300 },
1549 std::vector<rs2::device> list;
1554 for (
auto&&
dev : list)
1563 for (
auto&& snr :
dev.query_sensors())
1571 WARN(
"Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ?
" USB3" :
" USB2"));
1576 REQUIRE(test_patterns.size() > 0);
1578 for (
auto i = 0;
i < test_patterns.size(); ++
i)
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{};
1590 if (opt_orig_supported && opt_tgt_supported)
1597 auto slave_cur_val = snr.get_option(tgt_opt);
1598 if (slave_cur_val != test_patterns[
i].slave_val_before)
1600 REQUIRE_NOTHROW(snr.set_option(tgt_opt, test_patterns[
i].slave_val_before));
1602 REQUIRE(snr.get_option(tgt_opt) == test_patterns[
i].slave_val_before);
1609 (snr.set_option(orig_opt, master_range.
def));
1615 REQUIRE(snr.get_option(tgt_opt) == test_patterns[
i].slave_val_after);
1633 std::vector<sensor> list;
1637 SECTION(
"subdevices on a single device")
1639 for (
auto &
dev : list)
1643 SECTION(
"opening the same subdevice multiple times")
1645 auto modes =
dev.get_stream_profiles();
1647 CAPTURE(modes.front().stream_type());
1662 if (modes.size() == 1)
1667 WARN(
"subdevice has only 1 supported streaming mode. Skipping Same Subdevice, different modes test.");
1683 SECTION(
"opening different subdevices") {
1691 if (subdevice1 == subdevice2)
1695 REQUIRE_NOTHROW(subdevice1.open(subdevice1.get_stream_profiles().front()));
1699 auto profile = subdevice2.get_stream_profiles().front();
1708 REQUIRE_NOTHROW(subdevice2.open(subdevice2.get_stream_profiles().front()));
1717 REQUIRE_NOTHROW(subdevice2.open(subdevice2.get_stream_profiles().front()));
1733 if (list.size() == 1)
1735 WARN(
"Only one device connected. Skipping multi-device test");
1739 for (
auto & dev1 : list)
1742 for (
auto & dev2 : list)
1750 auto dev1_profiles = dev1.get_stream_profiles();
1751 auto dev2_profiles = dev2.get_stream_profiles();
1753 if (!dev1_profiles.size() || !dev2_profiles.size())
1756 auto dev1_profile = dev1_profiles.front();
1757 auto dev2_profile = dev2_profiles.front();
1759 CAPTURE(dev1_profile.stream_type());
1760 CAPTURE(dev1_profile.format());
1766 CAPTURE(dev2_profile.stream_type());
1767 CAPTURE(dev2_profile.format());
1793 TEST_CASE(
"Multiple applications",
"[live][multicam][!mayfail]")
1799 std::vector<sensor> list1;
1805 std::vector<sensor> list2;
1807 REQUIRE(list2.size() == list1.size());
1808 SECTION(
"subdevices on a single device")
1810 for (
auto&& dev1 : list1)
1813 for (
auto&& dev2 : list2)
1819 bool skip_section =
false;
1821 skip_section =
true;
1827 std::vector<rs2::stream_profile> modes1, modes2;
1831 REQUIRE(modes1.size() == modes2.size());
1841 CAPTURE(modes1.front().stream_name());
1855 if (modes1.size() == 1)
1860 WARN(
"Device has only 1 supported streaming mode. Skipping Same Subdevice, different modes test.");
1878 SECTION(
"different subdevice")
1885 CAPTURE(dev2.get_stream_profiles().front().stream_type());
1909 SECTION(
"subdevices on separate devices")
1911 if (list1.size() == 1)
1913 WARN(
"Only one device connected. Skipping multi-device test");
1917 for (
auto & dev1 : list1)
1920 for (
auto & dev2 : list2)
1928 std::vector<rs2::stream_profile> modes1, modes2;
1935 CAPTURE(modes1.front().stream_type());
1982 int64_t last_val[3] = { -1, -1, -1 };
1984 for (
size_t i = 0;
i < data.size();
i++)
1990 if (data[
i].frame_md.md_attributes[
j].first)
1996 REQUIRE((value > last_val[j]));
1999 REQUIRE((1 == (value - last_val[j])));
2002 last_val[
j] = data[
i].frame_md.md_attributes[
j].second;
2008 if (md.first)
REQUIRE(md.second >= 0);
2010 if (md.first)
REQUIRE(md.second >= 0);
2012 if (md.first)
REQUIRE(md.second >= 0);
2014 if (md.first)
REQUIRE(md.second >= 0);
2016 if (md.first)
REQUIRE(md.second >= 0);
2018 if (md.first)
REQUIRE(md.second >= 0);
2022 if (md.first)
REQUIRE((md.second == 0 || md.second == 1));
2024 if (md.first)
REQUIRE((md.second == 0 || md.second == 1));
2026 if (md.first)
REQUIRE((md.second == 0 || md.second == 1));
2028 if (md.first)
REQUIRE((md.second == 0 || md.second == 1));
2030 if (md.first)
REQUIRE((md.second == 0 || md.second == 1));
2038 std::vector<uint8_t> raw_data(24, 0);
2045 debug.send_and_receive_raw_data(raw_data);
2056 std::vector<sensor> list;
2062 std::condition_variable
cv;
2066 const std::map< uint8_t, std::string> error_report = {
2068 { 1,
"Laser hot - power reduce" },
2069 { 2,
"Laser hot - disabled" },
2070 { 3,
"Flag B - laser disabled" },
2074 for (
auto && subdevice : list) {
2082 std::unique_lock<std::mutex>
lock(m);
2092 for (
auto i = 1;
i < error_report.size();
i++)
2095 std::unique_lock<std::mutex>
lock(m);
2100 return notification_description.compare(error_report.at(
i)) == 0
2103 REQUIRE(cv.wait_for(lock, std::chrono::seconds(10), pred));
2113 std::stringstream ss(s);
2115 std::vector<uint32_t> tokens;
2116 while (std::getline(ss, item, delim)) {
2117 tokens.push_back(
std::stoi(item,
nullptr));
2126 auto fw =
split(fw_version_str,
'.');
2127 if (fw[0] > other_fw[0])
2129 if (fw[0] == other_fw[0] && fw[1] > other_fw[1])
2131 if (fw[0] == other_fw[0] && fw[1] == other_fw[1] && fw[2] > other_fw[2])
2133 if (fw[0] == other_fw[0] && fw[1] == other_fw[1] && fw[2] == other_fw[2] && fw[3] > other_fw[3])
2135 if (fw[0] == other_fw[0] && fw[1] == other_fw[1] && fw[2] == other_fw[2] && fw[3] == other_fw[3])
2146 std::vector<sensor> list;
2150 for (
auto && subdevice : list)
2160 SECTION(
"Disable auto exposure when setting a value")
2173 SECTION(
"Disable emitter when setting a value")
2175 for (
auto elem : { 0.f, 2.f })
2186 const uint32_t MIN_FW_VER[4] = { 5, 9, 11, 0 };
2194 SECTION(
"Disable white balance when setting a value")
2217 std::shared_ptr<rs2::device>
dev;
2219 std::weak_ptr<rs2::device> weak_dev(dev);
2223 return std::pair<std::shared_ptr<rs2::device>, std::weak_ptr<rs2::device>>(
dev, weak_dev);
2231 strong = std::make_shared<rs2::device>(new_dev);
2245 auto dev_strong = dev.first;
2246 auto dev_weak = dev.second;
2249 auto disconnected =
false;
2250 auto connected =
false;
2256 std::condition_variable
cv;
2262 auto&& strong = dev_weak.lock();
2266 if (info.was_removed(*strong))
2268 std::unique_lock<std::mutex> lock(m);
2269 disconnected = true;
2274 for (auto d : info.get_new_devices())
2276 for (auto&& s : d.query_sensors())
2277 disable_sensitive_options_for(s);
2279 if (serial == d.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER))
2283 std::unique_lock<std::mutex> lock(m);
2301 dev_strong->hardware_reset();
2319 auto dev_strong = dev.first;
2320 auto dev_weak = dev.second;
2326 auto disconnected =
false;
2327 auto connected =
false;
2328 std::condition_variable
cv;
2334 auto&& strong = dev_weak.lock();
2338 if (info.was_removed(*strong))
2340 std::unique_lock<std::mutex> lock(m);
2341 disconnected = true;
2346 for (auto d : info.get_new_devices())
2348 if (serial == d.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER))
2352 std::unique_lock<std::mutex> lock(m);
2354 reset_device(dev_strong, dev_weak, list, d);
2373 dev_strong->hardware_reset();
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>>();
2384 std::shared_ptr<std::function<void(rs2::frame fref)>>
func;
2386 std::vector<rs2::stream_profile> modes;
2389 auto streaming =
false;
2391 for (
auto p : modes)
2395 if (video.width() == 640 && video.height() == 480 && video.fps() == 60 && video.format())
2401 (*streams_frames)[
p.stream_type()] = 0;
2405 func = std::make_shared< std::function<void(frame fref)>>([num_of_frames,
m, streams_frames,
cv](
frame fref)
mutable 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)
2421 std::unique_lock<std::mutex>
lock(*m);
2422 cv->wait_for(lock, std::chrono::seconds(30), [&]
2424 for (
auto f : (*streams_frames))
2426 if (
f.second < num_of_frames)
2432 if (!infinite && streaming)
2442 TEST_CASE(
"Connect Disconnect events while streaming",
"[live]") {
2452 auto dev_strong =
dev.first;
2453 auto dev_weak =
dev.second;
2459 auto disconnected =
false;
2460 auto connected =
false;
2461 std::condition_variable
cv;
2467 auto&& strong = dev_weak.lock();
2471 if (info.was_removed(*strong))
2473 std::unique_lock<std::mutex> lock(m);
2474 disconnected = true;
2479 for (auto d : info.get_new_devices())
2481 if (serial == d.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER))
2485 std::unique_lock<std::mutex> lock(m);
2487 reset_device(dev_strong, dev_weak, list, d);
2503 for (
auto&&
s : dev_strong->query_sensors())
2506 for (
auto i = 0;
i < 3;
i++)
2511 dev_strong->hardware_reset();
2514 for (
auto&&
s : dev_strong->query_sensors())
2517 disconnected = connected =
false;
2535 TEST_CASE(
"Connect Disconnect events while controls",
"[live]")
2544 auto dev_strong = dev.first;
2545 auto dev_weak = dev.second;
2552 auto disconnected =
false;
2553 auto connected =
false;
2554 std::condition_variable
cv;
2560 auto&& strong = dev_weak.lock();
2564 if (info.was_removed(*strong))
2566 std::unique_lock<std::mutex> lock(m);
2567 disconnected = true;
2571 for (auto d : info.get_new_devices())
2573 if (serial == d.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER))
2577 std::unique_lock<std::mutex> lock(m);
2579 reset_device(dev_strong, dev_weak, list, d);
2597 dev_strong->hardware_reset();
2600 for (
auto&&
s : dev_strong->query_sensors())
2610 std::shared_ptr<rs2::device>
dev;
2617 std::weak_ptr<rs2::device> weak(dev);
2621 dev->hardware_reset();
2625 std::this_thread::sleep_for(std::chrono::milliseconds(10));
2652 TEST_CASE(
"Auto-complete feature works",
"[offline][util::config][using_pipeline]") {
2659 std::vector<stream_format> given;
2660 std::vector<stream_format> expected;
2662 std::vector<Test>
tests = {
2676 { { {
RS2_STREAM_INFRARED, 0, 0, 200,
RS2_FORMAT_ANY, 1 }, {
RS2_STREAM_DEPTH , 0, 0, 0,
RS2_FORMAT_ANY, -1 } },
2682 { { {
RS2_STREAM_DEPTH , 640, 480, 0,
RS2_FORMAT_ANY, -1 }, {
RS2_STREAM_INFRARED, 0, 0, 110,
RS2_FORMAT_ANY, 1 } },
2685 { { {
RS2_STREAM_DEPTH , 640, 480, 0,
RS2_FORMAT_ANY, -1 }, {
RS2_STREAM_INFRARED, 0, 0, 30,
RS2_FORMAT_ANY, 1 } },
2686 { {
RS2_STREAM_DEPTH , 640, 480, 30,
RS2_FORMAT_ANY, 0 }, {
RS2_STREAM_INFRARED, 640, 480, 30,
RS2_FORMAT_ANY, 1 } } },
2688 { { {
RS2_STREAM_INFRARED, 640, 480, 0,
RS2_FORMAT_ANY, 1 }, {
RS2_STREAM_DEPTH , 0, 0, 0,
RS2_FORMAT_ANY , 0 } },
2689 { {
RS2_STREAM_INFRARED, 640, 480, 10,
RS2_FORMAT_ANY, 1 }, {
RS2_STREAM_INFRARED, 640, 480, 30,
RS2_FORMAT_ANY , 1 },
2690 {
RS2_STREAM_DEPTH , 640, 480, 10,
RS2_FORMAT_ANY, 0 }, {
RS2_STREAM_DEPTH , 640, 480, 30,
RS2_FORMAT_ANY , 0 } } }
2696 for (
int i = 0;
i < tests.size(); ++
i)
2699 for (
auto &
profile : tests[
i].given) {
2704 if (tests[
i].expected.size() == 0) {
2824 std::vector<profile> actual_streams_arrived;
2825 for (
auto i = 0;
i <
frames.size();
i++)
2828 auto ts = timestamps[
i];
2829 if (
frame.size() == 0)
2835 std::vector<profile> stream_arrived;
2841 stream_arrived.push_back({
image.stream_type(),
image.format(),
image.width(),
image.height() });
2847 if (ts[ts.size() - 1] - ts[0] > (float)gap / (
float)2)
2850 CAPTURE((
float)gap / (
float)2);
2853 CAPTURE(ts[ts.size() - 1] - ts[0]);
2857 for (
auto&
str : stream_arrived)
2858 actual_streams_arrived.push_back(
str);
2860 if (stream_arrived.size() != requests.
streams.size())
2863 std::sort(stream_arrived.begin(), stream_arrived.end());
2867 for (
auto i = 0;
i < requests.
streams.size();
i++)
2869 if (stream_arrived[
i] != requests.
streams[
i])
2883 std::stringstream ss;
2884 ss <<
"Requested profiles : " << std::endl;
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());
2903 for (
auto profile : actual_streams_arrived)
2917 { {
"0AD1",
true} ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 1280, 720, 1 } }, 30,
true}},
2918 { {
"0AD2",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 1280, 720, 1 } }, 30,
true }},
2919 { {
"0AD2",
false },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 640, 480, 1 } }, 15,
true } },
2920 { {
"0AD3",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30,
true }},
2921 { {
"0AD3",
false },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 640, 480, 0 } }, 15,
true } },
2922 { {
"0AD4",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_Y8, 1280, 720, 1 } }, 30,
true }},
2923 { {
"0AD5",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_Y8, 1280, 720, 1 } }, 30,
true }},
2924 { {
"0AF6",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_Y8, 1280, 720, 1 } }, 30,
true }},
2925 { {
"0AFE",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_Y8, 1280, 720, 1 } }, 30,
true }},
2926 { {
"0AFF",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 1280, 720, 1 } }, 30,
true } },
2927 { {
"0B00",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 1280, 720, 1 } }, 30,
true } },
2928 { {
"0B01",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30,
true }},
2929 { {
"0B03",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 1280, 720, 1 } }, 30,
true }},
2930 { {
"0B07",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30,
true }},
2931 { {
"0B07",
false },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 640, 480, 0 } }, 15,
true } },
2933 { {
"0B3A",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30,
true } },
2934 { {
"0AA5",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 1920, 1080, 0 } }, 30,
true } },
2937 TEST_CASE(
"Pipeline wait_for_frames",
"[live][pipeline][using_pipeline][!mayfail]") {
2958 WARN(
"Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ?
" USB3" :
" USB2"));
2966 std::vector<std::vector<stream_profile>>
frames;
2967 std::vector<std::vector<double>> timestamps;
2969 for (
auto i = 0;
i < 30;
i++)
2974 while (frames.size() < 100)
2978 std::vector<stream_profile> frames_set;
2979 std::vector<double> ts;
2981 for (
auto f : frame)
2989 frames_set.push_back(
f.get_profile());
2990 ts.push_back(
f.get_timestamp());
2992 frames.push_back(frames_set);
2993 timestamps.push_back(ts);
3003 TEST_CASE(
"Pipeline poll_for_frames",
"[live][pipeline][using_pipeline][!mayfail]")
3026 WARN(
"Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ?
" USB3" :
" USB2"));
3034 std::vector<std::vector<stream_profile>>
frames;
3035 std::vector<std::vector<double>> timestamps;
3037 for (
auto i = 0;
i < 30;
i++)
3041 while (frames.size() < 100)
3046 std::vector<stream_profile> frames_set;
3047 std::vector<double> ts;
3048 for (
auto f : frame)
3056 frames_set.push_back(
f.get_profile());
3057 ts.push_back(
f.get_timestamp());
3059 frames.push_back(frames_set);
3060 timestamps.push_back(ts);
3072 { {
"0AD1",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 640, 480, 1 } }, 30,
true } },
3073 { {
"0AD2",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 640, 480, 1 } }, 30,
true } },
3074 { {
"0AD2",
false },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 480, 270, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 480, 270, 1 } }, 30,
true } },
3075 { {
"0AD3",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30,
true } },
3076 { {
"0AD3",
false },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 480, 270, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 424, 240, 0 } }, 30,
true } },
3077 { {
"0AD4",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_Y8, 640, 480, 1 } }, 30,
true } },
3078 { {
"0AD5",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_Y8, 640, 480, 1 } }, 30,
true } },
3079 { {
"0AF6",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_Y8, 640, 480, 1 } }, 30,
true } },
3080 { {
"0AFE",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_Y8, 640, 480, 1 } }, 30,
true } },
3081 { {
"0AFF",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 640, 480, 1 } }, 30,
true } },
3082 { {
"0B00",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 640, 480, 1 } }, 30,
true } },
3083 { {
"0B01",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30,
true } },
3084 { {
"0B03",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 640, 480, 0 } }, 30,
true } },
3085 { {
"0B07",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30,
true } },
3086 { {
"0B07",
false },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 480, 270, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 424, 240, 0 } }, 30,
true } },
3096 TEST_CASE(
"Pipeline enable stream",
"[live][pipeline][using_pipeline]") {
3120 if (dev_requests.end() == dev_requests.find(PID))
3122 WARN(
"Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ?
" USB3" :
" USB2"));
3134 std::vector<std::vector<stream_profile>>
frames;
3135 std::vector<std::vector<double>> timestamps;
3137 for (
auto i = 0;
i < 30;
i++)
3142 while (frames.size() < 100)
3146 std::vector<stream_profile> frames_set;
3147 std::vector<double> ts;
3149 for (
auto f : frame)
3157 frames_set.push_back(
f.get_profile());
3158 ts.push_back(
f.get_timestamp());
3160 frames.push_back(frames_set);
3161 timestamps.push_back(ts);
3170 { {
"0AD1",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_ANY, 0, 0, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_ANY, 0, 0, 1 } }, 30,
true } },
3171 { {
"0AD2",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_ANY, 0, 0, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_ANY, 0, 0, 1 } }, 30,
true } },
3172 { {
"0AD2",
false },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 0, 0, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 0, 0, 0 } }, 15,
true } },
3176 { {
"0AD3",
false },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 0, 0, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 0, 0, 0 } }, 60,
true } },
3178 { {
"0AD5",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_ANY, 0, 0, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_ANY, 0, 0, 1 } }, 30,
true } },
3180 { {
"0AFE",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 0, 0, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 0, 0, 0 } }, 30,
true } },
3181 { {
"0AFF",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 0, 0, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 0, 0, 0 } }, 30,
true } },
3182 { {
"0B00",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 0, 0, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 0, 0, 0 } }, 30,
true } },
3183 { {
"0B01",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 0, 0, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 0, 0, 0 } }, 30,
true } },
3184 { {
"0B03",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 0, 0, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_ANY, 0, 0, 1 } }, 30,
true } },
3193 TEST_CASE(
"Pipeline enable stream auto complete",
"[live][pipeline][using_pipeline]")
3219 WARN(
"Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ?
" USB3" :
" USB2"));
3233 std::vector<std::vector<stream_profile>>
frames;
3234 std::vector<std::vector<double>> timestamps;
3236 for (
auto i = 0;
i < 30;
i++)
3241 while (frames.size() < 100)
3245 std::vector<stream_profile> frames_set;
3246 std::vector<double> ts;
3247 for (
auto f : frame)
3255 frames_set.push_back(
f.get_profile());
3256 ts.push_back(
f.get_timestamp());
3258 frames.push_back(frames_set);
3259 timestamps.push_back(ts);
3268 TEST_CASE(
"Pipeline disable_all",
"[live][pipeline][using_pipeline][!mayfail]") {
3293 if ((not_default_configurations.end() == not_default_configurations.find(PID)) || ((default_configurations.find(PID) == default_configurations.end())))
3295 WARN(
"Skipping test - the Device-Under-Test profile is not defined properly for PID " << PID.first << (PID.second ?
" USB3" :
" USB2"));
3301 for (
auto req : not_default_configurations[PID].
streams)
3311 std::vector<std::vector<stream_profile>>
frames;
3312 std::vector<std::vector<double>> timestamps;
3314 for (
auto i = 0;
i < 30;
i++)
3317 auto actual_fps = default_configurations[PID].fps;
3319 while (frames.size() < 100)
3323 std::vector<stream_profile> frames_set;
3324 std::vector<double> ts;
3325 for (
auto f : frame)
3333 frames_set.push_back(
f.get_profile());
3334 ts.push_back(
f.get_timestamp());
3336 frames.push_back(frames_set);
3337 timestamps.push_back(ts);
3346 TEST_CASE(
"Pipeline disable stream",
"[live][pipeline][using_pipeline]") {
3372 WARN(
"Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ?
" USB3" :
" USB2"));
3385 streams.erase(streams.end() - 1);
3391 std::vector<std::vector<stream_profile>>
frames;
3392 std::vector<std::vector<double>> timestamps;
3394 for (
auto i = 0;
i < 30;
i++)
3398 while (frames.size() < 100)
3402 std::vector<stream_profile> frames_set;
3403 std::vector<double> ts;
3404 for (
auto f : frame)
3412 frames_set.push_back(
f.get_profile());
3413 ts.push_back(
f.get_timestamp());
3415 frames.push_back(frames_set);
3416 timestamps.push_back(ts);
3425 TEST_CASE(
"Pipeline with specific device",
"[live][pipeline][using_pipeline]")
3467 bool operator==(std::vector<profile> streams1, std::vector<profile> streams2)
3469 if (streams1.size() != streams2.size())
3472 std::sort(streams1.begin(), streams1.end());
3473 std::sort(streams2.begin(), streams2.end());
3476 for (
auto i = 0;
i < streams1.size();
i++)
3478 if (streams1[
i] != streams2[
i])
3487 TEST_CASE(
"Pipeline start stop",
"[live][pipeline][using_pipeline]") {
3513 WARN(
"Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ?
" USB3" :
" USB2"));
3526 std::vector<device_profiles>
frames;
3528 for (
auto i = 0;
i < 10;
i++)
3535 for (
auto i = 0;
i < 20;
i++)
3540 for (
auto i = 0;
i < 30;
i++)
3546 for (
auto f : frame)
3551 profiles.push_back({
profile.stream_type(),
3553 video_profile.width(),
3554 video_profile.height(),
3555 video_profile.stream_index() });
3558 if (profiles == streams)
3609 TEST_CASE(
"Pipeline get selection",
"[live][pipeline][using_pipeline]") {
3633 WARN(
"Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ?
" USB3" :
" USB2"));
3643 std::vector<stream_profile>
profiles;
3649 std::vector<profile> pipe_streams;
3650 for (
auto s : profiles)
3655 pipe_streams.push_back({ video.stream_type(), video.format(), video.width(), video.height(), video.stream_index() });
3657 REQUIRE(pipe_streams.size() == streams.size());
3659 std::sort(pipe_streams.begin(), pipe_streams.end());
3660 std::sort(streams.begin(), streams.end());
3662 for (
auto i = 0;
i < pipe_streams.size();
i++)
3670 TEST_CASE(
"Per-frame metadata sanity check",
"[live][!mayfail]") {
3675 std::vector<sensor> list;
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;
3685 for (
auto && subdevice : list) {
3686 std::vector<rs2::stream_profile> modes;
3693 for (
int i = 0;
i < modes.size();
i +=
static_cast<int>(std::ceil((
float)modes.size() / (float)num_of_profiles_for_each_subdevice)))
3696 if (
auto video_profile = modes[
i].as<video_stream_profile>())
3698 if (video_profile.width() == 1920 && video_profile.height() == 1080 && video_profile.fps() == 60)
3711 if (
auto video = modes[
i].as<video_stream_profile>())
3717 std::vector<internal_frame_additional_data> frames_additional_data;
3720 std::condition_variable
cv;
3729 if (frames_additional_data.size() >= frames_for_fps_measure)
3734 if ((
frames >= frames_before_start_measure) && (frames_additional_data.size() < frames_for_fps_measure))
3752 bool supported =
false;
3758 data.frame_md.md_attributes[
i] = std::make_pair(
true,
val);
3764 data.frame_md.md_attributes[
i].first =
false;
3769 std::unique_lock<std::mutex>
lock(m);
3770 frames_additional_data.push_back(
data);
3776 CAPTURE(frames_additional_data.size());
3777 CAPTURE(frames_for_fps_measure);
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)); });
3788 auto seconds = (
end -
start)*msec_to_sec;
3796 if (frames_additional_data.size())
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);
3804 if (metadata_seconds <= 0)
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";
3809 REQUIRE(metadata_seconds > 0);
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;
3814 for (
auto i = 0;
i < frames_additional_data.size() - 1;
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));
3822 CAPTURE(frames_additional_data[
i + 1].frame_number);
3824 REQUIRE((frames_additional_data[
i].frame_number < frames_additional_data[
i + 1].frame_number));
3830 CAPTURE(frames_additional_data.size());
3835 REQUIRE(std::fabs(metadata_fps /
actual_fps - 1) < max_diff_between_real_and_metadata_fps);
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") }))
3869 WARN(
"Skipping test - no motion sensor is device type: " << PID.first << (PID.second ?
" USB3" :
" USB2"));
3882 REQUIRE(module_name.size() > 0);
3901 std::string(
"0AFE"),
3902 std::string(
"0AFF"),
3903 std::string(
"0B00"),
3904 std::string(
"0B01"),
3905 std::string(
"0B3A"),
3906 std::string(
"0B3D")}))
3908 WARN(
"Skipping test - no motion sensor is device type: " << PID.first << (PID.second ?
" USB3" :
" USB2"));
3915 REQUIRE(module_name.size() > 0);
3935 std::string(
"0AFE"),
3936 std::string(
"0AFF"),
3937 std::string(
"0B00"),
3938 std::string(
"0B01") }))
3940 WARN(
"Skipping test - no fisheye sensor is device type: " << PID.first << (PID.second ?
" USB3" :
" USB2"));
3947 REQUIRE(module_name.size() > 0);
3970 const size_t record_frames = 60;
3975 WARN(
"Skipping test - the Alternating Emitter feature is not supported for device type: " << PID.first << (PID.second ?
" USB3" :
" USB2"));
3983 GIVEN(
"Success scenario"){
3990 WHEN(
"Sequence - idle - flickering on/off")
3992 THEN(
"Stress test succeed")
3994 for (
int i=0 ;
i<30;
i++)
4017 WHEN(
"Sequence=[idle->:laser_on->: emitter_toggle_on->:streaming]") {
4022 THEN(
"The emitter is alternating on/off") {
4024 std::vector<int> emitter_state;
4025 emitter_state.reserve(record_frames);
4032 for (
int i=0;
i<10; )
4040 while (emitter_state.size() < record_frames)
4051 emitter_state.push_back(
val);
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());
4080 REQUIRE(std::adjacent_find(emitter_state.begin(), emitter_state.end()) == emitter_state.end());
4084 WHEN(
"Sequence=[idle->:streaming-:laser_on->: emitter_toggle_on]") {
4086 THEN(
"The emitter is alternating on/off") {
4088 std::vector<int> emitter_state;
4089 emitter_state.reserve(record_frames);
4098 for (
int i=0;
i<10; )
4106 while (emitter_state.size() < record_frames)
4117 emitter_state.push_back(
val);
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());
4129 REQUIRE(std::adjacent_find(emitter_state.begin(), emitter_state.end()) == emitter_state.end());
4134 GIVEN(
"Negative scenario"){
4143 WHEN(
"Sequence=[idle->:laser_off->: emitter_toggle_on]") {
4144 THEN (
"Cannot set alternating emitter when laser is set off") {
4149 WHEN(
"Sequence=[idle->:laser_on->:emitter_toggle_on->:laser_off]") {
4150 THEN (
"Cannot turn_off laser while the alternating emitter option is on") {
4168 TEST_CASE(
"All suggested profiles can be opened",
"[live][!mayfail]") {
4175 const int num_of_profiles_for_each_subdevice = 2;
4177 std::vector<sensor> list;
4181 for (
auto && subdevice : list) {
4185 std::vector<rs2::stream_profile> modes;
4190 for (
auto i = 0UL;
i < modes.size();
i += (int)std::ceil((
float)modes.size() / (float)num_of_profiles_for_each_subdevice)) {
4204 TEST_CASE(
"Pipeline config enable resolve start flow",
"[live][pipeline][using_pipeline]") {
4236 CAPTURE(depth_profile.stream_index());
4237 CAPTURE(depth_profile.stream_type());
4238 CAPTURE(depth_profile.format());
4240 CAPTURE(depth_profile.width());
4241 CAPTURE(depth_profile.height());
4242 std::vector<device_profiles>
frames;
4247 for (
auto i = 0;
i < 5;
i++)
4253 for (
auto i = 0;
i < 5;
i++)
4272 TEST_CASE(
"Pipeline - multicam scenario with specific devices",
"[live][multicam][pipeline][using_pipeline]") {
4279 int realsense_devices_count = 0;
4281 for (
auto&&
dev : list)
4286 if (name !=
"Platform Camera")
4288 realsense_devices_count++;
4293 if (realsense_devices_count < 2)
4295 WARN(
"Skipping test! This test requires multiple RealSense devices connected");
4312 required_profile = vid_profile;
4316 if (required_profile)
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()));
4337 REQUIRE(resolved_profile_from_start);
4350 REQUIRE(actual_serial == required_serial);
4351 REQUIRE(actual_serial == actual_serial_from_start);
4354 std::vector<rs2::stream_profile> actual_streams;
4356 REQUIRE(actual_streams.size() == 1);
4357 REQUIRE(actual_streams[0] == required_profile);
4358 std::vector<rs2::stream_profile> actual_streams_from_start;
4360 REQUIRE(actual_streams_from_start.size() == 1);
4361 REQUIRE(actual_streams_from_start[0] == required_profile);
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()));
4383 REQUIRE(started_serial == required_serial);
4386 std::vector<rs2::stream_profile> started_streams;
4388 REQUIRE(started_streams.size() == 1);
4389 REQUIRE(started_streams[0] == required_profile);
4394 TEST_CASE(
"Empty Pipeline Profile",
"[live][pipeline][using_pipeline]") {
4413 std::vector<rs2::stream_profile> spv;
4429 if (serial1 != serial2)
4431 throw std::runtime_error(serial1 +
" is different than " + serial2);
4439 throw std::runtime_error(name1 +
" is different than " + name2);
4444 if (streams1.size() != streams2.size())
4449 auto streams1_and_2_equals =
true;
4450 for (
auto&&
s : streams1)
4452 auto it = std::find_if(streams2.begin(), streams2.end(), [&
s](
const stream_profile& sp) {
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();
4461 if (
it == streams2.end())
4463 streams1_and_2_equals =
false;
4467 if (!streams1_and_2_equals)
4469 throw std::runtime_error(
std::string(
"Profiles contain different streams"));
4472 TEST_CASE(
"Pipeline empty Config",
"[live][pipeline][using_pipeline]") {
4482 bool can_resolve =
false;
4492 TEST_CASE(
"Pipeline 2 Configs",
"[live][pipeline][using_pipeline]") {
4500 bool can_resolve1 =
false;
4501 bool can_resolve2 =
false;
4518 TEST_CASE(
"Pipeline start after resolve uses the same profile",
"[live][pipeline][using_pipeline]") {
4537 TEST_CASE(
"Pipeline start ignores previous config if it was changed",
"[live][pipeline][using_pipeline][!mayfail]") {
4554 TEST_CASE(
"Pipeline Config disable all is a nop with empty config",
"[live][pipeline][using_pipeline]") {
4573 TEST_CASE(
"Pipeline Config disable each stream is nop on empty config",
"[live][pipeline][using_pipeline]") {
4642 TEST_CASE(
"Pipeline enable bad configuration",
"[pipeline][using_pipeline]")
4663 std::vector<stream_profile> default_streams = pipe.
start(cfg).
get_streams();
4672 std::vector<stream_profile> wildcards_streams = pipe.
start(cfg).
get_streams();
4675 for (
auto d : default_streams)
4680 for (
auto w : wildcards_streams)
4687 TEST_CASE(
"Pipeline stream with callback",
"[live][pipeline][using_pipeline][!mayfail]")
4713 REQUIRE(frame_from_queue ==
false);
4726 REQUIRE(frame_from_callback ==
false);
4730 TEST_CASE(
"Syncer sanity with software-device device",
"[live][software-device][!mayfail]") {
4738 std::shared_ptr<software_device>
dev =
std::move(std::make_shared<software_device>());
4739 auto s = dev->add_sensor(
"software_sensor");
4741 rs2_intrinsics intrinsics{
W,
H, 0, 0, 0, 0,
RS2_DISTORTION_NONE ,{ 0,0,0,0,0 } };
4749 auto profiles =
s.get_stream_profiles();
4757 std::vector<uint8_t>
pixels(W * H * BPP, 0);
4758 std::weak_ptr<rs2::software_device> weak_dev(dev);
4760 std::thread
t([&
s, weak_dev, pixels,
depth, ir]()
mutable {
4762 auto shared_dev = weak_dev.lock();
4763 if (shared_dev ==
nullptr)
4775 std::vector<std::vector<std::pair<rs2_stream, uint64_t>>> expected =
4783 std::vector<std::vector<std::pair<rs2_stream, uint64_t>>> results;
4785 for (
auto i = 0UL;
i < expected.size();
i++)
4789 std::vector < std::pair<rs2_stream, uint64_t>> curr;
4793 curr.push_back({
f.get_profile().stream_type(),
f.get_frame_number() });
4795 results.push_back(curr);
4800 REQUIRE(results.size() == expected.size());
4802 for (
size_t i = 0;
i < expected.size();
i++)
4804 auto exp = expected[
i];
4805 auto curr = results[
i];
4809 REQUIRE(exp.size() == curr.size());
4811 for (
size_t j = 0;
j < exp.size();
j++)
4824 TEST_CASE(
"Syncer clean_inactive_streams by frame number with software-device device",
"[live][software-device]") {
4833 std::shared_ptr<software_device>
dev = std::make_shared<software_device>();
4834 auto s = dev->add_sensor(
"software_sensor");
4836 rs2_intrinsics intrinsics{
W,
H, 0, 0, 0, 0,
RS2_DISTORTION_NONE ,{ 0,0,0,0,0 } };
4842 auto profiles = s.get_stream_profiles();
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)
4872 std::vector<std::vector<std::pair<rs2_stream, uint64_t>>> expected =
4883 std::vector<std::vector<std::pair<rs2_stream, uint64_t>>> results;
4885 for (
auto i = 0UL;
i < expected.size();
i++)
4890 std::vector < std::pair<rs2_stream, uint64_t>> curr;
4894 curr.push_back({
f.get_profile().stream_type(),
f.get_frame_number() });
4896 results.push_back(curr);
4901 REQUIRE(results.size() == expected.size());
4903 for (
size_t i = 0;
i < expected.size();
i++)
4905 auto exp = expected[
i];
4906 auto curr = results[
i];
4910 REQUIRE(exp.size() == exp.size());
4912 for (
size_t j = 0;
j < exp.size();
j++)
4925 TEST_CASE(
"Unit transform test",
"[live][software-device]") {
4935 int expected_frames = 1;
4937 float depth_unit = 1.5;
4939 rs2_intrinsics intrinsics{
W,
H, 0, 0, 0, 0,
RS2_DISTORTION_NONE ,{ 0,0,0,0,0 } };
4941 std::shared_ptr<software_device>
dev = std::make_shared<software_device>();
4942 auto s = dev->add_sensor(
"software_sensor");
4946 auto profiles = s.get_stream_profiles();
4953 std::vector<uint16_t>
pixels(W * H, 0);
4954 for (
int i = 0;
i < W *
H;
i++) {
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)
4963 for (
int i = 1;
i <= expected_frames;
i++)
4968 for (
auto i = 0;
i < expected_frames;
i++)
4976 auto depth_distance = ut.process(f);
4977 auto depth_distance_format = depth_distance.get_profile().format();
4981 auto depth_distance_data =
reinterpret_cast<const float*
>(depth_distance.get_data());
4983 for (
size_t i = 0;
i <
W*
H;
i++)
4985 auto frame_data_units_transformed = (
frame_data[
i] * depth_unit);
4986 REQUIRE(depth_distance_data[
i] == frame_data_units_transformed);
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++) \ 4996 rs2_enum_type enum_value = static_cast<rs2_enum_type>(i); \ 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 ") ?"; \ 5005 REQUIRE(str != "UNKNOWN"); \ 5008 for (int i = last_item_index; i < last_item_index + 1; i++) \ 5010 rs2_enum_type enum_value = static_cast<rs2_enum_type>(i); \ 5012 REQUIRE_NOTHROW(str = rs2_enum_type##_to_string(enum_value)); \ 5013 REQUIRE(str == "UNKNOWN"); \ 5041 TEST_CASE(
"Syncer try wait for frames",
"[live][software-device]") {
5045 std::shared_ptr<software_device>
dev =
std::move(std::make_shared<software_device>());
5046 auto s = dev->add_sensor(
"software_sensor");
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 } };
5054 auto profiles =
s.get_stream_profiles();
5060 std::weak_ptr<rs2::software_device> weak_dev(dev);
5064 std::thread
t([&
s, weak_dev, pixels,
depth, ir]()
mutable {
5066 auto shared_dev = weak_dev.lock();
5067 if (shared_dev ==
nullptr)
5079 std::vector<std::vector<std::pair<rs2_stream, uint64_t>>> expected =
5087 std::vector<std::vector<std::pair<rs2_stream, uint64_t>>> results;
5088 for (
auto i = 0UL;
i < expected.size();
i++)
5092 std::vector < std::pair<rs2_stream, uint64_t>> curr;
5096 curr.push_back({
f.get_profile().stream_type(),
f.get_frame_number() });
5098 results.push_back(curr);
5103 REQUIRE(results.size() == expected.size());
5105 for (
size_t i = 0;
i < expected.size();
i++)
5107 auto exp = expected[
i];
5108 auto curr = results[
i];
5111 REQUIRE(exp.size() == curr.size());
5113 for (
size_t j = 0;
j < exp.size();
j++)
5123 TEST_CASE(
"Test Motion Module Extension",
"[software-device][using_pipeline][projection]") {
5131 dev.set_real_time(
false);
5134 std::vector<sensor> sensors =
dev.query_sensors();
5135 for (
auto s : sensors)
5144 TEST_CASE(
"Projection from recording",
"[software-device][using_pipeline][projection][!mayfail]") {
5152 dev.set_real_time(
false);
5155 std::vector<sensor> sensors =
dev.query_sensors();
5157 for (
auto s : sensors)
5167 while (!depth_profile || !color_profile)
5171 if (frames.
size() == 1)
5176 depth_profile = depth.get_profile();
5186 depth_profile = depth.get_profile();
5197 for (
auto s : sensors)
5209 for (
float i = 0;
i < depth_intrin.width;
i++)
5211 for (
float j = 0;
j < depth_intrin.height;
j++)
5213 float depth_pixel[2] = {
i,
j };
5214 auto udist = depth.as<
rs2::depth_frame>().get_distance(static_cast<int>(depth_pixel[0]+0.5
f),
static_cast<int>(depth_pixel[1]+0.5f));
5215 if (udist == 0)
continue;
5217 float from_pixel[2] = { 0 }, to_pixel[2] = { 0 },
point[3] = { 0 }, other_point[3] = { 0 };
5224 &depth_intrin, &color_intrin,
5225 &color_extrin_to_depth, &depth_extrin_to_color, from_pixel);
5227 float dist = sqrt(pow((depth_pixel[1] - to_pixel[1]), 2) + pow((depth_pixel[0] - to_pixel[0]), 2));
5232 WARN(
"Projecting color->depth, distance > 2 pixels. Origin: [" 5233 << depth_pixel[0] <<
"," << depth_pixel[1] <<
"], Projected << " 5234 << to_pixel[0] <<
"," << to_pixel[1] <<
"]");
5238 const double MAX_ERROR_PERCENTAGE = 0.1;
5240 REQUIRE(count * 100 / (depth_intrin.width * depth_intrin.height) < MAX_ERROR_PERCENTAGE);
5243 TEST_CASE(
"software-device pose stream",
"[software-device]")
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);
5270 TEST_CASE(
"software-device motion stream",
"[software-device]")
5275 rs2_motion_device_intrinsic intrinsics = { { 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1 },{ 2, 2, 2 },{ 3, 3 ,3 } };
5284 float data[3] = { 1, 1, 1 };
5286 sensor.on_motion_frame(frame);
5298 TEST_CASE(
"Record software-device",
"[software-device][record][!mayfail]")
5314 auto depth_stream_profile =
sensor.add_video_stream(video_stream);
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 } };
5325 stream_profiles.push_back(depth_stream_profile);
5329 std::vector<uint8_t>
pixels(W * H * BPP, 100);
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 };
5341 sensor.on_video_frame(video_frame);
5342 sensor.on_motion_frame(motion_frame);
5343 sensor.on_pose_frame(pose_frame);
5354 auto s = player_dev.query_sensors()[0];
5358 rs2::frame recorded_depth, recorded_accel, recorded_pose;
5379 REQUIRE(((memcmp(motion_frame.
data, recorded_accel.
get_data(),
sizeof(float) * 3) == 0) &&
5399 REQUIRE(first_options.size() == second_options.size());
5401 REQUIRE(first_options == second_options);
5403 for (
auto i = 0UL;
i < first_options.size();
i++)
5405 auto opt =
static_cast<rs2_option>(first_options[
i]);
5413 void compare(std::vector<filter>
first, std::vector<std::shared_ptr<filter>> second)
5415 REQUIRE(first.size() == second.size());
5417 for (
size_t i = 0;
i < first.size();
i++)
5423 TEST_CASE(
"Sensor get recommended filters",
"[live][!mayfail]") {
5434 std::map<sensors, std::vector<std::shared_ptr<filter>>> sensors_to_filters;
5436 auto dec_color = std::make_shared<decimation_filter>();
5440 sensors_to_filters[
color] = {
5444 auto huff_decoder = std::make_shared<depth_huffman_decoder>();
5445 auto dec_depth = std::make_shared<decimation_filter>();
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>();
5454 sensors_to_filters[
depth] = {
5462 auto depth2disparity = std::make_shared<disparity_transform>(
true);
5463 auto disparity2depth = std::make_shared<disparity_transform>(
false);
5465 sensors_to_filters[depth_stereo] = {
5478 std::vector<sensor> sensors;
5482 for (
auto sensor : sensors)
5505 const int RETRIES = 30;
5509 std::vector<sensor> sensors;
5513 for (
auto sensor : sensors)
5532 std::map<rs2_stream, bool> stream_arrived;
5537 for (
auto i = 0;
i < RETRIES;
i++)
5540 auto res = zo->process(frame);
5545 for (
auto&&
f :
set)
5547 stream_arrived[
f.get_profile().stream_type()] =
true;
5549 auto stream_missing = std::find_if(stream_arrived.begin(), stream_arrived.end(), [](std::pair< rs2_stream, bool> item)
5551 return !item.second;
5554 REQUIRE(stream_missing == stream_arrived.end());
5584 WARN(
"Skipping test - Applicable for Positional Tracking sensors only. Current device type: " << PID.first << (PID.second ?
" USB3" :
" USB2"));
5595 WHEN(
"Sequence - Streaming.")
5597 THEN(
"Export/Import must Fail")
5607 WARN(
"T2xx Collecting frames started");
5610 for (
auto i = 0;
i < 200;
i++)
5616 std::vector<uint8_t> results{}, vnv{};
5617 WARN(
"T2xx export map");
5621 WARN(
"T2xx import map");
5622 REQUIRE_THROWS(pose_snr.import_localization_map({ 0, 1, 2, 3, 4 }));
5624 WARN(
"T2xx import/export during streaming finished");
5628 WHEN(
"Sequence - idle.")
5630 THEN(
"Export/Import Success")
5632 std::vector<uint8_t> results, vnv;
5648 WHEN(
"Sequence - Streaming.")
5650 THEN(
"Set/Get Static node functionality")
5662 for (
auto i = 0;
i < 100;
i++)
5668 rs2_vector init_pose{}, test_pose{ 1,2,3 }, vnv_pose{};
5674 std::this_thread::sleep_for(std::chrono::milliseconds(500));
5718 WARN(
"Skipping test - Applicable for Positional Tracking sensors only. Current device type: " << PID.first << (PID.second ?
" USB3" :
" USB2"));
5728 WHEN(
"Sequence - idle.")
5730 THEN(
"Load wheel odometry calibration")
5732 std::ifstream calibrationFile(
"calibration_odometry.json");
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());
5739 REQUIRE_NOTHROW(b = wheel_odom_snr.load_wheel_odometery_config(wo_calib));
5745 WHEN(
"Sequence - Streaming.")
5747 THEN(
"Send wheel odometry data")
5759 WARN(
"T2xx Collecting frames started - Keep device static");
5761 for (
int i = 0;
i < 100;
i++)
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;
5785 TEST_CASE(
"get_sensor_from_frame",
"[live][using_pipeline][!mayfail]")
5791 std::vector<sensor> list;
5810 for (
auto i = 0;
i < 5;
i++)
5813 for (
auto&&
frame : data)
5816 REQUIRE(dev_serial_no == frame_serial_no);
5831 std::vector<sensor> list;
5837 for (
auto&&
s : list)
5848 for (
auto&&
option : _hw_controls)
5860 std::map< rs2_option, option_range> options_range;
5862 for (
auto&&
option : _hw_controls)
5870 std::map<int, int> expected_ambient_per_preset =
5878 std::map<int, int> expected_laser_power_per_preset =
5884 std::map< float, float> apd_per_ambient;
5885 for (
auto i : expected_ambient_per_preset)
5888 for (
auto res : resolutions)
5895 auto expected_laser_power = expected_laser_power_per_preset.find(
i.first);
5896 if (expected_laser_power != expected_laser_power_per_preset.end())
5907 REQUIRE(apd_per_ambient[RS2_SENSOR_MODE_XGA] != apd_per_ambient[RS2_SENSOR_MODE_VGA]);
5908 for (
auto&& opt : options_range)
5910 ds.set_option(opt.first, opt.second.min);
static const textual_icon lock
rs2_camera_info
Read-only strings that can be queried from the device. Not all information attributes are available o...
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])
GLboolean GLboolean GLboolean b
bool is_connected(const device &dev) const
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.
float get_depth_scale() const
GLenum GLuint GLenum severity
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.
std::vector< sensor > query_sensors() const
static const std::map< dev_type, device_profiles > pipeline_default_configurations
const std::shared_ptr< rs2_device > & get() const
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...
bool operator==(const plane &lhs, const plane &rhs)
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
TEST_CASE("Sync sanity","[live][mayfail]")
std::vector< uint32_t > split(const std::string &s, char delim)
device get_sensor_parent(const sensor &s) const
rs2_distortion
Distortion model: defines how pixel coordinates should be mapped to sensor coordinates.
GLenum GLenum GLenum GLenum GLenum scale
rs2_metadata_type get_frame_metadata(rs2_frame_metadata_value frame_metadata) const
rs2_sr300_visual_preset
For SR300 devices: provides optimized settings (presets) for specific types of usage.
bool val_in_range(const T &val, const std::initializer_list< T > &list)
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)
std::vector< filter > get_recommended_filters() const
#define REQUIRE_THROWS_AS(expr, exceptionType)
stream_profile get_profile() const
device_list query_devices() const
void enqueue(frame f) const
rs2_log_severity get_severity() const
static const std::map< dev_type, device_profiles > pipeline_autocomplete_configurations
All the parameters required to define a video stream.
Approx & epsilon(T const &newEpsilon)
All the parameters required to define a pose frame.
frame wait_for_frame(unsigned int timeout_ms=5000) const
std::string get_folder_path(special_folder f)
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
bool supports_frame_metadata(rs2_frame_metadata_value frame_metadata) const
GLdouble GLdouble GLdouble w
GLsizei const GLchar *const * string
std::string get_description() const
void enable_device(const std::string &serial)
software_sensor add_sensor(std::string name)
rs2_timestamp_domain domain
bool get_mode(rs2::device &dev, stream_profile *profile, int mode_index=0)
GLsizei GLsizei GLfloat distance
std::vector< rs2::stream_profile > get_supported_streams(rs2::sensor sensor, std::vector< rs2::stream_profile > profiles)
rs2_timestamp_domain domain
void require_zero_vector(const float(&vector)[3])
void sort(sort_type m_sort_type, const std::string &in, const std::string &out)
static const std::map< dev_type, device_profiles > pipeline_custom_configurations
::realsense_legacy_msgs::pose_< std::allocator< void > > pose
GLenum GLenum GLsizei void * image
frameset wait_for_frames(unsigned int timeout_ms=5000) const
depth_frame get_depth_frame() const
frame first_or_default(rs2_stream s, rs2_format f=RS2_FORMAT_ANY) const
GLboolean GLboolean GLboolean GLboolean a
video_frame get_color_frame() const
def info(name, value, persistent=False)
Quaternion used to represent rotation.
std::vector< rs2_option > get_supported_options()
bool poll_for_frames(frameset *f) const
static void rs2_deproject_pixel_to_point(float point[3], const struct rs2_intrinsics *intrin, const float pixel[2], float depth)
void trigger_error(const rs2::device &dev, int num)
std::shared_ptr< rs2_config > get() const
static const std::map< dev_type, device_profiles > pipeline_configurations_for_extrinsic
All the parameters required to define a pose stream.
void disable_all_streams()
std::pair< std::shared_ptr< rs2::device >, std::weak_ptr< rs2::device > > make_device(device_list &list)
double get_timestamp() const
const char * get_info(rs2_camera_info info) const
void require_rotation_matrix(const float(&matrix)[9])
GLint GLsizei GLsizei height
GLenum GLint GLenum GLsizei GLsizei GLsizei GLint GLsizei const void * bits
static std::condition_variable cv
GLint GLint GLsizei GLint GLenum format
#define REQUIRE_THROWS(...)
void require_transposed(const float(&a)[9], const float(&b)[9])
#define SECTION_FROM_TEST_NAME
stream_profile get_stream(rs2_stream stream_type, int stream_index=-1) const
void disable_stream(rs2_stream stream, int index=-1)
float vector_length(const float(&v)[3])
All the parameters required to define a motion stream.
rs2_format
A stream's format identifies how binary data is encoded within a frame.
#define CHECK_THROWS(...)
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)
bool supports(rs2_camera_info info) const
void enable_stream(rs2_stream stream_type, int stream_index, int width, int height, rs2_format format=RS2_FORMAT_ANY, int framerate=0)
bool can_resolve(std::shared_ptr< rs2_pipeline > p) const
std::vector< std::shared_ptr< stream_profile_interface >> stream_profiles
rs2_stream
Streams are different types of data provided by RealSense devices.
std::vector< profile > streams
device get_device() const
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)
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented...
void log_to_console(rs2_log_severity min_severity)
rs2_format format() const
3D vector in Euclidean coordinate space
bool is_fw_version_newer(rs2::sensor &subdevice, const uint32_t other_fw[4])
static void rs2_project_point_to_pixel(float pixel[2], const struct rs2_intrinsics *intrin, const float point[3])
GLdouble GLdouble GLdouble q
pipeline_profile resolve(std::shared_ptr< rs2_pipeline > p) const
std::vector< stream_profile > get_streams() const
dev_type get_PID(rs2::device &dev)
rs2_extension
Specifies advanced interfaces (capabilities) objects may implement.
rs2_notification_category
Category of the librealsense notification.
GLbitfield GLuint64 timeout
const char * get_info(rs2_camera_info info) const
long long rs2_metadata_type
rs2_timestamp_domain get_frame_timestamp_domain() const
void set_real_time(bool real_time) const
void require_pipeline_profile_same(const rs2::pipeline_profile &profile1, const rs2::pipeline_profile &profile2)
All the parameters required to define a motion frame.
rs2_rs400_visual_preset
For RS400 devices: provides optimized settings (presets) for specific types of usage.
rs2_timestamp_domain domain
void metadata_verification(const std::vector< internal_frame_additional_data > &data)
typename::boost::move_detail::remove_reference< T >::type && move(T &&t) BOOST_NOEXCEPT
void open(const stream_profile &profile) const
::realsense_legacy_msgs::motion_intrinsics_< std::allocator< void > > motion_intrinsics
void set_devices_changed_callback(T callback)
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)
void rs2_set_devices_changed_callback(const rs2_context *context, rs2_devices_changed_callback_ptr callback, void *user, rs2_error **error)
int stoi(const std::string &value)
#define REQUIRE_FALSE(...)
Motion device intrinsics: scale, bias, and variances.
REQUIRE_NOTHROW(rs2_log(RS2_LOG_SEVERITY_INFO,"Log message using rs2_log()", nullptr))
void disable_sensitive_options_for(rs2::sensor &sen)
std::array< float, 3 > color
const char * get_info(rs2_camera_info info) const
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.
bool file_exists(const std::string &filename)
void check_controls_sanity(const context &ctx, const sensor &dev)
pipeline_profile get_active_profile() const
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])
void validate(std::vector< std::vector< stream_profile >> frames, std::vector< std::vector< double >> timestamps, device_profiles requests, int actual_fps)
unsigned long long get_frame_number() const
device wait_for_device() const
bool is_usb3(const rs2::device &dev)
rs2_log_severity
Severity of the librealsense logger.
std::vector< stream_profile > get_stream_profiles() const
rs2_stream stream_type() const
void set_option(rs2_option option, float value) const
const std::map< dev_type, dev_group > dev_map
float get_option(rs2_option option) const
std::shared_ptr< sensor > sensor_from_frame(frame f)
const std::map< dev_group, std::vector< option_bundle > > auto_disabling_controls
rs2_frame_metadata_value
Per-Frame-Metadata is the set of read-only properties that might be exposed for each individual frame...
void start(T callback) const
void copy(void *dst, void const *src, size_t size)
void compare(filter first, filter second)
std::string to_string(T value)
rs2_timestamp_domain
Specifies the clock in relation to which the frame timestamp was measured.