APM:Libraries
boards.cpp
Go to the documentation of this file.
1 /******************************************************************************
2  * The MIT License
3  *
4  (c) 2017 night_ghost@ykoctpa.ru
5 
6 based on:
7 
8  * Copyright (c) 2010 Perry Hung.
9  *
10  * Permission is hereby granted, free of charge, to any person
11  * obtaining a copy of this software and associated documentation
12  * files (the "Software"), to deal in the Software without
13  * restriction, including without limitation the rights to use, copy,
14  * modify, merge, publish, distribute, sublicense, and/or sell copies
15  * of the Software, and to permit persons to whom the Software is
16  * furnished to do so, subject to the following conditions:
17  *
18  * The above copyright notice and this permission notice shall be
19  * included in all copies or substantial portions of the Software.
20  *
21  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
22  * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
23  * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
24  * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
25  * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
26  * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
27  * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
28  * SOFTWARE.
29  *****************************************************************************/
30 
36 #pragma GCC optimize ("O2")
37 
38 #include "boards.h"
39 #include <usb.h>
40 
41 static void setupNVIC(void);
42 static void enableFPU(void);
43 static void setupCCM(void);
44 
45 
46 void setupADC(void);
47 void setupTimers(void);
48 void usb_init(void);
49 
50 
51 void usb_init(void){
52 
53 
55  usb_open();
56 
57  usb_default_attr(&usb_attr);
58  usb_attr.preempt_prio = USB_INT_PRIORITY;
59  usb_attr.sub_prio = 0;
60  usb_attr.use_present_pin = 1;
63 
64  usb_configure(&usb_attr);
65 
66 }
67 
68 static INLINE void enableFPU(void){
69 #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
70  SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); // set CP10 and CP11 Full Access
71 
72 /*
73 FPU_FPCCR_ASPEN_Msk
74 FPU_FPCCR_LSPEN_Msk
75 */
76 
77 #endif
78 }
79 
80 
81 
82 
83 static INLINE void setupCCM(){
84  extern unsigned _sccm,_eccm; // defined by link script
85 /* enabled by startup code
86  RCC->AHB1ENR |= RCC_AHB1ENR_CCMDATARAMEN;
87  asm volatile("dsb \n");
88 */
89 
90 
91 // volatile unsigned *src = &_siccm; // CCM initializers in flash
92  volatile unsigned *dest = &_sccm; // start of CCM
93 
94 #if 0 // no support for initialized data in CCM
95 
96  while (dest < &_eccm) {
97  *dest++ = *src++;
98  }
99 #endif
100  while (dest < &_eccm) {
101  *dest++ = 0;
102  }
103 
104 // only for stack debugging
105 #if 0
106  uint32_t sp;
107 
108  // Get stack pointer
109  asm volatile ("mov %0, sp\n\t" : "=rm" (sp) );
110 
111  #if 0 // memset is much faster but uses too much stack for own needs
112  memset((void *)dest,0x55, (sp-(uint32_t)dest) -128);
113  #else
114  while ((uint32_t)dest < (sp-8)) {
115  *dest++ = 0x55555555; // fill stack to check it's usage
116  }
117  #endif
118 #endif
119 }
120 
121 
122 
123 static INLINE void setupNVIC()
124 {
125  /* 4 bit preemption, 0 bit subpriority */
126  NVIC_PriorityGroupConfig( NVIC_PriorityGroup_4);
127 
128  exti_init();
129 }
130 
131 
132 /*
133 [..] To enable access to the RTC Domain and RTC registers, proceed as follows:
134  (+) Enable the Power Controller (PWR) APB1 interface clock using the
135  RCC_APB1PeriphClockCmd() function.
136  (+) Enable access to RTC domain using the PWR_BackupAccessCmd() function.
137  (+) Select the RTC clock source using the RCC_RTCCLKConfig() function.
138  (+) Enable RTC Clock using the RCC_RTCCLKCmd() function.
139 */
140 
141 void board_set_rtc_register(uint32_t sig, uint16_t reg)
142 {
143  PWR->CR |= PWR_CR_DBP;
144 
145  RTC_WriteBackupRegister(reg, sig);
146 
147  PWR->CR &= ~PWR_CR_DBP;
148 }
149 
150 
151 uint32_t board_get_rtc_register(uint16_t reg)
152 {
153  // enable the backup registers.
154  PWR->CR |= PWR_CR_DBP;
155 
156  uint32_t ret = RTC_ReadBackupRegister(reg);
157 
158  PWR->CR &= ~PWR_CR_DBP;
159  return ret;
160 }
161 
162 
163 // 1st executing function
164 
165 void inline init(void) {
166 
167  // now we can use stack
168 
169 // turn on and enable RTC
170  RCC->APB1ENR |= RCC_APB1ENR_PWREN;
171  RCC->AHB1ENR |= RCC_AHB1ENR_BKPSRAMEN;
172  PWR_BackupAccessCmd(ENABLE);
173 
174  RCC_RTCCLKConfig(RCC_RTCCLKSource_LSI);
175  RCC_RTCCLKCmd(ENABLE);
176 
177  // enable the backup registers.
178  RCC->BDCR |= RCC_BDCR_RTCEN;
179 
180  RTC_WriteProtectionCmd(DISABLE);
181  for(volatile int i=0; i<50; i++); // small delay
182 // RTC is ready
185  for(volatile int i=0; i<50; i++); // small delay
186  uint32_t reg=board_get_rtc_register(RTC_SIGNATURE_REG); // read again
187  if(reg==0) {
188  goDFU(); // just after reset - so all hardware is in boot state
189  }
190  }
191 
192 
193  bool overclock_failed = false;
194  uint8_t overclock=0;
195 
197 
198  if(g == OV_GUARD_FAIL_SIGNATURE) {
199  overclock_failed = true; // never reset it to 0 if failed once
200  } else if(g == OV_GUARD_SIGNATURE) { // overclock fails
201  overclock_failed = true; // never reset it to 0 if failed once
203  } else {
205  if((sig & ~OVERCLOCK_SIG_MASK ) == OVERCLOCK_SIGNATURE) {
207  overclock = (uint8_t)sig & OVERCLOCK_SIG_MASK;
208 
209  if(overclock) {
210  board_set_rtc_register(OV_GUARD_SIGNATURE, RTC_OV_GUARD_REG); // set guard in case overclock fails
211  } else {
212  board_set_rtc_register(0, RTC_OV_GUARD_REG); // clear guard
213  }
214  }
215  }
216 
217 
218  systemInit(overclock); // calls SetSysClock
219  SystemCoreClockUpdate(); // update SystemCoreClock variable to current frequency
220 
221  enableFPU();
222 
223  setupNVIC();
225 
226  stopwatch_init(); // will use stopwatch_delay_us() and stopwatch_get_ticks()
227 
228 #ifdef DEBUG_BUILD
229 //*/// enable clock in sleep for debugging
230  DBGMCU->CR |= DBGMCU_STANDBY | DBGMCU_STOP | DBGMCU_SLEEP;
231  DBGMCU->APB1FZ |= DBGMCU_TIM4_STOP | DBGMCU_TIM5_STOP | DBGMCU_TIM7_STOP; // stop internal timers
232  DBGMCU->APB2FZ |= DBGMCU_TIM10_STOP | DBGMCU_TIM11_STOP;
233 //*///
234 #endif
235 
236  boardInit(); // board-specific part of init
237 /*
238  only CPU init here, all another moved to modules .init() functions
239 */
240  interrupts();
241 
242  if(!overclock_failed) {
243  // comes here - all ok, we can clear guard
245  }
246 
247 }
248 
249 // called with stack in MSP
250 void pre_init(){ // before any stack usage @NG
251  setupCCM(); // needs because stack in CCM
252 
253  init();
254 }
255 
256 // частота неправильная и штатными функциями задержки мы не можем пользоваться
257 void emerg_delay(uint32_t n){
258  volatile uint32_t i;
259 
260  while(n){
261  for (i=4000; i!=0; i--) { // 16MHz, command each tick - ~4MHz or 0.25uS * 4000 = 1ms
262  asm volatile("nop \n");
263  }
264  n--;
265  }
266 }
267 
268 
269 void NMI_Handler() {
270 
271  //Очищаем флаг прерывания CSS
272  RCC->CIR |= RCC_CIR_CSSC;
273  //Ждем некоторое время после сбоя, если он кратковременный
274  //Возможно удастся перезапустить
275  emerg_delay(100); // clock is wrong so all micros() etc lies!
276 
277 
278  //Пытаемся запустить HSE
279  RCC_HSEConfig(RCC_HSE_ON);
280  emerg_delay(1); //Задержка на запуск кварца
281 
282 
283  if (RCC_WaitForHSEStartUp() == SUCCESS){
284  //Если запустился - проводим установку заново
285  SetSysClock(0); // without overclocking
286 
287  } else {
288 
289 // кварц не запустился, переключаемся на HSI и выставляем полную частоту
290 
291 /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */
292 #define PLL_M 8
293 #define PLL_N 168
294 
295 /* SYSCLK = PLL_VCO / PLL_P */
296 #define PLL_P 2
297 
298 /* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
299 #define PLL_Q 7
300 
301  /* Enable high performance mode, System frequency up to 168 MHz */
302  RCC->APB1ENR |= RCC_APB1ENR_PWREN;
303  PWR->CR |= PWR_CR_PMODE;
304 
305  /* HCLK = SYSCLK / 1*/
306  RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
307 
308  /* PCLK2 = HCLK / 2*/
309  RCC->CFGR |= RCC_CFGR_PPRE2_DIV2;
310 
311  /* PCLK1 = HCLK / 4*/
312  RCC->CFGR |= RCC_CFGR_PPRE1_DIV4;
313 
314  /* Configure the main PLL */
315  RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
316  (RCC_PLLCFGR_PLLSRC_HSI) | (PLL_Q << 24);
317 
318  /* Enable the main PLL */
319  RCC->CR |= RCC_CR_PLLON;
320 
321  /* Wait till the main PLL is ready */
322  while((RCC->CR & RCC_CR_PLLRDY) == 0) { } // TODO: do something on failure?
323 
324  /* Select the main PLL as system clock source */
325  RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
326  RCC->CFGR |= RCC_CFGR_SW_PLL;
327 
328  SystemCoreClock=168000000;
329  }
330 }
331 
uint32_t SystemCoreClock
#define OV_GUARD_FAIL_SIGNATURE
Definition: boards.h:309
int usb_configure(usb_attr_t *attr)
Definition: usb.c:350
uint16_t present_pin
Definition: usb.h:79
void SystemCoreClockUpdate(void)
Update SystemCoreClock variable according to Clock Register Values. The SystemCoreClock variable cont...
int usb_open(void)
Definition: usb.c:674
static INLINE void interrupts()
Definition: exti.h:106
void init(void)
Generic board initialization function.
Definition: boards.cpp:165
void emerg_delay(uint32_t n)
Definition: boards.cpp:257
void stopwatch_init(void)
Definition: stopwatch.c:12
#define RTC_OVERCLOCK_REG
Definition: boards.h:316
void setupTimers(void)
#define OVERCLOCK_SIG_MASK
Definition: boards.h:307
const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]
#define PLL_Q
void exti_init()
Definition: exti.c:46
Definition: usb.h:74
#define BOARD_USB_SENSE
Definition: board.h:75
void * _sccm
#define OV_GUARD_SIGNATURE
Definition: boards.h:308
void setupADC(void)
static void setupCCM(void)
Definition: boards.cpp:83
#define SYSTICK_RELOAD_VAL
Definition: board.h:21
void SetSysClock(uint8_t oc)
Configures the System clock source, PLL Multiplier and Divider factors, AHB/APBx prescalers and Flash...
void NMI_Handler()
Definition: boards.cpp:269
static usb_attr_t * usb_attr
Definition: usb.c:38
#define RTC_OV_GUARD_REG
Definition: boards.h:317
#define INLINE
Definition: hal_types.h:79
#define USB_INT_PRIORITY
Definition: Config.h:50
void pre_init()
Definition: boards.cpp:250
static void goDFU()
Definition: boards.h:137
uint8_t preempt_prio
Definition: usb.h:75
Board-specific pin information.
void boardInit(void)
Board-specific initialization code.
Definition: board.c:118
caddr_t _eccm
static void setupNVIC(void)
Generic board initialization routines.
Definition: boards.cpp:123
const gpio_dev * present_port
Definition: usb.h:78
uint8_t sub_prio
Definition: usb.h:76
uint32_t board_get_rtc_register(uint16_t reg)
Definition: boards.cpp:151
#define PLL_M
void board_set_rtc_register(uint32_t sig, uint16_t reg)
Definition: boards.cpp:141
#define DFU_RTC_SIGNATURE
Definition: boards.h:292
static void enableFPU(void)
Definition: boards.cpp:68
#define RTC_SIGNATURE_REG
Definition: boards.h:312
#define OVERCLOCK_SIGNATURE
Definition: boards.h:306
uint8_t gpio_bit
Definition: boards.h:92
void systemInit(uint8_t oc)
Setup the microcontroller system Initialize the Embedded Flash Interface, the PLL and update the Syst...
void usb_default_attr(usb_attr_t *attr)
Definition: usb.c:296
void usb_init(void)
Definition: boards.cpp:51
const gpio_dev *const gpio_device
Definition: boards.h:89
uint8_t use_present_pin
Definition: usb.h:77
void systick_init(uint32_t reload_val)
Initialize and enable SysTick.
Definition: systick.c:50