drv_system.c
Go to the documentation of this file.
1 /*
2  drv_sytem.c : system utilities (init, reset, delay, etc.) for STM32F103CB
3 
4  Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_system.c
5 
6  This file is part of BreezySTM32.
7 
8  BreezySTM32 is free software: you can redistribute it and/or modify
9  it under the terms of the GNU General Public License as published by
10  the Free Software Foundation, either version 3 of the License, or
11  (at your option) any later version.
12 
13  BreezySTM32 is distributed in the hope that it will be useful,
14  but WITHOUT ANY WARRANTY; without even the implied warranty of
15  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  GNU General Public License for more details.
17 
18  You should have received a copy of the GNU General Public License
19  along with BreezySTM32. If not, see <http://www.gnu.org/licenses/>.
20  */
21 
22 
23 #include <stdint.h>
24 #include <stdbool.h>
25 #include <stdlib.h>
26 
27 #include "stm32f10x_conf.h"
28 
29 #include "drv_gpio.h"
30 #include "drv_system.h"
31 
32 static volatile uint64_t sysTickUptime = 0;
33 
34 static void cycleCounterInit(void)
35 {
36  RCC_ClocksTypeDef clocks;
37  RCC_GetClocksFreq(&clocks);
38 }
39 
40 // SysTick
41 void SysTick_Handler(void)
42 {
43  sysTickUptime++;
44 }
45 
46 uint64_t micros(void)
47 {
48  return sysTickUptime * 20;
49 }
50 
51 uint32_t millis(void)
52 {
53  return (uint32_t)(sysTickUptime / 50);
54 }
55 
56 void systemInit(void)
57 {
58  struct {
59  GPIO_TypeDef *gpio;
60  gpio_config_t cfg;
61  } gpio_setup[3];
62 
63  gpio_setup[0].gpio = LED0_GPIO;
64  gpio_setup[0].cfg.pin = LED0_PIN;
65  gpio_setup[0].cfg.mode = Mode_Out_PP;
66  gpio_setup[0].cfg.speed = Speed_2MHz;
67 
68  gpio_setup[1].gpio = LED1_GPIO;
69  gpio_setup[1].cfg.pin = LED1_PIN;
70  gpio_setup[1].cfg.mode = Mode_Out_PP;
71  gpio_setup[1].cfg.speed = Speed_2MHz;
72 
73  gpio_setup[2].gpio = INV_GPIO;
74  gpio_setup[2].cfg.pin = INV_PIN;
75  gpio_setup[2].cfg.mode = Mode_Out_PP;
76  gpio_setup[2].cfg.speed = Speed_2MHz;
77 
78  gpio_config_t gpio;
79  int i, gpio_count = sizeof(gpio_setup) / sizeof(gpio_setup[0]);
80 
81  // Configure NVIC preempt/priority groups
82  // This means we have two bits for the preemption priority, two bits for sub-priority
84 
85  // Turn on clocks for stuff we use
89  RCC_ClearFlag();
90 
91  // Make all GPIO in by default to save power and reduce noise
92  gpio.pin = Pin_All;
93  gpio.mode = Mode_AIN;
94  gpioInit(GPIOA, &gpio);
95  gpioInit(GPIOB, &gpio);
96  gpioInit(GPIOC, &gpio);
97 
98  // Turn off JTAG port 'cause we're using the GPIO for leds
99 #define AFIO_MAPR_SWJ_CFG_NO_JTAG_SW (0x2 << 24)
101 
102  LED0_OFF;
103  LED1_OFF;
104 
105  for (i = 0; i < gpio_count; i++) {
106  gpioInit(gpio_setup[i].gpio, &gpio_setup[i].cfg);
107  }
108 
109  // Init cycle counter
111 
112  // SysTick
113  // Set to fire of at 50,000 Hz (which will give us 0.02 microsecond accuracy)
115 
116  // escalate the priority of the systick IRQn to highest
118 }
119 
120 void delayMicroseconds(uint32_t us)
121 {
122  uint64_t now = micros();
123  while(micros() < (now + us));
124 }
125 
126 void delay(uint32_t ms)
127 {
128  while (ms--)
129  delayMicroseconds(1000);
130 }
131 
133 {
134  LED1_OFF;
135  LED0_ON;
136  systemReset(false);
137 }
138 
139 uint32_t rccReadBkpDr(void)
140 {
141  return *((uint16_t *)BKP_BASE + 0x04) | *((uint16_t *)BKP_BASE + 0x08) << 16;
142 }
143 
144 void rccWriteBkpDr(uint32_t value)
145 {
147  PWR->CR |= PWR_CR_DBP;
148 
149  *((uint16_t *)BKP_BASE + 0x04) = value & 0xffff;
150  *((uint16_t *)BKP_BASE + 0x08) = (value & 0xffff0000) >> 16;
151 }
152 
153 #define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000)
154 
155 void systemReset(bool toBootloader)
156 {
157  if (toBootloader) {
158  // 1FFFF000 -> 20000200 -> SP
159  // 1FFFF004 -> 1FFFF021 -> PC
160  *((uint32_t *)0x20004FF0) = 0xDEADBEEF; // 20KB STM32F103
161  }
162 
163  // write magic value that we're doing a soft reset
165 
166  // Generate system reset
167  SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04;
168 }
void rccWriteBkpDr(uint32_t value)
Definition: drv_system.c:144
uint32_t millis(void)
Definition: drv_system.c:51
void NVIC_PriorityGroupConfig(uint32_t NVIC_PriorityGroup)
Configures the priority grouping: pre-emption priority and subpriority.
GPIO_Mode mode
Definition: drv_gpio.h:63
void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
Enables or disables the Low Speed APB (APB1) peripheral clock.
#define LED1_OFF
Definition: drv_system.h:52
#define GPIOA
Definition: stm32f4xx.h:2110
#define GPIOB
Definition: stm32f4xx.h:2111
static void cycleCounterInit(void)
Definition: drv_system.c:34
#define RCC_APB2Periph_GPIOB
#define LED0_PIN
Definition: drv_system.h:34
__STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority)
Set Interrupt Priority.
Definition: core_cm0.h:611
#define LED0_ON
Definition: drv_system.h:43
uint32_t SystemCoreClock
#define LED0_GPIO
Definition: drv_system.h:33
void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
Enables or disables the High Speed APB (APB2) peripheral clock.
#define GPIOC
Definition: stm32f4xx.h:2112
void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config)
Definition: drv_gpio.c:56
#define LED1_GPIO
Definition: revo_f4.h:126
#define SCB
Definition: core_cm0.h:503
uint16_t pin
Definition: drv_gpio.h:62
uint64_t micros(void)
Definition: drv_system.c:46
#define AFIO_MAPR_SWJ_CFG_NO_JTAG_SW
General Purpose I/O.
Definition: stm32f4xx.h:1281
#define RCC_AHBPeriph_DMA1
#define AIRCR_VECTKEY_MASK
Definition: drv_system.c:153
#define LED1_PIN
Definition: revo_f4.h:127
#define RCC_APB2Periph_AFIO
__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks)
System Tick Configuration.
Definition: core_cm0.h:685
#define RCC_APB2Periph_GPIOA
void failureMode()
Definition: drv_system.c:132
void delayMicroseconds(uint32_t us)
Definition: drv_system.c:120
static volatile uint64_t sysTickUptime
Definition: drv_system.c:32
#define INV_PIN
Definition: drv_system.h:37
#define RCC_APB1Periph_BKP
void SysTick_Handler(void)
Definition: drv_system.c:41
void RCC_ClearFlag(void)
Clears the RCC reset flags. The reset flags are: RCC_FLAG_PINRST, RCC_FLAG_PORRST, RCC_FLAG_SFTRST, RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST, RCC_FLAG_LPWRRST.
void systemInit(void)
Definition: drv_system.c:56
void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState)
Enables or disables the AHB peripheral clock.
#define BKP_SOFTRESET
Definition: drv_system.h:24
#define PWR
Definition: stm32f4xx.h:2074
uint32_t rccReadBkpDr(void)
Definition: drv_system.c:139
#define INV_GPIO
Definition: drv_system.h:38
#define RCC_APB2Periph_GPIOC
void RCC_GetClocksFreq(RCC_ClocksTypeDef *RCC_Clocks)
Returns the frequencies of different on chip clocks; SYSCLK, HCLK, PCLK1 and PCLK2.
#define PWR_CR_DBP
Definition: stm32f4xx.h:8373
void systemReset(bool toBootloader)
Definition: drv_system.c:155
void delay(uint32_t ms)
Definition: drv_system.c:126
#define LED0_OFF
Definition: drv_system.h:42
#define AFIO
Definition: stm32f10x.h:1406
#define BKP_BASE
Definition: stm32f10x.h:1308


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:46