mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: Enforce THR_MIN/THR_MAX in VTOL modes
This commit is contained in:
parent
f6f40afcda
commit
624aef401d
@ -378,7 +378,8 @@ void Plane::set_servos_controlled(void)
|
|||||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, channel_throttle->get_control_in_zero_dz());
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, channel_throttle->get_control_in_zero_dz());
|
||||||
} else if (quadplane.in_vtol_mode()) {
|
} else if (quadplane.in_vtol_mode()) {
|
||||||
// ask quadplane code for forward throttle
|
// ask quadplane code for forward throttle
|
||||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, quadplane.forward_throttle_pct());
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle,
|
||||||
|
constrain_int16(quadplane.forward_throttle_pct(), min_throttle, max_throttle));
|
||||||
}
|
}
|
||||||
|
|
||||||
// suppress throttle when soaring is active
|
// suppress throttle when soaring is active
|
||||||
|
Loading…
Reference in New Issue
Block a user