AP_AHRS: implement timing jitter in SITL

make the AHRS update take a random amount of extra CPU time
This commit is contained in:
Andrew Tridgell 2022-12-05 15:06:45 +11:00
parent 7039088c7b
commit 81b519056b
1 changed files with 10 additions and 0 deletions

View File

@ -420,6 +420,16 @@ void AP_AHRS::update(bool skip_ins_update)
}
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AHRS: %s active", shortname);
}
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
/*
add timing jitter to simulate slow EKF response
*/
const auto *sitl = AP::sitl();
if (sitl->loop_time_jitter_us > 0) {
hal.scheduler->delay_microseconds(random() % sitl->loop_time_jitter_us);
}
#endif
}
/*