mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: use tesla conversion from AP_Math/definitions.h
This commit is contained in:
parent
ee1975d47a
commit
80730d6c02
|
@ -61,7 +61,6 @@
|
|||
#define GAIN_CC50 20.0f // LSB/uT
|
||||
#define GAIN_CC100 38.0f
|
||||
#define GAIN_CC200 75.0f
|
||||
#define UTESLA_TO_MGAUSS 10.0f // uT to mGauss conversion
|
||||
|
||||
#define TMRC 0x94 // Update rate 150Hz
|
||||
#define CMM 0x71 // read 3 axes and set data ready if 3 axes are ready
|
||||
|
|
Loading…
Reference in New Issue