AP_Scheduler.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367
  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. #include "AP_Scheduler.h"
  19. #include <AP_HAL/AP_HAL.h>
  20. #include <AP_Param/AP_Param.h>
  21. #include <AP_Vehicle/AP_Vehicle.h>
  22. #include <AP_Logger/AP_Logger.h>
  23. #include <AP_InertialSensor/AP_InertialSensor.h>
  24. #include <AP_InternalError/AP_InternalError.h>
  25. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  26. #include <SITL/SITL.h>
  27. #endif
  28. #include <stdio.h>
  29. #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
  30. #define SCHEDULER_DEFAULT_LOOP_RATE 400
  31. #else
  32. #define SCHEDULER_DEFAULT_LOOP_RATE 50
  33. #endif
  34. #define debug(level, fmt, args...) do { if ((level) <= _debug.get()) { hal.console->printf(fmt, ##args); }} while (0)
  35. extern const AP_HAL::HAL& hal;
  36. const AP_Param::GroupInfo AP_Scheduler::var_info[] = {
  37. // @Param: DEBUG
  38. // @DisplayName: Scheduler debug level
  39. // @Description: Set to non-zero to enable scheduler debug messages. When set to show "Slips" the scheduler will display a message whenever a scheduled task is delayed due to too much CPU load. When set to ShowOverruns the scheduled will display a message whenever a task takes longer than the limit promised in the task table.
  40. // @Values: 0:Disabled,2:ShowSlips,3:ShowOverruns
  41. // @User: Advanced
  42. AP_GROUPINFO("DEBUG", 0, AP_Scheduler, _debug, 0),
  43. // @Param: LOOP_RATE
  44. // @DisplayName: Scheduling main loop rate
  45. // @Description: This controls the rate of the main control loop in Hz. This should only be changed by developers. This only takes effect on restart. Values over 400 are considered highly experimental.
  46. // @Values: 50:50Hz,100:100Hz,200:200Hz,250:250Hz,300:300Hz,400:400Hz
  47. // @RebootRequired: True
  48. // @User: Advanced
  49. AP_GROUPINFO("LOOP_RATE", 1, AP_Scheduler, _loop_rate_hz, SCHEDULER_DEFAULT_LOOP_RATE),
  50. AP_GROUPEND
  51. };
  52. // constructor
  53. AP_Scheduler::AP_Scheduler(scheduler_fastloop_fn_t fastloop_fn) :
  54. _fastloop_fn(fastloop_fn)
  55. {
  56. if (_singleton) {
  57. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  58. AP_HAL::panic("Too many schedulers");
  59. #endif
  60. return;
  61. }
  62. _singleton = this;
  63. AP_Param::setup_object_defaults(this, var_info);
  64. // only allow 50 to 2000 Hz
  65. if (_loop_rate_hz < 50) {
  66. _loop_rate_hz.set(50);
  67. } else if (_loop_rate_hz > 2000) {
  68. _loop_rate_hz.set(2000);
  69. }
  70. _last_loop_time_s = 1.0 / _loop_rate_hz;
  71. }
  72. /*
  73. * Get the AP_Scheduler singleton
  74. */
  75. AP_Scheduler *AP_Scheduler::_singleton;
  76. AP_Scheduler *AP_Scheduler::get_singleton()
  77. {
  78. return _singleton;
  79. }
  80. // initialise the scheduler
  81. void AP_Scheduler::init(const AP_Scheduler::Task *tasks, uint8_t num_tasks, uint32_t log_performance_bit)
  82. {
  83. _tasks = tasks;
  84. _num_tasks = num_tasks;
  85. _last_run = new uint16_t[_num_tasks];
  86. memset(_last_run, 0, sizeof(_last_run[0]) * _num_tasks);
  87. _tick_counter = 0;
  88. // setup initial performance counters
  89. perf_info.set_loop_rate(get_loop_rate_hz());
  90. perf_info.reset();
  91. _log_performance_bit = log_performance_bit;
  92. }
  93. // one tick has passed
  94. void AP_Scheduler::tick(void)
  95. {
  96. _tick_counter++;
  97. }
  98. /*
  99. run one tick
  100. this will run as many scheduler tasks as we can in the specified time
  101. */
  102. void AP_Scheduler::run(uint32_t time_available)
  103. {
  104. uint32_t run_started_usec = AP_HAL::micros();
  105. uint32_t now = run_started_usec;
  106. if (_debug > 1 && _perf_counters == nullptr) {
  107. _perf_counters = new AP_HAL::Util::perf_counter_t[_num_tasks];
  108. if (_perf_counters != nullptr) {
  109. for (uint8_t i=0; i<_num_tasks; i++) {
  110. _perf_counters[i] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, _tasks[i].name);
  111. }
  112. }
  113. }
  114. for (uint8_t i=0; i<_num_tasks; i++) {
  115. uint32_t dt = _tick_counter - _last_run[i];
  116. uint32_t interval_ticks = _loop_rate_hz / _tasks[i].rate_hz;
  117. if (interval_ticks < 1) {
  118. interval_ticks = 1;
  119. }
  120. if (dt < interval_ticks) {
  121. // this task is not yet scheduled to run again
  122. continue;
  123. }
  124. // this task is due to run. Do we have enough time to run it?
  125. _task_time_allowed = _tasks[i].max_time_micros;
  126. if (dt >= interval_ticks*2) {
  127. // we've slipped a whole run of this task!
  128. debug(2, "Scheduler slip task[%u-%s] (%u/%u/%u)\n",
  129. (unsigned)i,
  130. _tasks[i].name,
  131. (unsigned)dt,
  132. (unsigned)interval_ticks,
  133. (unsigned)_task_time_allowed);
  134. }
  135. if (dt >= interval_ticks*max_task_slowdown) {
  136. // we are going beyond the maximum slowdown factor for a
  137. // task. This will trigger increasing the time budget
  138. task_not_achieved++;
  139. }
  140. if (_task_time_allowed > time_available) {
  141. // not enough time to run this task. Continue loop -
  142. // maybe another task will fit into time remaining
  143. continue;
  144. }
  145. // run it
  146. _task_time_started = now;
  147. hal.util->persistent_data.scheduler_task = i;
  148. if (_debug > 1 && _perf_counters && _perf_counters[i]) {
  149. hal.util->perf_begin(_perf_counters[i]);
  150. }
  151. _tasks[i].function();
  152. if (_debug > 1 && _perf_counters && _perf_counters[i]) {
  153. hal.util->perf_end(_perf_counters[i]);
  154. }
  155. hal.util->persistent_data.scheduler_task = -1;
  156. // record the tick counter when we ran. This drives
  157. // when we next run the event
  158. _last_run[i] = _tick_counter;
  159. // work out how long the event actually took
  160. now = AP_HAL::micros();
  161. uint32_t time_taken = now - _task_time_started;
  162. if (time_taken > _task_time_allowed) {
  163. // the event overran!
  164. debug(3, "Scheduler overrun task[%u-%s] (%u/%u)\n",
  165. (unsigned)i,
  166. _tasks[i].name,
  167. (unsigned)time_taken,
  168. (unsigned)_task_time_allowed);
  169. }
  170. if (time_taken >= time_available) {
  171. time_available = 0;
  172. break;
  173. }
  174. time_available -= time_taken;
  175. }
  176. // update number of spare microseconds
  177. _spare_micros += time_available;
  178. _spare_ticks++;
  179. if (_spare_ticks == 32) {
  180. _spare_ticks /= 2;
  181. _spare_micros /= 2;
  182. }
  183. }
  184. /*
  185. return number of micros until the current task reaches its deadline
  186. */
  187. uint16_t AP_Scheduler::time_available_usec(void)
  188. {
  189. uint32_t dt = AP_HAL::micros() - _task_time_started;
  190. if (dt > _task_time_allowed) {
  191. return 0;
  192. }
  193. return _task_time_allowed - dt;
  194. }
  195. /*
  196. calculate load average as a number from 0 to 1
  197. */
  198. float AP_Scheduler::load_average()
  199. {
  200. if (_spare_ticks == 0) {
  201. return 0.0f;
  202. }
  203. const uint32_t loop_us = get_loop_period_us();
  204. const uint32_t used_time = loop_us - (_spare_micros/_spare_ticks);
  205. return used_time / (float)loop_us;
  206. }
  207. void AP_Scheduler::loop()
  208. {
  209. // wait for an INS sample
  210. hal.util->persistent_data.scheduler_task = -3;
  211. AP::ins().wait_for_sample();
  212. hal.util->persistent_data.scheduler_task = -1;
  213. const uint32_t sample_time_us = AP_HAL::micros();
  214. if (_loop_timer_start_us == 0) {
  215. _loop_timer_start_us = sample_time_us;
  216. _last_loop_time_s = get_loop_period_s();
  217. } else {
  218. _last_loop_time_s = (sample_time_us - _loop_timer_start_us) * 1.0e-6;
  219. }
  220. // Execute the fast loop
  221. // ---------------------
  222. if (_fastloop_fn) {
  223. hal.util->persistent_data.scheduler_task = -2;
  224. _fastloop_fn();
  225. hal.util->persistent_data.scheduler_task = -1;
  226. }
  227. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  228. {
  229. /*
  230. for testing low CPU conditions we can add an optional delay in SITL
  231. */
  232. auto *sitl = AP::sitl();
  233. uint32_t loop_delay_us = sitl->loop_delay.get();
  234. hal.scheduler->delay_microseconds(loop_delay_us);
  235. }
  236. #endif
  237. // tell the scheduler one tick has passed
  238. tick();
  239. // run all the tasks that are due to run. Note that we only
  240. // have to call this once per loop, as the tasks are scheduled
  241. // in multiples of the main loop tick. So if they don't run on
  242. // the first call to the scheduler they won't run on a later
  243. // call until scheduler.tick() is called again
  244. const uint32_t loop_us = get_loop_period_us();
  245. uint32_t now = AP_HAL::micros();
  246. uint32_t time_available = 0;
  247. if (now - sample_time_us < loop_us) {
  248. // get remaining time available for this loop
  249. time_available = loop_us - (now - sample_time_us);
  250. }
  251. // add in extra loop time determined by not achieving scheduler tasks
  252. time_available += extra_loop_us;
  253. // run the tasks
  254. run(time_available);
  255. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  256. // move result of AP_HAL::micros() forward:
  257. hal.scheduler->delay_microseconds(1);
  258. #endif
  259. if (task_not_achieved > 0) {
  260. // add some extra time to the budget
  261. extra_loop_us = MIN(extra_loop_us+100U, 5000U);
  262. task_not_achieved = 0;
  263. task_all_achieved = 0;
  264. } else if (extra_loop_us > 0) {
  265. task_all_achieved++;
  266. if (task_all_achieved > 50) {
  267. // we have gone through 50 loops without a task taking too
  268. // long. CPU pressure has eased, so drop the extra time we're
  269. // giving each loop
  270. task_all_achieved = 0;
  271. // we are achieving all tasks, slowly lower the extra loop time
  272. extra_loop_us = MAX(0U, extra_loop_us-50U);
  273. }
  274. }
  275. // check loop time
  276. perf_info.check_loop_time(sample_time_us - _loop_timer_start_us);
  277. _loop_timer_start_us = sample_time_us;
  278. }
  279. void AP_Scheduler::update_logging()
  280. {
  281. if (debug_flags()) {
  282. perf_info.update_logging();
  283. }
  284. if (_log_performance_bit != (uint32_t)-1 &&
  285. AP::logger().should_log(_log_performance_bit)) {
  286. Log_Write_Performance();
  287. }
  288. perf_info.set_loop_rate(get_loop_rate_hz());
  289. perf_info.reset();
  290. }
  291. // Write a performance monitoring packet
  292. void AP_Scheduler::Log_Write_Performance()
  293. {
  294. const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
  295. struct log_Performance pkt = {
  296. LOG_PACKET_HEADER_INIT(LOG_PERFORMANCE_MSG),
  297. time_us : AP_HAL::micros64(),
  298. num_long_running : perf_info.get_num_long_running(),
  299. num_loops : perf_info.get_num_loops(),
  300. max_time : perf_info.get_max_time(),
  301. mem_avail : hal.util->available_memory(),
  302. load : (uint16_t)(load_average() * 1000),
  303. internal_errors : AP::internalerror().errors(),
  304. internal_error_count : AP::internalerror().count(),
  305. spi_count : pd.spi_count,
  306. i2c_count : pd.i2c_count,
  307. i2c_isr_count : pd.i2c_isr_count,
  308. extra_loop_us : extra_loop_us,
  309. };
  310. AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt));
  311. }
  312. namespace AP {
  313. AP_Scheduler &scheduler()
  314. {
  315. return *AP_Scheduler::get_singleton();
  316. }
  317. };