system.cpp 7.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208
  1. /*
  2. * This file is free software: you can redistribute it and/or modify it
  3. * under the terms of the GNU General Public License as published by the
  4. * Free Software Foundation, either version 3 of the License, or
  5. * (at your option) any later version.
  6. *
  7. * This file is distributed in the hope that it will be useful, but
  8. * WITHOUT ANY WARRANTY; without even the implied warranty of
  9. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  10. * See the GNU General Public License for more details.
  11. *
  12. * You should have received a copy of the GNU General Public License along
  13. * with this program. If not, see <http://www.gnu.org/licenses/>.
  14. *
  15. * Code by Andrew Tridgell and Siddharth Bharat Purohit
  16. */
  17. #include <stdarg.h>
  18. #include <stdio.h>
  19. #include <AP_HAL/AP_HAL.h>
  20. #include <AP_HAL/system.h>
  21. #include <AP_BoardConfig/AP_BoardConfig.h>
  22. #include "hwdef/common/watchdog.h"
  23. #include <ch.h>
  24. #include "hal.h"
  25. #include <hrt.h>
  26. extern const AP_HAL::HAL& hal;
  27. extern "C"
  28. {
  29. #define bkpt() __asm volatile("BKPT #0\n")
  30. typedef enum {
  31. Reset = 1,
  32. NMI = 2,
  33. HardFault = 3,
  34. MemManage = 4,
  35. BusFault = 5,
  36. UsageFault = 6,
  37. } FaultType;
  38. void *__dso_handle;
  39. void __cxa_pure_virtual(void);
  40. void __cxa_pure_virtual() { while (1); } //TODO: Handle properly, maybe generate a traceback
  41. void NMI_Handler(void);
  42. void NMI_Handler(void) { while (1); }
  43. /*
  44. save watchdog data for a hard fault
  45. */
  46. static void save_fault_watchdog(uint16_t line, FaultType fault_type, uint32_t fault_addr)
  47. {
  48. #ifndef HAL_BOOTLOADER_BUILD
  49. bool using_watchdog = AP_BoardConfig::watchdog_enabled();
  50. if (using_watchdog) {
  51. AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
  52. pd.fault_line = line;
  53. pd.fault_type = fault_type;
  54. pd.fault_addr = fault_addr;
  55. pd.fault_thd_prio = chThdGetPriorityX();
  56. pd.fault_icsr = SCB->ICSR;
  57. stm32_watchdog_save((uint32_t *)&hal.util->persistent_data, (sizeof(hal.util->persistent_data)+3)/4);
  58. }
  59. #endif
  60. }
  61. void HardFault_Handler(void);
  62. void HardFault_Handler(void) {
  63. //Copy to local variables (not pointers) to allow GDB "i loc" to directly show the info
  64. //Get thread context. Contains main registers including PC and LR
  65. struct port_extctx ctx;
  66. memcpy(&ctx, (void*)__get_PSP(), sizeof(struct port_extctx));
  67. (void)ctx;
  68. //Interrupt status register: Which interrupt have we encountered, e.g. HardFault?
  69. FaultType faultType = (FaultType)__get_IPSR();
  70. (void)faultType;
  71. //For HardFault/BusFault this is the address that was accessed causing the error
  72. uint32_t faultAddress = SCB->BFAR;
  73. (void)faultAddress;
  74. //Flags about hardfault / busfault
  75. //See http://infocenter.arm.com/help/index.jsp?topic=/com.arm.doc.dui0552a/Cihdjcfc.html for reference
  76. bool isFaultPrecise = ((SCB->CFSR >> SCB_CFSR_BUSFAULTSR_Pos) & (1 << 1) ? true : false);
  77. bool isFaultImprecise = ((SCB->CFSR >> SCB_CFSR_BUSFAULTSR_Pos) & (1 << 2) ? true : false);
  78. bool isFaultOnUnstacking = ((SCB->CFSR >> SCB_CFSR_BUSFAULTSR_Pos) & (1 << 3) ? true : false);
  79. bool isFaultOnStacking = ((SCB->CFSR >> SCB_CFSR_BUSFAULTSR_Pos) & (1 << 4) ? true : false);
  80. bool isFaultAddressValid = ((SCB->CFSR >> SCB_CFSR_BUSFAULTSR_Pos) & (1 << 7) ? true : false);
  81. (void)isFaultPrecise;
  82. (void)isFaultImprecise;
  83. (void)isFaultOnUnstacking;
  84. (void)isFaultOnStacking;
  85. (void)isFaultAddressValid;
  86. save_fault_watchdog(__LINE__, faultType, faultAddress);
  87. //Cause debugger to stop. Ignored if no debugger is attached
  88. while(1) {}
  89. }
  90. void BusFault_Handler(void) __attribute__((alias("HardFault_Handler")));
  91. void UsageFault_Handler(void);
  92. void UsageFault_Handler(void) {
  93. //Copy to local variables (not pointers) to allow GDB "i loc" to directly show the info
  94. //Get thread context. Contains main registers including PC and LR
  95. struct port_extctx ctx;
  96. memcpy(&ctx, (void*)__get_PSP(), sizeof(struct port_extctx));
  97. (void)ctx;
  98. //Interrupt status register: Which interrupt have we encountered, e.g. HardFault?
  99. FaultType faultType = (FaultType)__get_IPSR();
  100. (void)faultType;
  101. uint32_t faultAddress = SCB->BFAR;
  102. //Flags about hardfault / busfault
  103. //See http://infocenter.arm.com/help/index.jsp?topic=/com.arm.doc.dui0552a/Cihdjcfc.html for reference
  104. bool isUndefinedInstructionFault = ((SCB->CFSR >> SCB_CFSR_USGFAULTSR_Pos) & (1 << 0) ? true : false);
  105. bool isEPSRUsageFault = ((SCB->CFSR >> SCB_CFSR_USGFAULTSR_Pos) & (1 << 1) ? true : false);
  106. bool isInvalidPCFault = ((SCB->CFSR >> SCB_CFSR_USGFAULTSR_Pos) & (1 << 2) ? true : false);
  107. bool isNoCoprocessorFault = ((SCB->CFSR >> SCB_CFSR_USGFAULTSR_Pos) & (1 << 3) ? true : false);
  108. bool isUnalignedAccessFault = ((SCB->CFSR >> SCB_CFSR_USGFAULTSR_Pos) & (1 << 8) ? true : false);
  109. bool isDivideByZeroFault = ((SCB->CFSR >> SCB_CFSR_USGFAULTSR_Pos) & (1 << 9) ? true : false);
  110. (void)isUndefinedInstructionFault;
  111. (void)isEPSRUsageFault;
  112. (void)isInvalidPCFault;
  113. (void)isNoCoprocessorFault;
  114. (void)isUnalignedAccessFault;
  115. (void)isDivideByZeroFault;
  116. save_fault_watchdog(__LINE__, faultType, faultAddress);
  117. //Cause debugger to stop. Ignored if no debugger is attached
  118. while(1) {}
  119. }
  120. void MemManage_Handler(void);
  121. void MemManage_Handler(void) {
  122. //Copy to local variables (not pointers) to allow GDB "i loc" to directly show the info
  123. //Get thread context. Contains main registers including PC and LR
  124. struct port_extctx ctx;
  125. memcpy(&ctx, (void*)__get_PSP(), sizeof(struct port_extctx));
  126. (void)ctx;
  127. //Interrupt status register: Which interrupt have we encountered, e.g. HardFault?
  128. FaultType faultType = (FaultType)__get_IPSR();
  129. (void)faultType;
  130. //For HardFault/BusFault this is the address that was accessed causing the error
  131. uint32_t faultAddress = SCB->MMFAR;
  132. (void)faultAddress;
  133. //Flags about hardfault / busfault
  134. //See http://infocenter.arm.com/help/index.jsp?topic=/com.arm.doc.dui0552a/Cihdjcfc.html for reference
  135. bool isInstructionAccessViolation = ((SCB->CFSR >> SCB_CFSR_MEMFAULTSR_Pos) & (1 << 0) ? true : false);
  136. bool isDataAccessViolation = ((SCB->CFSR >> SCB_CFSR_MEMFAULTSR_Pos) & (1 << 1) ? true : false);
  137. bool isExceptionUnstackingFault = ((SCB->CFSR >> SCB_CFSR_MEMFAULTSR_Pos) & (1 << 3) ? true : false);
  138. bool isExceptionStackingFault = ((SCB->CFSR >> SCB_CFSR_MEMFAULTSR_Pos) & (1 << 4) ? true : false);
  139. bool isFaultAddressValid = ((SCB->CFSR >> SCB_CFSR_MEMFAULTSR_Pos) & (1 << 7) ? true : false);
  140. (void)isInstructionAccessViolation;
  141. (void)isDataAccessViolation;
  142. (void)isExceptionUnstackingFault;
  143. (void)isExceptionStackingFault;
  144. (void)isFaultAddressValid;
  145. save_fault_watchdog(__LINE__, faultType, faultAddress);
  146. while(1) {}
  147. }
  148. }
  149. namespace AP_HAL {
  150. void init()
  151. {
  152. }
  153. void panic(const char *errormsg, ...)
  154. {
  155. va_list ap;
  156. va_start(ap, errormsg);
  157. vprintf(errormsg, ap);
  158. va_end(ap);
  159. hal.scheduler->delay_microseconds(10000);
  160. while(1) {}
  161. }
  162. uint32_t micros()
  163. {
  164. return hrt_micros32();
  165. }
  166. uint32_t millis()
  167. {
  168. return hrt_millis32();
  169. }
  170. uint16_t millis16()
  171. {
  172. return hrt_millis32() & 0xFFFF;
  173. }
  174. uint64_t micros64()
  175. {
  176. return hrt_micros64();
  177. }
  178. uint64_t millis64()
  179. {
  180. return hrt_micros64() / 1000U;
  181. }
  182. } // namespace AP_HAL