AP_InternalError.cpp 845 B

123456789101112131415161718192021222324252627282930313233343536
  1. #include "AP_InternalError.h"
  2. #include <AP_BoardConfig/AP_BoardConfig.h>
  3. extern const AP_HAL::HAL &hal;
  4. // actually create the instance:
  5. static AP_InternalError instance;
  6. void AP_InternalError::error(const AP_InternalError::error_t e) {
  7. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  8. switch (e) {
  9. case AP_InternalError::error_t::watchdog_reset:
  10. case AP_InternalError::error_t::main_loop_stuck:
  11. // don't panic on these to facilitate watchdog testing
  12. break;
  13. default:
  14. AP_HAL::panic("internal error %u", unsigned(e));
  15. }
  16. #endif
  17. internal_errors |= uint32_t(e);
  18. total_error_count++;
  19. hal.util->persistent_data.internal_errors = internal_errors;
  20. hal.util->persistent_data.internal_error_count = total_error_count;
  21. }
  22. namespace AP {
  23. AP_InternalError &internalerror()
  24. {
  25. return instance;
  26. }
  27. };