1use cfg_if::cfg_if;
2
3cfg_if! {
4 if #[cfg(all(target_os = "linux", not(target_env = "musl"), feature = "libudev"))]{
5 use std::ffi::OsStr;
6 }
7}
8
9cfg_if! {
10 if #[cfg(any(target_os = "ios", target_os = "macos"))] {
11 use core_foundation::base::CFType;
12 use core_foundation::base::TCFType;
13 use core_foundation::dictionary::CFDictionary;
14 use core_foundation::dictionary::CFMutableDictionary;
15 use core_foundation::number::CFNumber;
16 use core_foundation::string::CFString;
17 use core_foundation_sys::base::{kCFAllocatorDefault, CFRetain};
18 use io_kit_sys::*;
19 use io_kit_sys::keys::*;
20 use io_kit_sys::serial::keys::*;
21 use io_kit_sys::types::*;
22 use io_kit_sys::usb::lib::*;
23 use nix::libc::{c_char, c_void};
24 use std::ffi::CStr;
25 use std::mem::MaybeUninit;
26 }
27}
28
29#[cfg(any(
30 target_os = "freebsd",
31 target_os = "ios",
32 target_os = "linux",
33 target_os = "macos"
34))]
35use crate::SerialPortType;
36#[cfg(any(target_os = "ios", target_os = "linux", target_os = "macos"))]
37use crate::UsbPortInfo;
38#[cfg(any(
39 target_os = "android",
40 target_os = "ios",
41 all(target_os = "linux", not(target_env = "musl"), feature = "libudev"),
42 target_os = "macos",
43 target_os = "netbsd",
44 target_os = "openbsd",
45))]
46use crate::{Error, ErrorKind};
47use crate::{Result, SerialPortInfo};
48
49#[cfg(all(target_os = "linux", not(target_env = "musl"), feature = "libudev"))]
52fn udev_property_as_string(d: &libudev::Device, key: &str) -> Option<String> {
53 d.property_value(key)
54 .and_then(OsStr::to_str)
55 .map(|s| s.to_string())
56}
57
58#[cfg(all(target_os = "linux", not(target_env = "musl"), feature = "libudev"))]
65fn udev_hex_property_as_int<T>(
66 d: &libudev::Device,
67 key: &str,
68 from_str_radix: &dyn Fn(&str, u32) -> std::result::Result<T, std::num::ParseIntError>,
69) -> Result<T> {
70 if let Some(hex_str) = d.property_value(key).and_then(OsStr::to_str) {
71 if let Ok(num) = from_str_radix(hex_str, 16) {
72 Ok(num)
73 } else {
74 Err(Error::new(ErrorKind::Unknown, "value not hex string"))
75 }
76 } else {
77 Err(Error::new(ErrorKind::Unknown, "key not found"))
78 }
79}
80
81#[cfg(all(target_os = "linux", not(target_env = "musl"), feature = "libudev"))]
89fn udev_property_encoded_or_replaced_as_string(
90 d: &libudev::Device,
91 encoded_key: &str,
92 replaced_key: &str,
93) -> Option<String> {
94 udev_property_as_string(d, encoded_key)
95 .and_then(|s| unescaper::unescape(&s).ok())
96 .or_else(|| udev_property_as_string(d, replaced_key))
97 .map(udev_restore_spaces)
98}
99
100#[cfg(all(target_os = "linux", not(target_env = "musl"), feature = "libudev"))]
108fn udev_restore_spaces(source: String) -> String {
109 source.replace('_', " ")
110}
111
112#[cfg(all(target_os = "linux", not(target_env = "musl"), feature = "libudev"))]
113fn port_type(d: &libudev::Device) -> Result<SerialPortType> {
114 match d.property_value("ID_BUS").and_then(OsStr::to_str) {
115 Some("usb") => {
116 let serial_number = udev_property_as_string(d, "ID_SERIAL_SHORT");
117 let manufacturer =
121 udev_property_encoded_or_replaced_as_string(d, "ID_VENDOR_ENC", "ID_VENDOR")
122 .or_else(|| udev_property_as_string(d, "ID_VENDOR_FROM_DATABASE"));
123 let product =
124 udev_property_encoded_or_replaced_as_string(d, "ID_MODEL_ENC", "ID_MODEL")
125 .or_else(|| udev_property_as_string(d, "ID_MODEL_FROM_DATABASE"));
126 Ok(SerialPortType::UsbPort(UsbPortInfo {
127 vid: udev_hex_property_as_int(d, "ID_VENDOR_ID", &u16::from_str_radix)?,
128 pid: udev_hex_property_as_int(d, "ID_MODEL_ID", &u16::from_str_radix)?,
129 serial_number,
130 manufacturer,
131 product,
132 #[cfg(feature = "usbportinfo-interface")]
133 interface: udev_hex_property_as_int(d, "ID_USB_INTERFACE_NUM", &u8::from_str_radix)
134 .ok(),
135 }))
136 }
137 Some("pci") => {
138 let usb_properties = vec![
139 d.property_value("ID_USB_VENDOR_ID"),
140 d.property_value("ID_USB_MODEL_ID"),
141 ]
142 .into_iter()
143 .collect::<Option<Vec<_>>>();
144 if usb_properties.is_some() {
145 let manufacturer = udev_property_encoded_or_replaced_as_string(
148 d,
149 "ID_USB_VENDOR_ENC",
150 "ID_USB_VENDOR",
151 );
152 let product = udev_property_encoded_or_replaced_as_string(
153 d,
154 "ID_USB_MODEL_ENC",
155 "ID_USB_MODEL",
156 );
157 Ok(SerialPortType::UsbPort(UsbPortInfo {
158 vid: udev_hex_property_as_int(d, "ID_USB_VENDOR_ID", &u16::from_str_radix)?,
159 pid: udev_hex_property_as_int(d, "ID_USB_MODEL_ID", &u16::from_str_radix)?,
160 serial_number: udev_property_as_string(d, "ID_USB_SERIAL_SHORT"),
161 manufacturer,
162 product,
163 #[cfg(feature = "usbportinfo-interface")]
164 interface: udev_hex_property_as_int(
165 d,
166 "ID_USB_INTERFACE_NUM",
167 &u8::from_str_radix,
168 )
169 .ok(),
170 }))
171 } else {
172 Ok(SerialPortType::PciPort)
173 }
174 }
175 None if is_rfcomm(d) => Ok(SerialPortType::BluetoothPort),
176 None => find_usb_interface_from_parents(d.parent())
177 .and_then(get_modalias_from_device)
178 .as_deref()
179 .and_then(parse_modalias)
180 .map_or(Ok(SerialPortType::Unknown), |port_info| {
181 Ok(SerialPortType::UsbPort(port_info))
182 }),
183 _ => Ok(SerialPortType::Unknown),
184 }
185}
186
187#[cfg(all(target_os = "linux", not(target_env = "musl"), feature = "libudev"))]
188fn find_usb_interface_from_parents(parent: Option<libudev::Device>) -> Option<libudev::Device> {
189 let mut p = parent?;
190
191 for _ in 1..4 {
193 match p.devtype() {
194 None => match p.parent() {
195 None => break,
196 Some(x) => p = x,
197 },
198 Some(s) => {
199 if s.to_str()? == "usb_interface" {
200 break;
201 } else {
202 match p.parent() {
203 None => break,
204 Some(x) => p = x,
205 }
206 }
207 }
208 }
209 }
210
211 Some(p)
212}
213
214#[cfg(all(target_os = "linux", not(target_env = "musl"), feature = "libudev"))]
215fn get_modalias_from_device(d: libudev::Device) -> Option<String> {
216 Some(
217 d.property_value("MODALIAS")
218 .and_then(OsStr::to_str)?
219 .to_owned(),
220 )
221}
222
223#[cfg(all(target_os = "linux", not(target_env = "musl"), feature = "libudev"))]
235fn parse_modalias(moda: &str) -> Option<UsbPortInfo> {
236 let mod_start = moda.find("usb:v")?;
238
239 let mut mod_tail = moda.get(mod_start + 5..)?;
241
242 let vid = mod_tail.get(..4)?;
244 mod_tail = mod_tail.get(4..)?;
245
246 let pid_start = mod_tail.find('p')?;
248 let pid = mod_tail.get(pid_start + 1..pid_start + 5)?;
249
250 Some(UsbPortInfo {
251 vid: u16::from_str_radix(vid, 16).ok()?,
252 pid: u16::from_str_radix(pid, 16).ok()?,
253 serial_number: None,
254 manufacturer: None,
255 product: None,
256 #[cfg(feature = "usbportinfo-interface")]
258 interface: mod_tail.get(pid_start + 4..).and_then(|mod_tail| {
259 mod_tail.find("in").and_then(|i_start| {
260 mod_tail
261 .get(i_start + 2..i_start + 4)
262 .and_then(|interface| u8::from_str_radix(interface, 16).ok())
263 })
264 }),
265 })
266}
267
268#[cfg(any(target_os = "ios", target_os = "macos"))]
269fn get_parent_device_by_type(
270 device: io_object_t,
271 parent_type: *const c_char,
272) -> Option<io_registry_entry_t> {
273 let parent_type = unsafe { CStr::from_ptr(parent_type) };
274 use mach2::kern_return::KERN_SUCCESS;
275 let mut device = device;
276 loop {
277 let mut class_name = MaybeUninit::<[c_char; 128]>::uninit();
278 unsafe { IOObjectGetClass(device, class_name.as_mut_ptr() as *mut c_char) };
279 let class_name = unsafe { class_name.assume_init() };
280 let name = unsafe { CStr::from_ptr(&class_name[0]) };
281 if name == parent_type {
282 return Some(device);
283 }
284 let mut parent = MaybeUninit::uninit();
285 if unsafe {
286 IORegistryEntryGetParentEntry(device, kIOServiceClass, parent.as_mut_ptr())
287 != KERN_SUCCESS
288 } {
289 return None;
290 }
291 device = unsafe { parent.assume_init() };
292 }
293}
294
295#[cfg(any(target_os = "ios", target_os = "macos"))]
296#[allow(non_upper_case_globals)]
297fn get_int_property(device_type: io_registry_entry_t, property: &str) -> Result<u32> {
299 let cf_property = CFString::new(property);
300
301 let cf_type_ref = unsafe {
302 IORegistryEntryCreateCFProperty(
303 device_type,
304 cf_property.as_concrete_TypeRef(),
305 kCFAllocatorDefault,
306 0,
307 )
308 };
309 if cf_type_ref.is_null() {
310 return Err(Error::new(ErrorKind::Unknown, "Failed to get property"));
311 }
312
313 let cf_type = unsafe { CFType::wrap_under_create_rule(cf_type_ref) };
314 cf_type
315 .downcast::<CFNumber>()
316 .and_then(|n| n.to_i64())
317 .map(|n| n as u32)
318 .ok_or(Error::new(
319 ErrorKind::Unknown,
320 "Failed to get numerical value",
321 ))
322}
323
324#[cfg(any(target_os = "ios", target_os = "macos"))]
325fn get_string_property(device_type: io_registry_entry_t, property: &str) -> Result<String> {
327 let cf_property = CFString::new(property);
328
329 let cf_type_ref = unsafe {
330 IORegistryEntryCreateCFProperty(
331 device_type,
332 cf_property.as_concrete_TypeRef(),
333 kCFAllocatorDefault,
334 0,
335 )
336 };
337 if cf_type_ref.is_null() {
338 return Err(Error::new(ErrorKind::Unknown, "Failed to get property"));
339 }
340
341 let cf_type = unsafe { CFType::wrap_under_create_rule(cf_type_ref) };
342 cf_type
343 .downcast::<CFString>()
344 .map(|s| s.to_string())
345 .ok_or(Error::new(ErrorKind::Unknown, "Failed to get string value"))
346}
347
348#[cfg(any(target_os = "ios", target_os = "macos"))]
349fn port_type(service: io_object_t) -> SerialPortType {
352 let bluetooth_device_class_name = b"IOBluetoothSerialClient\0".as_ptr() as *const c_char;
353 let usb_device_class_name = b"IOUSBHostInterface\0".as_ptr() as *const c_char;
354 let legacy_usb_device_class_name = kIOUSBDeviceClassName;
355
356 let maybe_usb_device = get_parent_device_by_type(service, usb_device_class_name)
357 .or_else(|| get_parent_device_by_type(service, legacy_usb_device_class_name));
358 if let Some(usb_device) = maybe_usb_device {
359 SerialPortType::UsbPort(UsbPortInfo {
360 vid: get_int_property(usb_device, "idVendor").unwrap_or_default() as u16,
361 pid: get_int_property(usb_device, "idProduct").unwrap_or_default() as u16,
362 serial_number: get_string_property(usb_device, "USB Serial Number").ok(),
363 manufacturer: get_string_property(usb_device, "USB Vendor Name").ok(),
364 product: get_string_property(usb_device, "USB Product Name").ok(),
365 #[cfg(feature = "usbportinfo-interface")]
372 interface: get_int_property(usb_device, "bInterfaceNumber")
373 .map(|x| x as u8)
374 .ok(),
375 })
376 } else if get_parent_device_by_type(service, bluetooth_device_class_name).is_some() {
377 SerialPortType::BluetoothPort
378 } else {
379 SerialPortType::PciPort
380 }
381}
382
383cfg_if! {
384 if #[cfg(any(target_os = "ios", target_os = "macos"))] {
385 pub fn available_ports() -> Result<Vec<SerialPortInfo>> {
388 use mach2::kern_return::KERN_SUCCESS;
389 use mach2::port::{mach_port_t, MACH_PORT_NULL};
390
391 let mut vec = Vec::new();
392 unsafe {
393 let classes_to_match = IOServiceMatching(kIOSerialBSDServiceValue);
395 if classes_to_match.is_null() {
396 return Err(Error::new(
397 ErrorKind::Unknown,
398 "IOServiceMatching returned a NULL dictionary.",
399 ));
400 }
401 let mut classes_to_match = CFMutableDictionary::wrap_under_create_rule(classes_to_match);
402
403 let search_key = CStr::from_ptr(kIOSerialBSDTypeKey);
406 let search_key = CFString::from_static_string(search_key.to_str().map_err(|_| Error::new(ErrorKind::Unknown, "Failed to convert search key string"))?);
407 let search_value = CStr::from_ptr(kIOSerialBSDAllTypes);
408 let search_value = CFString::from_static_string(search_value.to_str().map_err(|_| Error::new(ErrorKind::Unknown, "Failed to convert search key string"))?);
409 classes_to_match.set(search_key, search_value);
410
411 let mut master_port: mach_port_t = MACH_PORT_NULL;
413 let mut kern_result = IOMasterPort(MACH_PORT_NULL, &mut master_port);
414 if kern_result != KERN_SUCCESS {
415 return Err(Error::new(
416 ErrorKind::Unknown,
417 format!("ERROR: {}", kern_result),
418 ));
419 }
420
421 CFRetain(classes_to_match.as_CFTypeRef());
428 let mut matching_services = MaybeUninit::uninit();
429 kern_result = IOServiceGetMatchingServices(
430 kIOMasterPortDefault,
431 classes_to_match.as_concrete_TypeRef(),
432 matching_services.as_mut_ptr(),
433 );
434 if kern_result != KERN_SUCCESS {
435 return Err(Error::new(
436 ErrorKind::Unknown,
437 format!("ERROR: {}", kern_result),
438 ));
439 }
440 let matching_services = matching_services.assume_init();
441 let _matching_services_guard = scopeguard::guard((), |_| {
442 IOObjectRelease(matching_services);
443 });
444
445 loop {
446 let modem_service = IOIteratorNext(matching_services);
448 if modem_service == MACH_PORT_NULL {
450 break;
451 }
452 let _modem_service_guard = scopeguard::guard((), |_| {
453 IOObjectRelease(modem_service);
454 });
455
456 let mut props = MaybeUninit::uninit();
458 let result = IORegistryEntryCreateCFProperties(
459 modem_service,
460 props.as_mut_ptr(),
461 kCFAllocatorDefault,
462 0,
463 );
464 if result == KERN_SUCCESS {
465 let props = props.assume_init();
469 let props: CFDictionary<CFString, *const c_void> = CFDictionary::wrap_under_create_rule(props);
470
471 for key in ["IOCalloutDevice", "IODialinDevice"].iter() {
472 let cf_key = CFString::new(key);
473
474 if let Some(cf_ref) = props.find(cf_key) {
475 let cf_type = CFType::wrap_under_get_rule(*cf_ref);
476 match cf_type
477 .downcast::<CFString>()
478 .map(|s| s.to_string())
479 {
480 Some(path) => {
481 vec.push(SerialPortInfo {
482 port_name: path,
483 port_type: port_type(modem_service),
484 });
485 }
486 None => return Err(Error::new(ErrorKind::Unknown, format!("Failed to get string value for {}", key))),
487 }
488 } else {
489 return Err(Error::new(ErrorKind::Unknown, format!("Key {} missing in dict", key)));
490 }
491 }
492 } else {
493 return Err(Error::new(ErrorKind::Unknown, format!("ERROR: {}", result)));
494 }
495 }
496 }
497 Ok(vec)
498 }
499 } else if #[cfg(all(target_os = "linux", not(target_env = "musl"), feature = "libudev"))] {
500 fn is_rfcomm(device: &libudev::Device) -> bool {
501 device
502 .sysname()
503 .and_then(|o| o.to_str())
504 .map(|s| s.starts_with("rfcomm"))
505 .unwrap_or(false)
506 }
507
508 pub fn available_ports() -> Result<Vec<SerialPortInfo>> {
512 let mut vec = Vec::new();
513 if let Ok(context) = libudev::Context::new() {
514 let mut enumerator = libudev::Enumerator::new(&context)?;
515 enumerator.match_subsystem("tty")?;
516 let devices = enumerator.scan_devices()?;
517 for d in devices {
518 if let Some(devnode) = d.devnode().and_then(|o| o.to_str()) {
519 let parent = d.parent();
520 if parent.is_some() || is_rfcomm(&d) {
521 if let Some(driver) = parent.as_ref().and_then(|d| d.driver()) {
522 if driver == "serial8250" && crate::new(devnode, 9600).open().is_err() {
523 continue;
524 }
525 }
526
527 if let Ok(pt) = port_type(&d) {
530 vec.push(SerialPortInfo {
531 port_name: String::from(devnode),
532 port_type: pt,
533 });
534 }
535 }
536 }
537 }
538 }
539 Ok(vec)
540 }
541 } else if #[cfg(target_os = "linux")] {
542 use std::fs::File;
543 use std::io::Read;
544 use std::path::Path;
545
546 fn is_rfcomm(path: &Path) -> bool {
547 path
548 .file_name()
549 .and_then(|o| o.to_str())
550 .map(|s| s.starts_with("rfcomm"))
551 .unwrap_or(false)
552 }
553
554 fn read_file_to_trimmed_string(dir: &Path, file: &str) -> Option<String> {
555 let path = dir.join(file);
556 let mut s = String::new();
557 File::open(path).ok()?.read_to_string(&mut s).ok()?;
558 Some(s.trim().to_owned())
559 }
560
561 fn read_file_to_u16(dir: &Path, file: &str) -> Option<u16> {
562 u16::from_str_radix(&read_file_to_trimmed_string(dir, file)?, 16).ok()
563 }
564
565 #[cfg(feature = "usbportinfo-interface")]
566 fn read_file_to_u8(dir: &Path, file: &str) -> Option<u8> {
567 u8::from_str_radix(&read_file_to_trimmed_string(dir, file)?, 16).ok()
568 }
569
570 fn read_port_type(path: &Path) -> Option<SerialPortType> {
571 let path = path
572 .canonicalize()
573 .ok()?;
574 let subsystem = path.join("subsystem").canonicalize().ok()?;
575 let subsystem = subsystem.file_name()?.to_string_lossy();
576
577 match subsystem.as_ref() {
578 "amba" => Some(SerialPortType::Unknown),
580 "pci" => Some(SerialPortType::PciPort),
581 "pnp" => Some(SerialPortType::Unknown),
582 "usb" => usb_port_type(&path),
583 "usb-serial" => usb_port_type(path.parent()?),
584 _ => None,
585 }
586 }
587
588 fn usb_port_type(interface_path: &Path) -> Option<SerialPortType> {
589 let info = read_usb_port_info(interface_path)?;
590 Some(SerialPortType::UsbPort(info))
591 }
592
593 fn read_usb_port_info(interface_path: &Path) -> Option<UsbPortInfo> {
594 let device_path = interface_path.parent()?;
595
596 let vid = read_file_to_u16(&device_path, "idVendor")?;
597 let pid = read_file_to_u16(&device_path, "idProduct")?;
598 #[cfg(feature = "usbportinfo-interface")]
599 let interface = read_file_to_u8(&interface_path, &"bInterfaceNumber");
600 let serial_number = read_file_to_trimmed_string(&device_path, &"serial");
601 let product = read_file_to_trimmed_string(&device_path, &"product");
602 let manufacturer = read_file_to_trimmed_string(&device_path, &"manufacturer");
603
604 Some(UsbPortInfo {
605 vid,
606 pid,
607 serial_number,
608 manufacturer,
609 product,
610 #[cfg(feature = "usbportinfo-interface")]
611 interface,
612 })
613 }
614
615 pub fn available_ports() -> Result<Vec<SerialPortInfo>> {
617 let mut vec = Vec::new();
618 let sys_path = Path::new("/sys/class/tty/");
619 let dev_path = Path::new("/dev");
620 for path in sys_path.read_dir().expect("/sys/class/tty/ doesn't exist on this system") {
621 let raw_path = path?.path().clone();
622 let mut path = raw_path.clone();
623
624 let port_type = if is_rfcomm(&raw_path) {
625 SerialPortType::BluetoothPort
626 } else {
627 path.push("device");
628 if !path.is_dir() {
629 continue;
630 }
631
632 let port_type = read_port_type(&path);
637 if let Some(port_type) = port_type {
638 port_type
639 } else {
640 continue;
641 }
642 };
643
644 if let Some(file_name) = raw_path.file_name() {
650 let device_file = dev_path.join(file_name);
651 if !device_file.exists() {
652 continue;
653 }
654
655 vec.push(SerialPortInfo {
656 port_name: device_file.to_string_lossy().to_string(),
657 port_type,
658 });
659 }
660 }
661 Ok(vec)
662 }
663 } else if #[cfg(target_os = "freebsd")] {
664 use std::path::Path;
665
666 pub fn available_ports() -> Result<Vec<SerialPortInfo>> {
670 let mut vec = Vec::new();
671 let dev_path = Path::new("/dev/");
672 for path in dev_path.read_dir()? {
673 let path = path?;
674 let filename = path.file_name();
675 let filename_string = filename.to_string_lossy();
676 if filename_string.starts_with("cuaU") || filename_string.starts_with("cuau") || filename_string.starts_with("cuad") {
677 if !filename_string.ends_with(".init") && !filename_string.ends_with(".lock") {
678 vec.push(SerialPortInfo {
679 port_name: path.path().to_string_lossy().to_string(),
680 port_type: SerialPortType::Unknown,
681 });
682 }
683 }
684 }
685 Ok(vec)
686 }
687 } else {
688 pub fn available_ports() -> Result<Vec<SerialPortInfo>> {
690 Err(Error::new(
691 ErrorKind::Unknown,
692 "Not implemented for this OS",
693 ))
694 }
695 }
696}
697
698#[cfg(all(
699 test,
700 target_os = "linux",
701 not(target_env = "musl"),
702 feature = "libudev"
703))]
704mod tests {
705 use super::*;
706
707 use quickcheck_macros::quickcheck;
708
709 #[quickcheck]
710 fn quickcheck_parse_modalias_does_not_panic_from_random_data(modalias: String) -> bool {
711 let _ = parse_modalias(&modalias);
712 true
713 }
714
715 #[test]
716 fn parse_modalias_canonical() {
717 const MODALIAS: &str = "usb:v303Ap1001d0101dcEFdsc02dp01ic02isc02ip00in0C";
718
719 let port_info = parse_modalias(MODALIAS).expect("parse failed");
720
721 assert_eq!(port_info.vid, 0x303A, "vendor parse invalid");
722 assert_eq!(port_info.pid, 0x1001, "product parse invalid");
723
724 #[cfg(feature = "usbportinfo-interface")]
725 assert_eq!(port_info.interface, Some(0x0C), "interface parse invalid");
726 }
727
728 #[test]
729 fn parse_modalias_corner_cases() {
730 assert!(parse_modalias("").is_none());
731 assert!(parse_modalias("usb").is_none());
732 assert!(parse_modalias("usb:").is_none());
733 assert!(parse_modalias("usb:vdcdc").is_none());
734 assert!(parse_modalias("usb:pdcdc").is_none());
735
736 let info = parse_modalias("usb:vdcdcpabcd").unwrap();
738 assert_eq!(info.vid, 0xdcdc);
739 assert_eq!(info.pid, 0xabcd);
740 #[cfg(feature = "usbportinfo-interface")]
741 assert!(info.interface.is_none());
742
743 let info = parse_modalias("usb:v1234p5678indc").unwrap();
745 assert_eq!(info.vid, 0x1234);
746 assert_eq!(info.pid, 0x5678);
747 #[cfg(feature = "usbportinfo-interface")]
748 assert_eq!(info.interface, Some(0xdc));
749 }
750}