mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-24 16:53:57 -04:00
INS: show calibration values on failure
this will help debug bad calibrations
This commit is contained in:
parent
e3f94963d8
commit
b9fb683236
@ -320,9 +320,13 @@ bool AP_InertialSensor::calibrate_accel(void (*delay_cb)(unsigned long t), void
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (send_msg == NULL) {
|
if (send_msg == NULL) {
|
||||||
Serial.printf_P(PSTR("Calibration failed\n"));
|
Serial.printf_P(PSTR("Calibration failed (%.1f %.1f %.1f %.1f %.1f %.1f)\n"),
|
||||||
|
new_offsets.x, new_offsets.y, new_offsets.z,
|
||||||
|
new_scaling.x, new_scaling.y, new_scaling.z);
|
||||||
} else {
|
} else {
|
||||||
send_msg(PSTR("Calibration failed\n"));
|
send_msg(PSTR("Calibration failed (%.1f %.1f %.1f %.1f %.1f %.1f)\n"),
|
||||||
|
new_offsets.x, new_offsets.y, new_offsets.z,
|
||||||
|
new_scaling.x, new_scaling.y, new_scaling.z);
|
||||||
}
|
}
|
||||||
// restore original scaling and offsets
|
// restore original scaling and offsets
|
||||||
_accel_offset.set(orig_offset);
|
_accel_offset.set(orig_offset);
|
||||||
|
Loading…
Reference in New Issue
Block a user