diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index a5ec2d6c10..82e52109c3 100644 --- a/ArduCopter/RC_Channel.cpp +++ b/ArduCopter/RC_Channel.cpp @@ -68,8 +68,6 @@ void RC_Channel_Copter::init_aux_function(const aux_func_t ch_option, const aux_ case FENCE: case SUPERSIMPLE_MODE: case ACRO_TRAINER: - case GRIPPER: - case SPRAYER: case PARACHUTE_ENABLE: case PARACHUTE_3POS: // we trust the vehicle will be disarmed so even if switch is in release position the chute will not release case RETRACT_MOUNT: @@ -266,32 +264,6 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw #endif break; - case GRIPPER: -#if GRIPPER_ENABLED == ENABLED - switch(ch_flag) { - case LOW: - copter.g2.gripper.release(); - copter.Log_Write_Event(DATA_GRIPPER_RELEASE); - break; - case MIDDLE: - // nothing - break; - case HIGH: - copter.g2.gripper.grab(); - copter.Log_Write_Event(DATA_GRIPPER_GRAB); - break; - } -#endif - break; - - case SPRAYER: -#if SPRAYER_ENABLED == ENABLED - copter.sprayer.run(ch_flag == HIGH); - // if we are disarmed the pilot must want to test the pump - copter.sprayer.test_pump((ch_flag == HIGH) && !copter.motors->armed()); -#endif - break; - case AUTOTUNE: #if AUTOTUNE_ENABLED == ENABLED do_aux_function_change_mode(control_mode_t::AUTOTUNE, ch_flag);