mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-12 10:58:30 -04:00
Added check for armed motors in failsafe
This commit is contained in:
parent
a640311f58
commit
57c3405658
@ -142,6 +142,7 @@ static void read_radio()
|
|||||||
|
|
||||||
static void throttle_failsafe(uint16_t pwm)
|
static void throttle_failsafe(uint16_t pwm)
|
||||||
{
|
{
|
||||||
|
// Don't enter Failsafe if not enabled by user
|
||||||
if(g.throttle_fs_enabled == 0)
|
if(g.throttle_fs_enabled == 0)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
@ -155,6 +156,8 @@ static void throttle_failsafe(uint16_t pwm)
|
|||||||
SendDebug("MSG FS ON ");
|
SendDebug("MSG FS ON ");
|
||||||
SendDebugln(pwm, DEC);
|
SendDebugln(pwm, DEC);
|
||||||
}else if(failsafeCounter == 10) {
|
}else if(failsafeCounter == 10) {
|
||||||
|
// Don't enter Failsafe if we are not armed
|
||||||
|
if(motor_armed == true)
|
||||||
set_failsafe(true);
|
set_failsafe(true);
|
||||||
}else if (failsafeCounter > 10){
|
}else if (failsafeCounter > 10){
|
||||||
failsafeCounter = 11;
|
failsafeCounter = 11;
|
||||||
|
Loading…
Reference in New Issue
Block a user