APM:Libraries
system.cpp
Go to the documentation of this file.
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 
22 #include <ch.h>
23 #include "hal.h"
24 #include <hrt.h>
25 
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,
37 } FaultType;
38 
40 
41 void __cxa_pure_virtual(void);
42 void __cxa_pure_virtual() { while (1); } //TODO: Handle properly, maybe generate a traceback
43 
44 void NMI_Handler(void);
45 void NMI_Handler(void) { while (1); }
46 
47 void HardFault_Handler(void);
48 void HardFault_Handler(void) {
49  //Copy to local variables (not pointers) to allow GDB "i loc" to directly show the info
50  //Get thread context. Contains main registers including PC and LR
51  struct port_extctx ctx;
52  memcpy(&ctx, (void*)__get_PSP(), sizeof(struct port_extctx));
53  (void)ctx;
54  //Interrupt status register: Which interrupt have we encountered, e.g. HardFault?
55  FaultType faultType = (FaultType)__get_IPSR();
56  (void)faultType;
57  //For HardFault/BusFault this is the address that was accessed causing the error
58  uint32_t faultAddress = SCB->BFAR;
59  (void)faultAddress;
60  //Flags about hardfault / busfault
61  //See http://infocenter.arm.com/help/index.jsp?topic=/com.arm.doc.dui0552a/Cihdjcfc.html for reference
62  bool isFaultPrecise = ((SCB->CFSR >> SCB_CFSR_BUSFAULTSR_Pos) & (1 << 1) ? true : false);
63  bool isFaultImprecise = ((SCB->CFSR >> SCB_CFSR_BUSFAULTSR_Pos) & (1 << 2) ? true : false);
64  bool isFaultOnUnstacking = ((SCB->CFSR >> SCB_CFSR_BUSFAULTSR_Pos) & (1 << 3) ? true : false);
65  bool isFaultOnStacking = ((SCB->CFSR >> SCB_CFSR_BUSFAULTSR_Pos) & (1 << 4) ? true : false);
66  bool isFaultAddressValid = ((SCB->CFSR >> SCB_CFSR_BUSFAULTSR_Pos) & (1 << 7) ? true : false);
67  (void)isFaultPrecise;
68  (void)isFaultImprecise;
69  (void)isFaultOnUnstacking;
70  (void)isFaultOnStacking;
71  (void)isFaultAddressValid;
72  //Cause debugger to stop. Ignored if no debugger is attached
73  while(1) {}
74 }
75 
76 void BusFault_Handler(void) __attribute__((alias("HardFault_Handler")));
77 
78 void UsageFault_Handler(void);
79 void UsageFault_Handler(void) {
80  //Copy to local variables (not pointers) to allow GDB "i loc" to directly show the info
81  //Get thread context. Contains main registers including PC and LR
82  struct port_extctx ctx;
83  memcpy(&ctx, (void*)__get_PSP(), sizeof(struct port_extctx));
84  (void)ctx;
85  //Interrupt status register: Which interrupt have we encountered, e.g. HardFault?
86  FaultType faultType = (FaultType)__get_IPSR();
87  (void)faultType;
88  //Flags about hardfault / busfault
89  //See http://infocenter.arm.com/help/index.jsp?topic=/com.arm.doc.dui0552a/Cihdjcfc.html for reference
90  bool isUndefinedInstructionFault = ((SCB->CFSR >> SCB_CFSR_USGFAULTSR_Pos) & (1 << 0) ? true : false);
91  bool isEPSRUsageFault = ((SCB->CFSR >> SCB_CFSR_USGFAULTSR_Pos) & (1 << 1) ? true : false);
92  bool isInvalidPCFault = ((SCB->CFSR >> SCB_CFSR_USGFAULTSR_Pos) & (1 << 2) ? true : false);
93  bool isNoCoprocessorFault = ((SCB->CFSR >> SCB_CFSR_USGFAULTSR_Pos) & (1 << 3) ? true : false);
94  bool isUnalignedAccessFault = ((SCB->CFSR >> SCB_CFSR_USGFAULTSR_Pos) & (1 << 8) ? true : false);
95  bool isDivideByZeroFault = ((SCB->CFSR >> SCB_CFSR_USGFAULTSR_Pos) & (1 << 9) ? true : false);
96  (void)isUndefinedInstructionFault;
97  (void)isEPSRUsageFault;
98  (void)isInvalidPCFault;
99  (void)isNoCoprocessorFault;
100  (void)isUnalignedAccessFault;
101  (void)isDivideByZeroFault;
102  //Cause debugger to stop. Ignored if no debugger is attached
103  while(1) {}
104 }
105 
106 void MemManage_Handler(void);
107 void MemManage_Handler(void) {
108  //Copy to local variables (not pointers) to allow GDB "i loc" to directly show the info
109  //Get thread context. Contains main registers including PC and LR
110  struct port_extctx ctx;
111  memcpy(&ctx, (void*)__get_PSP(), sizeof(struct port_extctx));
112  (void)ctx;
113  //Interrupt status register: Which interrupt have we encountered, e.g. HardFault?
114  FaultType faultType = (FaultType)__get_IPSR();
115  (void)faultType;
116  //For HardFault/BusFault this is the address that was accessed causing the error
117  uint32_t faultAddress = SCB->MMFAR;
118  (void)faultAddress;
119  //Flags about hardfault / busfault
120  //See http://infocenter.arm.com/help/index.jsp?topic=/com.arm.doc.dui0552a/Cihdjcfc.html for reference
121  bool isInstructionAccessViolation = ((SCB->CFSR >> SCB_CFSR_MEMFAULTSR_Pos) & (1 << 0) ? true : false);
122  bool isDataAccessViolation = ((SCB->CFSR >> SCB_CFSR_MEMFAULTSR_Pos) & (1 << 1) ? true : false);
123  bool isExceptionUnstackingFault = ((SCB->CFSR >> SCB_CFSR_MEMFAULTSR_Pos) & (1 << 3) ? true : false);
124  bool isExceptionStackingFault = ((SCB->CFSR >> SCB_CFSR_MEMFAULTSR_Pos) & (1 << 4) ? true : false);
125  bool isFaultAddressValid = ((SCB->CFSR >> SCB_CFSR_MEMFAULTSR_Pos) & (1 << 7) ? true : false);
126  (void)isInstructionAccessViolation;
127  (void)isDataAccessViolation;
128  (void)isExceptionUnstackingFault;
129  (void)isExceptionStackingFault;
130  (void)isFaultAddressValid;
131  while(1) {}
132 }
133 }
134 namespace AP_HAL {
135 
136 void init()
137 {
138 }
139 
140 void panic(const char *errormsg, ...)
141 {
142  va_list ap;
143 
144  va_start(ap, errormsg);
145  vprintf(errormsg, ap);
146  va_end(ap);
147 
148  hal.scheduler->delay_microseconds(10000);
149  while(1) {}
150 }
151 
152 uint32_t micros()
153 {
154  return micros64() & 0xFFFFFFFF;
155 }
156 
157 uint32_t millis()
158 {
159  return millis64() & 0xFFFFFFFF;
160 }
161 
162 uint64_t micros64()
163 {
164  return hrt_micros();
165 }
166 
167 uint64_t millis64()
168 {
169  return micros64() / 1000;
170 }
171 
172 } // namespace AP_HAL
void * __dso_handle
Definition: system.cpp:39
void UsageFault_Handler(void)
Definition: system.cpp:79
void __cxa_pure_virtual(void)
Definition: system.cpp:42
uint64_t hrt_micros()
Definition: hrt.c:25
void BusFault_Handler(void) __attribute__((alias("HardFault_Handler")))
uint64_t millis64()
Definition: system.cpp:167
__attribute__((used))
Definition: stubs.c:88
Definition: system.cpp:31
void MemManage_Handler(void)
Definition: system.cpp:107
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
uint32_t millis()
Definition: system.cpp:157
uint64_t micros64()
Definition: system.cpp:162
Definition: system.cpp:32
int vprintf(const char *fmt, va_list arg)
Definition: stdio.c:100
void HardFault_Handler(void)
Definition: system.cpp:48
void init()
Generic board initialization function.
Definition: system.cpp:136
virtual void delay_microseconds(uint16_t us)=0
void NMI_Handler(void)
Definition: system.cpp:45
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
uint32_t micros()
Definition: system.cpp:152
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
FaultType
Definition: system.cpp:30