APM: removed THROTTLE_REVERSE option
Better to use RC3_REV
This commit is contained in:
parent
988bc0238a
commit
54f97bb9e7
@ -367,12 +367,6 @@ static void set_servos(void)
|
||||
|
||||
g.channel_throttle.calc_pwm();
|
||||
|
||||
/* TO DO - fix this for RC_Channel library
|
||||
#if THROTTLE_REVERSE == 1
|
||||
radio_out[CH_THROTTLE] = radio_max(CH_THROTTLE) + radio_min(CH_THROTTLE) - radio_out[CH_THROTTLE];
|
||||
#endif
|
||||
*/
|
||||
|
||||
if (control_mode >= FLY_BY_WIRE_B) {
|
||||
/* only do throttle slew limiting in modes where throttle
|
||||
control is automatic */
|
||||
|
@ -378,14 +378,6 @@
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// THROTTLE_REVERSE
|
||||
//
|
||||
#ifndef THROTTLE_REVERSE
|
||||
# define THROTTLE_REVERSE DISABLED
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// THROTTLE_OUT
|
||||
//
|
||||
|
@ -90,11 +90,6 @@ static void read_radio()
|
||||
g.rc_7.set_pwm(APM_RC.InputCh(CH_7));
|
||||
g.rc_8.set_pwm(APM_RC.InputCh(CH_8));
|
||||
|
||||
// TO DO - go through and patch throttle reverse for RC_Channel library compatibility
|
||||
#if THROTTLE_REVERSE == 1
|
||||
g.channel_throttle.radio_in = g.channel_throttle.radio_max + g.channel_throttle.radio_min - g.channel_throttle.radio_in;
|
||||
#endif
|
||||
|
||||
control_failsafe(g.channel_throttle.radio_in);
|
||||
|
||||
g.channel_throttle.servo_out = g.channel_throttle.control_in;
|
||||
|
@ -157,11 +157,6 @@ test_radio(uint8_t argc, const Menu::arg *argv)
|
||||
print_hit_enter();
|
||||
delay(1000);
|
||||
|
||||
#if THROTTLE_REVERSE == 1
|
||||
Serial.printf_P(PSTR("Throttle is reversed in config: \n"));
|
||||
delay(1000);
|
||||
#endif
|
||||
|
||||
// read the radio to set trims
|
||||
// ---------------------------
|
||||
trim_radio();
|
||||
|
Loading…
Reference in New Issue
Block a user