The use of _gain_multiple is not necessary because the values of
expected_{x,yz} and _mag_{x,y,z} are both in sensor raw unit (i.e., lsbs).
That wasn't fixed before in order not to make APM users to recalibrate their
compasses.
the previous approach assumed a 1:1 mapping between compass backends
and compass instances, which isn't true on PX4.
It also only setup milligauss offsets on a set_and_save call, which is
not the only way offsets change
this adds a milligauss_ratio per instance, which is considerably
simpler
From now on there's a pair get_field_milligauss() and
get_offsets_milligauss() that can make the transition to the common
units across all compasses easier.
Like was done to inertial AK8963 and inertial sensor move the decision
regarding the I2C bus to the caller. We don't allow changing the address
because apparently HMC5843 doesn't support different addresses.
Changing only the bus could be more easily done but this prepares the
ground for using HMC5843 on an AuxiliarBus.
The need for a more generic abstraction is evidenced by this commit: a
"SerialBus" in AP_HAL would be a nice addition rather than letting each
driver to provide its own. However the methods are a little bit
different from what we have in AK8963. It's safer to do the simple
conversion now and later on to add the abstraction changing everybody to
use it.
read() calls accumulate() which takes the lock by itself so we must
release it like we were doing before 669ae26 ("AP_Compass: encapsulated
calibration in HMC").
This commit changes the way libraries headers are included in source files:
- If the header is in the same directory the source belongs to, so the
notation '#include ""' is used with the path relative to the directory
containing the source.
- If the header is outside the directory containing the source, then we use
the notation '#include <>' with the path relative to libraries folder.
Some of the advantages of such approach:
- Only one search path for libraries headers.
- OSs like Windows may have a better lookup time.
_copy_to_frontend function takes care of abstracting
this code from the driver. For now the function takes
care of the offset and rotation that is common.
the first couple of values after we enter strap mode may be low, but
just above our 0.7 threshold. We now discard the first two values to
prevent these affecting the average.
Also added some commented out debug code and a comment on the scaling
of the calibration code
- Define float versions of math functions to the double versions
on AVR (eg. #define sinf sin).
- These macros appear to be missing in older versions of avr-libs.
- Include AP_Math.h rather than math.h to get these definitions.
- Allows use of hardware floating point on the Cortex-M4.
- Added "f" suffix to floating point literals.
- Call floating point versions of stdlib math functions.
these allow you to control if the compass should be used for yaw and
if it should learn its offsets. This is useful for locking in compass
offsets once they are confirmed to be good, and for learning offsets
without using them in flights.
The default is to behave the same as previously, which is
COMPASS_LEARN=1 and COMPASS_USE=1
this changes the calibration code to require at least 5 good reads
from the compass during initialisation. The calibration is taken as
the average of the 5 values.
This also fixes the expected values for the 3 axes for the 5883 to
match reality.
We also save a bit of code space by adding a common rotate_for_5883L()
routine.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@3087 f9c3cf11-9bcb-44bc-f272-b75c42450872
this adds a 50ms delay after setting the compass gains before reading
the compass. Added as paranoia after some strange results on a 5843
git-svn-id: https://arducopter.googlecode.com/svn/trunk@3070 f9c3cf11-9bcb-44bc-f272-b75c42450872
we were looking for the wrong regA value
Thanks to Chris for the debugging help! (and happy birthday!)
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2828 f9c3cf11-9bcb-44bc-f272-b75c42450872
this adds error checking to all operations on the compass, to ensure
that we don't accept invalid data
This also fixes the calibration values for the 5883L to match the
recommended values in the spec
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2815 f9c3cf11-9bcb-44bc-f272-b75c42450872
this fixes a compass initialisation bug where if the first value from
the compass isn't in the right range we would set bad calibration
scaling factors.
This also changes the maximum acceptable calibration values to 2000,
which is needed for the 5883 compass
pair-programmed-with: Randy Mackay
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2718 f9c3cf11-9bcb-44bc-f272-b75c42450872
Most of the compass functionality is now abstracted in a base class, with the various sub-classes implementing just their unique functionality.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1647 f9c3cf11-9bcb-44bc-f272-b75c42450872