mirror of https://github.com/ArduPilot/ardupilot
Plane: remove unused param OVERRIDE_SAFETY
This commit is contained in:
parent
e82860266d
commit
88f2f7ccae
|
@ -726,17 +726,11 @@ const AP_Param::Info Plane::var_info[] = {
|
|||
#if HAL_WITH_IO_MCU
|
||||
// @Param: OVERRIDE_CHAN
|
||||
// @DisplayName: IO override channel
|
||||
// @Description: If set to a non-zero value then this is an RC input channel number to use for giving IO manual control in case the main FMU microcontroller on a board with a IO co-processor fails. When this RC input channel goes above 1750 the FMU microcontroller will no longer be involved in controlling the servos and instead the IO microcontroller will directly control the servos. Note that IO manual control will be automatically activated if the FMU crashes for any reason. This parameter allows you to test for correct manual behaviour without actually crashing the FMU. This parameter is can be set to a non-zero value either for ground testing purposes or for giving the effect of an external override control board. Please also see the docs on OVERRIDE_SAFETY. Note that you may set OVERRIDE_CHAN to the same channel as FLTMODE_CH to get IO based override when in flight mode 6. Note that when override is triggered due to a FMU crash the 6 auxiliary output channels on the FMU will no longer be updated, so all the flight controls you need must be assigned to the first 8 channels on boards with an IOMCU.
|
||||
// @Description: If set to a non-zero value then this is an RC input channel number to use for giving IO manual control in case the main FMU microcontroller on a board with a IO co-processor fails. When this RC input channel goes above 1750 the FMU microcontroller will no longer be involved in controlling the servos and instead the IO microcontroller will directly control the servos. Note that IO manual control will be automatically activated if the FMU crashes for any reason. This parameter allows you to test for correct manual behaviour without actually crashing the FMU. This parameter is can be set to a non-zero value either for ground testing purposes or for giving the effect of an external override control board. Note that you may set OVERRIDE_CHAN to the same channel as FLTMODE_CH to get IO based override when in flight mode 6. Note that when override is triggered due to a FMU crash the 6 auxiliary output channels on the FMU will no longer be updated, so all the flight controls you need must be assigned to the first 8 channels on boards with an IOMCU.
|
||||
// @Range: 0 16
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
GSCALAR(override_channel, "OVERRIDE_CHAN", 0),
|
||||
|
||||
// @Param: OVERRIDE_SAFETY
|
||||
// @DisplayName: IO override safety switch
|
||||
// @Description: This controls whether the safety switch is turned off when you activate override with OVERRIDE_CHAN. When set to 1 the safety switch is de-activated (activating the servos) then a IO override is triggered. In that case the safety remains de-activated after override is disabled. If OVERRIDE_SAFETTY is set to 0 then the safety switch state does not change. Note that regardless of the value of this parameter the servos will be active while override is active.
|
||||
// @User: Advanced
|
||||
GSCALAR(override_safety, "OVERRIDE_SAFETY", 1),
|
||||
#endif
|
||||
|
||||
// @Param: RTL_AUTOLAND
|
||||
|
|
|
@ -144,7 +144,7 @@ public:
|
|||
k_param_arming = 100,
|
||||
k_param_parachute_channel, // unused - moved to RC option
|
||||
k_param_crash_accel_threshold,
|
||||
k_param_override_safety,
|
||||
k_param_override_safety, // unused
|
||||
k_param_land_throttle_slewrate, // 104 unused - moved to AP_Landing
|
||||
|
||||
// 105: Extra parameters
|
||||
|
@ -473,7 +473,6 @@ public:
|
|||
AP_Int8 flap_slewrate;
|
||||
#if HAL_WITH_IO_MCU
|
||||
AP_Int8 override_channel;
|
||||
AP_Int8 override_safety;
|
||||
#endif
|
||||
AP_Int16 gcs_pid_mask;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue