Use Naze hardware revision when initialising beeper. Cleanup inverted

beeper configuration.
This commit is contained in:
Dominic Clifton 2014-10-16 00:44:56 +01:00
parent 2ed09b0b2f
commit 50391f2c8e
8 changed files with 70 additions and 3808 deletions

File diff suppressed because it is too large Load Diff

View File

@ -61,21 +61,11 @@ void systemBeep(bool onoff)
#endif
}
static inline bool isBeeperOutputInverted(void)
{
#ifdef BEEPER_INVERTED
return true;
#else
// Naze rev5 needs inverted beeper.
return hse_value == 12000000;
#endif
}
void beeperInit(void)
void beeperInit(beeperConfig_t *config)
{
#ifdef BEEPER
initBeeperHardware();
if (isBeeperOutputInverted())
initBeeperHardware(config);
if (config->isInverted)
systemBeepPtr = beepInverted;
else
systemBeepPtr = beepNormal;

View File

@ -17,17 +17,25 @@
#pragma once
#ifdef BEEP_GPIO
#define BEEP_TOGGLE digitalToggle(BEEP_GPIO, BEEP_PIN);
#define BEEP_OFF systemBeep(false);
#define BEEP_ON systemBeep(true);
#ifdef BEEPER
#define BEEP_TOGGLE digitalToggle(BEEP_GPIO, BEEP_PIN)
#define BEEP_OFF systemBeep(false)
#define BEEP_ON systemBeep(true)
#else
#define BEEP_TOGGLE ;
#define BEEP_OFF ;
#define BEEP_ON ;
#define BEEP_TOGGLE
#define BEEP_OFF
#define BEEP_ON
#endif
void systemBeep(bool onoff);
void beeperInit(void);
typedef struct beeperConfig_s {
uint32_t gpioPeripheral;
uint16_t gpioPin;
GPIO_TypeDef *gpioPort;
GPIO_Mode gpioMode;
bool isInverted;
} beeperConfig_t;
void initBeeperHardware(void);
void systemBeep(bool onoff);
void beeperInit(beeperConfig_t *beeperConfig);
void initBeeperHardware(beeperConfig_t *config);

View File

@ -26,27 +26,17 @@
#include "sound_beeper.h"
void initBeeperHardware(void)
void initBeeperHardware(beeperConfig_t *config)
{
#ifdef BEEPER
struct {
GPIO_TypeDef *gpio;
gpio_config_t cfg;
} gpio_setup = {
.gpio = BEEP_GPIO,
.cfg = { BEEP_PIN, Mode_Out_OD, Speed_2MHz }
gpio_config_t gpioConfig = {
config->gpioPin,
config->gpioMode,
Speed_2MHz
};
RCC_APB2PeriphClockCmd(BEEP_PERIPHERAL, ENABLE);
#ifdef NAZE
// Hack - naze rev4 and below used opendrain to PNP for buzzer. Rev5 and above use PP to NPN.
if (hse_value == 12000000 && gpio_setup.cfg.mode == Mode_Out_OD)
gpio_setup.cfg.mode = Mode_Out_PP;
#endif
gpioInit(gpio_setup.gpio, &gpio_setup.cfg);
RCC_APB2PeriphClockCmd(config->gpioPeripheral, ENABLE);
gpioInit(config->gpioPort, &gpioConfig);
#endif
}

View File

@ -25,20 +25,17 @@
#include "sound_beeper.h"
void initBeeperHardware(void)
void initBeeperHardware(beeperConfig_t *config)
{
#ifdef BEEPER
struct {
GPIO_TypeDef *gpio;
gpio_config_t cfg;
} gpio_setup = {
.gpio = BEEP_GPIO,
.cfg = { BEEP_PIN, Mode_Out_OD, Speed_2MHz }
gpio_config_t gpioConfig = {
config->gpioPin,
config->gpioMode,
Speed_2MHz
};
RCC_AHBPeriphClockCmd(BEEP_PERIPHERAL, ENABLE);
gpioInit(gpio_setup.gpio, &gpio_setup.cfg);
RCC_AHBPeriphClockCmd(config->gpioPeripheral, ENABLE);
gpioInit(config->gpioPort, &gpioConfig);
#endif
}

View File

@ -26,7 +26,6 @@
#include "gpio.h"
#include "light_led.h"
#include "sound_beeper.h"
#include "inverter.h"
#include "system.h"
@ -93,20 +92,11 @@ void systemInit(void)
AFIO->MAPR |= AFIO_MAPR_SWJ_CFG_NO_JTAG_SW;
#endif
ledInit();
beeperInit();
#ifdef INVERTER
initInverter();
#endif
// Init cycle counter
cycleCounterInit();
// SysTick
SysTick_Config(SystemCoreClock / 1000);
// sleep for 100ms
delay(100);
}
#if 1
@ -158,7 +148,7 @@ void failureMode(uint8_t mode)
LED1_TOGGLE;
LED0_TOGGLE;
delay(475 * mode - 2);
BEEP_ON
BEEP_ON;
delay(25);
BEEP_OFF;
}

View File

@ -19,6 +19,8 @@
#include "stdint.h"
#include "platform.h"
#include "drivers/gpio.h"
#include "drivers/sound_beeper.h"
#include "drivers/system.h"
#include "flight/failsafe.h"

View File

@ -39,6 +39,10 @@
#include "drivers/adc.h"
#include "drivers/bus_i2c.h"
#include "drivers/bus_spi.h"
#include "drivers/gpio.h"
#include "drivers/light_led.h"
#include "drivers/sound_beeper.h"
#include "drivers/inverter.h"
#include "flight/flight.h"
#include "flight/mixer.h"
@ -169,6 +173,34 @@ void init(void)
systemInit();
delay(100);
ledInit();
#ifdef BEEPER
beeperConfig_t beeperConfig = {
.gpioMode = Mode_Out_OD,
.gpioPin = BEEP_PIN,
.gpioPort = BEEP_GPIO,
.gpioPeripheral = BEEP_PERIPHERAL,
.isInverted = false
};
#ifdef NAZE
if (hardwareRevision >= NAZE32_REV5) {
// naze rev4 and below used opendrain to PNP for buzzer. Rev5 and above use PP to NPN.
beeperConfig.gpioMode = Mode_Out_PP;
beeperConfig.isInverted = true;
}
#endif
beeperInit(&beeperConfig);
#endif
#ifdef INVERTER
initInverter();
#endif
#ifdef USE_SPI
spiInit(SPI1);
spiInit(SPI2);