mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: move mission reset aux switch option to RC_Channel
This commit is contained in:
parent
84ba6e859c
commit
4b51239920
@ -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_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::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::RETRACT_MOUNT:
|
||||||
case AUX_FUNC::MISSION_RESET:
|
|
||||||
case AUX_FUNC::ATTCON_FEEDFWD:
|
case AUX_FUNC::ATTCON_FEEDFWD:
|
||||||
case AUX_FUNC::ATTCON_ACCEL_LIM:
|
case AUX_FUNC::ATTCON_ACCEL_LIM:
|
||||||
case AUX_FUNC::MOTOR_INTERLOCK:
|
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
|
|||||||
#endif
|
#endif
|
||||||
break;
|
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:
|
case AUX_FUNC::AUTO:
|
||||||
#if MODE_AUTO_ENABLED == ENABLED
|
#if MODE_AUTO_ENABLED == ENABLED
|
||||||
do_aux_function_change_mode(control_mode_t::AUTO, ch_flag);
|
do_aux_function_change_mode(control_mode_t::AUTO, ch_flag);
|
||||||
|
Loading…
Reference in New Issue
Block a user