Plane: move forward throttle output in VTOL modes to QuadPlane update

This commit is contained in:
Iampete1 2024-01-18 12:11:29 +00:00 committed by Andrew Tridgell
parent 3973c28f15
commit c84e5b337e
2 changed files with 9 additions and 9 deletions

View File

@ -1872,6 +1872,15 @@ void QuadPlane::update(void)
tiltrotor.update();
if (in_vtol_mode()) {
// if enabled output forward throttle else 0
float fwd_thr = 0;
if (allow_forward_throttle_in_vtol_mode()) {
fwd_thr = forward_throttle_pct();
}
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, fwd_thr);
}
#if HAL_LOGGING_ENABLED
// motors logging
if (motors->armed()) {

View File

@ -605,15 +605,6 @@ void Plane::set_throttle(void)
guided_throttle_passthru) {
// manual pass through of throttle while in GUIDED
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, get_throttle_input(true));
#if HAL_QUADPLANE_ENABLED
} else if (quadplane.in_vtol_mode()) {
float fwd_thr = 0;
// if enabled ask quadplane code for forward throttle
if (quadplane.allow_forward_throttle_in_vtol_mode()) {
fwd_thr = quadplane.forward_throttle_pct();
}
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, fwd_thr);
#endif // HAL_QUADPLANE_ENABLED
}
if (control_mode->use_battery_compensation()) {