AP_Scheduler: allow registration of tasks at loop rate

This commit is contained in:
Andy Piper 2020-01-01 20:36:19 +00:00 committed by Andrew Tridgell
parent 7663c67eec
commit a16bb2f188
2 changed files with 3 additions and 1 deletions

View File

@ -160,7 +160,8 @@ void AP_Scheduler::run(uint32_t time_available)
const AP_Scheduler::Task& task = (i < _num_unshared_tasks) ? _tasks[i] : _common_tasks[i - _num_unshared_tasks];
uint32_t dt = _tick_counter - _last_run[i];
uint32_t interval_ticks = _loop_rate_hz / task.rate_hz;
// we allow 0 to mean loop rate
uint32_t interval_ticks = (is_zero(task.rate_hz) ? 1 : _loop_rate_hz / task.rate_hz);
if (interval_ticks < 1) {
interval_ticks = 1;
}

View File

@ -26,6 +26,7 @@
#include "PerfInfo.h" // loop perf monitoring
#define AP_SCHEDULER_NAME_INITIALIZER(_name) .name = #_name,
#define LOOP_RATE 0
/*
useful macro for creating scheduler task table