APM:Libraries
PollerThread.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 "PollerThread.h"
18 
19 #include <algorithm>
20 #include <poll.h>
21 #include <sys/epoll.h>
22 #include <sys/timerfd.h>
23 
24 #include <AP_Math/AP_Math.h>
25 
26 namespace Linux {
27 
29 {
30  if (_removeme) {
31  return;
32  }
33 
34  uint64_t nevents = 0;
35  int r = read(_fd, &nevents, sizeof(nevents));
36  if (r < 0) {
37  return;
38  }
39 
40  if (_wrapper) {
41  _wrapper->start_cb();
42  }
43 
44  _cb();
45 
46  if (_wrapper) {
47  _wrapper->end_cb();
48  }
49 }
50 
51 bool TimerPollable::setup_timer(uint32_t timeout_usec)
52 {
53  if (_fd >= 0) {
54  return false;
55  }
56 
57  _fd = timerfd_create(CLOCK_MONOTONIC, TFD_CLOEXEC|TFD_NONBLOCK);
58  if (_fd < 0) {
59  return false;
60  }
61 
62  if (!adjust_timer(timeout_usec)) {
63  ::close(_fd);
64  _fd = -1;
65  return false;
66  }
67 
68  return true;
69 }
70 
71 bool TimerPollable::adjust_timer(uint32_t timeout_usec)
72 {
73  if (_fd < 0) {
74  return false;
75  }
76 
77  struct itimerspec spec = { };
78 
79  spec.it_interval.tv_nsec = timeout_usec * AP_NSEC_PER_USEC;
80  spec.it_value.tv_nsec = timeout_usec * AP_NSEC_PER_USEC;
81 
82  if (timerfd_settime(_fd, 0, &spec, nullptr) < 0) {
83  return false;
84  }
85 
86  return true;
87 }
88 
90  TimerPollable::WrapperCb *wrapper,
91  uint32_t timeout_usec)
92 {
93  if (!_poller) {
94  return nullptr;
95  }
96  TimerPollable *p = new TimerPollable(cb, wrapper);
97  if (!p || !p->setup_timer(timeout_usec) ||
98  !_poller.register_pollable(p, POLLIN)) {
99  delete p;
100  return nullptr;
101  }
102 
103  _timers.push_back(p);
104 
105  return p;
106 }
107 
108 bool PollerThread::adjust_timer(TimerPollable *p, uint32_t timeout_usec)
109 {
110  /* Make sure the handle points to a valid timer */
111  auto it = std::find(_timers.begin(), _timers.end(), p);
112  if (it == _timers.end()) {
113  return false;
114  }
115 
116  return (*it)->adjust_timer(timeout_usec);
117 }
118 
120 {
121  if (!_poller) {
122  return;
123  }
124 
125  for (auto it = _timers.begin(); it != _timers.end(); it++) {
126  TimerPollable *p = *it;
127  if (p->_removeme) {
128  _timers.erase(it);
129  _poller.unregister_pollable(p);
130  delete p;
131  }
132  }
133 }
134 
136 {
137  if (!_poller) {
138  return;
139  }
140 
141  while (!_should_exit) {
142  _poller.poll();
143  _cleanup_timers();
144  }
145 
146  _started = false;
147  _should_exit = false;
148 }
149 
151 {
152  if (!is_started()) {
153  return false;
154  }
155 
156  _should_exit = true;
157  _poller.wakeup();
158 
159  return true;
160 }
161 
162 }
#define AP_NSEC_PER_USEC
Definition: definitions.h:91
bool stop() override
bool adjust_timer(uint32_t timeout_usec)
bool adjust_timer(TimerPollable *p, uint32_t timeout_usec)
AP_HAL::Device::PeriodicCb PeriodicCb
Definition: PollerThread.h:41
WrapperCb * _wrapper
Definition: PollerThread.h:58
void on_can_read() override
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
bool setup_timer(uint32_t timeout_usec)
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
TimerPollable(PeriodicCb cb, WrapperCb *wrapper)
Definition: PollerThread.h:51
TimerPollable * add_timer(TimerPollable::PeriodicCb cb, TimerPollable::WrapperCb *wrapper, uint32_t timeout_usec)