mirror of https://github.com/ArduPilot/ardupilot
Plane: use throttle in for transition max comparison
This commit is contained in:
parent
74c47827d9
commit
abee62abc4
|
@ -1760,7 +1760,7 @@ void QuadPlane::update_transition(void)
|
|||
plane.nav_pitch_cd,
|
||||
0);
|
||||
// set throttle at either hover throttle or current throttle, whichever is higher, through the transition
|
||||
attitude_control->set_throttle_out(MAX(motors->get_throttle_hover(),motors->get_throttle()), true, 0);
|
||||
attitude_control->set_throttle_out(MAX(motors->get_throttle_hover(),attitude_control->get_throttle_in()), true, 0);
|
||||
break;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue