uncrustify libraries/AP_Compass/Compass.cpp

This commit is contained in:
uncrustify 2012-08-16 23:19:22 -07:00 committed by Pat Hickey
parent ad8df60749
commit 662d285f44
1 changed files with 30 additions and 30 deletions

View File

@ -159,24 +159,24 @@ Compass::calculate_heading(const Matrix3f &dcm_matrix)
/* /*
this offset nulling algorithm is inspired by this paper from Bill Premerlani * this offset nulling algorithm is inspired by this paper from Bill Premerlani
*
http://gentlenav.googlecode.com/files/MagnetometerOffsetNullingRevisited.pdf * http://gentlenav.googlecode.com/files/MagnetometerOffsetNullingRevisited.pdf
*
The base algorithm works well, but is quite sensitive to * The base algorithm works well, but is quite sensitive to
noise. After long discussions with Bill, the following changes were * noise. After long discussions with Bill, the following changes were
made: * made:
*
1) we keep a history buffer that effectively divides the mag * 1) we keep a history buffer that effectively divides the mag
vectors into a set of N streams. The algorithm is run on the * vectors into a set of N streams. The algorithm is run on the
streams separately * streams separately
*
2) within each stream we only calculate a change when the mag * 2) within each stream we only calculate a change when the mag
vector has changed by a significant amount. * vector has changed by a significant amount.
*
This gives us the property that we learn quickly if there is no * This gives us the property that we learn quickly if there is no
noise, but still learn correctly (and slowly) in the face of lots of * noise, but still learn correctly (and slowly) in the face of lots of
noise. * noise.
*/ */
void void
Compass::null_offsets(void) Compass::null_offsets(void)