Browse Source

AP_IOMCU: added healthy API for use in arming checks

master
Andrew Tridgell 7 years ago
parent
commit
214fb096eb
  1. 10
      libraries/AP_IOMCU/AP_IOMCU.cpp
  2. 5
      libraries/AP_IOMCU/AP_IOMCU.h
  3. 3
      libraries/AP_IOMCU/fw_uploader.cpp

10
libraries/AP_IOMCU/AP_IOMCU.cpp

@ -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

5
libraries/AP_IOMCU/AP_IOMCU.h

@ -75,6 +75,9 @@ public: @@ -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: @@ -195,6 +198,8 @@ private:
bool corked;
bool crc_is_ok;
// firmware upload
const char *fw_name = "io_firmware.bin";
const uint8_t *fw;

3
libraries/AP_IOMCU/fw_uploader.cpp

@ -436,6 +436,9 @@ bool AP_IOMCU::verify_rev3(uint32_t fw_size_local) @@ -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…
Cancel
Save