Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fixed altitude estimator error estimation #10367

Merged

Conversation

RomanLut
Copy link
Contributor

ISSUE:

The signed difference is currently used to update the error estimation in the altitude estimator. A large negative difference incorrectly reduces the error, while it should actually increase the error.

Explanation: The difference gpsAltResudual should be passed through fabsf() to ensure that the error magnitude is always positive, preventing incorrect reduction of the error when the difference is negative.

IS:

const float gpsAltResudual = posEstimator.gps.pos.z - posEstimator.est.pos.z;
ctx->newEPV = updateEPE(posEstimator.est.epv, ctx->dt, MAX(posEstimator.gps.epv, gpsAltResudual), positionEstimationConfig()->w_z_gps_p);

SHOULD:

ctx->newEPV = updateEPE(posEstimator.est.epv, ctx->dt, MAX(posEstimator.gps.epv, fabsf(gpsAltResudual)), positionEstimationConfig()->w_z_gps_p);

@sensei-hacker sensei-hacker merged commit c5febe2 into iNavFlight:master Sep 18, 2024
21 checks passed
@Jetrell
Copy link

Jetrell commented Sep 18, 2024

@RomanLut I ran some tests with a copter in Poshold, using this commit against the old method. At the same location, and all tests done within 5 minutes of each other.

I ran your change first... The first test was armed with a HDOP of 1.4.. It held the target rather well. With minimal vertical drift, based on line of sight reference. Maybe 0.2m drift over a period of 4 minutes.
Then I loaded another battery and armed with a HDOP of 1.0.. It too held the same position a little better again.

Then I loaded the old method, before this was merged. It was armed with a HDOP of 0.8.. It started out looking okay, by holding its altitude within the same variance.. But after around 80 seconds, it slowly started to rise in altitude, to a maximum of 0.9m above what it was when I entered Poshold.. Which was typical of what I had seen previously in other testing.. This too was based on line of sight reference, from the position above the ground I enabled Poshold.
So your fix appears to have made a noticeable improvement. 👍

The interesting part about testing this stuff, is the vertical drift can't be reliably referenced with the logs alone, due to the Target Altitude rarely being correct, based on the ground arming reference.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants