forked from jerry73204/realsense-rust
-
Notifications
You must be signed in to change notification settings - Fork 8
/
connectivity_l500.rs
265 lines (225 loc) · 9.75 KB
/
connectivity_l500.rs
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
//! Tests for evaluating connectivity / configuration of sensors
#![cfg(feature = "test-single-device")]
use realsense_rust::{
config::Config,
context::Context,
frame::{ColorFrame, DepthFrame, InfraredFrame},
kind::{Rs2CameraInfo, Rs2Format, Rs2Option, Rs2ProductLine, Rs2StreamKind},
pipeline::InactivePipeline,
};
use std::{
collections::{HashMap, HashSet},
convert::TryFrom,
time::Duration,
};
#[test]
fn l500_can_resolve_color_and_depth_and_infrared() {
let context = Context::new().unwrap();
let mut queryable_set = HashSet::new();
queryable_set.insert(Rs2ProductLine::L500);
let devices = context.query_devices(queryable_set);
if let Some(device) = devices.first() {
let serial = device.info(Rs2CameraInfo::SerialNumber).unwrap();
let mut config = Config::new();
config
.enable_device_from_serial(serial)
.unwrap()
.disable_all_streams()
.unwrap()
.enable_stream(Rs2StreamKind::Color, None, 0, 0, Rs2Format::Rgba8, 30)
.unwrap()
.enable_stream(Rs2StreamKind::Depth, Some(0), 0, 0, Rs2Format::Z16, 30)
.unwrap()
.enable_stream(Rs2StreamKind::Infrared, Some(0), 0, 0, Rs2Format::Y8, 30)
.unwrap();
let pipeline = InactivePipeline::try_from(&context).unwrap();
assert!(pipeline.can_resolve(&config));
assert!(pipeline.resolve(&config).is_some());
}
}
#[test]
fn l500_streams_at_expected_framerate() {
let context = Context::new().unwrap();
let mut queryable_set = HashSet::new();
queryable_set.insert(Rs2ProductLine::L500);
let devices = context.query_devices(queryable_set);
if let Some(device) = devices.first() {
let serial = device.info(Rs2CameraInfo::SerialNumber).unwrap();
let mut config = Config::new();
let usb_cstr = device.info(Rs2CameraInfo::UsbTypeDescriptor).unwrap();
let usb_val: f32 = usb_cstr.to_str().unwrap().parse().unwrap();
let framerate = 30;
let stream_count: usize;
if usb_val >= 3.0 {
stream_count = 2;
config
.enable_device_from_serial(serial)
.unwrap()
.disable_all_streams()
.unwrap()
.enable_stream(Rs2StreamKind::Depth, None, 0, 0, Rs2Format::Z16, framerate)
.unwrap()
.enable_stream(
Rs2StreamKind::Infrared,
None,
0,
0,
Rs2Format::Y8,
framerate,
)
.unwrap();
} else {
stream_count = 1;
config
.enable_device_from_serial(serial)
.unwrap()
.disable_all_streams()
.unwrap()
.enable_stream(Rs2StreamKind::Depth, None, 0, 0, Rs2Format::Z16, framerate)
.unwrap();
}
let pipeline = InactivePipeline::try_from(&context).unwrap();
assert!(pipeline.can_resolve(&config));
let mut pipeline = pipeline.start(Some(config)).unwrap();
let mut nframes = 0usize;
let number_of_seconds = 5;
let iters = number_of_seconds * framerate;
let begin = std::time::SystemTime::now();
let mut first_iter_time = 0;
for i in 0..iters {
let frames = if i == 0 {
// The first frame captured always seems to have a delay.
//
// For the L515, this is observably around 1.5s, but can probably be worse than
// this. Instead, we choose the default timeout for the first frame.
let frames = pipeline.wait(None).unwrap();
first_iter_time = begin.elapsed().unwrap().as_millis();
frames
} else {
pipeline.wait(Some(Duration::from_millis(50))).unwrap()
};
nframes += frames.count();
}
let elapsed_time_ms = begin.elapsed().unwrap().as_millis();
let expected_time_ms = 1000 * (number_of_seconds as u128);
let absdiff_from_expected = if elapsed_time_ms > expected_time_ms {
elapsed_time_ms - expected_time_ms
} else {
expected_time_ms - elapsed_time_ms
};
assert!(
absdiff_from_expected <= first_iter_time + 200,
"Difference in time from expected time: {}",
absdiff_from_expected
);
assert_eq!(nframes, framerate * number_of_seconds * stream_count);
}
}
#[test]
fn l500_streams_are_distinct() {
let context = Context::new().unwrap();
let mut queryable_set = HashSet::new();
queryable_set.insert(Rs2ProductLine::L500);
let devices = context.query_devices(queryable_set);
if let Some(device) = devices.first() {
let serial = device.info(Rs2CameraInfo::SerialNumber).unwrap();
let mut config = Config::new();
config
.enable_device_from_serial(serial)
.unwrap()
.disable_all_streams()
.unwrap()
.enable_stream(Rs2StreamKind::Color, None, 0, 0, Rs2Format::Yuyv, 30)
.unwrap()
.enable_stream(Rs2StreamKind::Depth, None, 0, 0, Rs2Format::Z16, 30)
.unwrap()
.enable_stream(Rs2StreamKind::Infrared, None, 0, 0, Rs2Format::Y8, 30)
.unwrap();
let pipeline = InactivePipeline::try_from(&context).unwrap();
let mut pipeline = pipeline.start(Some(config)).unwrap();
let frames = pipeline.wait(None).unwrap();
assert_eq!(frames.count(), 3);
assert_eq!(frames.frames_of_type::<ColorFrame>().len(), 1);
assert_eq!(frames.frames_of_type::<DepthFrame>().len(), 1);
assert_eq!(frames.frames_of_type::<InfraredFrame>().len(), 1);
}
}
// Options we will attempt to set
fn possible_options_and_vals_map() -> HashMap<Rs2Option, Option<f32>> {
let mut options_set = HashMap::<Rs2Option, Option<f32>>::new();
options_set.insert(Rs2Option::GlobalTimeEnabled, Some(1.0));
options_set
}
// Options we know are ignored, and their actual returned values on `get_option`
fn supported_but_ignored_options_and_vals_map() -> HashMap<Rs2Option, Option<f32>> {
let mut options_ignored = HashMap::<Rs2Option, Option<f32>>::new();
options_ignored.insert(Rs2Option::GlobalTimeEnabled, Some(0.0));
options_ignored
}
/// Check for supported but ignored sensor options.
///
/// This test is a direct result of decisions made in the Intel RealSense SDK to obfuscate the behavior of a few sensor
/// options. There are a few Options that are registered as "supported" by the sensor, but are actually just set to
/// their default values on runtime. These options are listed in `supported_but_ignored_options_and_vals_map()` above.
///
/// Currently, [Rs2Option::GlobalTimeEnabled] on the L500 is the only setting known to suffer from this. However, this
/// test has been written in a way that makes it easy to test more Options for this same behavior.
///
/// A ticket addressing this issue in the RealSense SDK can be found
/// [here](https://github.com/IntelRealSense/librealsense/issues/8579)
///
#[test]
fn l500_streams_check_supported_but_ignored_sensor_options() {
let options_to_set = possible_options_and_vals_map();
let options_ignored = supported_but_ignored_options_and_vals_map();
let context = Context::new().unwrap();
let mut queryable_set = HashSet::new();
queryable_set.insert(Rs2ProductLine::L500);
let devices = context.query_devices(queryable_set);
if let Some(device) = devices.first() {
// Grab the sensor list
for mut sensor in device.sensors() {
for (option, val) in &options_to_set {
// We unwrap here because we don't care about the result of the set for this test. RealSense is pretty
// tricky when it comes to what can be set and what can't; the best way to check this would be to use
// `sensor.supports_option` or `sensor.is_option_read_only`.
//
// However, there are exceptions, as one can see from setting GlobalTimeEnabled on the L500 series.
sensor.set_option(*option, val.unwrap()).unwrap();
}
}
let serial = device.info(Rs2CameraInfo::SerialNumber).unwrap();
let mut config = Config::new();
config
.enable_device_from_serial(serial)
.unwrap()
.disable_all_streams()
.unwrap()
.enable_stream(Rs2StreamKind::Color, None, 0, 0, Rs2Format::Yuyv, 30)
.unwrap()
.enable_stream(Rs2StreamKind::Depth, None, 0, 0, Rs2Format::Z16, 30)
.unwrap()
.enable_stream(Rs2StreamKind::Infrared, None, 0, 0, Rs2Format::Y8, 30)
.unwrap();
let pipeline = InactivePipeline::try_from(&context).unwrap();
let _pipeline = pipeline.start(Some(config)).unwrap();
for sensor in device.sensors() {
for (option, val) in &options_to_set {
// Check that the Options we wanted to set are
// 1. Theoretically supported by the sensor, but
// 2. Actually discarded when set.
if options_ignored.contains_key(option) {
assert!(sensor.supports_option(*option));
assert_ne!(
sensor.get_option(*option),
*options_ignored.get(option).unwrap()
);
}
// If we get here, it means that the option should actually set successfully. Fail if it's not.
else {
assert_eq!(sensor.get_option(*option), *val);
}
}
}
}
}