|
|
|
@ -658,6 +658,7 @@ bool AP_IOMCU::check_crc(void)
@@ -658,6 +658,7 @@ bool AP_IOMCU::check_crc(void)
|
|
|
|
|
if (read_registers(PAGE_SETUP, PAGE_REG_SETUP_CRC, 2, (uint16_t *)&io_crc) && |
|
|
|
|
io_crc == crc) { |
|
|
|
|
hal.console->printf("IOMCU: CRC ok\n"); |
|
|
|
|
crc_is_ok = true; |
|
|
|
|
return true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -669,4 +670,13 @@ bool AP_IOMCU::check_crc(void)
@@ -669,4 +670,13 @@ bool AP_IOMCU::check_crc(void)
|
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
check that IO is healthy. This should be used in arming checks |
|
|
|
|
*/ |
|
|
|
|
bool AP_IOMCU::healthy(void) |
|
|
|
|
{ |
|
|
|
|
// for now just check CRC
|
|
|
|
|
return crc_is_ok; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#endif // HAL_WITH_IO_MCU
|
|
|
|
|