mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
AP_IOMCU: added healthy API for use in arming checks
This commit is contained in:
parent
77c922e6b8
commit
214fb096eb
@ -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)
|
||||
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
|
||||
|
@ -75,6 +75,9 @@ public:
|
||||
// set to oneshot mode
|
||||
void set_oneshot_mode(void);
|
||||
|
||||
// check if IO is healthy
|
||||
bool healthy(void);
|
||||
|
||||
private:
|
||||
AP_HAL::UARTDriver &uart;
|
||||
|
||||
@ -195,6 +198,8 @@ private:
|
||||
|
||||
bool corked;
|
||||
|
||||
bool crc_is_ok;
|
||||
|
||||
// firmware upload
|
||||
const char *fw_name = "io_firmware.bin";
|
||||
const uint8_t *fw;
|
||||
|
@ -436,6 +436,9 @@ bool AP_IOMCU::verify_rev3(uint32_t fw_size_local)
|
||||
debug("CRC wrong: received: 0x%x, expected: 0x%x", (unsigned)crc, (unsigned)sum);
|
||||
return false;
|
||||
}
|
||||
|
||||
crc_is_ok = true;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user