1use std::mem::MaybeUninit;
2use std::os::unix::prelude::*;
3use std::path::Path;
4use std::time::{Duration, Instant};
5use std::{io, mem};
6
7use nix::fcntl::{fcntl, OFlag};
8use nix::{libc, unistd};
9
10use crate::posix::ioctl::{self, SerialLines};
11use crate::posix::termios;
12use crate::{
13 ClearBuffer, DataBits, Error, ErrorKind, FlowControl, Parity, Result, SerialPort,
14 SerialPortBuilder, StopBits,
15};
16
17fn close(fd: RawFd) {
20 let _ = ioctl::tiocnxcl(fd);
22
23 let _ = unistd::close(fd);
32}
33
34#[derive(Debug)]
61pub struct TTYPort {
62 fd: RawFd,
63 timeout: Duration,
64 exclusive: bool,
65 port_name: Option<String>,
66 #[cfg(any(target_os = "ios", target_os = "macos"))]
67 baud_rate: u32,
68}
69
70#[derive(Clone, Copy, Debug)]
72pub enum BreakDuration {
73 Short,
75 Arbitrary(std::num::NonZeroI32),
77}
78
79struct OwnedFd(RawFd);
84
85impl Drop for OwnedFd {
86 fn drop(&mut self) {
87 close(self.0);
88 }
89}
90
91impl OwnedFd {
92 fn into_raw(self) -> RawFd {
93 let fd = self.0;
94 mem::forget(self);
95 fd
96 }
97}
98
99impl TTYPort {
100 pub fn open(builder: &SerialPortBuilder) -> Result<TTYPort> {
118 use nix::fcntl::FcntlArg::F_SETFL;
119 use nix::libc::{cfmakeraw, tcgetattr, tcsetattr};
120
121 let path = Path::new(&builder.path);
122 let fd = OwnedFd(nix::fcntl::open(
123 path,
124 OFlag::O_RDWR | OFlag::O_NOCTTY | OFlag::O_NONBLOCK | OFlag::O_CLOEXEC,
125 nix::sys::stat::Mode::empty(),
126 )?);
127
128 ioctl::tiocexcl(fd.0)?;
132
133 let mut termios = MaybeUninit::uninit();
134 nix::errno::Errno::result(unsafe { tcgetattr(fd.0, termios.as_mut_ptr()) })?;
135 let mut termios = unsafe { termios.assume_init() };
136
137 termios.c_cflag |= libc::CREAD | libc::CLOCAL;
140 unsafe { cfmakeraw(&mut termios) };
144
145 unsafe { tcsetattr(fd.0, libc::TCSANOW, &termios) };
147
148 let mut actual_termios = MaybeUninit::uninit();
150 unsafe { tcgetattr(fd.0, actual_termios.as_mut_ptr()) };
151 let actual_termios = unsafe { actual_termios.assume_init() };
152
153 if actual_termios.c_iflag != termios.c_iflag
154 || actual_termios.c_oflag != termios.c_oflag
155 || actual_termios.c_lflag != termios.c_lflag
156 || actual_termios.c_cflag != termios.c_cflag
157 {
158 return Err(Error::new(
159 ErrorKind::Unknown,
160 "Settings did not apply correctly",
161 ));
162 };
163
164 #[cfg(any(target_os = "ios", target_os = "macos"))]
165 if builder.baud_rate > 0 {
166 unsafe { libc::tcflush(fd.0, libc::TCIOFLUSH) };
167 }
168
169 fcntl(fd.0, F_SETFL(nix::fcntl::OFlag::empty()))?;
171
172 let mut termios = termios::get_termios(fd.0)?;
174 termios::set_parity(&mut termios, builder.parity);
175 termios::set_flow_control(&mut termios, builder.flow_control);
176 termios::set_data_bits(&mut termios, builder.data_bits);
177 termios::set_stop_bits(&mut termios, builder.stop_bits);
178 #[cfg(not(any(target_os = "ios", target_os = "macos")))]
179 termios::set_baud_rate(&mut termios, builder.baud_rate)?;
180 #[cfg(any(target_os = "ios", target_os = "macos"))]
181 termios::set_termios(fd.0, &termios, builder.baud_rate)?;
182 #[cfg(not(any(target_os = "ios", target_os = "macos")))]
183 termios::set_termios(fd.0, &termios)?;
184
185 let mut port = TTYPort {
187 fd: fd.into_raw(),
188 timeout: builder.timeout,
189 exclusive: true,
190 port_name: Some(builder.path.clone()),
191 #[cfg(any(target_os = "ios", target_os = "macos"))]
192 baud_rate: builder.baud_rate,
193 };
194
195 if builder.baud_rate > 0 {
198 if let Some(dtr) = builder.dtr_on_open {
199 let _ = port.write_data_terminal_ready(dtr);
200 }
201 }
202
203 Ok(port)
204 }
205
206 pub fn exclusive(&self) -> bool {
211 self.exclusive
212 }
213
214 pub fn set_exclusive(&mut self, exclusive: bool) -> Result<()> {
225 let setting_result = if exclusive {
226 ioctl::tiocexcl(self.fd)
227 } else {
228 ioctl::tiocnxcl(self.fd)
229 };
230
231 setting_result?;
232 self.exclusive = exclusive;
233 Ok(())
234 }
235
236 fn set_pin(&mut self, pin: ioctl::SerialLines, level: bool) -> Result<()> {
237 if level {
238 ioctl::tiocmbis(self.fd, pin)
239 } else {
240 ioctl::tiocmbic(self.fd, pin)
241 }
242 }
243
244 fn read_pin(&mut self, pin: ioctl::SerialLines) -> Result<bool> {
245 ioctl::tiocmget(self.fd).map(|pins| pins.contains(pin))
246 }
247
248 pub fn pair() -> Result<(Self, Self)> {
271 let next_pty_fd = nix::pty::posix_openpt(nix::fcntl::OFlag::O_RDWR)?;
273
274 nix::pty::grantpt(&next_pty_fd)?;
276
277 nix::pty::unlockpt(&next_pty_fd)?;
279
280 #[cfg(not(any(
282 target_os = "linux",
283 target_os = "android",
284 target_os = "emscripten",
285 target_os = "fuchsia"
286 )))]
287 let ptty_name = unsafe { nix::pty::ptsname(&next_pty_fd)? };
288
289 #[cfg(any(
290 target_os = "linux",
291 target_os = "android",
292 target_os = "emscripten",
293 target_os = "fuchsia"
294 ))]
295 let ptty_name = nix::pty::ptsname_r(&next_pty_fd)?;
296
297 #[cfg(any(target_os = "ios", target_os = "macos"))]
299 let baud_rate = 9600;
300 let fd = nix::fcntl::open(
301 Path::new(&ptty_name),
302 OFlag::O_RDWR | OFlag::O_NOCTTY | OFlag::O_NONBLOCK,
303 nix::sys::stat::Mode::empty(),
304 )?;
305
306 let mut termios = MaybeUninit::uninit();
308 let res = unsafe { crate::posix::tty::libc::tcgetattr(fd, termios.as_mut_ptr()) };
309 if let Err(e) = nix::errno::Errno::result(res) {
310 close(fd);
311 return Err(e.into());
312 }
313 let mut termios = unsafe { termios.assume_init() };
314 unsafe { crate::posix::tty::libc::cfmakeraw(&mut termios) };
315 unsafe { crate::posix::tty::libc::tcsetattr(fd, libc::TCSANOW, &termios) };
316
317 fcntl(
318 fd,
319 nix::fcntl::FcntlArg::F_SETFL(nix::fcntl::OFlag::empty()),
320 )?;
321
322 let slave_tty = TTYPort {
323 fd,
324 timeout: Duration::from_millis(100),
325 exclusive: true,
326 port_name: Some(ptty_name),
327 #[cfg(any(target_os = "ios", target_os = "macos"))]
328 baud_rate,
329 };
330
331 let master_tty = TTYPort {
335 fd: next_pty_fd.into_raw_fd(),
336 timeout: Duration::from_millis(100),
337 exclusive: true,
338 port_name: None,
339 #[cfg(any(target_os = "ios", target_os = "macos"))]
340 baud_rate,
341 };
342
343 Ok((master_tty, slave_tty))
344 }
345
346 pub fn send_break(&self, duration: BreakDuration) -> Result<()> {
348 match duration {
349 BreakDuration::Short => nix::sys::termios::tcsendbreak(self.fd, 0),
350 BreakDuration::Arbitrary(n) => nix::sys::termios::tcsendbreak(self.fd, n.get()),
351 }
352 .map_err(|e| e.into())
353 }
354
355 pub fn try_clone_native(&self) -> Result<TTYPort> {
370 let fd_cloned: i32 = fcntl(self.fd, nix::fcntl::F_DUPFD_CLOEXEC(self.fd))?;
371 Ok(TTYPort {
372 fd: fd_cloned,
373 exclusive: self.exclusive,
374 port_name: self.port_name.clone(),
375 timeout: self.timeout,
376 #[cfg(any(target_os = "ios", target_os = "macos"))]
377 baud_rate: self.baud_rate,
378 })
379 }
380}
381
382impl Drop for TTYPort {
383 fn drop(&mut self) {
384 close(self.fd);
385 }
386}
387
388impl AsRawFd for TTYPort {
389 fn as_raw_fd(&self) -> RawFd {
390 self.fd
391 }
392}
393
394impl IntoRawFd for TTYPort {
395 fn into_raw_fd(self) -> RawFd {
396 let TTYPort { fd, .. } = self;
400 mem::forget(self);
401 fd
402 }
403}
404
405#[cfg(any(target_os = "ios", target_os = "macos"))]
407fn get_termios_speed(fd: RawFd) -> u32 {
408 let mut termios = MaybeUninit::uninit();
409 let res = unsafe { libc::tcgetattr(fd, termios.as_mut_ptr()) };
410 nix::errno::Errno::result(res).expect("Failed to get termios data");
411 let termios = unsafe { termios.assume_init() };
412 assert_eq!(termios.c_ospeed, termios.c_ispeed);
413 termios.c_ospeed as u32
414}
415
416impl FromRawFd for TTYPort {
417 unsafe fn from_raw_fd(fd: RawFd) -> Self {
418 TTYPort {
419 fd,
420 timeout: Duration::from_millis(100),
421 exclusive: ioctl::tiocexcl(fd).is_ok(),
422 port_name: None,
425 #[cfg(any(target_os = "ios", target_os = "macos"))]
429 baud_rate: get_termios_speed(fd),
430 }
431 }
432}
433
434impl io::Read for TTYPort {
435 fn read(&mut self, buf: &mut [u8]) -> io::Result<usize> {
436 if let Err(e) = super::poll::wait_read_fd(self.fd, self.timeout) {
437 return Err(io::Error::from(Error::from(e)));
438 }
439
440 nix::unistd::read(self.fd, buf).map_err(|e| io::Error::from(Error::from(e)))
441 }
442}
443
444impl io::Write for TTYPort {
445 fn write(&mut self, buf: &[u8]) -> io::Result<usize> {
446 if let Err(e) = super::poll::wait_write_fd(self.fd, self.timeout) {
447 return Err(io::Error::from(Error::from(e)));
448 }
449
450 nix::unistd::write(self.fd, buf).map_err(|e| io::Error::from(Error::from(e)))
451 }
452
453 fn flush(&mut self) -> io::Result<()> {
454 let timeout = Instant::now() + self.timeout;
455 loop {
456 return match nix::sys::termios::tcdrain(self.fd) {
457 Ok(_) => Ok(()),
458 Err(nix::errno::Errno::EINTR) => {
459 if Instant::now() < timeout {
462 continue;
463 } else {
464 Err(io::Error::new(
465 io::ErrorKind::TimedOut,
466 "timeout for retrying flush reached",
467 ))
468 }
469 }
470 Err(_) => Err(io::Error::new(io::ErrorKind::Other, "flush failed")),
471 };
472 }
473 }
474}
475
476impl SerialPort for TTYPort {
477 fn name(&self) -> Option<String> {
478 self.port_name.clone()
479 }
480
481 #[cfg(any(
486 target_os = "android",
487 all(
488 target_os = "linux",
489 not(any(
490 target_env = "musl",
491 target_arch = "powerpc",
492 target_arch = "powerpc64"
493 ))
494 )
495 ))]
496 fn baud_rate(&self) -> Result<u32> {
497 let termios2 = ioctl::tcgets2(self.fd)?;
498
499 assert!(termios2.c_ospeed == termios2.c_ispeed);
500
501 Ok(termios2.c_ospeed)
502 }
503
504 #[cfg(any(
509 target_os = "dragonfly",
510 target_os = "freebsd",
511 target_os = "netbsd",
512 target_os = "openbsd"
513 ))]
514 fn baud_rate(&self) -> Result<u32> {
515 let termios = termios::get_termios(self.fd)?;
516
517 let ospeed = unsafe { libc::cfgetospeed(&termios) };
518 let ispeed = unsafe { libc::cfgetispeed(&termios) };
519
520 assert!(ospeed == ispeed);
521
522 Ok(ospeed as u32)
523 }
524
525 #[cfg(any(target_os = "ios", target_os = "macos"))]
530 fn baud_rate(&self) -> Result<u32> {
531 Ok(self.baud_rate)
532 }
533
534 #[cfg(all(
539 target_os = "linux",
540 any(
541 target_env = "musl",
542 target_arch = "powerpc",
543 target_arch = "powerpc64"
544 )
545 ))]
546 fn baud_rate(&self) -> Result<u32> {
547 use self::libc::{
548 B1000000, B1152000, B1500000, B2000000, B2500000, B3000000, B3500000, B4000000,
549 B460800, B500000, B576000, B921600,
550 };
551 use self::libc::{
552 B110, B115200, B1200, B134, B150, B1800, B19200, B200, B230400, B2400, B300, B38400,
553 B4800, B50, B57600, B600, B75, B9600,
554 };
555
556 let termios = termios::get_termios(self.fd)?;
557 let ospeed = unsafe { libc::cfgetospeed(&termios) };
558 let ispeed = unsafe { libc::cfgetispeed(&termios) };
559
560 assert!(ospeed == ispeed);
561
562 let res: u32 = match ospeed {
563 B50 => 50,
564 B75 => 75,
565 B110 => 110,
566 B134 => 134,
567 B150 => 150,
568 B200 => 200,
569 B300 => 300,
570 B600 => 600,
571 B1200 => 1200,
572 B1800 => 1800,
573 B2400 => 2400,
574 B4800 => 4800,
575 B9600 => 9600,
576 B19200 => 19_200,
577 B38400 => 38_400,
578 B57600 => 57_600,
579 B115200 => 115_200,
580 B230400 => 230_400,
581 B460800 => 460_800,
582 B500000 => 500_000,
583 B576000 => 576_000,
584 B921600 => 921_600,
585 B1000000 => 1_000_000,
586 B1152000 => 1_152_000,
587 B1500000 => 1_500_000,
588 B2000000 => 2_000_000,
589 B2500000 => 2_500_000,
590 B3000000 => 3_000_000,
591 B3500000 => 3_500_000,
592 B4000000 => 4_000_000,
593 _ => unreachable!(),
594 };
595
596 Ok(res)
597 }
598
599 fn data_bits(&self) -> Result<DataBits> {
600 let termios = termios::get_termios(self.fd)?;
601 match termios.c_cflag & libc::CSIZE {
602 libc::CS8 => Ok(DataBits::Eight),
603 libc::CS7 => Ok(DataBits::Seven),
604 libc::CS6 => Ok(DataBits::Six),
605 libc::CS5 => Ok(DataBits::Five),
606 _ => Err(Error::new(
607 ErrorKind::Unknown,
608 "Invalid data bits setting encountered",
609 )),
610 }
611 }
612
613 fn flow_control(&self) -> Result<FlowControl> {
614 let termios = termios::get_termios(self.fd)?;
615 if termios.c_cflag & libc::CRTSCTS == libc::CRTSCTS {
616 Ok(FlowControl::Hardware)
617 } else if termios.c_iflag & (libc::IXON | libc::IXOFF) == (libc::IXON | libc::IXOFF) {
618 Ok(FlowControl::Software)
619 } else {
620 Ok(FlowControl::None)
621 }
622 }
623
624 fn parity(&self) -> Result<Parity> {
625 let termios = termios::get_termios(self.fd)?;
626 if termios.c_cflag & libc::PARENB == libc::PARENB {
627 if termios.c_cflag & libc::PARODD == libc::PARODD {
628 Ok(Parity::Odd)
629 } else {
630 Ok(Parity::Even)
631 }
632 } else {
633 Ok(Parity::None)
634 }
635 }
636
637 fn stop_bits(&self) -> Result<StopBits> {
638 let termios = termios::get_termios(self.fd)?;
639 if termios.c_cflag & libc::CSTOPB == libc::CSTOPB {
640 Ok(StopBits::Two)
641 } else {
642 Ok(StopBits::One)
643 }
644 }
645
646 fn timeout(&self) -> Duration {
647 self.timeout
648 }
649
650 #[cfg(any(
651 target_os = "android",
652 target_os = "dragonfly",
653 target_os = "freebsd",
654 target_os = "netbsd",
655 target_os = "openbsd",
656 target_os = "linux"
657 ))]
658 fn set_baud_rate(&mut self, baud_rate: u32) -> Result<()> {
659 let mut termios = termios::get_termios(self.fd)?;
660 termios::set_baud_rate(&mut termios, baud_rate)?;
661 termios::set_termios(self.fd, &termios)
662 }
663
664 #[cfg(any(target_os = "ios", target_os = "macos"))]
666 fn set_baud_rate(&mut self, baud_rate: u32) -> Result<()> {
667 ioctl::iossiospeed(self.fd, &(baud_rate as libc::speed_t))?;
668 self.baud_rate = baud_rate;
669 Ok(())
670 }
671
672 fn set_flow_control(&mut self, flow_control: FlowControl) -> Result<()> {
673 let mut termios = termios::get_termios(self.fd)?;
674 termios::set_flow_control(&mut termios, flow_control);
675 #[cfg(any(target_os = "ios", target_os = "macos"))]
676 return termios::set_termios(self.fd, &termios, self.baud_rate);
677 #[cfg(not(any(target_os = "ios", target_os = "macos")))]
678 return termios::set_termios(self.fd, &termios);
679 }
680
681 fn set_parity(&mut self, parity: Parity) -> Result<()> {
682 let mut termios = termios::get_termios(self.fd)?;
683 termios::set_parity(&mut termios, parity);
684 #[cfg(any(target_os = "ios", target_os = "macos"))]
685 return termios::set_termios(self.fd, &termios, self.baud_rate);
686 #[cfg(not(any(target_os = "ios", target_os = "macos")))]
687 return termios::set_termios(self.fd, &termios);
688 }
689
690 fn set_data_bits(&mut self, data_bits: DataBits) -> Result<()> {
691 let mut termios = termios::get_termios(self.fd)?;
692 termios::set_data_bits(&mut termios, data_bits);
693 #[cfg(any(target_os = "ios", target_os = "macos"))]
694 return termios::set_termios(self.fd, &termios, self.baud_rate);
695 #[cfg(not(any(target_os = "ios", target_os = "macos")))]
696 return termios::set_termios(self.fd, &termios);
697 }
698
699 fn set_stop_bits(&mut self, stop_bits: StopBits) -> Result<()> {
700 let mut termios = termios::get_termios(self.fd)?;
701 termios::set_stop_bits(&mut termios, stop_bits);
702 #[cfg(any(target_os = "ios", target_os = "macos"))]
703 return termios::set_termios(self.fd, &termios, self.baud_rate);
704 #[cfg(not(any(target_os = "ios", target_os = "macos")))]
705 return termios::set_termios(self.fd, &termios);
706 }
707
708 fn set_timeout(&mut self, timeout: Duration) -> Result<()> {
709 self.timeout = timeout;
710 Ok(())
711 }
712
713 fn write_request_to_send(&mut self, level: bool) -> Result<()> {
714 self.set_pin(SerialLines::REQUEST_TO_SEND, level)
715 }
716
717 fn write_data_terminal_ready(&mut self, level: bool) -> Result<()> {
718 self.set_pin(SerialLines::DATA_TERMINAL_READY, level)
719 }
720
721 fn read_clear_to_send(&mut self) -> Result<bool> {
722 self.read_pin(SerialLines::CLEAR_TO_SEND)
723 }
724
725 fn read_data_set_ready(&mut self) -> Result<bool> {
726 self.read_pin(SerialLines::DATA_SET_READY)
727 }
728
729 fn read_ring_indicator(&mut self) -> Result<bool> {
730 self.read_pin(SerialLines::RING)
731 }
732
733 fn read_carrier_detect(&mut self) -> Result<bool> {
734 self.read_pin(SerialLines::DATA_CARRIER_DETECT)
735 }
736
737 fn bytes_to_read(&self) -> Result<u32> {
738 ioctl::fionread(self.fd)
739 }
740
741 fn bytes_to_write(&self) -> Result<u32> {
742 ioctl::tiocoutq(self.fd)
743 }
744
745 fn clear(&self, buffer_to_clear: ClearBuffer) -> Result<()> {
746 let buffer_id = match buffer_to_clear {
747 ClearBuffer::Input => libc::TCIFLUSH,
748 ClearBuffer::Output => libc::TCOFLUSH,
749 ClearBuffer::All => libc::TCIOFLUSH,
750 };
751
752 let res = unsafe { nix::libc::tcflush(self.fd, buffer_id) };
753
754 nix::errno::Errno::result(res)
755 .map(|_| ())
756 .map_err(|e| e.into())
757 }
758
759 fn try_clone(&self) -> Result<Box<dyn SerialPort>> {
760 match self.try_clone_native() {
761 Ok(p) => Ok(Box::new(p)),
762 Err(e) => Err(e),
763 }
764 }
765
766 fn set_break(&self) -> Result<()> {
767 ioctl::tiocsbrk(self.fd)
768 }
769
770 fn clear_break(&self) -> Result<()> {
771 ioctl::tioccbrk(self.fd)
772 }
773}
774
775#[test]
776fn test_ttyport_into_raw_fd() {
777 #![allow(unused_variables)]
782 let (master, slave) = TTYPort::pair().expect("Unable to create ptty pair");
783
784 let master_fd = master.into_raw_fd();
786 let mut termios = MaybeUninit::uninit();
787 let res = unsafe { nix::libc::tcgetattr(master_fd, termios.as_mut_ptr()) };
788 if res != 0 {
789 close(master_fd);
790 panic!("tcgetattr on the master port failed");
791 }
792
793 let slave_fd = slave.into_raw_fd();
795 let res = unsafe { nix::libc::tcgetattr(slave_fd, termios.as_mut_ptr()) };
796 if res != 0 {
797 close(slave_fd);
798 panic!("tcgetattr on the master port failed");
799 }
800 close(master_fd);
801 close(slave_fd);
802}