mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_IOMCU: added a health check based on status read errors
if we have more than 1 in 128 read status requests failing then mark IOMCU unhealthy
This commit is contained in:
parent
630ccb2ef9
commit
2d817db7f3
@ -296,8 +296,14 @@ void AP_IOMCU::read_status()
|
||||
{
|
||||
uint16_t *r = (uint16_t *)®_status;
|
||||
if (!read_registers(PAGE_STATUS, 0, sizeof(reg_status)/2, r)) {
|
||||
read_status_errors++;
|
||||
return;
|
||||
}
|
||||
if (read_status_ok == 0) {
|
||||
// reset error count on first good read
|
||||
read_status_errors = 0;
|
||||
}
|
||||
read_status_ok++;
|
||||
|
||||
check_iomcu_reset();
|
||||
|
||||
@ -443,6 +449,7 @@ bool AP_IOMCU::read_registers(uint8_t page, uint8_t offset, uint8_t count, uint1
|
||||
if (!uart.wait_timeout(count*2+4, 10)) {
|
||||
debug("t=%u timeout read page=%u offset=%u count=%u\n",
|
||||
AP_HAL::millis(), page, offset, count);
|
||||
protocol_fail_count++;
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -855,7 +862,7 @@ void AP_IOMCU::set_safety_mask(uint16_t chmask)
|
||||
*/
|
||||
bool AP_IOMCU::healthy(void)
|
||||
{
|
||||
return crc_is_ok && protocol_fail_count == 0 && !detected_io_reset;
|
||||
return crc_is_ok && protocol_fail_count == 0 && !detected_io_reset && read_status_errors < read_status_ok/128U;
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -212,6 +212,8 @@ private:
|
||||
uint32_t total_errors;
|
||||
uint32_t num_delayed;
|
||||
uint32_t last_iocmu_timestamp_ms;
|
||||
uint32_t read_status_errors;
|
||||
uint32_t read_status_ok;
|
||||
|
||||
// firmware upload
|
||||
const char *fw_name = "io_firmware.bin";
|
||||
|
Loading…
Reference in New Issue
Block a user