serialport/posix/
enumerate.rs

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/// Retrieves the udev property value named by `key`. If the value exists, then it will be
50/// converted to a String, otherwise None will be returned.
51#[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/// Retrieves the udev property value named by `key`. This function assumes that the retrieved
59/// string is comprised of hex digits and the integer value of this will be returned as  a u16.
60/// If the property value doesn't exist or doesn't contain valid hex digits, then an error
61/// will be returned.
62/// This function uses a built-in type's `from_str_radix` to implementation to perform the
63/// actual conversion.
64#[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/// Looks up a property which is provided in two "flavors": Where special charaters and whitespaces
82/// are encoded/escaped and where they are replaced (with underscores). This is for example done
83/// by udev for manufacturer and model information.
84///
85/// See
86/// https://github.com/systemd/systemd/blob/38c258398427d1f497268e615906759025e51ea6/src/udev/udev-builtin-usb_id.c#L432
87/// for details.
88#[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/// Converts the underscores from `udev_replace_whitespace` back to spaces quick and dirtily. We
101/// are ignoring the different types of whitespaces and the substitutions from `udev_replace_chars`
102/// deliberately for keeping a low profile.
103///
104/// See
105/// https://github.com/systemd/systemd/blob/38c258398427d1f497268e615906759025e51ea6/src/shared/udev-util.c#L281
106/// for more details.
107#[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            // For devices on the USB, udev also provides manufacturer and product information from
118            // its hardware dataase. Use this as a fallback if this information is not provided
119            // from the device itself.
120            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                // For USB devices reported at a PCI bus, there is apparently no fallback
146                // information from udevs hardware database provided.
147                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    // limit the query depth
192    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//  MODALIAS = usb:v303Ap1001d0101dcEFdsc02dp01ic02isc02ip00in00
224//  v    303A  (device vendor)
225//  p    1001  (device product)
226//  d    0101  (bcddevice)
227//  dc     EF  (device class)
228//  dsc    02  (device subclass)
229//  dp     01  (device protocol)
230//  ic     02  (interface class)
231//  isc    02  (interface subclass)
232//  ip     00  (interface protocol)
233//  in     00  (interface number)
234#[cfg(all(target_os = "linux", not(target_env = "musl"), feature = "libudev"))]
235fn parse_modalias(moda: &str) -> Option<UsbPortInfo> {
236    // Find the start of the string, will start with "usb:"
237    let mod_start = moda.find("usb:v")?;
238
239    // Tail to update while searching.
240    let mut mod_tail = moda.get(mod_start + 5..)?;
241
242    // The next four characters should be hex values of the vendor.
243    let vid = mod_tail.get(..4)?;
244    mod_tail = mod_tail.get(4..)?;
245
246    // The next portion we care about is the device product ID.
247    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        // Only attempt to find the interface if the feature is enabled.
257        #[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)]
297/// Returns a specific property of the given device as an integer.
298fn 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"))]
325/// Returns a specific property of the given device as a string.
326fn 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"))]
349/// Determine the serial port type based on the service object (like that returned by
350/// `IOIteratorNext`). Specific properties are extracted for USB devices.
351fn 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            // Apple developer documentation indicates `bInterfaceNumber` is the supported key for
366            // looking up the composite usb interface id. `idVendor` and `idProduct` are included in the same tables, so
367            // we will lookup the interface number using the same method. See:
368            //
369            // https://developer.apple.com/documentation/bundleresources/entitlements/com_apple_developer_driverkit_transport_usb
370            // https://developer.apple.com/library/archive/documentation/DeviceDrivers/Conceptual/USBBook/USBOverview/USBOverview.html#//apple_ref/doc/uid/TP40002644-BBCEACAJ
371            #[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        /// Scans the system for serial ports and returns a list of them.
386        /// The `SerialPortInfo` struct contains the name of the port which can be used for opening it.
387        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                // Create a dictionary for specifying the search terms against the IOService
394                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                // Populate the search dictionary with a single key/value pair indicating that we're
404                // searching for serial devices matching the RS232 device type.
405                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                // Get an interface to IOKit
412                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                // Run the search. IOServiceGetMatchingServices consumes one reference count of
422                // classes_to_match, so explicitly retain.
423                //
424                // TODO: We could also just mem::forget classes_to_match like in
425                // TCFType::into_CFType. Is there a special reason that there is no
426                // TCFType::into_concrete_TypeRef()?
427                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                    // Grab the next result.
447                    let modem_service = IOIteratorNext(matching_services);
448                    // Break out if we've reached the end of the iterator
449                    if modem_service == MACH_PORT_NULL {
450                        break;
451                    }
452                    let _modem_service_guard = scopeguard::guard((), |_| {
453                        IOObjectRelease(modem_service);
454                    });
455
456                    // Fetch all properties of the current search result item.
457                    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                        // A successful call to IORegistryEntryCreateCFProperties indicates that a
466                        // properties dict has been allocated and we as the caller are in charge of
467                        // releasing it.
468                        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        /// Scans the system for serial ports and returns a list of them.
509        /// The `SerialPortInfo` struct contains the name of the port
510        /// which can be used for opening it.
511        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                            // Stop bubbling up port_type errors here so problematic ports are just
528                            // skipped instead of causing no ports to be returned.
529                            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                // Broadcom SoC UARTs (of Raspberry Pi devices).
579                "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        /// Scans `/sys/class/tty` for serial devices (on Linux systems without libudev).
616        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                    // Determine port type and proceed, if it's a known.
633                    //
634                    // TODO: Switch to a likely more readable let-else statement when our MSRV supports
635                    // it.
636                    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                // Generate the device file path `/dev/DEVICE` from the TTY class path
645                // `/sys/class/tty/DEVICE` and emit a serial device if this path exists. There are
646                // no further checks (yet) due to `Path::is_file` reports only regular files.
647                //
648                // See https://github.com/serialport/serialport-rs/issues/66 for details.
649                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        /// Scans the system for serial ports and returns a list of them.
667        /// The `SerialPortInfo` struct contains the name of the port
668        /// which can be used for opening it.
669        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        /// Enumerating serial ports on this platform is not supported
689        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        // Just vendor and product IDs.
737        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        // Vendor and product ID plus an interface number.
744        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}