AP_Compass: revert change to RM3100 scale factor and increase scale limit

This reverts the change from #13895 and instead resolves the issue by
increasing the scale factor limit to 1.4

There is an open question as to why some RM3100 compasses show a
different scale factor (by about 1.25 times) to other versions of the
same sensor. As we haven't resolved this properly it seems the correct
thing to do is follow the datasheet but allow for a wider range of
scale factors to cope with the variation between sensors
This commit is contained in:
Andrew Tridgell 2020-05-23 14:38:00 +10:00
parent 49918d070e
commit a0cf4e158a
3 changed files with 8 additions and 4 deletions

View File

@ -58,8 +58,7 @@ public:
DEVTYPE_MAG3110 = 0x0E,
DEVTYPE_SITL = 0x0F,
DEVTYPE_IST8308 = 0x10,
DEVTYPE_RM3100_OLD = 0x11,
DEVTYPE_RM3100 = 0x12,
DEVTYPE_RM3100 = 0x11,
};

View File

@ -135,7 +135,7 @@ bool AP_Compass_RM3100::init()
dev->write_register(RM3100_CCZ1_REG, CCP1, true); // cycle count z
dev->write_register(RM3100_CCZ0_REG, CCP0, true); // cycle count z
_scaler = (1 / GAIN_CC200) * UTESLA_TO_MGAUSS / 200.0; // has to be changed if using a different cycle count
_scaler = (1 / GAIN_CC200) * UTESLA_TO_MGAUSS; // has to be changed if using a different cycle count
// lower retries for run
dev->set_retries(3);
@ -204,6 +204,11 @@ void AP_Compass_RM3100::timer()
magy = ((uint32_t)data.magy_2 << 24) | ((uint32_t)data.magy_1 << 16) | ((uint32_t)data.magy_0 << 8);
magz = ((uint32_t)data.magz_2 << 24) | ((uint32_t)data.magz_1 << 16) | ((uint32_t)data.magz_0 << 8);
// right-shift signed integer back to get correct measurement value
magx >>= 8;
magy >>= 8;
magz >>= 8;
// apply scaler and store in field vector
field(magx * _scaler, magy * _scaler, magz * _scaler);

View File

@ -7,7 +7,7 @@
#define COMPASS_CAL_NUM_SAMPLES 300 // number of samples required before fitting begins
#define COMPASS_MIN_SCALE_FACTOR 0.85
#define COMPASS_MAX_SCALE_FACTOR 1.3
#define COMPASS_MAX_SCALE_FACTOR 1.4
class CompassCalibrator {
public: