Skip to content
Snippets Groups Projects
Commit ada0dd55 authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

Plane: check both ground and airspeed in autocal test

when the airspeed ratio is far too low we were not raising it as the
airspeed was never getting above the minimum airspeed

Pair-Programmed-With: Jon Challinger
parent 87cc95dd
No related branches found
No related tags found
No related merge requests found
......@@ -1014,9 +1014,16 @@ static void airspeed_ratio_update(void)
{
if (!airspeed.enabled() ||
g_gps->status() < GPS::GPS_OK_FIX_3D ||
g_gps->ground_speed_cm < 400 ||
airspeed.get_airspeed() < aparm.airspeed_min) {
g_gps->ground_speed_cm < 400) {
// don't calibrate when not moving
return;
}
if (airspeed.get_airspeed() < aparm.airspeed_min &&
g_gps->ground_speed_cm < (uint32_t)aparm.airspeed_min*100) {
// don't calibrate when flying below the minimum airspeed. We
// check both airspeed and ground speed to catch cases where
// the airspeed ratio is way too low, which could lead to it
// never coming up again
return;
}
if (abs(ahrs.roll_sensor) > roll_limit_cd ||
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment