diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde index 9e0d0adefe..6d50b2c2fa 100644 --- a/ArduPlane/Attitude.pde +++ b/ArduPlane/Attitude.pde @@ -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 */ diff --git a/ArduPlane/config.h b/ArduPlane/config.h index 6cbd7e3945..65d3286a8a 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -378,14 +378,6 @@ #endif -////////////////////////////////////////////////////////////////////////////// -// THROTTLE_REVERSE -// -#ifndef THROTTLE_REVERSE -# define THROTTLE_REVERSE DISABLED -#endif - - ////////////////////////////////////////////////////////////////////////////// // THROTTLE_OUT // diff --git a/ArduPlane/radio.pde b/ArduPlane/radio.pde index 27ed32ccea..e958226786 100644 --- a/ArduPlane/radio.pde +++ b/ArduPlane/radio.pde @@ -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; diff --git a/ArduPlane/test.pde b/ArduPlane/test.pde index f716ae6074..e70e1a8942 100644 --- a/ArduPlane/test.pde +++ b/ArduPlane/test.pde @@ -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();