APM:Libraries
Poller.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2016 Intel Corporation. All rights reserved.
3  *
4  * This file is free software: you can redistribute it and/or modify it
5  * under the terms of the GNU General Public License as published by the
6  * Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8  *
9  * This file is distributed in the hope that it will be useful, but
10  * WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
12  * See the GNU General Public License for more details.
13  *
14  * You should have received a copy of the GNU General Public License along
15  * with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 #include <errno.h>
18 #include <fcntl.h>
19 #include <inttypes.h>
20 #include <stdio.h>
21 #include <sys/epoll.h>
22 #include <sys/eventfd.h>
23 #include <sys/types.h>
24 #include <sys/uio.h>
25 #include <unistd.h>
26 
27 #include "Poller.h"
28 
29 extern const AP_HAL::HAL &hal;
30 
31 namespace Linux {
32 
34 {
35  ssize_t r;
36  uint64_t val;
37 
38  do {
39  r = read(_fd, &val, sizeof(val));
40  } while (!(r == -1 && errno == EAGAIN));
41 }
42 
44 {
45  _epfd = epoll_create1(EPOLL_CLOEXEC);
46  if (_epfd == -1) {
47  fprintf(stderr, "Failed to create epoll: %m\n");
48  return;
49  }
50 
51  _wakeup._fd = eventfd(0, EFD_NONBLOCK | EFD_CLOEXEC);
52  if (_wakeup._fd == -1) {
53  fprintf(stderr, "Failed to create wakeup fd: %m\n");
54  goto fail_eventfd;
55  }
56 
57  if (!register_pollable(&_wakeup, EPOLLIN)) {
58  fprintf(stderr, "Failed to add wakeup fd\n");
59  goto fail_register;
60  }
61 
62  return;
63 
64 fail_register:
65  close(_wakeup._fd);
66  _wakeup._fd = -1;
67 fail_eventfd:
68  close(_epfd);
69  _epfd = -1;
70 }
71 
72 bool Poller::register_pollable(Pollable *p, uint32_t events)
73 {
74  /*
75  * EPOLLWAKEUP prevents the system from hibernating or suspending when
76  * inside epoll_wait() for this particular event. It is silently
77  * ignored if the process does not have the CAP_BLOCK_SUSPEND
78  * capability.
79  */
80  events |= EPOLLWAKEUP;
81 
82  if (_epfd < 0) {
83  return false;
84  }
85 
86  struct epoll_event epev = { };
87  epev.events = events;
88  epev.data.ptr = static_cast<void *>(p);
89 
90  return epoll_ctl(_epfd, EPOLL_CTL_ADD, p->get_fd(), &epev) == 0;
91 }
92 
94 {
95  if (_epfd >= 0 && p->get_fd() >= 0) {
96  epoll_ctl(_epfd, EPOLL_CTL_DEL, p->get_fd(), nullptr);
97  }
98 }
99 
100 int Poller::poll() const
101 {
102  const int max_events = 16;
103  epoll_event events[max_events];
104  int r;
105 
106  do {
107  r = epoll_wait(_epfd, events, max_events, -1);
108  } while (r < 0 && errno == EINTR);
109 
110  if (r < 0) {
111  return -errno;
112  }
113 
114  for (int i = 0; i < r; i++) {
115  Pollable *p = static_cast<Pollable *>(events[i].data.ptr);
116 
117  if (events[i].events & EPOLLIN) {
118  p->on_can_read();
119  }
120  if (events[i].events & EPOLLOUT) {
121  p->on_can_write();
122  }
123  if (events[i].events & EPOLLERR) {
124  p->on_error();
125  }
126  if (events[i].events & EPOLLHUP) {
127  p->on_hang_up();
128  }
129  }
130 
131  return r;
132 }
133 
134 void Poller::wakeup() const
135 {
136  ssize_t r;
137  uint64_t val = 1;
138 
139  do {
140  r = write(_wakeup.get_fd(), &val, sizeof(val));
141  } while (r == -1 && errno == EINTR);
142 
143  if (r == -1) {
144  fprintf(stderr, "Failed to wakeup poller: %m\n");
145  }
146 }
147 
149 {
150  /*
151  * Make sure to remove the file descriptor from epoll since events could
152  * continue to be reported if the file descriptor was dup()'ed. However
153  * we rely on user unregistering it rather than taking a reference to the
154  * Poller. Here we just close our file descriptor.
155  */
156  if (_fd >= 0) {
157  close(_fd);
158  }
159 }
160 
161 }
virtual void on_can_write()
Definition: Poller.h:45
virtual ~Pollable()
Definition: Poller.cpp:148
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
Definition: posix.c:1169
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define EPOLLWAKEUP
Definition: epoll.h:6
int get_fd() const
Definition: Poller.h:36
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
virtual void on_can_read()
Definition: Poller.h:39
void on_can_read() override
Definition: Poller.cpp:33
void wakeup() const
Definition: Poller.cpp:134
int poll() const
Definition: Poller.cpp:100
virtual void on_error()
Definition: Poller.h:51
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
bool register_pollable(Pollable *p, uint32_t events)
Definition: Poller.cpp:72
void unregister_pollable(const Pollable *p)
Definition: Poller.cpp:93
virtual void on_hang_up()
Definition: Poller.h:57