Sub: add arming check for backup origin

Co-authored-by: Clyde McQueen <clyde@mcqueen.net>
This commit is contained in:
Willian Galvani 2024-06-27 16:30:31 -03:00
parent bd27edc9f5
commit 62d9b14a65
2 changed files with 6 additions and 3 deletions

View File

@ -152,8 +152,11 @@ bool AP_Arming_Sub::arm(AP_Arming::Method method, bool do_arming_checks)
// if we do not have an ekf origin then we can't use the WMM tables
if (!sub.ensure_ekf_origin()) {
gcs().send_text(MAV_SEVERITY_WARNING, "Compass performance degraded");
if (check_enabled(ARMING_CHECK_PARAMETERS)) {
check_failed(ARMING_CHECK_PARAMETERS, true, "No world position, check ORIGIN_* parameters");
return false;
}
}
// return success
return true;
}

View File

@ -709,14 +709,14 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Param: ORIGIN_LAT
// @DisplayName: Backup latitude for EKF origin
// @Description: Backup EKF origin latitude used when not using a positioning system.
// @Units: degrees
// @Units: deg
// @User: Standard
AP_GROUPINFO("ORIGIN_LAT", 19, ParametersG2, backup_origin_lat, 0),
// @Param: ORIGIN_LON
// @DisplayName: Backup longitude for EKF origin
// @Description: Backup EKF origin longitude used when not using a positioning system.
// @Units: degrees
// @Units: deg
// @User: Standard
AP_GROUPINFO("ORIGIN_LON", 20, ParametersG2, backup_origin_lon, 0),