mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed bug in pullup code
if we have poor pitch trim it is possible we will pullup before reaching the target airspeed. Check pitch threshold during airspeed stage of pullup
This commit is contained in:
parent
834863fdb7
commit
1c194878ee
|
@ -115,7 +115,7 @@ bool GliderPullup::verify_pullup(void)
|
|||
switch (stage) {
|
||||
case Stage::WAIT_AIRSPEED: {
|
||||
float aspeed;
|
||||
if (ahrs.airspeed_estimate(aspeed) && aspeed > airspeed_start) {
|
||||
if (ahrs.airspeed_estimate(aspeed) && (aspeed > airspeed_start || ahrs.pitch_sensor*0.01 > pitch_start)) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Pullup airspeed %.1fm/s alt %.1fm AMSL", aspeed, current_loc.alt*0.01);
|
||||
stage = Stage::WAIT_PITCH;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue