mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_Scheduler: use continue instead of nested-if (NFC)
This commit is contained in:
parent
224ea50260
commit
badfde6f18
@ -137,40 +137,44 @@ void AP_Scheduler::run(uint32_t time_available)
|
||||
(unsigned)_task_time_allowed);
|
||||
}
|
||||
|
||||
if (_task_time_allowed <= time_available) {
|
||||
// run it
|
||||
_task_time_started = now;
|
||||
current_task = i;
|
||||
if (_debug > 1 && _perf_counters && _perf_counters[i]) {
|
||||
hal.util->perf_begin(_perf_counters[i]);
|
||||
}
|
||||
_tasks[i].function();
|
||||
if (_debug > 1 && _perf_counters && _perf_counters[i]) {
|
||||
hal.util->perf_end(_perf_counters[i]);
|
||||
}
|
||||
current_task = -1;
|
||||
|
||||
// record the tick counter when we ran. This drives
|
||||
// when we next run the event
|
||||
_last_run[i] = _tick_counter;
|
||||
|
||||
// work out how long the event actually took
|
||||
now = AP_HAL::micros();
|
||||
uint32_t time_taken = now - _task_time_started;
|
||||
|
||||
if (time_taken > _task_time_allowed) {
|
||||
// the event overran!
|
||||
debug(3, "Scheduler overrun task[%u-%s] (%u/%u)\n",
|
||||
(unsigned)i,
|
||||
_tasks[i].name,
|
||||
(unsigned)time_taken,
|
||||
(unsigned)_task_time_allowed);
|
||||
}
|
||||
if (time_taken >= time_available) {
|
||||
goto update_spare_ticks;
|
||||
}
|
||||
time_available -= time_taken;
|
||||
if (_task_time_allowed > time_available) {
|
||||
// not enough time to run this task. Continue loop -
|
||||
// maybe another task will fit into time remaining
|
||||
continue;
|
||||
}
|
||||
|
||||
// run it
|
||||
_task_time_started = now;
|
||||
current_task = i;
|
||||
if (_debug > 1 && _perf_counters && _perf_counters[i]) {
|
||||
hal.util->perf_begin(_perf_counters[i]);
|
||||
}
|
||||
_tasks[i].function();
|
||||
if (_debug > 1 && _perf_counters && _perf_counters[i]) {
|
||||
hal.util->perf_end(_perf_counters[i]);
|
||||
}
|
||||
current_task = -1;
|
||||
|
||||
// record the tick counter when we ran. This drives
|
||||
// when we next run the event
|
||||
_last_run[i] = _tick_counter;
|
||||
|
||||
// work out how long the event actually took
|
||||
now = AP_HAL::micros();
|
||||
uint32_t time_taken = now - _task_time_started;
|
||||
|
||||
if (time_taken > _task_time_allowed) {
|
||||
// the event overran!
|
||||
debug(3, "Scheduler overrun task[%u-%s] (%u/%u)\n",
|
||||
(unsigned)i,
|
||||
_tasks[i].name,
|
||||
(unsigned)time_taken,
|
||||
(unsigned)_task_time_allowed);
|
||||
}
|
||||
if (time_taken >= time_available) {
|
||||
goto update_spare_ticks;
|
||||
}
|
||||
time_available -= time_taken;
|
||||
}
|
||||
|
||||
// update number of spare microseconds
|
||||
|
Loading…
Reference in New Issue
Block a user