Plane: also limit throttle during quadplane transitions

This commit is contained in:
Mark Whitehorn 2019-12-19 10:14:20 -07:00 committed by Andrew Tridgell
parent 839e03f3e4
commit ab2eb6185f
1 changed files with 5 additions and 2 deletions

View File

@ -448,8 +448,11 @@ void Plane::set_servos_controlled(void)
min_throttle = 0; min_throttle = 0;
} }
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) { if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF ||
if(aparm.takeoff_throttle_max != 0) { flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND ||
quadplane.in_transition()) {
if (aparm.takeoff_throttle_max != 0) {
max_throttle = aparm.takeoff_throttle_max; max_throttle = aparm.takeoff_throttle_max;
} else { } else {
max_throttle = aparm.throttle_max; max_throttle = aparm.throttle_max;