mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: use AUX_PWM_TRIGGER_LOW and AUX_PWM_TRIGGER_HIGH
This commit is contained in:
parent
7430a415fb
commit
6062e4ee81
|
@ -139,7 +139,7 @@ void Plane::read_control_switch()
|
|||
|
||||
#if PARACHUTE == ENABLED
|
||||
if (g.parachute_channel > 0) {
|
||||
if (RC_Channels::get_radio_in(g.parachute_channel-1) >= 1700) {
|
||||
if (RC_Channels::get_radio_in(g.parachute_channel-1) >= RC_Channel::AUX_PWM_TRIGGER_HIGH) {
|
||||
parachute_manual_release();
|
||||
}
|
||||
}
|
||||
|
|
|
@ -25,7 +25,7 @@ void ModeFBWA::update()
|
|||
}
|
||||
if (plane.g.fbwa_tdrag_chan > 0) {
|
||||
// check for the user enabling FBWA taildrag takeoff mode
|
||||
bool tdrag_mode = (RC_Channels::get_radio_in(plane.g.fbwa_tdrag_chan-1) > 1700);
|
||||
bool tdrag_mode = (RC_Channels::get_radio_in(plane.g.fbwa_tdrag_chan-1) > RC_Channel::AUX_PWM_TRIGGER_HIGH);
|
||||
if (tdrag_mode && !plane.auto_state.fbwa_tdrag_takeoff_mode) {
|
||||
if (plane.auto_state.highest_airspeed < plane.g.takeoff_tdrag_speed1) {
|
||||
plane.auto_state.fbwa_tdrag_takeoff_mode = true;
|
||||
|
|
|
@ -217,7 +217,7 @@ void QuadPlane::tailsitter_output(void)
|
|||
|
||||
if (tailsitter.input_mask_chan > 0 &&
|
||||
tailsitter.input_mask > 0 &&
|
||||
RC_Channels::get_radio_in(tailsitter.input_mask_chan-1) > 1700) {
|
||||
RC_Channels::get_radio_in(tailsitter.input_mask_chan-1) > RC_Channel::AUX_PWM_TRIGGER_HIGH) {
|
||||
// the user is learning to prop-hang
|
||||
if (tailsitter.input_mask & TAILSITTER_MASK_AILERON) {
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, plane.channel_roll->get_control_in_zero_dz());
|
||||
|
|
Loading…
Reference in New Issue