mirror of https://github.com/ArduPilot/ardupilot
Plane: added THR_FAILSAFE=2 option
this allows for RC inputs to be ignored at low throttle, but won't trigger failsafe. It is meant for users flying BVLOS missions, where they want GCS failsafe enabled, but don't want RC failsafe, and want to be sure that RC inputs will be ignored at low RC throttle values Thanks to suggestion from Pompecukor
This commit is contained in:
parent
92e35f6a9e
commit
747fc5bbda
|
@ -58,7 +58,7 @@ bool AP_Arming_Plane::pre_arm_checks(bool display_failure)
|
||||||
}
|
}
|
||||||
|
|
||||||
if (plane.channel_throttle->get_reverse() &&
|
if (plane.channel_throttle->get_reverse() &&
|
||||||
plane.g.throttle_fs_enabled &&
|
Plane::ThrFailsafe(plane.g.throttle_fs_enabled.get()) != Plane::ThrFailsafe::Disabled &&
|
||||||
plane.g.throttle_fs_value <
|
plane.g.throttle_fs_value <
|
||||||
plane.channel_throttle->get_radio_max()) {
|
plane.channel_throttle->get_radio_max()) {
|
||||||
check_failed(display_failure, "Invalid THR_FS_VALUE for rev throttle");
|
check_failed(display_failure, "Invalid THR_FS_VALUE for rev throttle");
|
||||||
|
|
|
@ -460,10 +460,10 @@ const AP_Param::Info Plane::var_info[] = {
|
||||||
|
|
||||||
// @Param: THR_FAILSAFE
|
// @Param: THR_FAILSAFE
|
||||||
// @DisplayName: Throttle and RC Failsafe Enable
|
// @DisplayName: Throttle and RC Failsafe Enable
|
||||||
// @Description: This enables failsafe on loss of RC input. How this is detected depends on the type of RC receiver being used. For older radios an input below the THR_FS_VALUE is used to trigger failsafe. For newer radios the failsafe trigger is part of the protocol between the autopilot and receiver.
|
// @Description: This enables failsafe on loss of RC input. How this is detected depends on the type of RC receiver being used. For older radios an input below the THR_FS_VALUE is used to trigger failsafe. For newer radios the failsafe trigger is part of the protocol between the autopilot and receiver. A value of 2 means that the RC input won't be used when throttle goes below the THR_FS_VALUE, but it won't trigger a failsafe
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled,2:EnabledNoFailsafe
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(throttle_fs_enabled, "THR_FAILSAFE", 1),
|
GSCALAR(throttle_fs_enabled, "THR_FAILSAFE", int(ThrFailsafe::Enabled)),
|
||||||
|
|
||||||
|
|
||||||
// @Param: THR_FS_VALUE
|
// @Param: THR_FS_VALUE
|
||||||
|
|
|
@ -1056,6 +1056,12 @@ private:
|
||||||
static_assert(_failsafe_priorities[ARRAY_SIZE(_failsafe_priorities) - 1] == -1,
|
static_assert(_failsafe_priorities[ARRAY_SIZE(_failsafe_priorities) - 1] == -1,
|
||||||
"_failsafe_priorities is missing the sentinel");
|
"_failsafe_priorities is missing the sentinel");
|
||||||
|
|
||||||
|
enum class ThrFailsafe {
|
||||||
|
Disabled = 0,
|
||||||
|
Enabled = 1,
|
||||||
|
EnabledNoFS = 2
|
||||||
|
};
|
||||||
|
|
||||||
public:
|
public:
|
||||||
void mavlink_delay_cb();
|
void mavlink_delay_cb();
|
||||||
void failsafe_check(void);
|
void failsafe_check(void);
|
||||||
|
|
|
@ -282,7 +282,7 @@ void Plane::control_failsafe()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if(g.throttle_fs_enabled == 0) {
|
if (ThrFailsafe(g.throttle_fs_enabled.get()) != ThrFailsafe::Enabled) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -375,7 +375,7 @@ bool Plane::trim_radio()
|
||||||
*/
|
*/
|
||||||
bool Plane::rc_throttle_value_ok(void) const
|
bool Plane::rc_throttle_value_ok(void) const
|
||||||
{
|
{
|
||||||
if (!g.throttle_fs_enabled) {
|
if (ThrFailsafe(g.throttle_fs_enabled.get()) == ThrFailsafe::Disabled) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
if (channel_throttle->get_reverse()) {
|
if (channel_throttle->get_reverse()) {
|
||||||
|
|
Loading…
Reference in New Issue