PollerThread.cpp 3.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162
  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. #include <algorithm>
  19. #include <poll.h>
  20. #include <sys/epoll.h>
  21. #include <sys/timerfd.h>
  22. #include <AP_Math/AP_Math.h>
  23. namespace Linux {
  24. void TimerPollable::on_can_read()
  25. {
  26. if (_removeme) {
  27. return;
  28. }
  29. uint64_t nevents = 0;
  30. int r = read(_fd, &nevents, sizeof(nevents));
  31. if (r < 0) {
  32. return;
  33. }
  34. if (_wrapper) {
  35. _wrapper->start_cb();
  36. }
  37. _cb();
  38. if (_wrapper) {
  39. _wrapper->end_cb();
  40. }
  41. }
  42. bool TimerPollable::setup_timer(uint32_t timeout_usec)
  43. {
  44. if (_fd >= 0) {
  45. return false;
  46. }
  47. _fd = timerfd_create(CLOCK_MONOTONIC, TFD_CLOEXEC|TFD_NONBLOCK);
  48. if (_fd < 0) {
  49. return false;
  50. }
  51. if (!adjust_timer(timeout_usec)) {
  52. ::close(_fd);
  53. _fd = -1;
  54. return false;
  55. }
  56. return true;
  57. }
  58. bool TimerPollable::adjust_timer(uint32_t timeout_usec)
  59. {
  60. if (_fd < 0) {
  61. return false;
  62. }
  63. struct itimerspec spec = { };
  64. spec.it_interval.tv_nsec = timeout_usec * AP_NSEC_PER_USEC;
  65. spec.it_value.tv_nsec = timeout_usec * AP_NSEC_PER_USEC;
  66. if (timerfd_settime(_fd, 0, &spec, nullptr) < 0) {
  67. return false;
  68. }
  69. return true;
  70. }
  71. TimerPollable *PollerThread::add_timer(TimerPollable::PeriodicCb cb,
  72. TimerPollable::WrapperCb *wrapper,
  73. uint32_t timeout_usec)
  74. {
  75. if (!_poller) {
  76. return nullptr;
  77. }
  78. TimerPollable *p = new TimerPollable(cb, wrapper);
  79. if (!p || !p->setup_timer(timeout_usec) ||
  80. !_poller.register_pollable(p, POLLIN)) {
  81. delete p;
  82. return nullptr;
  83. }
  84. _timers.push_back(p);
  85. return p;
  86. }
  87. bool PollerThread::adjust_timer(TimerPollable *p, uint32_t timeout_usec)
  88. {
  89. /* Make sure the handle points to a valid timer */
  90. auto it = std::find(_timers.begin(), _timers.end(), p);
  91. if (it == _timers.end()) {
  92. return false;
  93. }
  94. return (*it)->adjust_timer(timeout_usec);
  95. }
  96. void PollerThread::_cleanup_timers()
  97. {
  98. if (!_poller) {
  99. return;
  100. }
  101. for (auto it = _timers.begin(); it != _timers.end(); it++) {
  102. TimerPollable *p = *it;
  103. if (p->_removeme) {
  104. _timers.erase(it);
  105. _poller.unregister_pollable(p);
  106. delete p;
  107. }
  108. }
  109. }
  110. void PollerThread::mainloop()
  111. {
  112. if (!_poller) {
  113. return;
  114. }
  115. while (!_should_exit) {
  116. _poller.poll();
  117. _cleanup_timers();
  118. }
  119. _started = false;
  120. _should_exit = false;
  121. }
  122. bool PollerThread::stop()
  123. {
  124. if (!is_started()) {
  125. return false;
  126. }
  127. _should_exit = true;
  128. _poller.wakeup();
  129. return true;
  130. }
  131. }