APM:Libraries
ConsoleDevice.cpp
Go to the documentation of this file.
1 #include <errno.h>
2 #include <fcntl.h>
3 #include <stdio.h>
4 #include <unistd.h>
5 #include <signal.h>
6 
7 #include <AP_HAL/AP_HAL.h>
8 
9 #include "ConsoleDevice.h"
10 
11 
13 {
14 }
15 
17 {
18  close();
19 }
20 
22 {
23  _closed = true;
24 
25  return true;
26 }
27 
29 {
30  _rd_fd = STDIN_FILENO;
31  _wr_fd = STDOUT_FILENO;
32 
33  _closed = false;
34 
35  if (!_set_signal_handlers()) {
36  close();
37  return false;
38  }
39 
40  return true;
41 }
42 
44 {
45  struct sigaction sa;
46  sigemptyset(&sa.sa_mask);
47  sa.sa_handler = SIG_IGN;
48 
49  return (sigaction(SIGTTIN, &sa, nullptr) == 0);
50 
51 }
52 
53 ssize_t ConsoleDevice::read(uint8_t *buf, uint16_t n)
54 {
55  if (_closed) {
56  return -EAGAIN;
57  }
58 
59  return ::read(_rd_fd, buf, n);
60 }
61 
62 ssize_t ConsoleDevice::write(const uint8_t *buf, uint16_t n)
63 {
64  if (_closed) {
65  return -EAGAIN;
66  }
67 
68  return ::write(_wr_fd, buf, n);
69 }
70 
71 void ConsoleDevice::set_blocking(bool blocking)
72 {
73  int rd_flags;
74  int wr_flags;
75 
76  rd_flags = fcntl(_rd_fd, F_GETFL, 0);
77  wr_flags = fcntl(_wr_fd, F_GETFL, 0);
78 
79  if (blocking) {
80  rd_flags = rd_flags & ~O_NONBLOCK;
81  wr_flags = wr_flags & ~O_NONBLOCK;
82  } else {
83  rd_flags = rd_flags | O_NONBLOCK;
84  wr_flags = wr_flags | O_NONBLOCK;
85  }
86 
87  if (fcntl(_rd_fd, F_SETFL, rd_flags) < 0) {
88  ::fprintf(stderr, "Failed to set Console nonblocking %s\n", strerror(errno));
89  }
90 
91  if (fcntl(_wr_fd, F_SETFL, wr_flags) < 0) {
92  ::fprintf(stderr, "Failed to set Console nonblocking %s\n",strerror(errno));
93  }
94 
95 }
96 
97 void ConsoleDevice::set_speed(uint32_t baudrate)
98 {
99 }
virtual void set_speed(uint32_t speed) override
virtual ~ConsoleDevice()
virtual void set_blocking(bool blocking) override
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
Definition: posix.c:1852
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
Definition: posix.c:1169
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
bool _set_signal_handlers(void) const
virtual bool close() override
int errno
Note: fdevopen assigns stdin,stdout,stderr.
Definition: posix.c:118
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
Definition: posix.c:2539
virtual ssize_t write(const uint8_t *buf, uint16_t n) override
virtual bool open() override
virtual ssize_t read(uint8_t *buf, uint16_t n) override