Compass: added some more comments

explain the algorithm a bit more
This commit is contained in:
Andrew Tridgell 2012-03-28 22:40:32 +11:00
parent dd3218c913
commit 79deeef0a0
1 changed files with 6 additions and 1 deletions

View File

@ -250,7 +250,12 @@ Compass::null_offsets(void)
length = diff.length(); length = diff.length();
if (length < min_diff) { if (length < min_diff) {
// the mag vector hasn't changed enough - we don't get // the mag vector hasn't changed enough - we don't get
// enough information from this vector to use it // enough information from this vector to use it.
// Note that we don't put the current vector into the mag
// history here. We want to wait for a larger rotation to
// build up before calculating an offset change, as accuracy
// of the offset change is highly dependent on the size of the
// rotation.
_mag_history_index = (_mag_history_index + 1) % _mag_history_size; _mag_history_index = (_mag_history_index + 1) % _mag_history_size;
return; return;
} }