mirror of https://github.com/ArduPilot/ardupilot
updated failsafe code
This commit is contained in:
parent
19c3c27ed0
commit
ea911e0bcb
|
@ -139,7 +139,7 @@ static void read_radio()
|
||||||
g.rc_3.control_in = min(g.rc_3.control_in, 800);
|
g.rc_3.control_in = min(g.rc_3.control_in, 800);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//throttle_failsafe(g.rc_3.radio_in);
|
throttle_failsafe(g.rc_3.radio_in);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -158,8 +158,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) {
|
||||||
ch3_failsafe = true;
|
//ch3_failsafe = true;
|
||||||
//set_failsafe(true);
|
set_failsafe(true);
|
||||||
//failsafeCounter = 10;
|
//failsafeCounter = 10;
|
||||||
}else if (failsafeCounter > 10){
|
}else if (failsafeCounter > 10){
|
||||||
failsafeCounter = 11;
|
failsafeCounter = 11;
|
||||||
|
@ -176,8 +176,8 @@ static void throttle_failsafe(uint16_t pwm)
|
||||||
SendDebug("MSG FS OFF ");
|
SendDebug("MSG FS OFF ");
|
||||||
SendDebugln(pwm, DEC);
|
SendDebugln(pwm, DEC);
|
||||||
}else if(failsafeCounter == 0) {
|
}else if(failsafeCounter == 0) {
|
||||||
ch3_failsafe = false;
|
//ch3_failsafe = false;
|
||||||
//set_failsafe(false);
|
set_failsafe(false);
|
||||||
//failsafeCounter = -1;
|
//failsafeCounter = -1;
|
||||||
}else if (failsafeCounter <0){
|
}else if (failsafeCounter <0){
|
||||||
failsafeCounter = -1;
|
failsafeCounter = -1;
|
||||||
|
|
Loading…
Reference in New Issue