Extract led and buzzer hardware initialisation from system.c.

This commit is contained in:
Dominic Clifton 2014-06-02 19:55:52 +01:00
parent d407a4d15e
commit 8f2da892a6
15 changed files with 219 additions and 35 deletions

View File

@ -181,6 +181,7 @@ NAZE_SRC = startup_stm32f10x_md_gcc.S \
drivers/bus_i2c_stm32f10x.c \
drivers/compass_hmc5883l.c \
drivers/gpio_stm32f10x.c \
drivers/light_led_stm32f10x.c \
drivers/light_ledring.c \
drivers/sonar_hcsr04.c \
drivers/pwm_mapping.c \
@ -189,6 +190,7 @@ NAZE_SRC = startup_stm32f10x_md_gcc.S \
drivers/serial_softserial.c \
drivers/serial_uart.c \
drivers/serial_uart_stm32f10x.c \
drivers/sound_beeper_stm32f10x.c \
drivers/system_stm32f10x.c \
drivers/timer.c \
$(COMMON_SRC)
@ -200,6 +202,7 @@ OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \
drivers/bus_i2c_stm32f10x.c \
drivers/bus_spi.c \
drivers/gpio_stm32f10x.c \
drivers/light_led_stm32f10x.c \
drivers/pwm_mapping.c \
drivers/pwm_output.c \
drivers/pwm_rssi.c \
@ -207,6 +210,7 @@ OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \
drivers/serial_softserial.c \
drivers/serial_uart.c \
drivers/serial_uart_stm32f10x.c \
drivers/sound_beeper_stm32f10x.c \
drivers/system_stm32f10x.c \
drivers/timer.c \
$(COMMON_SRC)
@ -217,6 +221,7 @@ STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S \
drivers/bus_i2c_stm32f30x.c \
drivers/bus_spi.c \
drivers/gpio_stm32f30x.c \
drivers/light_led_stm32f30x.c \
drivers/pwm_mapping.c \
drivers/pwm_output.c \
drivers/pwm_rssi.c \
@ -225,6 +230,7 @@ STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S \
drivers/serial_uart_stm32f30x.c \
drivers/serial_softserial.c \
drivers/serial_usb_vcp.c \
drivers/sound_beeper_stm32f30x.c \
drivers/system_stm32f30x.c \
drivers/timer.c \
vcp/hw_config.c \

View File

@ -0,0 +1,26 @@
initLeds(void)
{
struct {
GPIO_TypeDef *gpio;
gpio_config_t cfg;
} gpio_setup[] = {
#ifdef LED0
{
.gpio = LED0_GPIO,
.cfg = { LED0_PIN, Mode_Out_PP, Speed_2MHz }
},
#endif
#ifdef LED1
{
.gpio = LED1_GPIO,
.cfg = { LED1_PIN, Mode_Out_PP, Speed_2MHz }
},
#endif
}
uint8_t gpio_count = sizeof(gpio_setup) / sizeof(gpio_setup[0]);
}

View File

@ -30,3 +30,5 @@
#define LED1_OFF
#define LED1_ON
#endif
void ledInit(void);

View File

@ -0,0 +1,53 @@
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#include "system.h"
#include "gpio.h"
#include "light_led.h"
void ledInit(void)
{
uint32_t i;
struct {
GPIO_TypeDef *gpio;
gpio_config_t cfg;
} gpio_setup[] = {
#ifdef LED0
{
.gpio = LED0_GPIO,
.cfg = { LED0_PIN, Mode_Out_PP, Speed_2MHz }
},
#endif
#ifdef LED1
{
.gpio = LED1_GPIO,
.cfg = { LED1_PIN, Mode_Out_PP, Speed_2MHz }
}
#endif
};
uint8_t gpio_count = sizeof(gpio_setup) / sizeof(gpio_setup[0]);
#ifdef LED0
RCC_APB2PeriphClockCmd(LED0_PERIPHERAL, ENABLE);
#endif
#ifdef LED1
RCC_APB2PeriphClockCmd(LED1_PERIPHERAL, ENABLE);
#endif
LED0_OFF;
LED1_OFF;
for (i = 0; i < gpio_count; i++) {
if (hse_value == 12000000 && gpio_setup[i].cfg.mode == Mode_Out_OD)
gpio_setup[i].cfg.mode = Mode_Out_PP;
gpioInit(gpio_setup[i].gpio, &gpio_setup[i].cfg);
}
}

View File

@ -0,0 +1,49 @@
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#include "gpio.h"
#include "light_led.h"
void ledInit(void)
{
uint32_t i;
struct {
GPIO_TypeDef *gpio;
gpio_config_t cfg;
} gpio_setup[] = {
#ifdef LED0
{
.gpio = LED0_GPIO,
.cfg = { LED0_PIN, Mode_Out_PP, Speed_2MHz }
},
#endif
#ifdef LED1
{
.gpio = LED1_GPIO,
.cfg = { LED1_PIN, Mode_Out_PP, Speed_2MHz }
}
#endif
};
uint8_t gpio_count = sizeof(gpio_setup) / sizeof(gpio_setup[0]);
#ifdef LED0
RCC_AHBPeriphClockCmd(LED0_PERIPHERAL, ENABLE);
#endif
#ifdef LED1
RCC_AHBPeriphClockCmd(LED1_PERIPHERAL, ENABLE);
#endif
LED0_OFF;
LED1_OFF;
for (i = 0; i < gpio_count; i++) {
gpioInit(gpio_setup[i].gpio, &gpio_setup[i].cfg);
}
}

View File

@ -54,7 +54,7 @@ static inline bool isBuzzerOutputInverted(void)
void beeperInit(void)
{
#ifdef BUZZER
// Configure gpio
initBeeperHardware();
if (isBuzzerOutputInverted())
systemBeepPtr = beepInverted;
else

View File

@ -12,3 +12,5 @@
void systemBeep(bool onoff);
void beeperInit(void);
void initBeeperHardware(void);

View File

@ -0,0 +1,30 @@
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#include "system.h"
#include "gpio.h"
#include "sound_beeper.h"
void initBeeperHardware(void)
{
#ifdef BUZZER
struct {
GPIO_TypeDef *gpio;
gpio_config_t cfg;
} gpio_setup = {
.gpio = BEEP_GPIO,
.cfg = { BEEP_PIN, Mode_Out_OD, Speed_2MHz }
};
RCC_APB2PeriphClockCmd(BEEP_PERIPHERAL, ENABLE);
if (hse_value == 12000000 && gpio_setup.cfg.mode == Mode_Out_OD)
gpio_setup.cfg.mode = Mode_Out_PP;
gpioInit(gpio_setup.gpio, &gpio_setup.cfg);
#endif
}

View File

@ -0,0 +1,27 @@
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#include "gpio.h"
#include "sound_beeper.h"
void initBeeperHardware(void)
{
#ifdef BUZZER
struct {
GPIO_TypeDef *gpio;
gpio_config_t cfg;
} gpio_setup = {
.gpio = BEEP_GPIO,
.cfg = { BEEP_PIN, Mode_Out_OD, Speed_2MHz }
};
RCC_AHBPeriphClockCmd(BEEP_PERIPHERAL, ENABLE);
gpioInit(gpio_setup.gpio, &gpio_setup.cfg);
#endif
}

View File

@ -65,33 +65,7 @@ void systemInit(bool overclock)
SCB->CPACR = (0x3 << (10*2)) | (0x3 << (11*2));
#endif
struct {
GPIO_TypeDef *gpio;
gpio_config_t cfg;
} gpio_setup[] = {
#ifdef LED0
{
.gpio = LED0_GPIO,
.cfg = { LED0_PIN, Mode_Out_PP, Speed_2MHz }
},
#endif
#ifdef LED1
{
.gpio = LED1_GPIO,
.cfg = { LED1_PIN, Mode_Out_PP, Speed_2MHz }
},
#endif
#ifdef BUZZER
{
.gpio = BEEP_GPIO,
.cfg = { BEEP_PIN, Mode_Out_OD, Speed_2MHz }
},
#endif
};
gpio_config_t gpio;
uint32_t i;
uint8_t gpio_count = sizeof(gpio_setup) / sizeof(gpio_setup[0]);
#ifdef STM32F303xC
SetSysClock();
@ -209,15 +183,8 @@ void systemInit(bool overclock)
GPIO_PinAFConfig(GPIOB, GPIO_PinSource9, GPIO_AF_2);
#endif
ledInit();
beeperInit();
LED0_OFF;
LED1_OFF;
for (i = 0; i < gpio_count; i++) {
if (hse_value == 12000000 && gpio_setup[i].cfg.mode == Mode_Out_OD)
gpio_setup[i].cfg.mode = Mode_Out_PP;
gpioInit(gpio_setup[i].gpio, &gpio_setup[i].cfg);
}
// Init cycle counter
cycleCounterInit();

View File

@ -1,13 +1,18 @@
#define LED0_GPIO GPIOE
#define LED0_PIN Pin_8|Pin_12 // Blue LEDs - PE8/PE12
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOE
#define LED0_INVERTED
#define LED1_GPIO GPIOE
#define LED1_PIN Pin_10|Pin_14 // Orange LEDs - PE10/PE14
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOE
#define LED1_INVERTED
#define BEEP_GPIO GPIOE
#define BEEP_PIN Pin_9|Pin_13 // Red LEDs - PE9/PE13
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOE
#define BUZZER_INVERTED
#define BARO_GPIO GPIOC
#define BARO_PIN Pin_13

View File

@ -2,10 +2,16 @@
#define LED0_GPIO GPIOB
#define LED0_PIN Pin_3 // PB3 (LED)
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOA
#define LED1_GPIO GPIOB
#define LED1_PIN Pin_4 // PB4 (LED)
#define LED1_PERIPHERAL RCC_APB2Periph_GPIOB
#define BEEP_GPIO GPIOA
#define BEEP_PIN Pin_12 // PA12 (Buzzer)
#define BEEP_PERIPHERAL RCC_APB2Periph_GPIOA
#define BARO_GPIO GPIOC
#define BARO_PIN Pin_13

View File

@ -1,7 +1,9 @@
#define LED0_GPIO GPIOB
#define LED0_PIN Pin_12
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
#define BEEP_GPIO GPIOB
#define BEEP_PIN Pin_10
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOB
#define BUZZER
#define LED0

View File

@ -6,6 +6,7 @@
#ifdef OLIMEXINO_UNCUT_LED1_E_JUMPER
#define LED0_GPIO GPIOA
#define LED0_PIN Pin_5 // D13, PA5/SPI1_SCK/ADC5 - "LED1" on silkscreen, Green
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOA
#define LED0
#endif
@ -13,6 +14,7 @@
// "LED2" is using one of the PWM pins (CH2/PWM2), so we must not use PWM2 unless the jumper is cut. @See pwmInit()
#define LED1_GPIO GPIOA
#define LED1_PIN Pin_1 // D3, PA1/USART2_RTS/ADC1/TIM2_CH3 - "LED2" on silkscreen, Yellow
#define LED1_PERIPHERAL RCC_APB2Periph_GPIOA
#define LED1
#endif

View File

@ -1,12 +1,19 @@
#define LED0_GPIO GPIOE
#define LED0_PIN Pin_8|Pin_12 // Blue LEDs - PE8/PE12
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOE
#define LED0_INVERTED
#define LED1_GPIO GPIOE
#define LED1_PIN Pin_10|Pin_14 // Orange LEDs - PE10/PE14
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOE
#define LED1_INVERTED
#define BEEP_GPIO GPIOE
#define BEEP_PIN Pin_9|Pin_13 // Red LEDs - PE9/PE13
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOE
#define BUZZER_INVERTED
#define BUZZER_INVERTED
#define BARO_GPIO GPIOC
#define BARO_PIN Pin_13