AP_InternalError.h 2.9 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576
  1. /*
  2. AP_InternalError holds information about "should not happen" errors
  3. that have occured within ArduPilot. This covers things like code
  4. paths that should not be crossed or pointers being null when they
  5. really, really shouldn't be. It does NOT cover things like losing
  6. GPS lock at inopportune times - that's just bad luck, not bad
  7. programming.
  8. This program is free software: you can redistribute it and/or modify
  9. it under the terms of the GNU General Public License as published by
  10. the Free Software Foundation, either version 3 of the License, or
  11. (at your option) any later version.
  12. This program is distributed in the hope that it will be useful,
  13. but WITHOUT ANY WARRANTY; without even the implied warranty of
  14. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  15. GNU General Public License for more details.
  16. You should have received a copy of the GNU General Public License
  17. along with this program. If not, see <http://www.gnu.org/licenses/>.
  18. */
  19. #pragma once
  20. #include <stdint.h>
  21. class AP_InternalError {
  22. public:
  23. // internal error counters. Do not set these unless it is a
  24. // *true* internal error - a thread locking up, a codepath which
  25. // should never be taken, a code-sanity-check failing, that sort
  26. // of thing. Examples of what NOT to put in here - sd card
  27. // filling up, bad input received from GCS, GPS unit was working
  28. // and now is not.
  29. enum class error_t {
  30. logger_mapfailure = (1U << 0),
  31. logger_missing_logstructure = (1U << 1),
  32. logger_logwrite_missingfmt = (1U << 2),
  33. logger_too_many_deletions = (1U << 3),
  34. logger_bad_getfilename = (1U << 4),
  35. unused1 = (1U << 5), // was logger_stopping_without_sem
  36. logger_flushing_without_sem = (1U << 6),
  37. logger_bad_current_block = (1U << 7),
  38. logger_blockcount_mismatch = (1U << 8),
  39. logger_dequeue_failure = (1U << 9),
  40. constraining_nan = (1U << 10),
  41. watchdog_reset = (1U << 11),
  42. iomcu_reset = (1U << 12),
  43. iomcu_fail = (1U << 13),
  44. spi_fail = (1U << 14),
  45. main_loop_stuck = (1U << 15),
  46. gcs_bad_missionprotocol_link= (1U << 16),
  47. bitmask_range = (1U << 17),
  48. gcs_offset = (1U << 18),
  49. i2c_isr = (1U << 19),
  50. };
  51. void error(const AP_InternalError::error_t error);
  52. uint32_t count() const { return total_error_count; }
  53. // internal_errors - return mask of internal errors seen
  54. uint32_t errors() const {
  55. return internal_errors;
  56. }
  57. private:
  58. // bitmask holding errors from internal_error_t
  59. uint32_t internal_errors;
  60. uint32_t total_error_count;
  61. };
  62. namespace AP {
  63. AP_InternalError &internalerror();
  64. };