mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_Scheduler: initialise _last_loop_time_s in init()
This commit is contained in:
parent
f190ca0867
commit
6cc007598e
@ -71,6 +71,7 @@ AP_Scheduler::AP_Scheduler(scheduler_fastloop_fn_t fastloop_fn) :
|
|||||||
} else if (_loop_rate_hz > 2000) {
|
} else if (_loop_rate_hz > 2000) {
|
||||||
_loop_rate_hz.set(2000);
|
_loop_rate_hz.set(2000);
|
||||||
}
|
}
|
||||||
|
_last_loop_time_s = 1.0 / _loop_rate_hz;
|
||||||
}
|
}
|
||||||
|
|
||||||
// initialise the scheduler
|
// initialise the scheduler
|
||||||
|
Loading…
Reference in New Issue
Block a user