AP_Scheduler.h 6.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. * main loop scheduler for APM
  15. * Author: Andrew Tridgell, January 2013
  16. *
  17. */
  18. #pragma once
  19. #include <AP_Param/AP_Param.h>
  20. #include <AP_HAL/Util.h>
  21. #include <AP_Math/AP_Math.h>
  22. #include "PerfInfo.h" // loop perf monitoring
  23. #define AP_SCHEDULER_NAME_INITIALIZER(_name) .name = #_name,
  24. /*
  25. useful macro for creating scheduler task table
  26. */
  27. #define SCHED_TASK_CLASS(classname, classptr, func, _rate_hz, _max_time_micros) { \
  28. .function = FUNCTOR_BIND(classptr, &classname::func, void),\
  29. AP_SCHEDULER_NAME_INITIALIZER(func)\
  30. .rate_hz = _rate_hz,\
  31. .max_time_micros = _max_time_micros\
  32. }
  33. /*
  34. A task scheduler for APM main loops
  35. Sketches should call scheduler.init() on startup, then call
  36. scheduler.tick() at regular intervals (typically every 10ms).
  37. To run tasks use scheduler.run(), passing the amount of time that
  38. the scheduler is allowed to use before it must return
  39. */
  40. #include <AP_HAL/AP_HAL.h>
  41. #include <AP_Vehicle/AP_Vehicle.h>
  42. class AP_Scheduler
  43. {
  44. public:
  45. FUNCTOR_TYPEDEF(scheduler_fastloop_fn_t, void);
  46. AP_Scheduler(scheduler_fastloop_fn_t fastloop_fn = nullptr);
  47. /* Do not allow copies */
  48. AP_Scheduler(const AP_Scheduler &other) = delete;
  49. AP_Scheduler &operator=(const AP_Scheduler&) = delete;
  50. static AP_Scheduler *get_singleton();
  51. static AP_Scheduler *_singleton;
  52. FUNCTOR_TYPEDEF(task_fn_t, void);
  53. struct Task {
  54. task_fn_t function;
  55. const char *name;
  56. float rate_hz;
  57. uint16_t max_time_micros;
  58. };
  59. // initialise scheduler
  60. void init(const Task *tasks, uint8_t num_tasks, uint32_t log_performance_bit);
  61. // called by vehicle's main loop - which should be the only thing
  62. // that function does
  63. void loop();
  64. // call to update any logging the scheduler might do; call at 1Hz
  65. void update_logging();
  66. // write out PERF message to logger
  67. void Log_Write_Performance();
  68. // call when one tick has passed
  69. void tick(void);
  70. // return current tick counter
  71. uint16_t ticks() const { return _tick_counter; }
  72. // run the tasks. Call this once per 'tick'.
  73. // time_available is the amount of time available to run
  74. // tasks in microseconds
  75. void run(uint32_t time_available);
  76. // return the number of microseconds available for the current task
  77. uint16_t time_available_usec(void);
  78. // return debug parameter
  79. uint8_t debug_flags(void) { return _debug; }
  80. // return load average, as a number between 0 and 1. 1 means
  81. // 100% load. Calculated from how much spare time we have at the
  82. // end of a run()
  83. float load_average();
  84. // get the active main loop rate
  85. uint16_t get_loop_rate_hz(void) {
  86. if (_active_loop_rate_hz == 0) {
  87. _active_loop_rate_hz = _loop_rate_hz;
  88. }
  89. return _active_loop_rate_hz;
  90. }
  91. // get the time-allowed-per-loop in microseconds
  92. uint32_t get_loop_period_us() {
  93. if (_loop_period_us == 0) {
  94. _loop_period_us = 1000000UL / _loop_rate_hz;
  95. }
  96. return _loop_period_us;
  97. }
  98. // get the time-allowed-per-loop in seconds
  99. float get_loop_period_s() {
  100. if (is_zero(_loop_period_s)) {
  101. _loop_period_s = 1.0f / _loop_rate_hz;
  102. }
  103. return _loop_period_s;
  104. }
  105. float get_filtered_loop_time(void) const {
  106. return perf_info.get_filtered_time();
  107. }
  108. // get the time in seconds that the last loop took
  109. float get_last_loop_time_s(void) const {
  110. return _last_loop_time_s;
  111. }
  112. // get the amount of extra time being added on each loop
  113. uint32_t get_extra_loop_us(void) const {
  114. return extra_loop_us;
  115. }
  116. static const struct AP_Param::GroupInfo var_info[];
  117. // loop performance monitoring:
  118. AP::PerfInfo perf_info;
  119. private:
  120. // function that is called before anything in the scheduler table:
  121. scheduler_fastloop_fn_t _fastloop_fn;
  122. // used to enable scheduler debugging
  123. AP_Int8 _debug;
  124. // overall scheduling rate in Hz
  125. AP_Int16 _loop_rate_hz;
  126. // loop rate in Hz as set at startup
  127. AP_Int16 _active_loop_rate_hz;
  128. // calculated loop period in usec
  129. uint16_t _loop_period_us;
  130. // calculated loop period in seconds
  131. float _loop_period_s;
  132. // progmem list of tasks to run
  133. const struct Task *_tasks;
  134. // number of tasks in _tasks list
  135. uint8_t _num_tasks;
  136. // number of 'ticks' that have passed (number of times that
  137. // tick() has been called
  138. uint16_t _tick_counter;
  139. // tick counter at the time we last ran each task
  140. uint16_t *_last_run;
  141. // number of microseconds allowed for the current task
  142. uint32_t _task_time_allowed;
  143. // the time in microseconds when the task started
  144. uint32_t _task_time_started;
  145. // number of spare microseconds accumulated
  146. uint32_t _spare_micros;
  147. // number of ticks that _spare_micros is counted over
  148. uint8_t _spare_ticks;
  149. // start of loop timing
  150. uint32_t _loop_timer_start_us;
  151. // time of last loop in seconds
  152. float _last_loop_time_s;
  153. // performance counters
  154. AP_HAL::Util::perf_counter_t *_perf_counters;
  155. // bitmask bit which indicates if we should log PERF message
  156. uint32_t _log_performance_bit;
  157. // maximum task slowdown compared to desired task rate before we
  158. // start giving extra time per loop
  159. const uint8_t max_task_slowdown = 4;
  160. // counters to handle dynamically adjusting extra loop time to
  161. // cope with low CPU conditions
  162. uint32_t task_not_achieved;
  163. uint32_t task_all_achieved;
  164. // extra time available for each loop - used to dynamically adjust
  165. // the loop rate in case we are well over budget
  166. uint32_t extra_loop_us;
  167. };
  168. namespace AP {
  169. AP_Scheduler &scheduler();
  170. };