Browse Source

ArduPlane: add CRUISE mode RC AUX Function switch

gps-1.3.1
Hwurzburg 4 years ago committed by Andrew Tridgell
parent
commit
9ab0d2e387
  1. 6
      ArduPlane/RC_Channel.cpp

6
ArduPlane/RC_Channel.cpp

@ -151,6 +151,7 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option, @@ -151,6 +151,7 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option,
case AUX_FUNC::LANDING_FLARE:
case AUX_FUNC::PARACHUTE_RELEASE:
case AUX_FUNC::MODE_SWITCH_RESET:
case AUX_FUNC::CRUISE:
break;
case AUX_FUNC::Q_ASSIST:
@ -316,6 +317,11 @@ case AUX_FUNC::ARSPD_CALIBRATE: @@ -316,6 +317,11 @@ case AUX_FUNC::ARSPD_CALIBRATE:
plane.reset_control_switch();
break;
case AUX_FUNC::CRUISE:
do_aux_function_change_mode(Mode::Number::CRUISE, ch_flag);
break;
default:
return RC_Channel::do_aux_function(ch_option, ch_flag);
}

Loading…
Cancel
Save