fix mag calibration: remove px4_ioctl(fd, MAGIOCCALIBRATE, fd); call

Fixes a serious bug in combination with the HMC5883 driver (also used for
HMC5983): this driver estimates a scale in MAGIOCCALIBRATE and applies it.
The calibration routine does the calibration with that scale applied, and
then overwrites it, without considering it in any way.

Most other mag drivers only do some measurements and perform some checks
in MAGIOCCALIBRATE (but the result is just ignored).
This commit is contained in:
Beat Küng 2019-11-28 10:28:22 +01:00 committed by Daniel Agar
parent f30e01ec02
commit 991a0d3592
1 changed files with 1 additions and 11 deletions

View File

@ -214,23 +214,13 @@ int do_mag_calibration(orb_advert_t *mavlink_log_pub)
device_ids[cur_mag] = px4_ioctl(fd, DEVIOCGDEVICEID, 0);
internal[cur_mag] = (px4_ioctl(fd, MAGIOCGEXTERNAL, 0) <= 0);
// Reset mag scale
// Reset mag scale & offset
result = px4_ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale_null);
if (result != PX4_OK) {
calibration_log_critical(mavlink_log_pub, CAL_ERROR_RESET_CAL_MSG, cur_mag);
}
/* calibrate range */
if (result == PX4_OK) {
result = px4_ioctl(fd, MAGIOCCALIBRATE, fd);
if (result != PX4_OK) {
calibration_log_info(mavlink_log_pub, "[cal] Skipped scale calibration, sensor %u", cur_mag);
/* this is non-fatal - mark it accordingly */
result = PX4_OK;
}
}
px4_close(fd);
#endif