mirror of https://github.com/ArduPilot/ardupilot
AP_InternalError: imu resets aren't fatal on esp32
This commit is contained in:
parent
a896ab9e71
commit
81df897d88
|
@ -21,6 +21,9 @@ void AP_InternalError::error(const AP_InternalError::error_t e, uint16_t line) {
|
||||||
AP::internalerror().error_to_string(buffer, ARRAY_SIZE(buffer), e);
|
AP::internalerror().error_to_string(buffer, ARRAY_SIZE(buffer), e);
|
||||||
AP_HAL::panic("AP_InternalError::error_t::%s", buffer);
|
AP_HAL::panic("AP_InternalError::error_t::%s", buffer);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_ESP32
|
||||||
|
if (e == AP_InternalError::error_t::imu_reset) return;// don't worry about this for esp32
|
||||||
#endif
|
#endif
|
||||||
internal_errors |= uint32_t(e);
|
internal_errors |= uint32_t(e);
|
||||||
total_error_count++;
|
total_error_count++;
|
||||||
|
|
Loading…
Reference in New Issue