123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161 |
- #include <errno.h>
- #include <fcntl.h>
- #include <inttypes.h>
- #include <stdio.h>
- #include <sys/epoll.h>
- #include <sys/eventfd.h>
- #include <sys/types.h>
- #include <sys/uio.h>
- #include <unistd.h>
- #include "Poller.h"
- extern const AP_HAL::HAL &hal;
- namespace Linux {
- void WakeupPollable::on_can_read()
- {
- ssize_t r;
- uint64_t val;
- do {
- r = read(_fd, &val, sizeof(val));
- } while (!(r == -1 && errno == EAGAIN));
- }
- Poller::Poller()
- {
- _epfd = epoll_create1(EPOLL_CLOEXEC);
- if (_epfd == -1) {
- fprintf(stderr, "Failed to create epoll: %m\n");
- return;
- }
- _wakeup._fd = eventfd(0, EFD_NONBLOCK | EFD_CLOEXEC);
- if (_wakeup._fd == -1) {
- fprintf(stderr, "Failed to create wakeup fd: %m\n");
- goto fail_eventfd;
- }
- if (!register_pollable(&_wakeup, EPOLLIN)) {
- fprintf(stderr, "Failed to add wakeup fd\n");
- goto fail_register;
- }
- return;
- fail_register:
- close(_wakeup._fd);
- _wakeup._fd = -1;
- fail_eventfd:
- close(_epfd);
- _epfd = -1;
- }
- bool Poller::register_pollable(Pollable *p, uint32_t events)
- {
-
- events |= EPOLLWAKEUP;
- if (_epfd < 0) {
- return false;
- }
- struct epoll_event epev = { };
- epev.events = events;
- epev.data.ptr = static_cast<void *>(p);
- return epoll_ctl(_epfd, EPOLL_CTL_ADD, p->get_fd(), &epev) == 0;
- }
- void Poller::unregister_pollable(const Pollable *p)
- {
- if (_epfd >= 0 && p->get_fd() >= 0) {
- epoll_ctl(_epfd, EPOLL_CTL_DEL, p->get_fd(), nullptr);
- }
- }
- int Poller::poll() const
- {
- const int max_events = 16;
- epoll_event events[max_events];
- int r;
- do {
- r = epoll_wait(_epfd, events, max_events, -1);
- } while (r < 0 && errno == EINTR);
- if (r < 0) {
- return -errno;
- }
- for (int i = 0; i < r; i++) {
- Pollable *p = static_cast<Pollable *>(events[i].data.ptr);
- if (events[i].events & EPOLLIN) {
- p->on_can_read();
- }
- if (events[i].events & EPOLLOUT) {
- p->on_can_write();
- }
- if (events[i].events & EPOLLERR) {
- p->on_error();
- }
- if (events[i].events & EPOLLHUP) {
- p->on_hang_up();
- }
- }
- return r;
- }
- void Poller::wakeup() const
- {
- ssize_t r;
- uint64_t val = 1;
- do {
- r = write(_wakeup.get_fd(), &val, sizeof(val));
- } while (r == -1 && errno == EINTR);
- if (r == -1) {
- fprintf(stderr, "Failed to wakeup poller: %m\n");
- }
- }
- Pollable::~Pollable()
- {
-
- if (_fd >= 0) {
- close(_fd);
- }
- }
- }
|