mirror of https://github.com/ArduPilot/ardupilot
AP_IOMCU: prevent startup sync causing an internal error
This commit is contained in:
parent
e6c7fd2acc
commit
af54e8620e
|
@ -425,6 +425,7 @@ bool AP_IOMCU::read_registers(uint8_t page, uint8_t offset, uint8_t count, uint1
|
||||||
handle_repeated_failures();
|
handle_repeated_failures();
|
||||||
}
|
}
|
||||||
protocol_fail_count = 0;
|
protocol_fail_count = 0;
|
||||||
|
protocol_count++;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -493,6 +494,7 @@ bool AP_IOMCU::write_registers(uint8_t page, uint8_t offset, uint8_t count, cons
|
||||||
handle_repeated_failures();
|
handle_repeated_failures();
|
||||||
}
|
}
|
||||||
protocol_fail_count = 0;
|
protocol_fail_count = 0;
|
||||||
|
protocol_count++;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -898,6 +900,11 @@ const char *AP_IOMCU::get_rc_protocol(void)
|
||||||
*/
|
*/
|
||||||
void AP_IOMCU::handle_repeated_failures(void)
|
void AP_IOMCU::handle_repeated_failures(void)
|
||||||
{
|
{
|
||||||
|
if (protocol_count < 100) {
|
||||||
|
// we're just starting up, ignore initial failures caused by
|
||||||
|
// initial sync with IOMCU
|
||||||
|
return;
|
||||||
|
}
|
||||||
detected_io_reset = true;
|
detected_io_reset = true;
|
||||||
AP::internalerror().error(AP_InternalError::error_t::iomcu_reset);
|
AP::internalerror().error(AP_InternalError::error_t::iomcu_reset);
|
||||||
// we need to ensure the mixer data and the rates are sent over to
|
// we need to ensure the mixer data and the rates are sent over to
|
||||||
|
|
|
@ -205,6 +205,7 @@ private:
|
||||||
bool is_chibios_backend;
|
bool is_chibios_backend;
|
||||||
|
|
||||||
uint32_t protocol_fail_count;
|
uint32_t protocol_fail_count;
|
||||||
|
uint32_t protocol_count;
|
||||||
|
|
||||||
// firmware upload
|
// firmware upload
|
||||||
const char *fw_name = "io_firmware.bin";
|
const char *fw_name = "io_firmware.bin";
|
||||||
|
|
Loading…
Reference in New Issue