AP_IOMCU: added shutdown method

this cleans up the reboot process
This commit is contained in:
Andrew Tridgell 2018-10-30 08:50:59 +11:00
parent b3b5415081
commit ed48c24600
2 changed files with 25 additions and 3 deletions

View File

@ -85,7 +85,7 @@ void AP_IOMCU::thread_main(void)
trigger_event(IOEVENT_INIT);
while (true) {
while (!do_shutdown) {
eventmask_t mask = chEvtWaitAnyTimeout(~0, chTimeMS2I(10));
// check for pending IO events
@ -213,6 +213,7 @@ void AP_IOMCU::thread_main(void)
}
}
}
done_shutdown = true;
}
/*
@ -625,8 +626,13 @@ bool AP_IOMCU::check_crc(void)
}
uint32_t io_crc = 0;
if (read_registers(PAGE_SETUP, PAGE_REG_SETUP_CRC, 2, (uint16_t *)&io_crc) &&
io_crc == crc) {
uint8_t tries = 32;
while (tries--) {
if (read_registers(PAGE_SETUP, PAGE_REG_SETUP_CRC, 2, (uint16_t *)&io_crc)) {
break;
}
}
if (io_crc == crc) {
hal.console->printf("IOMCU: CRC ok\n");
crc_is_ok = true;
free(fw);
@ -707,4 +713,15 @@ bool AP_IOMCU::healthy(void)
return crc_is_ok;
}
/*
shutdown protocol, ready for reboot
*/
void AP_IOMCU::shutdown(void)
{
do_shutdown = true;
while (!done_shutdown) {
hal.scheduler->delay(1);
}
}
#endif // HAL_WITH_IO_MCU

View File

@ -86,6 +86,9 @@ public:
// check if IO is healthy
bool healthy(void);
// shutdown IO protocol (for reboot)
void shutdown();
private:
AP_HAL::UARTDriver &uart;
@ -171,6 +174,8 @@ private:
uint32_t last_servo_out_us;
bool corked;
bool do_shutdown;
bool done_shutdown;
bool crc_is_ok;