mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
Plane: support TRIM_TO_CURRENT_SERVO_RC RC option to trigger trim radio function
This commit is contained in:
parent
cbfa4e5746
commit
90dd36285e
@ -163,6 +163,7 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option,
|
|||||||
#if HAL_QUADPLANE_ENABLED
|
#if HAL_QUADPLANE_ENABLED
|
||||||
case AUX_FUNC::ARMDISARM_AIRMODE:
|
case AUX_FUNC::ARMDISARM_AIRMODE:
|
||||||
#endif
|
#endif
|
||||||
|
case AUX_FUNC::TRIM_TO_CURRENT_SERVO_RC:
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUX_FUNC::SOARING:
|
case AUX_FUNC::SOARING:
|
||||||
@ -347,6 +348,13 @@ case AUX_FUNC::ARSPD_CALIBRATE:
|
|||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
case AUX_FUNC::TRIM_TO_CURRENT_SERVO_RC:
|
||||||
|
if (ch_flag == AuxSwitchPos::HIGH) {
|
||||||
|
plane.trim_radio();
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
|
||||||
default:
|
default:
|
||||||
return RC_Channel::do_aux_function(ch_option, ch_flag);
|
return RC_Channel::do_aux_function(ch_option, ch_flag);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user