mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: prevent a single bad transfer causing an IMU to be marked unhealthy
This is a response to this issue: https://discuss.ardupilot.org/t/gyro-problem-after-waypoint-log-analisys The 2nd gyro went bad with a large offset. Then the first gyro was marked unhealthy, forcing the EKF to switch to the 2nd gyro. That resulted in a crash. I think the SPI bus was getting bad transfers and the register check code happened to get a bad transfer, thereby marking the first gyro unhealthy This change ensures we only fail the register check if two transfers in a row are bad. This makes it much less likely that a noisy bus will lead to an unhealthy gyro
This commit is contained in:
parent
2b71bf8e99
commit
6163659887
|
@ -99,7 +99,7 @@ bool AP_HAL::Device::check_next_register(void)
|
|||
_checked.counter = 0;
|
||||
|
||||
struct checkreg ® = _checked.regs[_checked.next];
|
||||
uint8_t v;
|
||||
uint8_t v, v2;
|
||||
|
||||
if (_bank_select) {
|
||||
if (!_bank_select(reg.bank)) {
|
||||
|
@ -113,7 +113,8 @@ bool AP_HAL::Device::check_next_register(void)
|
|||
}
|
||||
}
|
||||
|
||||
if (!read_registers(reg.regnum, &v, 1) || v != reg.value) {
|
||||
if ((!read_registers(reg.regnum, &v, 1) || v != reg.value) &&
|
||||
(!read_registers(reg.regnum, &v2, 1) || v2 != reg.value)) {
|
||||
// a register has changed value unexpectedly. Try changing it back
|
||||
// and re-check it next time
|
||||
#if 0
|
||||
|
|
Loading…
Reference in New Issue