22 #include <sys/eventfd.h> 23 #include <sys/types.h> 39 r =
read(
_fd, &val,
sizeof(val));
40 }
while (!(r == -1 &&
errno == EAGAIN));
45 _epfd = epoll_create1(EPOLL_CLOEXEC);
47 fprintf(stderr,
"Failed to create epoll: %m\n");
51 _wakeup._fd = eventfd(0, EFD_NONBLOCK | EFD_CLOEXEC);
52 if (_wakeup._fd == -1) {
53 fprintf(stderr,
"Failed to create wakeup fd: %m\n");
57 if (!register_pollable(&_wakeup, EPOLLIN)) {
58 fprintf(stderr,
"Failed to add wakeup fd\n");
86 struct epoll_event epev = { };
88 epev.data.ptr =
static_cast<void *
>(p);
90 return epoll_ctl(_epfd, EPOLL_CTL_ADD, p->
get_fd(), &epev) == 0;
95 if (_epfd >= 0 && p->
get_fd() >= 0) {
96 epoll_ctl(_epfd, EPOLL_CTL_DEL, p->
get_fd(),
nullptr);
102 const int max_events = 16;
103 epoll_event events[max_events];
107 r = epoll_wait(_epfd, events, max_events, -1);
108 }
while (r < 0 &&
errno == EINTR);
114 for (
int i = 0; i < r; i++) {
117 if (events[i].events & EPOLLIN) {
120 if (events[i].events & EPOLLOUT) {
123 if (events[i].events & EPOLLERR) {
126 if (events[i].events & EPOLLHUP) {
140 r =
write(_wakeup.get_fd(), &val,
sizeof(val));
141 }
while (r == -1 &&
errno == EINTR);
144 fprintf(stderr,
"Failed to wakeup poller: %m\n");
virtual void on_can_write()
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
int close(int fileno)
POSIX Close a file with fileno handel.
virtual void on_can_read()
void on_can_read() override
int errno
Note: fdevopen assigns stdin,stdout,stderr.
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
bool register_pollable(Pollable *p, uint32_t events)
void unregister_pollable(const Pollable *p)
virtual void on_hang_up()