mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: reset groundspeed_undershoot value when GPS is lost
If we lose GPS lock the gndspd undershoot value gets stuck at the last calculated value forever (until GPS locks again)
This commit is contained in:
parent
1ef0f27786
commit
746ca91649
@ -163,6 +163,8 @@ void Plane::calc_gndspeed_undershoot()
|
||||
float gndSpdFwd = yawVect * gndVel;
|
||||
groundspeed_undershoot = (aparm.min_gndspeed_cm > 0) ? (aparm.min_gndspeed_cm - gndSpdFwd*100) : 0;
|
||||
}
|
||||
} else {
|
||||
groundspeed_undershoot = 0;
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user