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

AP_Compass: throw away all samples which aren't acceptable in thinning #29312

Open
wants to merge 1 commit into
base: master
Choose a base branch
from

Conversation

peterbarker
Copy link
Contributor

From my 5-year-old notes:

+Getting a good list of samples for the fits to run across is probably a good thing to get working well.
+
+I don't think we're doing that at the moment.
+
+At the moment: we test a sample, and if it is no good then we copy a random one in from the end of the list.  We do not test the sample we just copied in, rather move on through the list.
+
+This PR changes things such that we test every sample in the buffer as part of the thinning step.
+
+```
+2019-12-06 10:07:40.92: STATUSTEXT {severity : 6, text : Threw away 247/300 samples}
+2019-12-06 10:07:41.54: STATUSTEXT {severity : 6, text : Threw away 232/300 samples}
+```
+
+There are 576 faces on the default polyhedron.   This test shows that we're only hitting 50-70 of them in the initial collect-samples pass.

+After the initial collect samples pass we fill the buffer up with completely untested samples - I can't imagine we'd do better than the same again.  So overall we'll be hitting 20% of the faces with no guarantee on face distribution, except inasmuch

I have no idea how I was going to finish that sentence.

The "threw away line was extra debug in the thinning_samples method recording before/after sample counts.

I've tested this on a Durandal quadcopter here and the calibration result is similar to what was on there.

if (!accept_sample(_sample_buffer[i], i)) {
// throw sample away
_sample_buffer[i] = _sample_buffer[_samples_collected-1];
_samples_collected--;
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Couldn't this get to 0 meaning the check above would be a free memory read?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Then i would equal samples collected, so we would exit the while loop

// lattter case we MUST move the loop iterator forward (towards
// _samples_collected).
uint16_t i = 0;
while (i != _samples_collected) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

maybe i < _samples_collected-1 ? otherwise copies to itself

@tridge
Copy link
Contributor

tridge commented Feb 18, 2025

i think this looks good, but should have a bit more testing

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

Successfully merging this pull request may close these issues.

4 participants