diff --git a/Makefile b/Makefile
index 90217b59a..723545eee 100644
--- a/Makefile
+++ b/Makefile
@@ -28,6 +28,10 @@ OPBL ?=no
# Debugger optons, must be empty or GDB
DEBUG ?=
+# Insert the debugging hardfault debugger
+# releases should not be built with this flag as it does not disable pwm output
+DEBUG_HARDFAULTS ?=
+
# Serial port/Device for flashing
SERIAL_DEVICE ?= $(firstword $(wildcard /dev/ttyUSB*) no-port-found)
@@ -56,6 +60,13 @@ OPBL_VALID_TARGETS = CC3D_OPBL
F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI SPRACINGF3EVO DOGE
+# note that there is no hardfault debugging startup file assembly handler for other platforms
+ifeq ($(DEBUG_HARDFAULTS),F3)
+CFLAGS += -DDEBUG_HARDFAULTS
+STM32F30x_COMMON_SRC = startup_stm32f3_debug_hardfault_handler.S
+else
+STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S
+endif
# Configure default flash sizes for the targets
ifeq ($(FLASH_SIZE),)
@@ -534,8 +545,8 @@ CC3D_SRC = \
$(COMMON_SRC) \
$(VCP_SRC)
-STM32F30x_COMMON_SRC = \
- startup_stm32f30x_md_gcc.S \
+
+STM32F30x_COMMON_SRC += \
drivers/adc.c \
drivers/adc_stm32f30x.c \
drivers/bus_i2c_stm32f30x.c \
@@ -816,7 +827,7 @@ endif
DEBUG_FLAGS = -ggdb3 -DDEBUG
-CFLAGS = $(ARCH_FLAGS) \
+CFLAGS += $(ARCH_FLAGS) \
$(LTO_FLAGS) \
$(addprefix -D,$(OPTIONS)) \
$(addprefix -I,$(INCLUDE_DIRS)) \
diff --git a/src/main/main.c b/src/main/main.c
index 59158b2a5..49fc7c246 100644
--- a/src/main/main.c
+++ b/src/main/main.c
@@ -736,6 +736,66 @@ int main(void) {
}
}
+#ifdef DEBUG_HARDFAULTS
+//from: https://mcuoneclipse.com/2012/11/24/debugging-hard-faults-on-arm-cortex-m/
+/**
+ * hard_fault_handler_c:
+ * This is called from the HardFault_HandlerAsm with a pointer the Fault stack
+ * as the parameter. We can then read the values from the stack and place them
+ * into local variables for ease of reading.
+ * We then read the various Fault Status and Address Registers to help decode
+ * cause of the fault.
+ * The function ends with a BKPT instruction to force control back into the debugger
+ */
+void hard_fault_handler_c(unsigned long *hardfault_args){
+ volatile unsigned long stacked_r0 ;
+ volatile unsigned long stacked_r1 ;
+ volatile unsigned long stacked_r2 ;
+ volatile unsigned long stacked_r3 ;
+ volatile unsigned long stacked_r12 ;
+ volatile unsigned long stacked_lr ;
+ volatile unsigned long stacked_pc ;
+ volatile unsigned long stacked_psr ;
+ volatile unsigned long _CFSR ;
+ volatile unsigned long _HFSR ;
+ volatile unsigned long _DFSR ;
+ volatile unsigned long _AFSR ;
+ volatile unsigned long _BFAR ;
+ volatile unsigned long _MMAR ;
+
+ stacked_r0 = ((unsigned long)hardfault_args[0]) ;
+ stacked_r1 = ((unsigned long)hardfault_args[1]) ;
+ stacked_r2 = ((unsigned long)hardfault_args[2]) ;
+ stacked_r3 = ((unsigned long)hardfault_args[3]) ;
+ stacked_r12 = ((unsigned long)hardfault_args[4]) ;
+ stacked_lr = ((unsigned long)hardfault_args[5]) ;
+ stacked_pc = ((unsigned long)hardfault_args[6]) ;
+ stacked_psr = ((unsigned long)hardfault_args[7]) ;
+
+ // Configurable Fault Status Register
+ // Consists of MMSR, BFSR and UFSR
+ _CFSR = (*((volatile unsigned long *)(0xE000ED28))) ;
+
+ // Hard Fault Status Register
+ _HFSR = (*((volatile unsigned long *)(0xE000ED2C))) ;
+
+ // Debug Fault Status Register
+ _DFSR = (*((volatile unsigned long *)(0xE000ED30))) ;
+
+ // Auxiliary Fault Status Register
+ _AFSR = (*((volatile unsigned long *)(0xE000ED3C))) ;
+
+ // Read the Fault Address Registers. These may not contain valid values.
+ // Check BFARVALID/MMARVALID to see if they are valid values
+ // MemManage Fault Address Register
+ _MMAR = (*((volatile unsigned long *)(0xE000ED34))) ;
+ // Bus Fault Address Register
+ _BFAR = (*((volatile unsigned long *)(0xE000ED38))) ;
+
+ __asm("BKPT #0\n") ; // Break into the debugger
+}
+
+#else
void HardFault_Handler(void)
{
// fall out of the sky
@@ -753,3 +813,4 @@ void HardFault_Handler(void)
while (1);
}
+#endif
diff --git a/src/main/startup/startup_stm32f3_debug_hardfault_handler.S b/src/main/startup/startup_stm32f3_debug_hardfault_handler.S
new file mode 100644
index 000000000..65ee39a67
--- /dev/null
+++ b/src/main/startup/startup_stm32f3_debug_hardfault_handler.S
@@ -0,0 +1,501 @@
+/**
+ ******************************************************************************
+ * @file startup_stm32f30x.s
+ * @author MCD Application Team
+ * @version V1.0.0
+ * @date 04-Spetember-2012
+ * @brief STM32F30x Devices vector table for RIDE7 toolchain.
+ * This module performs:
+ * - Set the initial SP
+ * - Set the initial PC == Reset_Handler,
+ * - Set the vector table entries with the exceptions ISR address
+ * - Configure the clock system and the external SRAM mounted on
+ * STM3230C-EVAL board to be used as data memory (optional,
+ * to be enabled by user)
+ * - Branches to main in the C library (which eventually
+ * calls main()).
+ * After Reset the Cortex-M4 processor is in Thread mode,
+ * priority is Privileged, and the Stack is set to Main.
+ ******************************************************************************
+ * @attention
+ *
+ *
© COPYRIGHT 2012 STMicroelectronics
+ *
+ * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+ * You may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at:
+ *
+ * http://www.st.com/software_license_agreement_liberty_v2
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+ ******************************************************************************
+ */
+
+ .syntax unified
+ .cpu cortex-m4
+ .fpu softvfp
+ .thumb
+
+.global g_pfnVectors
+.global Default_Handler
+
+.global HardFault_Handler
+.extern hard_fault_handler_c
+
+/* start address for the initialization values of the .data section.
+defined in linker script */
+.word _sidata
+/* start address for the .data section. defined in linker script */
+.word _sdata
+/* end address for the .data section. defined in linker script */
+.word _edata
+/* start address for the .bss section. defined in linker script */
+.word _sbss
+/* end address for the .bss section. defined in linker script */
+.word _ebss
+/* stack used for SystemInit_ExtMemCtl; always internal RAM used */
+
+/**
+ * @brief This is the code that gets called when the processor first
+ * starts execution following a reset event. Only the absolutely
+ * necessary set is performed, after which the application
+ * supplied main() routine is called.
+ * @param None
+ * @retval : None
+*/
+
+ .section .text.Reset_Handler
+ .weak Reset_Handler
+ .type Reset_Handler, %function
+Reset_Handler:
+ ldr r0, =0x20009FFC // HJI 11/9/2012
+ ldr r1, =0xDEADBEEF // HJI 11/9/2012
+ ldr r2, [r0, #0] // HJI 11/9/2012
+ str r0, [r0, #0] // HJI 11/9/2012
+ cmp r2, r1 // HJI 11/9/2012
+ beq Reboot_Loader // HJI 11/9/2012
+
+/* Copy the data segment initializers from flash to SRAM */
+ movs r1, #0
+ b LoopCopyDataInit
+
+CopyDataInit:
+ ldr r3, =_sidata
+ ldr r3, [r3, r1]
+ str r3, [r0, r1]
+ adds r1, r1, #4
+
+LoopCopyDataInit:
+ ldr r0, =_sdata
+ ldr r3, =_edata
+ adds r2, r0, r1
+ cmp r2, r3
+ bcc CopyDataInit
+ ldr r2, =_sbss
+ b LoopFillZerobss
+/* Zero fill the bss segment. */
+FillZerobss:
+ movs r3, #0
+ str r3, [r2], #4
+
+LoopFillZerobss:
+ ldr r3, = _ebss
+ cmp r2, r3
+ bcc FillZerobss
+
+/* Call the clock system intitialization function.*/
+ bl SystemInit
+/* Call the application's entry point.*/
+ bl main
+ bx lr
+
+LoopForever:
+ b LoopForever
+
+Reboot_Loader: // HJI 11/9/2012
+
+ // Reboot to ROM // HJI 11/9/2012
+ ldr r0, =0x1FFFD800 // HJI 4/26/2013
+ ldr sp,[r0, #0] // HJI 11/9/2012
+ ldr r0,[r0, #4] // HJI 11/9/2012
+ bx r0 // HJI 11/9/2012
+
+.size Reset_Handler, .-Reset_Handler
+
+.section .text.Reset_Handler
+.weak HardFault_Handler
+.type HardFault_Handler, %function
+HardFault_Handler:
+ movs r0,#4
+ movs r1, lr
+ tst r0, r1
+ beq _MSP
+ mrs r0, psp
+ b _HALT
+_MSP:
+ mrs r0, msp
+_HALT:
+ ldr r1,[r0,#20]
+ b hard_fault_handler_c
+ bkpt #0
+
+.size HardFault_Handler, .-HardFault_Handler
+
+/**
+ * @brief This is the code that gets called when the processor receives an
+ * unexpected interrupt. This simply enters an infinite loop, preserving
+ * the system state for examination by a debugger.
+ * @param None
+ * @retval None
+*/
+ .section .text.Default_Handler,"ax",%progbits
+Default_Handler:
+Infinite_Loop:
+ b Infinite_Loop
+ .size Default_Handler, .-Default_Handler
+/******************************************************************************
+*
+* The minimal vector table for a Cortex M4. Note that the proper constructs
+* must be placed on this to ensure that it ends up at physical address
+* 0x0000.0000.
+*
+*******************************************************************************/
+ .section .isr_vector,"a",%progbits
+ .type g_pfnVectors, %object
+ .size g_pfnVectors, .-g_pfnVectors
+
+g_pfnVectors:
+ .word _estack
+ .word Reset_Handler
+ .word NMI_Handler
+ .word HardFault_Handler
+ .word MemManage_Handler
+ .word BusFault_Handler
+ .word UsageFault_Handler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word SVC_Handler
+ .word DebugMon_Handler
+ .word 0
+ .word PendSV_Handler
+ .word SysTick_Handler
+ .word WWDG_IRQHandler
+ .word PVD_IRQHandler
+ .word TAMPER_STAMP_IRQHandler
+ .word RTC_WKUP_IRQHandler
+ .word FLASH_IRQHandler
+ .word RCC_IRQHandler
+ .word EXTI0_IRQHandler
+ .word EXTI1_IRQHandler
+ .word EXTI2_TS_IRQHandler
+ .word EXTI3_IRQHandler
+ .word EXTI4_IRQHandler
+ .word DMA1_Channel1_IRQHandler
+ .word DMA1_Channel2_IRQHandler
+ .word DMA1_Channel3_IRQHandler
+ .word DMA1_Channel4_IRQHandler
+ .word DMA1_Channel5_IRQHandler
+ .word DMA1_Channel6_IRQHandler
+ .word DMA1_Channel7_IRQHandler
+ .word ADC1_2_IRQHandler
+ .word USB_HP_CAN1_TX_IRQHandler
+ .word USB_LP_CAN1_RX0_IRQHandler
+ .word CAN1_RX1_IRQHandler
+ .word CAN1_SCE_IRQHandler
+ .word EXTI9_5_IRQHandler
+ .word TIM1_BRK_TIM15_IRQHandler
+ .word TIM1_UP_TIM16_IRQHandler
+ .word TIM1_TRG_COM_TIM17_IRQHandler
+ .word TIM1_CC_IRQHandler
+ .word TIM2_IRQHandler
+ .word TIM3_IRQHandler
+ .word TIM4_IRQHandler
+ .word I2C1_EV_IRQHandler
+ .word I2C1_ER_IRQHandler
+ .word I2C2_EV_IRQHandler
+ .word I2C2_ER_IRQHandler
+ .word SPI1_IRQHandler
+ .word SPI2_IRQHandler
+ .word USART1_IRQHandler
+ .word USART2_IRQHandler
+ .word USART3_IRQHandler
+ .word EXTI15_10_IRQHandler
+ .word RTC_Alarm_IRQHandler
+ .word USBWakeUp_IRQHandler
+ .word TIM8_BRK_IRQHandler
+ .word TIM8_UP_IRQHandler
+ .word TIM8_TRG_COM_IRQHandler
+ .word TIM8_CC_IRQHandler
+ .word ADC3_IRQHandler
+ .word 0
+ .word 0
+ .word 0
+ .word SPI3_IRQHandler
+ .word UART4_IRQHandler
+ .word UART5_IRQHandler
+ .word TIM6_DAC_IRQHandler
+ .word TIM7_IRQHandler
+ .word DMA2_Channel1_IRQHandler
+ .word DMA2_Channel2_IRQHandler
+ .word DMA2_Channel3_IRQHandler
+ .word DMA2_Channel4_IRQHandler
+ .word DMA2_Channel5_IRQHandler
+ .word ADC4_IRQHandler
+ .word 0
+ .word 0
+ .word COMP1_2_3_IRQHandler
+ .word COMP4_5_6_IRQHandler
+ .word COMP7_IRQHandler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word USB_HP_IRQHandler
+ .word USB_LP_IRQHandler
+ .word USBWakeUp_RMP_IRQHandler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word FPU_IRQHandler
+
+/*******************************************************************************
+*
+* Provide weak aliases for each Exception handler to the Default_Handler.
+* As they are weak aliases, any function with the same name will override
+* this definition.
+*
+*******************************************************************************/
+
+ .weak NMI_Handler
+ .thumb_set NMI_Handler,Default_Handler
+
+ .weak MemManage_Handler
+ .thumb_set MemManage_Handler,Default_Handler
+
+ .weak BusFault_Handler
+ .thumb_set BusFault_Handler,Default_Handler
+
+ .weak UsageFault_Handler
+ .thumb_set UsageFault_Handler,Default_Handler
+
+ .weak SVC_Handler
+ .thumb_set SVC_Handler,Default_Handler
+
+ .weak DebugMon_Handler
+ .thumb_set DebugMon_Handler,Default_Handler
+
+ .weak PendSV_Handler
+ .thumb_set PendSV_Handler,Default_Handler
+
+ .weak SysTick_Handler
+ .thumb_set SysTick_Handler,Default_Handler
+
+ .weak WWDG_IRQHandler
+ .thumb_set WWDG_IRQHandler,Default_Handler
+
+ .weak PVD_IRQHandler
+ .thumb_set PVD_IRQHandler,Default_Handler
+
+ .weak TAMPER_STAMP_IRQHandler
+ .thumb_set TAMPER_STAMP_IRQHandler,Default_Handler
+
+ .weak RTC_WKUP_IRQHandler
+ .thumb_set RTC_WKUP_IRQHandler,Default_Handler
+
+ .weak FLASH_IRQHandler
+ .thumb_set FLASH_IRQHandler,Default_Handler
+
+ .weak RCC_IRQHandler
+ .thumb_set RCC_IRQHandler,Default_Handler
+
+ .weak EXTI0_IRQHandler
+ .thumb_set EXTI0_IRQHandler,Default_Handler
+
+ .weak EXTI1_IRQHandler
+ .thumb_set EXTI1_IRQHandler,Default_Handler
+
+ .weak EXTI2_TS_IRQHandler
+ .thumb_set EXTI2_TS_IRQHandler,Default_Handler
+
+ .weak EXTI3_IRQHandler
+ .thumb_set EXTI3_IRQHandler,Default_Handler
+
+ .weak EXTI4_IRQHandler
+ .thumb_set EXTI4_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel1_IRQHandler
+ .thumb_set DMA1_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel2_IRQHandler
+ .thumb_set DMA1_Channel2_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel3_IRQHandler
+ .thumb_set DMA1_Channel3_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel4_IRQHandler
+ .thumb_set DMA1_Channel4_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel5_IRQHandler
+ .thumb_set DMA1_Channel5_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel6_IRQHandler
+ .thumb_set DMA1_Channel6_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel7_IRQHandler
+ .thumb_set DMA1_Channel7_IRQHandler,Default_Handler
+
+ .weak ADC1_2_IRQHandler
+ .thumb_set ADC1_2_IRQHandler,Default_Handler
+
+ .weak USB_HP_CAN1_TX_IRQHandler
+ .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler
+
+ .weak USB_LP_CAN1_RX0_IRQHandler
+ .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler
+
+ .weak CAN1_RX1_IRQHandler
+ .thumb_set CAN1_RX1_IRQHandler,Default_Handler
+
+ .weak CAN1_SCE_IRQHandler
+ .thumb_set CAN1_SCE_IRQHandler,Default_Handler
+
+ .weak EXTI9_5_IRQHandler
+ .thumb_set EXTI9_5_IRQHandler,Default_Handler
+
+ .weak TIM1_BRK_TIM15_IRQHandler
+ .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler
+
+ .weak TIM1_UP_TIM16_IRQHandler
+ .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler
+
+ .weak TIM1_TRG_COM_TIM17_IRQHandler
+ .thumb_set TIM1_TRG_COM_TIM17_IRQHandler,Default_Handler
+
+ .weak TIM1_CC_IRQHandler
+ .thumb_set TIM1_CC_IRQHandler,Default_Handler
+
+ .weak TIM2_IRQHandler
+ .thumb_set TIM2_IRQHandler,Default_Handler
+
+ .weak TIM3_IRQHandler
+ .thumb_set TIM3_IRQHandler,Default_Handler
+
+ .weak TIM4_IRQHandler
+ .thumb_set TIM4_IRQHandler,Default_Handler
+
+ .weak I2C1_EV_IRQHandler
+ .thumb_set I2C1_EV_IRQHandler,Default_Handler
+
+ .weak I2C1_ER_IRQHandler
+ .thumb_set I2C1_ER_IRQHandler,Default_Handler
+
+ .weak I2C2_EV_IRQHandler
+ .thumb_set I2C2_EV_IRQHandler,Default_Handler
+
+ .weak I2C2_ER_IRQHandler
+ .thumb_set I2C2_ER_IRQHandler,Default_Handler
+
+ .weak SPI1_IRQHandler
+ .thumb_set SPI1_IRQHandler,Default_Handler
+
+ .weak SPI2_IRQHandler
+ .thumb_set SPI2_IRQHandler,Default_Handler
+
+ .weak USART1_IRQHandler
+ .thumb_set USART1_IRQHandler,Default_Handler
+
+ .weak USART2_IRQHandler
+ .thumb_set USART2_IRQHandler,Default_Handler
+
+ .weak USART3_IRQHandler
+ .thumb_set USART3_IRQHandler,Default_Handler
+
+ .weak EXTI15_10_IRQHandler
+ .thumb_set EXTI15_10_IRQHandler,Default_Handler
+
+ .weak RTC_Alarm_IRQHandler
+ .thumb_set RTC_Alarm_IRQHandler,Default_Handler
+
+ .weak USBWakeUp_IRQHandler
+ .thumb_set USBWakeUp_IRQHandler,Default_Handler
+
+ .weak TIM8_BRK_IRQHandler
+ .thumb_set TIM8_BRK_IRQHandler,Default_Handler
+
+ .weak TIM8_UP_IRQHandler
+ .thumb_set TIM8_UP_IRQHandler,Default_Handler
+
+ .weak TIM8_TRG_COM_IRQHandler
+ .thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler
+
+ .weak TIM8_CC_IRQHandler
+ .thumb_set TIM8_CC_IRQHandler,Default_Handler
+
+ .weak ADC3_IRQHandler
+ .thumb_set ADC3_IRQHandler,Default_Handler
+
+ .weak SPI3_IRQHandler
+ .thumb_set SPI3_IRQHandler,Default_Handler
+
+ .weak UART4_IRQHandler
+ .thumb_set UART4_IRQHandler,Default_Handler
+
+ .weak UART5_IRQHandler
+ .thumb_set UART5_IRQHandler,Default_Handler
+
+ .weak TIM6_DAC_IRQHandler
+ .thumb_set TIM6_DAC_IRQHandler,Default_Handler
+
+ .weak TIM7_IRQHandler
+ .thumb_set TIM7_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel1_IRQHandler
+ .thumb_set DMA2_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel2_IRQHandler
+ .thumb_set DMA2_Channel2_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel3_IRQHandler
+ .thumb_set DMA2_Channel3_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel4_IRQHandler
+ .thumb_set DMA2_Channel4_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel5_IRQHandler
+ .thumb_set DMA2_Channel5_IRQHandler,Default_Handler
+
+ .weak ADC4_IRQHandler
+ .thumb_set ADC4_IRQHandler,Default_Handler
+
+ .weak COMP1_2_3_IRQHandler
+ .thumb_set COMP1_2_3_IRQHandler,Default_Handler
+
+ .weak COMP4_5_6_IRQHandler
+ .thumb_set COMP4_5_6_IRQHandler,Default_Handler
+
+ .weak COMP7_IRQHandler
+ .thumb_set COMP7_IRQHandler,Default_Handler
+
+ .weak USB_HP_IRQHandler
+ .thumb_set USB_HP_IRQHandler,Default_Handler
+
+ .weak USB_LP_IRQHandler
+ .thumb_set USB_LP_IRQHandler,Default_Handler
+
+ .weak USBWakeUp_RMP_IRQHandler
+ .thumb_set USBWakeUp_RMP_IRQHandler,Default_Handler
+
+ .weak FPU_IRQHandler
+ .thumb_set FPU_IRQHandler,Default_Handler
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/