15 #include "../include/librealsense2/rs_advanced_mode.hpp" 16 #include "../include/librealsense2/hpp/rs_frame.hpp" 17 #include "../include/librealsense2/hpp/rs_processing.hpp" 19 #include <../src/proc/synthetic-stream.h> 20 #include <../src/proc/disparity-transform.h> 21 #include <../src/proc/spatial-filter.h> 22 #include <../src/proc/temporal-filter.h> 27 # define SECTION_FROM_TEST_NAME space_to_underscore(Catch::getCurrentContext().getResultCapture()->getCurrentTestName()).c_str() 63 WARN(
"Reset workaround");
66 dev->hardware_reset();
76 bool usb3_device =
true;
81 usb3_device = (std::string::npos ==
usb_type.find(
"2."));
91 typedef std::pair<std::string, bool >
dev_type;
95 dev_type designator{
"",
true };
97 bool usb_descriptor =
false;
104 designator.second = (std::string::npos ==
usb_type.find(
"2."));
122 format == other.
format() &&
123 width == other.
width() &&
124 height == other.
height() &&
139 return stream == other.
stream &&
140 (format == 0 || other.
format == 0 || format == other.
format) &&
141 (width == 0 || other.
width == 0 || width == other.
width) &&
142 (height == 0 || other.
height == 0 || height == other.
height) &&
143 (index == 0 || other.
index == 0 || index == other.
index);
148 return !(*
this == other);
152 return stream < other.
stream;
165 std::vector<test_profile> all_profiles =
177 std::vector<rs2::stream_profile> modes;
180 for (
auto profile : all_profiles)
185 if (!video)
return false;
187 if (
p.fps() ==
fps &&
198 }) != all_modes.end())
204 if (modes.size() > 0)
211 std::vector<test_profile >
profiles;
212 std::vector<sensor > sensors;
217 profiles.insert(profiles.end(),
res.begin(),
res.end());
220 sensors.push_back(
s);
224 return{ sensors, profiles };
242 for (
auto s : dev.query_sensors())
247 std::vector<std::vector<double>> all_timestamps;
249 bool hw_timestamp_domain =
false;
250 bool system_timestamp_domain =
false;
251 for (
auto i = 0;
i < 200;
i++)
256 std::vector<double> timestamps;
267 hw_timestamp_domain =
true;
271 system_timestamp_domain =
true;
273 timestamps.push_back(
f.get_timestamp());
275 all_timestamps.push_back(timestamps);
278 for (
auto i = 0;
i < 30;
i++)
284 CAPTURE(system_timestamp_domain);
285 REQUIRE(hw_timestamp_domain != system_timestamp_domain);
287 size_t num_of_partial_sync_sets = 0;
288 for (
auto set_timestamps : all_timestamps)
290 if (set_timestamps.size() <
profiles.second.size())
291 num_of_partial_sync_sets++;
293 if (set_timestamps.size() <= 1)
296 std::sort(set_timestamps.begin(), set_timestamps.end());
297 REQUIRE(set_timestamps[set_timestamps.size() - 1] - set_timestamps[0] <= (float)1000/(
float)
actual_fps);
300 CAPTURE(num_of_partial_sync_sets);
301 CAPTURE(all_timestamps.size());
302 REQUIRE((
float(num_of_partial_sync_sets) / all_timestamps.size()) < 0.9
f);
304 for (
auto s : dev.query_sensors())
328 auto sensors = dev.query_sensors();
330 for (
auto s : sensors)
340 std::map<rs2_stream, rs2::sensor*> profiles_sensors;
341 std::map<rs2::sensor*, rs2_stream> sensors_profiles;
343 int fps_step =
is_usb3(dev) ? 30 : 15;
345 std::vector<int>
fps(sensors.size(), 0);
348 for (
auto i = 0;
i <
fps.size();
i++)
350 fps[
i] = (
fps.size() -
i - 1) * fps_step % 90 + fps_step;
352 std::vector<std::vector<rs2::sensor*>> streams_groups(
fps.size());
353 for (
auto i = 0;
i < sensors.size();
i++)
358 profiles_sensors[
p.stream] = &sensors[
i];
359 sensors_profiles[&sensors[
i]] =
p.stream;
361 if (profs.size() > 0)
362 sensors[i].
start(syncer);
365 for (
auto i = 0;
i < sensors.size();
i++)
367 for (
auto j = 0;
j < sensors.size();
j++)
369 if ((
float)
fps[
j] / (float)
fps[
i] >= 1)
371 streams_groups[
i].push_back(&sensors[
j]);
377 std::vector<std::vector<rs2_stream>> frames_arrived;
379 for (
auto i = 0;
i < 200;
i++)
383 std::vector<rs2_stream> streams_arrived;
386 auto s =
f.get_profile().stream_type();
387 streams_arrived.push_back(
s);
389 frames_arrived.push_back(streams_arrived);
392 std::vector<int> streams_groups_arrrived(streams_groups.size(), 0);
394 for (
auto streams : frames_arrived)
396 std::set<rs2::sensor*> sensors;
400 sensors.insert(profiles_sensors[
s]);
402 std::vector<rs2::sensor*> sensors_vec(sensors.size());
403 std::copy(sensors.begin(), sensors.end(), sensors_vec.begin());
404 auto it =
std::find(streams_groups.begin(), streams_groups.end(), sensors_vec);
405 if (it != streams_groups.end())
408 streams_groups_arrrived[
ind]++;
413 for (
auto i = 0;
i < streams_groups_arrrived.size();
i++)
415 for (
auto j = 0;
j < streams_groups_arrrived.size();
j++)
417 REQUIRE(streams_groups_arrrived[
j]);
418 auto num1 = streams_groups_arrrived[
i];
419 auto num2 = streams_groups_arrrived[
j];
420 CAPTURE(sensors_profiles[&sensors[
i]]);
422 CAPTURE(sensors_profiles[&sensors[j]]);
424 REQUIRE((
float)num1 / (
float)num2 <= 5 * (
float)
fps[i] / (
float)
fps[j]);
437 for (
auto i = 0;
i < sensors.size();
i++)
439 auto modes = sensors[
i].get_stream_profiles();
442 if (mode_index >= modes.size())
445 *profile = modes[mode_index];
465 bool usb3_device =
is_usb3(dev);
466 int fps = usb3_device ? 30 : 15;
467 int req_fps = usb3_device ? 60 : 30;
473 }
while (mode.
fps() != req_fps);
478 for (
auto s : res.first)
485 for (
auto i = 0;
i < 30;
i++)
500 while ((other_video.height() == video.height() && other_video.width() == video.width()) || other_video.fps() != req_fps)
517 for (
auto s : res.first)
524 for (
auto s : res.first)
529 for (
auto i = 0;
i < 10;
i++)
542 TEST_CASE(
"Device metadata enumerates correctly",
"[live]")
547 std::vector<rs2::device> list;
552 for (
auto&&
dev : list)
554 SECTION(
"supported device metadata strings are nonempty, unsupported ones throw")
557 auto is_supported =
false;
576 std::vector<sensor> list;
584 for (
auto i = 0;
i < 5;
i++)
606 TEST_CASE(
"No extrinsic transformation between a stream and itself",
"[live]")
612 std::vector<sensor> list;
614 const size_t device_count = list.size();
618 for (
auto&&
dev : list)
620 std::vector<rs2::stream_profile> profs;
626 auto prof = profs[0];
627 extrin = prof.get_extrinsics_to(prof);
641 TEST_CASE(
"Extrinsic transformation between two streams is a rigid transform",
"[live]")
647 std::vector<sensor> list;
649 const size_t device_count = list.size();
653 for (
int i = 0;
i < device_count; ++
i)
661 for (
auto j = 0;
j < adj_devices.size(); ++
j)
663 for (
int k =
j + 1; k < adj_devices.size(); ++k)
665 std::vector<rs2::stream_profile> profs_a, profs_b;
676 a_to_b = profs_a[0].get_extrinsics_to(profs_b[0]);
700 TEST_CASE(
"Extrinsic transformations are transitive",
"[live]")
706 std::vector<sensor> list;
711 for (
auto&&
dev : list)
716 for (
auto a = 0;
a < adj_devices.size(); ++
a)
718 for (
auto b = 0;
b < adj_devices.size(); ++
b)
720 for (
auto c = 0;
c < adj_devices.size(); ++
c)
722 std::vector<rs2::stream_profile> profs_a, profs_b, profs_c ;
736 a_to_b = profs_a[0].get_extrinsics_to(profs_b[0]);
737 b_to_c = profs_b[0].get_extrinsics_to(profs_c[0]);
738 a_to_c = profs_a[0].get_extrinsics_to(profs_c[0]);
747 REQUIRE(a_to_c.rotation[0] ==
approx(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]));
748 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]));
749 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]));
750 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]));
751 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]));
752 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]));
753 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]));
754 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]));
755 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]));
758 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]));
759 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]));
760 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]));
771 bool disconnected =
false;
772 bool connected =
false;
773 std::shared_ptr<device>
result;
774 std::condition_variable
cv;
780 std::unique_lock<std::mutex>
lock(m);
787 for (
auto cam : list)
791 std::unique_lock<std::mutex>
lock(m);
793 result = std::make_shared<device>(cam);
805 std::unique_lock<std::mutex>
lock(m);
807 return cv.wait_for(lock, std::chrono::seconds(20), [&]() {
return disconnected; });
809 REQUIRE(cv.wait_for(lock, std::chrono::seconds(20), [&]() { return connected; }));
815 for (
int i = 0;
i < 3; ++
i)
824 auto dev = std::make_shared<device>(list.
front());
835 if (!advanced.is_enabled())
845 REQUIRE(advanced.is_enabled());
852 REQUIRE(!advanced.is_enabled());
861 static const std::vector<res_type> resolutions = {
low_resolution,
872 auto dev = std::make_shared<device>(list.
front());
883 if (!advanced.is_enabled())
893 REQUIRE(advanced.is_enabled());
894 auto sensors = dev->query_sensors();
897 for (
sensor& elem : sensors)
899 auto supports =
false;
903 presets_sensor = elem;
909 for (
auto&
res : resolutions)
912 presets_sensor.
open(sp);
924 presets_sensor.
stop();
925 presets_sensor.
close();
934 REQUIRE(!advanced.is_enabled());
948 auto dev = std::make_shared<device>(list.
front());
959 if (!advanced.is_enabled())
969 REQUIRE(advanced.is_enabled());
971 auto sensors = dev->query_sensors();
973 for (
sensor& elem : sensors)
975 auto supports =
false;
979 presets_sensor = elem;
997 REQUIRE(!advanced.is_enabled());
1010 std::shared_ptr<device> dev = std::make_shared<device>(list.
front());
1022 if (!advanced.is_enabled())
1035 REQUIRE(advanced.is_enabled());
1046 REQUIRE(ctrl_curr == ctrl_min);
1058 REQUIRE(ctrl_curr == ctrl_min);
1063 REQUIRE_NOTHROW(ctrl_curr = advanced.get_rau_support_vector_control(0));
1065 REQUIRE_NOTHROW(ctrl_min = advanced.get_rau_support_vector_control(1));
1067 REQUIRE_NOTHROW(ctrl_max = advanced.get_rau_support_vector_control(2));
1069 REQUIRE_NOTHROW(ctrl_curr = advanced.get_rau_support_vector_control(0));
1070 REQUIRE(ctrl_curr == ctrl_min);
1082 REQUIRE(ctrl_curr == ctrl_min);
1094 REQUIRE(ctrl_curr == ctrl_min);
1099 REQUIRE_NOTHROW(ctrl_curr = advanced.get_slo_color_thresholds_control(0));
1101 REQUIRE_NOTHROW(ctrl_min = advanced.get_slo_color_thresholds_control(1));
1103 REQUIRE_NOTHROW(ctrl_max = advanced.get_slo_color_thresholds_control(2));
1105 REQUIRE_NOTHROW(ctrl_curr = advanced.get_slo_color_thresholds_control(0));
1106 REQUIRE(ctrl_curr == ctrl_min);
1118 REQUIRE(ctrl_curr == ctrl_min);
1127 REQUIRE(ctrl_curr1 == ctrl_curr2);
1139 REQUIRE(ctrl_curr == ctrl_min);
1148 REQUIRE(ctrl_curr1 == ctrl_curr2);
1160 REQUIRE(ctrl_curr == ctrl_min);
1172 REQUIRE(ctrl_curr == ctrl_min);
1184 REQUIRE(!advanced.is_enabled());
1190 TEST_CASE(
"Streaming modes sanity check",
"[live][!mayfail]")
1196 std::vector<sensor> list;
1201 for (
auto&& dev : list)
1211 REQUIRE(stream_profiles.size() > 0);
1213 SECTION(
"check stream profile settings are sane")
1216 for (
auto profile : stream_profiles) {
1226 REQUIRE(video.width() >= 320);
1227 REQUIRE(video.width() <= 1920);
1228 REQUIRE(video.height() >= 180);
1229 REQUIRE(video.height() <= 1080);
1242 SECTION(
"check stream intrinsics are sane")
1244 for (
auto profile : stream_profiles)
1254 bool calib_format = ((PID !=
"0AA5") &&
1291 std::vector<sensor> list;
1296 for (
auto&& dev : list)
1303 REQUIRE(stream_profiles.size() > 0);
1306 for (
auto profile : stream_profiles)
1308 SECTION(
"check motion intrisics") {
1320 for (
int j = 0;
j < 3;
j++)
1342 TEST_CASE(
"Check width and height of stream intrinsics",
"[live][AdvMd]")
1347 std::vector<device> devs;
1350 for (
auto&& dev : devs)
1352 auto shared_dev = std::make_shared<device>(
dev);
1362 if (advanced.is_enabled())
1372 REQUIRE(advanced.is_enabled() ==
false);
1375 std::vector<sensor> list;
1379 for (
auto&& dev : list)
1386 REQUIRE(stream_profiles.size() > 0);
1390 for (
const auto&
profile : stream_profiles)
1403 bool calib_format = ((PID !=
"0AA5") &&
1427 std::vector<sensor> list;
1432 for (
auto&& dev : list)
1438 bool is_opt_supported;
1444 if (!is_opt_supported)
1464 SECTION(
"get_option returns a legal value")
1466 if (!is_opt_supported)
1472 auto range = dev.get_option_range(opt);
1487 SECTION(
"set opt doesn't like bad values") {
1488 if (!is_opt_supported)
1494 auto range = dev.get_option_range(opt);
1514 for (
auto j = 1;
j <
range.step;
j++) {
1521 SECTION(
"check get/set sequencing works as expected") {
1522 if (!is_opt_supported)
continue;
1523 auto range = dev.get_option_range(opt);
1526 dev.set_option(opt,
range.min);
1533 dev.set_option(opt,
range.max);
1538 SECTION(
"get_description returns a non-empty, non-null string") {
1539 if (!is_opt_supported) {
1544 REQUIRE(dev.get_option_description(opt) !=
nullptr);
1562 std::vector<sensor> list;
1566 SECTION(
"subdevices on a single device")
1568 for (
auto & dev : list)
1572 SECTION(
"opening the same subdevice multiple times")
1574 auto modes = dev.get_stream_profiles();
1576 CAPTURE(modes.front().stream_type());
1591 if (modes.size() == 1)
1596 WARN(
"subdevice has only 1 supported streaming mode. Skipping Same Subdevice, different modes test.");
1612 SECTION(
"opening different subdevices") {
1620 if (subdevice1 == subdevice2)
1624 REQUIRE_NOTHROW(subdevice1.open(subdevice1.get_stream_profiles().front()));
1628 auto profile = subdevice2.get_stream_profiles().front();
1637 REQUIRE_NOTHROW(subdevice2.open(subdevice2.get_stream_profiles().front()));
1646 REQUIRE_NOTHROW(subdevice2.open(subdevice2.get_stream_profiles().front()));
1662 if (list.size() == 1)
1664 WARN(
"Only one device connected. Skipping multi-device test");
1668 for (
auto & dev1 : list)
1671 for (
auto & dev2 : list)
1679 auto dev1_profiles = dev1.get_stream_profiles();
1680 auto dev2_profiles = dev2.get_stream_profiles();
1682 if (!dev1_profiles.size() || !dev2_profiles.size())
1685 auto dev1_profile = dev1_profiles.front();
1686 auto dev2_profile = dev2_profiles.front();
1688 CAPTURE(dev1_profile.stream_type());
1689 CAPTURE(dev1_profile.format());
1695 CAPTURE(dev2_profile.stream_type());
1696 CAPTURE(dev2_profile.format());
1722 TEST_CASE(
"Multiple applications",
"[live][multicam][!mayfail]")
1728 std::vector<sensor> list1;
1734 std::vector<sensor> list2;
1736 REQUIRE(list2.size() == list1.size());
1737 SECTION(
"subdevices on a single device")
1739 for (
auto&& dev1 : list1)
1742 for (
auto&& dev2 : list2)
1748 bool skip_section =
false;
1750 skip_section =
true;
1756 std::vector<rs2::stream_profile> modes1, modes2;
1760 REQUIRE(modes1.size() == modes2.size());
1770 CAPTURE(modes1.front().stream_name());
1784 if (modes1.size() == 1)
1789 WARN(
"Device has only 1 supported streaming mode. Skipping Same Subdevice, different modes test.");
1807 SECTION(
"different subdevice")
1814 CAPTURE(dev2.get_stream_profiles().front().stream_type());
1838 SECTION(
"subdevices on separate devices")
1840 if (list1.size() == 1)
1842 WARN(
"Only one device connected. Skipping multi-device test");
1846 for (
auto & dev1 : list1)
1849 for (
auto & dev2 : list2)
1857 std::vector<rs2::stream_profile> modes1, modes2;
1864 CAPTURE(modes1.front().stream_type());
1911 int64_t last_val[3] = { -1, -1, -1 };
1913 for (
size_t i = 0;
i < data.size();
i++)
1919 if (data[
i].frame_md.md_attributes[
j].first)
1931 last_val[
j] = data[
i].frame_md.md_attributes[
j].second;
1947 std::vector<uint8_t> raw_data(24, 0);
1954 debug.send_and_receive_raw_data(raw_data);
1965 std::vector<sensor> list;
1971 std::condition_variable
cv;
1975 const std::map< uint8_t, std::string> error_report = {
1977 { 1,
"Laser hot - power reduce" },
1978 { 2,
"Laser hot - disabled" },
1979 { 3,
"Flag B - laser disabled" },
1983 for (
auto && subdevice : list) {
1991 std::unique_lock<std::mutex>
lock(m);
2001 for (
auto i = 1;
i < error_report.size();
i++)
2004 std::unique_lock<std::mutex>
lock(m);
2009 return notification_description.compare(error_report.at(
i)) == 0
2012 REQUIRE(cv.wait_for(lock, std::chrono::seconds(10), pred));
2026 std::vector<sensor> list;
2030 for (
auto && subdevice : list)
2040 SECTION(
"Disable auto exposure when setting a value")
2053 SECTION(
"Disable emitter when setting a value")
2055 for (
auto elem : { 0.f, 2.f })
2069 SECTION(
"Disable white balance when setting a value")
2092 std::shared_ptr<rs2::device>
dev;
2094 std::weak_ptr<rs2::device> weak_dev(dev);
2098 return std::pair<std::shared_ptr<rs2::device>, std::weak_ptr<rs2::device>>(
dev, weak_dev);
2106 strong = std::make_shared<rs2::device>(new_dev);
2120 auto dev_strong = dev.first;
2121 auto dev_weak = dev.second;
2124 auto disconnected =
false;
2125 auto connected =
false;
2131 std::condition_variable
cv;
2137 auto&& strong = dev_weak.lock();
2141 if (info.was_removed(*strong))
2143 std::unique_lock<std::mutex> lock(m);
2144 disconnected = true;
2149 for (auto d : info.get_new_devices())
2151 for (auto&& s : d.query_sensors())
2152 disable_sensitive_options_for(s);
2154 if (serial == d.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER))
2158 std::unique_lock<std::mutex> lock(m);
2176 dev_strong->hardware_reset();
2194 auto dev_strong = dev.first;
2195 auto dev_weak = dev.second;
2201 auto disconnected =
false;
2202 auto connected =
false;
2203 std::condition_variable
cv;
2209 auto&& strong = dev_weak.lock();
2213 if (info.was_removed(*strong))
2215 std::unique_lock<std::mutex> lock(m);
2216 disconnected = true;
2221 for (auto d : info.get_new_devices())
2223 if (serial == d.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER))
2227 std::unique_lock<std::mutex> lock(m);
2229 reset_device(dev_strong, dev_weak, list, d);
2248 dev_strong->hardware_reset();
2255 std::shared_ptr<std::condition_variable>
cv = std::make_shared<std::condition_variable>();
2256 std::shared_ptr<std::mutex>
m = std::make_shared<std::mutex>();
2257 std::shared_ptr<std::map<rs2_stream, int>> streams_frames = std::make_shared<std::map<rs2_stream, int>>();
2259 std::shared_ptr<std::function<void(rs2::frame fref)>>
func;
2261 std::vector<rs2::stream_profile> modes;
2264 auto streaming =
false;
2266 for (
auto p : modes)
2270 if (video.width() == 640 && video.height() == 480 && video.fps() == 60 && video.format())
2276 (*streams_frames)[
p.stream_type()] = 0;
2280 func = std::make_shared< std::function<void(rs2::frame fref)>>([num_of_frames,
m, streams_frames,
cv](
rs2::frame fref)
mutable 2282 std::unique_lock<std::mutex>
lock(*m);
2283 auto stream = fref.get_profile().stream_type();
2284 streams_frames->at(
stream)++;
2285 if (streams_frames->at(
stream) >= num_of_frames)
2296 std::unique_lock<std::mutex>
lock(*m);
2297 cv->wait_for(lock, std::chrono::seconds(30), [&]
2299 for (
auto f : (*streams_frames))
2301 if (
f.second < num_of_frames)
2307 if (!infinite && streaming)
2317 TEST_CASE(
"Connect Disconnect events while streaming",
"[live]") {
2327 auto dev_strong =
dev.first;
2328 auto dev_weak =
dev.second;
2334 auto disconnected =
false;
2335 auto connected =
false;
2336 std::condition_variable
cv;
2342 auto&& strong = dev_weak.lock();
2346 if (info.was_removed(*strong))
2348 std::unique_lock<std::mutex> lock(m);
2349 disconnected = true;
2354 for (auto d : info.get_new_devices())
2356 if (serial == d.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER))
2360 std::unique_lock<std::mutex> lock(m);
2362 reset_device(dev_strong, dev_weak, list, d);
2378 for (
auto&&
s : dev_strong->query_sensors())
2381 for (
auto i = 0;
i < 3;
i++)
2386 dev_strong->hardware_reset();
2389 for (
auto&&
s : dev_strong->query_sensors())
2392 disconnected = connected =
false;
2410 TEST_CASE(
"Connect Disconnect events while controls",
"[live]")
2419 auto dev_strong = dev.first;
2420 auto dev_weak = dev.second;
2427 auto disconnected =
false;
2428 auto connected =
false;
2429 std::condition_variable
cv;
2435 auto&& strong = dev_weak.lock();
2439 if (info.was_removed(*strong))
2441 std::unique_lock<std::mutex> lock(m);
2442 disconnected = true;
2446 for (auto d : info.get_new_devices())
2448 if (serial == d.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER))
2452 std::unique_lock<std::mutex> lock(m);
2454 reset_device(dev_strong, dev_weak, list, d);
2472 dev_strong->hardware_reset();
2475 for (
auto&&
s : dev_strong->query_sensors())
2485 std::shared_ptr<rs2::device>
dev;
2492 std::weak_ptr<rs2::device> weak(dev);
2496 dev->hardware_reset();
2500 std::this_thread::sleep_for(std::chrono::milliseconds(10));
2527 TEST_CASE(
"Auto-complete feature works",
"[offline][util::config]") {
2534 std::vector<stream_format> given;
2535 std::vector<stream_format> expected;
2537 std::vector<Test>
tests = {
2551 { { {
RS2_STREAM_INFRARED, 0, 0, 200,
RS2_FORMAT_ANY, 1 }, {
RS2_STREAM_DEPTH , 0, 0, 0,
RS2_FORMAT_ANY, -1 } },
2557 { { {
RS2_STREAM_DEPTH , 640, 480, 0,
RS2_FORMAT_ANY, -1 }, {
RS2_STREAM_INFRARED, 0, 0, 110,
RS2_FORMAT_ANY, 1 } },
2560 { { {
RS2_STREAM_DEPTH , 640, 480, 0,
RS2_FORMAT_ANY, -1 }, {
RS2_STREAM_INFRARED, 0, 0, 30,
RS2_FORMAT_ANY, 1 } },
2561 { {
RS2_STREAM_DEPTH , 640, 480, 30,
RS2_FORMAT_ANY, 0 }, {
RS2_STREAM_INFRARED, 640, 480, 30,
RS2_FORMAT_ANY, 1 } } },
2563 { { {
RS2_STREAM_INFRARED, 640, 480, 0,
RS2_FORMAT_ANY, 1 }, {
RS2_STREAM_DEPTH , 0, 0, 0,
RS2_FORMAT_ANY , 0 } },
2564 { {
RS2_STREAM_INFRARED, 640, 480, 10,
RS2_FORMAT_ANY, 1 }, {
RS2_STREAM_INFRARED, 640, 480, 30,
RS2_FORMAT_ANY , 1 },
2565 {
RS2_STREAM_DEPTH , 640, 480, 10,
RS2_FORMAT_ANY, 0 }, {
RS2_STREAM_DEPTH , 640, 480, 30,
RS2_FORMAT_ANY , 0 } } }
2571 for (
int i = 0;
i < tests.size(); ++
i)
2574 for (
auto &
profile : tests[
i].given) {
2579 if (tests[
i].expected.size() == 0) {
2699 std::vector<test_profile> actual_streams_arrived;
2700 for (
auto i = 0;
i <
frames.size();
i++)
2703 auto ts = timestamps[
i];
2704 if (
frame.size() == 0)
2710 std::vector<test_profile> stream_arrived;
2716 stream_arrived.push_back({
image.stream_type(),
image.format(),
image.width(),
image.height() });
2722 if (ts[ts.size() - 1] - ts[0] > (float)gap / (
float)2)
2725 CAPTURE((
float)gap / (
float)2);
2728 CAPTURE(ts[ts.size() - 1] - ts[0]);
2732 for (
auto&
str : stream_arrived)
2733 actual_streams_arrived.push_back(
str);
2735 if (stream_arrived.size() != requests.
streams.size())
2738 std::sort(stream_arrived.begin(), stream_arrived.end());
2742 for (
auto i = 0;
i < requests.
streams.size();
i++)
2744 if (stream_arrived[
i] != requests.
streams[
i])
2758 std::stringstream ss;
2759 ss <<
"Requested profiles : " << std::endl;
2760 for (
auto prof : requests.
streams)
2764 ss <<
STRINGIFY(prof.width) <<
" = " << prof.width << std::endl;
2765 ss <<
STRINGIFY(prof.height) <<
" = " << prof.height << std::endl;
2766 ss <<
STRINGIFY(prof.index) <<
" = " << prof.index << std::endl;
2773 ss <<
"\n\nReceived profiles : " << std::endl;
2774 std::sort(actual_streams_arrived.begin(), actual_streams_arrived.end());
2775 auto last = std::unique(actual_streams_arrived.begin(), actual_streams_arrived.end());
2776 actual_streams_arrived.erase(last, actual_streams_arrived.end());
2778 for (
auto prof : actual_streams_arrived)
2780 ss <<
STRINGIFY(prof.stream) <<
" = " << int(prof.stream) << std::endl;
2781 ss <<
STRINGIFY(prof.format) <<
" = " << int(prof.format) << std::endl;
2782 ss <<
STRINGIFY(prof.width) <<
" = " << prof.width << std::endl;
2783 ss <<
STRINGIFY(prof.height) <<
" = " << prof.height << std::endl;
2784 ss <<
STRINGIFY(prof.index) <<
" = " << prof.index << std::endl;
2792 { {
"0AD1",
true} ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30,
true}},
2793 { {
"0AD2",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30,
true }},
2794 { {
"0AD2",
false },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 640, 480, 0 } }, 15,
true } },
2795 { {
"0AD3",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 640, 480, 0 } }, 30,
true }},
2796 { {
"0AD3",
false },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 640, 480, 0 } }, 15,
true } },
2798 { {
"0AD5",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30,
true }},
2799 { {
"0AF6",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30,
true }},
2800 { {
"0AFE",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30,
true }},
2801 { {
"0AFF",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30,
true } },
2802 { {
"0B00",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30,
true } },
2803 { {
"0B01",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30,
true }},
2804 { {
"0B03",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30,
true }},
2805 { {
"0B07",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 1280, 720, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 640, 480, 0 } }, 30,
true }},
2806 { {
"0B07",
false },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 640, 480, 0 } }, 15,
true } },
2807 { {
"0AA5",
true } ,{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 1920, 1080, 0 } }, 30,
true } },
2831 WARN(
"Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ?
" USB3" :
" USB2"));
2839 std::vector<std::vector<rs2::stream_profile>>
frames;
2840 std::vector<std::vector<double>> timestamps;
2842 for (
auto i = 0;
i < 30;
i++)
2847 while (frames.size() < 100)
2851 std::vector<rs2::stream_profile> frames_set;
2852 std::vector<double> ts;
2854 for (
auto f : frame)
2862 frames_set.push_back(
f.get_profile());
2863 ts.push_back(
f.get_timestamp());
2865 frames.push_back(frames_set);
2866 timestamps.push_back(ts);
2899 WARN(
"Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ?
" USB3" :
" USB2"));
2907 std::vector<std::vector<rs2::stream_profile>>
frames;
2908 std::vector<std::vector<double>> timestamps;
2910 for (
auto i = 0;
i < 30;
i++)
2914 while (frames.size() < 100)
2919 std::vector<rs2::stream_profile> frames_set;
2920 std::vector<double> ts;
2921 for (
auto f : frame)
2929 frames_set.push_back(
f.get_profile());
2930 ts.push_back(
f.get_timestamp());
2932 frames.push_back(frames_set);
2933 timestamps.push_back(ts);
2945 { {
"0AD1",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 640, 480, 0 } }, 30,
true } },
2946 { {
"0AD2",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 640, 480, 0 } }, 30,
true } },
2947 { {
"0AD2",
false },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 480, 270, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 480, 270, 0 } }, 30,
true } },
2948 { {
"0AD3",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30,
true } },
2949 { {
"0AD3",
false },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 480, 270, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 424, 240, 0 } }, 30,
true } },
2950 { {
"0AD4",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_Y8, 640, 480, 1 } }, 30,
true } },
2951 { {
"0AD5",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 640, 480, 0 } }, 30,
true } },
2952 { {
"0AF6",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 640, 480, 0 } }, 30,
true } },
2953 { {
"0AFE",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 640, 480, 0 } }, 30,
true } },
2954 { {
"0AFF",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 640, 480, 0 } }, 30,
true } },
2955 { {
"0B00",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 640, 480, 0 } }, 30,
true } },
2956 { {
"0B01",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30,
true } },
2957 { {
"0B03",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 640, 480, 0 } }, 30,
true } },
2958 { {
"0B07",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 640, 480, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 1280, 720, 0 } }, 30,
true } },
2959 { {
"0B07",
false },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 480, 270, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 424, 240, 0 } }, 30,
true } },
2992 if (dev_requests.end() == dev_requests.find(PID))
2994 WARN(
"Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ?
" USB3" :
" USB2"));
3006 std::vector<std::vector<rs2::stream_profile>>
frames;
3007 std::vector<std::vector<double>> timestamps;
3009 for (
auto i = 0;
i < 30;
i++)
3014 while (frames.size() < 100)
3018 std::vector<rs2::stream_profile> frames_set;
3019 std::vector<double> ts;
3021 for (
auto f : frame)
3029 frames_set.push_back(
f.get_profile());
3030 ts.push_back(
f.get_timestamp());
3032 frames.push_back(frames_set);
3033 timestamps.push_back(ts);
3043 { {
"0AD1",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_ANY, 0, 0, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_ANY, 0, 0, 1 } }, 30,
true } },
3044 { {
"0AD2",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_ANY, 0, 0, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_ANY, 0, 0, 1 } }, 30,
true } },
3045 { {
"0AD2",
false },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 0, 0, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 0, 0, 0 } }, 15,
true } },
3049 { {
"0AD3",
false },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 0, 0, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 0, 0, 0 } }, 60,
true } },
3051 { {
"0AD5",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_ANY, 0, 0, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_ANY, 0, 0, 1 } }, 30,
true } },
3053 { {
"0AFE",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 0, 0, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 0, 0, 0 } }, 30,
true } },
3054 { {
"0AFF",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 0, 0, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 0, 0, 0 } }, 30,
true } },
3055 { {
"0B00",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 0, 0, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_RGB8, 0, 0, 0 } }, 30,
true } },
3056 { {
"0B01",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 0, 0, 0 },{
RS2_STREAM_COLOR,
RS2_FORMAT_RGB8, 0, 0, 0 } }, 30,
true } },
3057 { {
"0B03",
true },{ { {
RS2_STREAM_DEPTH,
RS2_FORMAT_Z16, 0, 0, 0 },{
RS2_STREAM_INFRARED,
RS2_FORMAT_ANY, 0, 0, 1 } }, 30,
true } },
3092 WARN(
"Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ?
" USB3" :
" USB2"));
3106 std::vector<std::vector<rs2::stream_profile>>
frames;
3107 std::vector<std::vector<double>> timestamps;
3109 for (
auto i = 0;
i < 30;
i++)
3114 while (frames.size() < 100)
3118 std::vector<rs2::stream_profile> frames_set;
3119 std::vector<double> ts;
3120 for (
auto f : frame)
3128 frames_set.push_back(
f.get_profile());
3129 ts.push_back(
f.get_timestamp());
3131 frames.push_back(frames_set);
3132 timestamps.push_back(ts);
3166 if ((not_default_configurations.end() == not_default_configurations.find(PID)) || ((default_configurations.find(PID) == default_configurations.end())))
3168 WARN(
"Skipping test - the Device-Under-Test profile is not defined properly for PID " << PID.first << (PID.second ?
" USB3" :
" USB2"));
3174 for (
auto req : not_default_configurations[PID].
streams)
3184 std::vector<std::vector<rs2::stream_profile>>
frames;
3185 std::vector<std::vector<double>> timestamps;
3187 for (
auto i = 0;
i < 30;
i++)
3190 auto actual_fps = default_configurations[PID].fps;
3192 while (frames.size() < 100)
3196 std::vector<rs2::stream_profile> frames_set;
3197 std::vector<double> ts;
3198 for (
auto f : frame)
3206 frames_set.push_back(
f.get_profile());
3207 ts.push_back(
f.get_timestamp());
3209 frames.push_back(frames_set);
3210 timestamps.push_back(ts);
3245 WARN(
"Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ?
" USB3" :
" USB2"));
3258 streams.erase(streams.end() - 1);
3264 std::vector<std::vector<rs2::stream_profile>>
frames;
3265 std::vector<std::vector<double>> timestamps;
3267 for (
auto i = 0;
i < 30;
i++)
3271 while (frames.size() < 100)
3275 std::vector<rs2::stream_profile> frames_set;
3276 std::vector<double> ts;
3277 for (
auto f : frame)
3285 frames_set.push_back(
f.get_profile());
3286 ts.push_back(
f.get_timestamp());
3288 frames.push_back(frames_set);
3289 timestamps.push_back(ts);
3340 bool operator==(std::vector<test_profile> streams1, std::vector<test_profile> streams2)
3342 if (streams1.size() != streams2.size())
3345 std::sort(streams1.begin(), streams1.end());
3346 std::sort(streams2.begin(), streams2.end());
3349 for (
auto i = 0;
i < streams1.size();
i++)
3351 if (streams1[
i] != streams2[
i])
3386 WARN(
"Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ?
" USB3" :
" USB2"));
3399 std::vector<device_profiles>
frames;
3401 for (
auto i = 0;
i < 10;
i++)
3408 for (
auto i = 0;
i < 20;
i++)
3411 std::vector<test_profile>
profiles;
3413 for (
auto i = 0;
i < 30;
i++)
3419 for (
auto f : frame)
3424 profiles.push_back({
profile.stream_type(),
3426 video_profile.width(),
3427 video_profile.height(),
3428 video_profile.stream_index() });
3431 if (profiles == streams)
3444 for (
auto i = 0;
i < 9;
i++)
3451 for (
auto i = 0;
i < 3;
i++)
3526 WARN(
"Skipping test - the Device-Under-Test profile is not defined for PID " << PID.first << (PID.second ?
" USB3" :
" USB2"));
3536 std::vector<rs2::stream_profile>
profiles;
3542 std::vector<test_profile> pipe_streams;
3543 for (
auto s : profiles)
3548 pipe_streams.push_back({ video.stream_type(), video.format(), video.width(), video.height(), video.stream_index() });
3550 REQUIRE(pipe_streams.size() == streams.size());
3552 std::sort(pipe_streams.begin(), pipe_streams.end());
3553 std::sort(streams.begin(), streams.end());
3555 for (
auto i = 0;
i < pipe_streams.size();
i++)
3563 TEST_CASE(
"Per-frame metadata sanity check",
"[live][!mayfail]") {
3568 std::vector<sensor> list;
3572 const int frames_before_start_measure = 10;
3573 const int frames_for_fps_measure = 50;
3574 const double msec_to_sec = 0.001;
3575 const int num_of_profiles_for_each_subdevice = 2;
3576 const float max_diff_between_real_and_metadata_fps = 1.0f;
3578 for (
auto && subdevice : list) {
3579 std::vector<rs2::stream_profile> modes;
3586 for (
int i = 0;
i < modes.size();
i +=
static_cast<int>(std::ceil((
float)modes.size() / (float)num_of_profiles_for_each_subdevice)))
3589 if (
auto video_profile = modes[
i].as<video_stream_profile>())
3591 if (video_profile.width() == 1920 && video_profile.height() == 1080 && video_profile.fps() == 60)
3604 if (
auto video = modes[
i].as<video_stream_profile>())
3610 std::vector<internal_frame_additional_data> frames_additional_data;
3613 std::condition_variable
cv;
3623 if ((frames >= frames_before_start_measure) && (frames_additional_data.size() < frames_for_fps_measure))
3627 start = internal::get_time();
3631 internal_frame_additional_data data{ f.get_timestamp(),
3632 f.get_frame_number(),
3633 f.get_frame_timestamp_domain(),
3634 f.get_profile().stream_type(),
3635 f.get_profile().format() };
3638 for (auto i = 0; i < rs2_frame_metadata_value::RS2_FRAME_METADATA_COUNT; i++)
3641 bool supported = false;
3642 REQUIRE_NOTHROW(supported = f.supports_frame_metadata((rs2_frame_metadata_value)i));
3645 rs2_metadata_type val{};
3646 REQUIRE_NOTHROW(val = f.get_frame_metadata((rs2_frame_metadata_value)i));
3647 data.frame_md.md_attributes[i] = std::make_pair(true, val);
3652 REQUIRE_THROWS(f.get_frame_metadata((rs2_frame_metadata_value)i));
3653 data.frame_md.md_attributes[i].first = false;
3658 std::unique_lock<std::mutex> lock(m);
3659 frames_additional_data.push_back(data);
3662 if (frames_additional_data.size() >= frames_for_fps_measure)
3669 CAPTURE(frames_additional_data.size());
3670 CAPTURE(frames_for_fps_measure);
3671 std::unique_lock<std::mutex>
lock(
m);
3672 cv.wait_for(lock, std::chrono::seconds(15), [&] {
return ((frames_additional_data.size() >= frames_for_fps_measure)); });
3680 auto seconds = (end -
start)*msec_to_sec;
3688 if (frames_additional_data.size())
3690 auto actual_fps = (double)frames_additional_data.size() / (double)seconds;
3691 double metadata_seconds = frames_additional_data[frames_additional_data.size() - 1].timestamp - frames_additional_data[0].timestamp;
3692 metadata_seconds *= msec_to_sec;
3694 if (metadata_seconds <= 0)
3696 std::cout <<
"Start metadata " << std::fixed << frames_additional_data[0].timestamp <<
"\n";
3697 std::cout <<
"End metadata " << std::fixed << frames_additional_data[frames_additional_data.size() - 1].timestamp <<
"\n";
3699 REQUIRE(metadata_seconds > 0);
3701 auto metadata_frames = frames_additional_data[frames_additional_data.size() - 1].frame_number - frames_additional_data[0].frame_number;
3702 auto metadata_fps = (double)metadata_frames / (
double)metadata_seconds;
3704 for (
auto i = 0;
i < frames_additional_data.size() - 1;
i++)
3707 CAPTURE(frames_additional_data[
i].timestamp_domain);
3708 CAPTURE(frames_additional_data[
i + 1].timestamp_domain);
3709 REQUIRE((frames_additional_data[
i].timestamp_domain == frames_additional_data[
i + 1].timestamp_domain));
3712 CAPTURE(frames_additional_data[
i + 1].frame_number);
3714 REQUIRE((frames_additional_data[
i].frame_number < frames_additional_data[
i + 1].frame_number));
3720 CAPTURE(frames_additional_data.size());
3725 REQUIRE(std::fabs(metadata_fps /
actual_fps - 1) < max_diff_between_real_and_metadata_fps);
3735 TEST_CASE(
"All suggested profiles can be opened",
"[live][!mayfail]") {
3742 const int num_of_profiles_for_each_subdevice = 2;
3744 std::vector<sensor> list;
3748 for (
auto && subdevice : list) {
3752 std::vector<rs2::stream_profile> modes;
3757 for (
int i = 0;
i < modes.size();
i += (int)std::ceil((
float)modes.size() / (float)num_of_profiles_for_each_subdevice)) {
3771 TEST_CASE(
"Pipeline config enable resolve start flow",
"[live]") {
3803 CAPTURE(depth_profile.stream_index());
3804 CAPTURE(depth_profile.stream_type());
3805 CAPTURE(depth_profile.format());
3807 CAPTURE(depth_profile.width());
3808 CAPTURE(depth_profile.height());
3809 std::vector<device_profiles>
frames;
3814 for (
auto i = 0;
i < 5;
i++)
3820 for (
auto i = 0;
i < 5;
i++)
3839 TEST_CASE(
"Pipeline - multicam scenario with specific devices",
"[live][multicam]") {
3846 int realsense_devices_count = 0;
3848 for (
auto&&
dev : list)
3853 if (name !=
"Platform Camera")
3855 realsense_devices_count++;
3860 if (realsense_devices_count < 2)
3862 WARN(
"Skipping test! This test requires multiple RealSense devices connected");
3879 required_profile = vid_profile;
3883 if (required_profile)
3896 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()));
3904 REQUIRE(resolved_profile_from_start);
3917 REQUIRE(actual_serial == required_serial);
3918 REQUIRE(actual_serial == actual_serial_from_start);
3921 std::vector<rs2::stream_profile> actual_streams;
3923 REQUIRE(actual_streams.size() == 1);
3924 REQUIRE(actual_streams[0] == required_profile);
3925 std::vector<rs2::stream_profile> actual_streams_from_start;
3927 REQUIRE(actual_streams_from_start.size() == 1);
3928 REQUIRE(actual_streams_from_start[0] == required_profile);
3939 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()));
3950 REQUIRE(started_serial == required_serial);
3953 std::vector<rs2::stream_profile> started_streams;
3955 REQUIRE(started_streams.size() == 1);
3956 REQUIRE(started_streams[0] == required_profile);
3980 std::vector<rs2::stream_profile> spv;
3996 if (serial1 != serial2)
3998 throw std::runtime_error(serial1 +
" is different than " + serial2);
4006 throw std::runtime_error(name1 +
" is different than " + name2);
4011 if (streams1.size() != streams2.size())
4016 auto streams1_and_2_equals =
true;
4017 for (
auto&&
s : streams1)
4021 s.format() == sp.format() &&
4022 s.fps() == sp.fps() &&
4023 s.is_default() == sp.is_default() &&
4024 s.stream_index() == sp.stream_index() &&
4025 s.stream_type() == sp.stream_type() &&
4026 s.stream_name() == sp.stream_name();
4028 if (
it == streams2.end())
4030 streams1_and_2_equals =
false;
4034 if (!streams1_and_2_equals)
4036 throw std::runtime_error(
std::string(
"Profiles contain different streams"));
4049 bool can_resolve =
false;
4069 bool can_resolve1 =
false;
4070 bool can_resolve2 =
false;
4087 TEST_CASE(
"Pipeline start after resolve uses the same profile",
"[live]") {
4106 TEST_CASE(
"Pipeline start ignores previous config if it was changed",
"[live]") {
4122 TEST_CASE(
"Pipeline Config disable all is a nop with empty config",
"[live]") {
4141 TEST_CASE(
"Pipeline Config disable each stream is nop on empty config",
"[live]") {
4178 auto dev = profile.get_device();
4182 std::this_thread::sleep_for(std::chrono::seconds(5));
4200 std::this_thread::sleep_for(std::chrono::seconds(5));
4210 TEST_CASE(
"Syncer sanity with software-device device",
"[live][software-device]") {
4218 std::shared_ptr<software_device>
dev =
std::move(std::make_shared<software_device>());
4219 auto s = dev->add_sensor(
"software_sensor");
4221 rs2_intrinsics intrinsics{
W,
H, 0, 0, 0, 0,
RS2_DISTORTION_NONE ,{ 0,0,0,0,0 } };
4229 auto profiles =
s.get_stream_profiles();
4237 std::vector<uint8_t>
pixels(W * H * BPP, 0);
4238 std::weak_ptr<rs2::software_device> weak_dev(dev);
4240 std::thread
t([&
s, weak_dev, pixels,
depth, ir]()
mutable {
4242 auto shared_dev = weak_dev.lock();
4243 if (shared_dev ==
nullptr)
4255 std::vector<std::vector<std::pair<rs2_stream, int>>> expected =
4263 std::vector<std::vector<std::pair<rs2_stream, int>>> results;
4265 for (
auto i = 0;
i < expected.size();
i++)
4269 std::vector < std::pair<rs2_stream, int>> curr;
4273 curr.push_back({
f.get_profile().stream_type(),
f.get_frame_number() });
4275 results.push_back(curr);
4280 REQUIRE(results.size() == expected.size());
4282 for (
auto i = 0;
i < expected.size();
i++)
4284 auto exp = expected[
i];
4285 auto curr = results[
i];
4289 REQUIRE(exp.size() == curr.size());
4291 for (
auto j = 0;
j < exp.size();
j++)
4304 TEST_CASE(
"Syncer clean_inactive_streams by frame number with software-device device",
"[live][software-device]") {
4313 std::shared_ptr<software_device>
dev = std::make_shared<software_device>();
4314 auto s = dev->add_sensor(
"software_sensor");
4316 rs2_intrinsics intrinsics{
W,
H, 0, 0, 0, 0,
RS2_DISTORTION_NONE ,{ 0,0,0,0,0 } };
4322 auto profiles = s.get_stream_profiles();
4330 std::vector<uint8_t>
pixels(W * H * BPP, 0);
4331 std::weak_ptr<rs2::software_device> weak_dev(dev);
4332 std::thread
t([s, weak_dev, pixels,
depth, ir]()
mutable {
4333 auto shared_dev = weak_dev.lock();
4334 if (shared_dev ==
nullptr)
4352 std::vector<std::vector<std::pair<rs2_stream, int>>> expected =
4363 std::vector<std::vector<std::pair<rs2_stream, int>>> results;
4365 for (
auto i = 0;
i < expected.size();
i++)
4370 std::vector < std::pair<rs2_stream, int>> curr;
4374 curr.push_back({
f.get_profile().stream_type(),
f.get_frame_number() });
4376 results.push_back(curr);
4381 REQUIRE(results.size() == expected.size());
4383 for (
auto i = 0;
i < expected.size();
i++)
4385 auto exp = expected[
i];
4386 auto curr = results[
i];
4390 REQUIRE(exp.size() == exp.size());
4392 for (
auto j = 0;
j < exp.size();
j++)
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
bool operator==(const test_profile &other) const
GLboolean GLboolean GLboolean b
void reset_device(std::shared_ptr< rs2::device > &strong, std::weak_ptr< rs2::device > &weak, device_list &list, const rs2::device &new_dev)
bool is_connected(const device &dev) const
GLenum GLuint GLenum severity
void check_controls_sanity(const rs2::context &ctx, const sensor &dev)
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
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)
void validate(std::vector< std::vector< rs2::stream_profile >> frames, std::vector< std::vector< double >> timestamps, device_profiles requests, int actual_fps)
device get_sensor_parent(const sensor &s) const
GLenum GLenum GLenum GLenum GLenum scale
bool wait_for_reset(std::function< bool(void)> func, std::shared_ptr< device > dev)
#define REQUIRE_THROWS_AS(expr, exceptionType)
void disable_sensitive_options_for(sensor &sen)
device_list query_devices() const
rs2_log_severity get_severity() const
TEST_CASE("Sync sanity","[live]")
std::string get_folder_path(special_folder f)
GLint GLint GLsizei GLsizei GLsizei depth
std::pair< std::string, bool > dev_type
GLsizei const GLchar *const * string
std::string get_description() const
void enable_device(const std::string &serial)
bool get_mode(rs2::device &dev, rs2::stream_profile *profile, int mode_index=0)
void trigger_error(const rs2::device &dev, int num)
GLsizei GLsizei GLfloat distance
void require_zero_vector(const float(&vector)[3])
void sort(sort_type m_sort_type, const std::string &in, const std::string &out)
GLenum GLenum GLsizei void * image
frameset wait_for_frames(unsigned int timeout_ms=5000) const
GLboolean GLboolean GLboolean GLboolean a
static const textual_icon usb_type
def info(name, value, persistent=False)
static const std::map< dev_type, device_profiles > pipeline_default_configurations
bool poll_for_frames(frameset *f) const
std::shared_ptr< rs2_config > get() const
bool is_usb3(const rs2::device &dev)
std::shared_ptr< device > do_with_waiting_for_camera_connection(rs2::context ctx, std::shared_ptr< device > dev, std::string serial, std::function< void()> operation)
void disable_all_streams()
void dev_changed(rs2_device_list *removed_devs, rs2_device_list *added_devs, void *ptr)
dev_type get_PID(rs2::device &dev)
bool operator==(const video_stream_profile &other) const
const char * get_info(rs2_camera_info info) const
void require_rotation_matrix(const float(&matrix)[9])
GLint GLsizei GLsizei height
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])
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])
rs2_format
A stream's format identifies how binary data is encoded within a frame.
#define CHECK_THROWS(...)
bool compare(const rs2_extrinsics &first, const rs2_extrinsics &second, double delta=0)
std::pair< std::string, bool > dev_type
bool operator!=(const test_profile &other) const
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 supports(rs2_camera_info info) const
bool make_context(const char *id, rs2::context *ctx, std::string min_api_version="0.0.0")
std::vector< test_profile > configure_all_supported_streams(rs2::sensor &sensor, int width=640, int height=480, int fps=60)
void require_identity_matrix(const float(&matrix)[9])
void require_pipeline_profile_same(const rs2::pipeline_profile &profile1, const rs2::pipeline_profile &profile2)
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented...
rs2_format format() const
GLdouble GLdouble GLdouble q
pipeline_profile resolve(std::shared_ptr< rs2_pipeline > p) const
std::vector< stream_profile > get_streams() const
void enable_record_to_file(const std::string &file_name)
GLbitfield GLuint64 timeout
std::pair< std::shared_ptr< rs2::device >, std::weak_ptr< rs2::device > > make_device(device_list &list)
static const std::map< dev_type, device_profiles > pipeline_autocomplete_configurations
std::shared_ptr< std::function< void(rs2::frame fref)> > check_stream_sanity(const rs2::context &ctx, const rs2::sensor &sub, int num_of_frames, bool infinite=false)
static const std::map< dev_type, device_profiles > pipeline_configurations_for_extrinsic
rs2_rs400_visual_preset
For RS400 devices: provides optimized settings (presets) for specific types of usage.
static const std::map< dev_type, device_profiles > pipeline_custom_configurations
bool operator<(const test_profile &other) const
#define SECTION_FROM_TEST_NAME
typename::boost::move_detail::remove_reference< T >::type && move(T &&t) BOOST_NOEXCEPT
void open(const stream_profile &profile) const
void set_devices_changed_callback(T callback)
std::vector< test_profile > streams
void rs2_set_devices_changed_callback(const rs2_context *context, rs2_devices_changed_callback_ptr callback, void *user, rs2_error **error)
#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 enable_device_from_file(const std::string &file_name, bool repeat_playback=true)
option_range get_option_range(rs2_option option) const
bool file_exists(const std::string &filename)
pipeline_profile get_active_profile() const
device wait_for_device() const
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
float get_option(rs2_option option) const
void metadata_verification(const std::vector< internal_frame_additional_data > &data)
void start(T callback) const
void copy(void *dst, void const *src, size_t size)
std::string to_string(T value)