mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
Plane: remove FS parameters default values macros.
They just add an un-necessary level of indirection in the code. The parameters are run-time configurable now.
This commit is contained in:
parent
6a01494d4a
commit
14b214eb9b
@ -478,7 +478,7 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @User: Standard
|
||||
GSCALAR(throttle_fs_enabled, "THR_FAILSAFE", THROTTLE_FAILSAFE),
|
||||
GSCALAR(throttle_fs_enabled, "THR_FAILSAFE", 1),
|
||||
|
||||
|
||||
// @Param: THR_FS_VALUE
|
||||
@ -487,7 +487,7 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
// @Range: 925 2200
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(throttle_fs_value, "THR_FS_VALUE", THROTTLE_FS_VALUE),
|
||||
GSCALAR(throttle_fs_value, "THR_FS_VALUE", 950),
|
||||
|
||||
// @Param: TRIM_THROTTLE
|
||||
// @DisplayName: Throttle cruise percentage
|
||||
@ -510,7 +510,7 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
// @Description: The action to take on a short (FS_SHORT_TIMEOUT) failsafe event. A short failsafe even can be triggered either by loss of RC control (see THR_FS_VALUE) or by loss of GCS control (see FS_GCS_ENABL). If in CIRCLE or RTL mode this parameter is ignored. A short failsafe event in stabilization and manual modes will cause an change to CIRCLE mode if FS_SHORT_ACTN is 0 or 1, and a change to FBWA mode if FS_SHORT_ACTN is 2. In all other modes (AUTO, GUIDED and LOITER) a short failsafe event will cause no mode change is FS_SHORT_ACTN is set to 0, will cause a change to CIRCLE mode if set to 1 and will change to FBWA mode if set to 2. Please see the documentation for FS_LONG_ACTN for the behaviour after FS_LONG_TIMEOUT seconds of failsafe.
|
||||
// @Values: 0:CIRCLE/no change(if already in AUTO|GUIDED|LOITER),1:CIRCLE,2:FBWA
|
||||
// @User: Standard
|
||||
GSCALAR(short_fs_action, "FS_SHORT_ACTN", SHORT_FAILSAFE_ACTION),
|
||||
GSCALAR(short_fs_action, "FS_SHORT_ACTN", 0),
|
||||
|
||||
// @Param: FS_SHORT_TIMEOUT
|
||||
// @DisplayName: Short failsafe timeout
|
||||
@ -526,7 +526,7 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
// @Description: The action to take on a long (FS_LONG_TIMEOUT seconds) failsafe event. If the aircraft was in a stabilization or manual mode when failsafe started and a long failsafe occurs then it will change to RTL mode if FS_LONG_ACTN is 0 or 1, and will change to FBWA if FS_LONG_ACTN is set to 2. If the aircraft was in an auto mode (such as AUTO or GUIDED) when the failsafe started then it will continue in the auto mode if FS_LONG_ACTN is set to 0, will change to RTL mode if FS_LONG_ACTN is set to 1 and will change to FBWA mode if FS_LONG_ACTN is set to 2. If FS_LONG_ACTION is set to 3, the parachute will be deployed (make sure the chute is configured and enabled).
|
||||
// @Values: 0:Continue,1:ReturnToLaunch,2:Glide,3:Deploy Parachute
|
||||
// @User: Standard
|
||||
GSCALAR(long_fs_action, "FS_LONG_ACTN", LONG_FAILSAFE_ACTION),
|
||||
GSCALAR(long_fs_action, "FS_LONG_ACTN", 0),
|
||||
|
||||
// @Param: FS_LONG_TIMEOUT
|
||||
// @DisplayName: Long failsafe timeout
|
||||
|
@ -154,24 +154,6 @@
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// THROTTLE_FAILSAFE
|
||||
// THROTTLE_FS_VALUE
|
||||
// SHORT_FAILSAFE_ACTION
|
||||
// LONG_FAILSAFE_ACTION
|
||||
#ifndef THROTTLE_FAILSAFE
|
||||
# define THROTTLE_FAILSAFE ENABLED
|
||||
#endif
|
||||
#ifndef THROTTLE_FS_VALUE
|
||||
# define THROTTLE_FS_VALUE 950
|
||||
#endif
|
||||
#ifndef SHORT_FAILSAFE_ACTION
|
||||
# define SHORT_FAILSAFE_ACTION 0
|
||||
#endif
|
||||
#ifndef LONG_FAILSAFE_ACTION
|
||||
# define LONG_FAILSAFE_ACTION 0
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// AUTO_TRIM
|
||||
//
|
||||
|
Loading…
Reference in New Issue
Block a user