mirror of https://github.com/ArduPilot/ardupilot
cosmetic
This commit is contained in:
parent
1883d0c1a8
commit
d7f4328441
|
@ -31,7 +31,6 @@ static void init_rc_in()
|
|||
// reverse: CW = left
|
||||
// normal: CW = left???
|
||||
|
||||
|
||||
g.rc_1.set_type(RC_CHANNEL_ANGLE_RAW);
|
||||
g.rc_2.set_type(RC_CHANNEL_ANGLE_RAW);
|
||||
g.rc_4.set_type(RC_CHANNEL_ANGLE_RAW);
|
||||
|
@ -43,13 +42,11 @@ static void init_rc_in()
|
|||
g.rc_4.dead_zone = 300;
|
||||
*/
|
||||
|
||||
|
||||
//set auxiliary ranges
|
||||
g.rc_5.set_range(0,1000);
|
||||
g.rc_6.set_range(0,1000);
|
||||
g.rc_7.set_range(0,1000);
|
||||
g.rc_8.set_range(0,1000);
|
||||
|
||||
}
|
||||
|
||||
static void init_rc_out()
|
||||
|
@ -158,9 +155,7 @@ static void throttle_failsafe(uint16_t pwm)
|
|||
SendDebug("MSG FS ON ");
|
||||
SendDebugln(pwm, DEC);
|
||||
}else if(failsafeCounter == 10) {
|
||||
//ch3_failsafe = true;
|
||||
set_failsafe(true);
|
||||
//failsafeCounter = 10;
|
||||
}else if (failsafeCounter > 10){
|
||||
failsafeCounter = 11;
|
||||
}
|
||||
|
@ -176,9 +171,7 @@ static void throttle_failsafe(uint16_t pwm)
|
|||
SendDebug("MSG FS OFF ");
|
||||
SendDebugln(pwm, DEC);
|
||||
}else if(failsafeCounter == 0) {
|
||||
//ch3_failsafe = false;
|
||||
set_failsafe(false);
|
||||
//failsafeCounter = -1;
|
||||
}else if (failsafeCounter <0){
|
||||
failsafeCounter = -1;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue