diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index d146c3b26a..fb585e970a 100644 --- a/ArduCopter/RC_Channel.cpp +++ b/ArduCopter/RC_Channel.cpp @@ -73,7 +73,6 @@ void RC_Channel_Copter::init_aux_function(const aux_func_t ch_option, const aux_ case AUX_FUNC::ATTCON_FEEDFWD: case AUX_FUNC::ATTCON_ACCEL_LIM: case AUX_FUNC::MOTOR_INTERLOCK: - case AUX_FUNC::AVOID_ADSB: case AUX_FUNC::PRECISION_LOITER: case AUX_FUNC::INVERTED: case AUX_FUNC::WINCH_ENABLE: @@ -366,19 +365,6 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw #endif break; - case AUX_FUNC::AVOID_ADSB: -#if ADSB_ENABLED == ENABLED - // enable or disable AP_Avoidance - if (ch_flag == HIGH) { - copter.avoidance_adsb.enable(); - AP::logger().Write_Event(LogEvent::AVOIDANCE_ADSB_ENABLE); - } else { - copter.avoidance_adsb.disable(); - AP::logger().Write_Event(LogEvent::AVOIDANCE_ADSB_DISABLE); - } -#endif - break; - case AUX_FUNC::PRECISION_LOITER: #if PRECISION_LANDING == ENABLED && MODE_LOITER_ENABLED == ENABLED switch (ch_flag) {