Rover: do common gps arming checks first before moving on

This commit is contained in:
Siddharth Purohit 2021-03-03 15:03:12 +05:30 committed by Randy Mackay
parent da7d34224d
commit 694801254f
1 changed files with 6 additions and 2 deletions

View File

@ -39,6 +39,11 @@ bool AP_Arming_Rover::gps_checks(bool display_failure)
return true;
}
// call parent gps checks
if (!AP_Arming::gps_checks(display_failure)) {
return false;
}
const AP_AHRS &ahrs = AP::ahrs();
// always check if inertial nav has started and is ready
@ -61,8 +66,7 @@ bool AP_Arming_Rover::gps_checks(bool display_failure)
return false;
}
// call parent gps checks
return AP_Arming::gps_checks(display_failure);
return true;
}
bool AP_Arming_Rover::pre_arm_checks(bool report)