mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_Scheduler: make loop times cover INS wait_for_sample
this matches past behaviour, and gives much more useful information to a user wanting to know if their board it meeting its desired loop rate
This commit is contained in:
parent
434c3fffc7
commit
24d6493453
@ -209,11 +209,11 @@ float AP_Scheduler::load_average()
|
||||
|
||||
void AP_Scheduler::loop()
|
||||
{
|
||||
const uint32_t timer = AP_HAL::micros();
|
||||
|
||||
// wait for an INS sample
|
||||
AP::ins().wait_for_sample();
|
||||
|
||||
const uint32_t timer = AP_HAL::micros();
|
||||
|
||||
// used by PI Loops
|
||||
last_loop_time = (float)(timer - loop_start) / 1000000.0f;
|
||||
loop_start = timer;
|
||||
|
Loading…
Reference in New Issue
Block a user