mirror of https://github.com/ArduPilot/ardupilot
Plane: also limit throttle during quadplane transitions
This commit is contained in:
parent
839e03f3e4
commit
ab2eb6185f
|
@ -448,8 +448,11 @@ void Plane::set_servos_controlled(void)
|
|||
min_throttle = 0;
|
||||
}
|
||||
|
||||
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) {
|
||||
if(aparm.takeoff_throttle_max != 0) {
|
||||
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF ||
|
||||
flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND ||
|
||||
quadplane.in_transition()) {
|
||||
|
||||
if (aparm.takeoff_throttle_max != 0) {
|
||||
max_throttle = aparm.takeoff_throttle_max;
|
||||
} else {
|
||||
max_throttle = aparm.throttle_max;
|
||||
|
|
Loading…
Reference in New Issue