13 _device_path(device_path)
39 ::fprintf(stderr,
"Failed to open UART device %s - %s\n",
63 if (poll(&fds, 1, 0) == 1) {
72 int flags = fcntl(
_fd, F_GETFL, 0);
75 flags = flags & ~O_NONBLOCK;
77 flags = flags | O_NONBLOCK;
80 if (fcntl(
_fd, F_SETFL, flags) < 0) {
81 ::fprintf(stderr,
"Failed to make UART nonblocking %s - %s\n",
90 memset(&t, 0,
sizeof(t));
95 t.c_iflag &= ~(BRKINT | ICRNL | IMAXBEL | IXON | IXOFF);
96 t.c_oflag &= ~(OPOST | ONLCR);
97 t.c_lflag &= ~(ISIG | ICANON | IEXTEN | ECHO | ECHOE | ECHOK | ECHOCTL | ECHOKE);
100 tcsetattr(
_fd, TCSANOW, &t);
106 memset(&t, 0,
sizeof(t));
109 cfsetspeed(&t, baudrate);
110 tcsetattr(
_fd, TCSANOW, &t);
124 t.c_cflag |= CRTSCTS;
126 t.c_cflag &= ~CRTSCTS;
129 tcsetattr(
_fd, TCSANOW, &t);
virtual void set_speed(uint32_t speed) override
AP_HAL::UARTDriver::flow_control _flow_control
virtual ssize_t read(uint8_t *buf, uint16_t n) override
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
virtual void set_blocking(bool blocking) override
virtual ssize_t write(const uint8_t *buf, uint16_t n) override
const char * _device_path
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
virtual void set_flow_control(enum AP_HAL::UARTDriver::flow_control flow_control_setting) override
UARTDevice(const char *device_path)
virtual bool close() override
int errno
Note: fdevopen assigns stdin,stdout,stderr.
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
virtual bool open() override