mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
Copter: pre-arm check that gyro cal succeeded
This commit is contained in:
parent
834f2bea07
commit
128058362b
@ -368,6 +368,14 @@ static void pre_arm_checks(bool display_failure)
|
||||
return;
|
||||
}
|
||||
|
||||
// check gyros calibrated successfully
|
||||
if(!ins.gyro_calibrated_ok_all()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Gyro cal failed"));
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
#if INS_MAX_INSTANCES > 1
|
||||
// check all gyros are consistent
|
||||
if (ins.get_gyro_count() > 1) {
|
||||
|
Loading…
Reference in New Issue
Block a user