2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
26 #include "drivers/accgyro/accgyro_mpu.h"
27 #include "drivers/exti.h"
28 #include "drivers/nvic.h"
29 #include "drivers/system.h"
30 #include "drivers/persistent.h"
32 #define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000)
33 void SetSysClock(void);
35 void systemReset(void)
41 void systemResetToBootloader(bootloaderRequestType_e requestType
)
43 switch (requestType
) {
44 case BOOTLOADER_REQUEST_ROM
:
46 persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON
, RESET_BOOTLOADER_REQUEST_ROM
);
55 typedef void resetHandler_t(void);
57 typedef struct isrVector_s
{
58 __I
uint32_t stackEnd
;
59 resetHandler_t
*resetHandler
;
62 // Used in the startup files for F4
63 void checkForBootLoaderRequest(void)
65 uint32_t bootloaderRequest
= persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON
);
67 if (bootloaderRequest
!= RESET_BOOTLOADER_REQUEST_ROM
) {
70 persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON
, RESET_NONE
);
72 extern isrVector_t system_isr_vector_table_base
;
74 __set_MSP(system_isr_vector_table_base
.stackEnd
);
75 system_isr_vector_table_base
.resetHandler();
79 void enableGPIOPowerUsageAndNoiseReductions(void)
82 RCC_AHB1PeriphClockCmd(
83 RCC_AHB1Periph_SRAM1
|
84 RCC_AHB1Periph_SRAM2
|
85 RCC_AHB1Periph_BKPSRAM
|
91 RCC_AHB2PeriphClockCmd(0, ENABLE
);
93 RCC_AHB3PeriphClockCmd(0, ENABLE
);
95 RCC_APB1PeriphClockCmd(
100 RCC_APB1Periph_TIM6
|
101 RCC_APB1Periph_TIM7
|
102 RCC_APB1Periph_TIM12
|
103 RCC_APB1Periph_TIM13
|
104 RCC_APB1Periph_TIM14
|
105 RCC_APB1Periph_WWDG
|
106 RCC_APB1Periph_SPI2
|
107 RCC_APB1Periph_SPI3
|
108 RCC_APB1Periph_USART2
|
109 RCC_APB1Periph_USART3
|
110 RCC_APB1Periph_UART4
|
111 RCC_APB1Periph_UART5
|
112 RCC_APB1Periph_I2C1
|
113 RCC_APB1Periph_I2C2
|
114 RCC_APB1Periph_I2C3
|
115 RCC_APB1Periph_CAN1
|
116 RCC_APB1Periph_CAN2
|
121 RCC_APB2PeriphClockCmd(
122 RCC_APB2Periph_TIM1
|
123 RCC_APB2Periph_TIM8
|
124 RCC_APB2Periph_USART1
|
125 RCC_APB2Periph_USART6
|
127 RCC_APB2Periph_ADC1
|
128 RCC_APB2Periph_ADC2
|
129 RCC_APB2Periph_ADC3
|
130 RCC_APB2Periph_SDIO
|
131 RCC_APB2Periph_SPI1
|
132 RCC_APB2Periph_SYSCFG
|
133 RCC_APB2Periph_TIM9
|
134 RCC_APB2Periph_TIM10
|
135 RCC_APB2Periph_TIM11
|
139 bool isMPUSoftReset(void)
141 if (cachedRccCsrValue
& RCC_CSR_SFTRSTF
)
147 void systemInit(void)
149 persistentObjectInit();
151 checkForBootLoaderRequest();
155 // Configure NVIC preempt/priority groups
156 NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING
);
158 // cache RCC->CSR value to use it in isMPUSoftReset() and others
159 cachedRccCsrValue
= RCC
->CSR
;
161 // Although VTOR is already loaded with a possible vector table in RAM,
162 // removing the call to NVIC_SetVectorTable causes USB not to become active,
164 extern uint8_t isr_vector_table_base
;
165 NVIC_SetVectorTable((uint32_t)&isr_vector_table_base
, 0x0);
167 RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS
, DISABLE
);
171 enableGPIOPowerUsageAndNoiseReductions();
173 // Init cycle counter
177 SysTick_Config(SystemCoreClock
/ 1000);