Copter: Add GCS Failsafe Brake option

This commit is contained in:
Tatsuya Yamaguchi 2023-05-19 13:01:35 +09:00 committed by Peter Barker
parent 5333f404d3
commit 6b40fd11d6
3 changed files with 5 additions and 1 deletions

View File

@ -162,7 +162,7 @@ const AP_Param::Info Copter::var_info[] = {
// @Param: FS_GCS_ENABLE
// @DisplayName: Ground Station Failsafe Enable
// @Description: Controls whether failsafe will be invoked (and what action to take) when connection with Ground station is lost for at least 5 seconds. See FS_OPTIONS param for additional actions, or for cases allowing Mission continuation, when GCS failsafe is enabled.
// @Values: 0:Disabled/NoAction,1:RTL,2:RTL or Continue with Mission in Auto Mode (Removed in 4.0+-see FS_OPTIONS),3:SmartRTL or RTL,4:SmartRTL or Land,5:Land,6:Auto DO_LAND_START or RTL
// @Values: 0:Disabled/NoAction,1:RTL,2:RTL or Continue with Mission in Auto Mode (Removed in 4.0+-see FS_OPTIONS),3:SmartRTL or RTL,4:SmartRTL or Land,5:Land,6:Auto DO_LAND_START or RTL,7:Brake or Land
// @User: Standard
GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_DISABLED),

View File

@ -151,6 +151,7 @@ enum LoggingParameters {
#define FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_LAND 4
#define FS_GCS_ENABLED_ALWAYS_LAND 5
#define FS_GCS_ENABLED_AUTO_RTL_OR_RTL 6
#define FS_GCS_ENABLED_BRAKE_OR_LAND 7
// EKF failsafe definitions (FS_EKF_ACTION parameter)
#define FS_EKF_ACTION_LAND 1 // switch to LAND mode on EKF failsafe

View File

@ -187,6 +187,9 @@ void Copter::failsafe_gcs_on_event(void)
case FS_GCS_ENABLED_AUTO_RTL_OR_RTL:
desired_action = FailsafeAction::AUTO_DO_LAND_START;
break;
case FS_GCS_ENABLED_BRAKE_OR_LAND:
desired_action = FailsafeAction::BRAKE_LAND;
break;
default: // if an invalid parameter value is set, the fallback is RTL
desired_action = FailsafeAction::RTL;
}