mirror of https://github.com/ArduPilot/ardupilot
Sub: add arming check for backup origin
Co-authored-by: Clyde McQueen <clyde@mcqueen.net>
This commit is contained in:
parent
bd27edc9f5
commit
62d9b14a65
|
@ -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 we do not have an ekf origin then we can't use the WMM tables
|
||||||
if (!sub.ensure_ekf_origin()) {
|
if (!sub.ensure_ekf_origin()) {
|
||||||
gcs().send_text(MAV_SEVERITY_WARNING, "Compass performance degraded");
|
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 success
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
|
@ -709,14 +709,14 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||||
// @Param: ORIGIN_LAT
|
// @Param: ORIGIN_LAT
|
||||||
// @DisplayName: Backup latitude for EKF origin
|
// @DisplayName: Backup latitude for EKF origin
|
||||||
// @Description: Backup EKF origin latitude used when not using a positioning system.
|
// @Description: Backup EKF origin latitude used when not using a positioning system.
|
||||||
// @Units: degrees
|
// @Units: deg
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("ORIGIN_LAT", 19, ParametersG2, backup_origin_lat, 0),
|
AP_GROUPINFO("ORIGIN_LAT", 19, ParametersG2, backup_origin_lat, 0),
|
||||||
|
|
||||||
// @Param: ORIGIN_LON
|
// @Param: ORIGIN_LON
|
||||||
// @DisplayName: Backup longitude for EKF origin
|
// @DisplayName: Backup longitude for EKF origin
|
||||||
// @Description: Backup EKF origin longitude used when not using a positioning system.
|
// @Description: Backup EKF origin longitude used when not using a positioning system.
|
||||||
// @Units: degrees
|
// @Units: deg
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("ORIGIN_LON", 20, ParametersG2, backup_origin_lon, 0),
|
AP_GROUPINFO("ORIGIN_LON", 20, ParametersG2, backup_origin_lon, 0),
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue