Plane: dont use VTOL throttle percentage in tailsitter vtol transisiton

This commit is contained in:
Iampete1 2020-11-13 23:58:05 +00:00 committed by Andrew Tridgell
parent 470c00b6b2
commit dd3ac893b3
1 changed files with 1 additions and 1 deletions

View File

@ -434,7 +434,7 @@ bool Plane::should_log(uint32_t mask)
*/
int8_t Plane::throttle_percentage(void)
{
if (quadplane.in_vtol_mode()) {
if (quadplane.in_vtol_mode() && !quadplane.in_tailsitter_vtol_transition()) {
return quadplane.throttle_percentage();
}
float throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle);