mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: apply the takeoff throttle slew limit to quadplanes
this applies the limit when we are in a fwd transition, both in AUTO modes and stabilized modes
This commit is contained in:
parent
56d33cce7a
commit
11fbeb9b8f
@ -37,6 +37,15 @@ void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)
|
||||
slewrate = landing.get_throttle_slewrate();
|
||||
}
|
||||
}
|
||||
if (g.takeoff_throttle_slewrate != 0 &&
|
||||
(flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF ||
|
||||
flight_stage == AP_Vehicle::FixedWing::FLIGHT_VTOL)) {
|
||||
// for VTOL we use takeoff slewrate, which helps with transition
|
||||
slewrate = g.takeoff_throttle_slewrate;
|
||||
}
|
||||
if (g.takeoff_throttle_slewrate != 0 && quadplane.in_transition()) {
|
||||
slewrate = g.takeoff_throttle_slewrate;
|
||||
}
|
||||
// if slew limit rate is set to zero then do not slew limit
|
||||
if (slewrate) {
|
||||
SRV_Channels::limit_slew_rate(func, slewrate, G_Dt);
|
||||
|
Loading…
Reference in New Issue
Block a user