Browse Source

Copter: move mission reset aux switch option to RC_Channel

master
Peter Barker 6 years ago committed by Andrew Tridgell
parent
commit
4b51239920
  1. 9
      ArduCopter/RC_Channel.cpp

9
ArduCopter/RC_Channel.cpp

@ -71,7 +71,6 @@ void RC_Channel_Copter::init_aux_function(const aux_func_t ch_option, const aux_ @@ -71,7 +71,6 @@ void RC_Channel_Copter::init_aux_function(const aux_func_t ch_option, const aux_
case AUX_FUNC::PARACHUTE_ENABLE:
case AUX_FUNC::PARACHUTE_3POS: // we trust the vehicle will be disarmed so even if switch is in release position the chute will not release
case AUX_FUNC::RETRACT_MOUNT:
case AUX_FUNC::MISSION_RESET:
case AUX_FUNC::ATTCON_FEEDFWD:
case AUX_FUNC::ATTCON_ACCEL_LIM:
case AUX_FUNC::MOTOR_INTERLOCK:
@ -229,14 +228,6 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw @@ -229,14 +228,6 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
#endif
break;
case AUX_FUNC::MISSION_RESET:
#if MODE_AUTO_ENABLED == ENABLED
if (ch_flag == HIGH) {
copter.mode_auto.mission.reset();
}
#endif
break;
case AUX_FUNC::AUTO:
#if MODE_AUTO_ENABLED == ENABLED
do_aux_function_change_mode(control_mode_t::AUTO, ch_flag);

Loading…
Cancel
Save