mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 21:35:44 +03:00
Cleanup mismatch of buzzer/beeper terminology. Beep and Beeper should
be used from now on.
This commit is contained in:
parent
bcc7f10e26
commit
9afcb20b7e
17 changed files with 50 additions and 50 deletions
2
Makefile
2
Makefile
|
@ -136,7 +136,7 @@ COMMON_SRC = build_config.c \
|
||||||
drivers/serial.c \
|
drivers/serial.c \
|
||||||
drivers/sound_beeper.c \
|
drivers/sound_beeper.c \
|
||||||
drivers/system.c \
|
drivers/system.c \
|
||||||
io/buzzer.c \
|
io/beeper.c \
|
||||||
io/gps.c \
|
io/gps.c \
|
||||||
io/gps_conversion.c \
|
io/gps_conversion.c \
|
||||||
io/ledstrip.c \
|
io/ledstrip.c \
|
||||||
|
|
|
@ -459,9 +459,9 @@
|
||||||
<FilePath>.\src\spektrum.c</FilePath>
|
<FilePath>.\src\spektrum.c</FilePath>
|
||||||
</File>
|
</File>
|
||||||
<File>
|
<File>
|
||||||
<FileName>buzzer.c</FileName>
|
<FileName>beeper.c</FileName>
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<FilePath>.\src\buzzer.c</FilePath>
|
<FilePath>.\src\beeper.c</FilePath>
|
||||||
</File>
|
</File>
|
||||||
<File>
|
<File>
|
||||||
<FileName>utils.c</FileName>
|
<FileName>utils.c</FileName>
|
||||||
|
@ -1202,9 +1202,9 @@
|
||||||
<FilePath>.\src\spektrum.c</FilePath>
|
<FilePath>.\src\spektrum.c</FilePath>
|
||||||
</File>
|
</File>
|
||||||
<File>
|
<File>
|
||||||
<FileName>buzzer.c</FileName>
|
<FileName>beeper.c</FileName>
|
||||||
<FileType>1</FileType>
|
<FileType>1</FileType>
|
||||||
<FilePath>.\src\buzzer.c</FilePath>
|
<FilePath>.\src\beeper.c</FilePath>
|
||||||
</File>
|
</File>
|
||||||
<File>
|
<File>
|
||||||
<FileName>utils.c</FileName>
|
<FileName>utils.c</FileName>
|
||||||
|
|
|
@ -19,7 +19,7 @@ Launch the multirotor.
|
||||||
|
|
||||||
Turn on/hold the autotune switch on your transmitter.
|
Turn on/hold the autotune switch on your transmitter.
|
||||||
|
|
||||||
Observe roll left/right. A beep code will sound on the buzzer.
|
Observe roll left/right. A beep code will sound on the beeper.
|
||||||
|
|
||||||
Turn off/release the switch while still flying to stop this phase of tuning.
|
Turn off/release the switch while still flying to stop this phase of tuning.
|
||||||
|
|
||||||
|
@ -27,7 +27,7 @@ PID settings will have been updated for ROLL/YAW.
|
||||||
|
|
||||||
Turn on/hold the switch again.
|
Turn on/hold the switch again.
|
||||||
|
|
||||||
Observe pitch forwards/backwards. A beep code will sound on the buzzer.
|
Observe pitch forwards/backwards. A beep code will sound on the beeper.
|
||||||
|
|
||||||
Turn off/release the switch while still flying to stop this phase of tuning.
|
Turn off/release the switch while still flying to stop this phase of tuning.
|
||||||
|
|
||||||
|
|
|
@ -42,7 +42,7 @@ C:\Users\nico\Documents\GitHub\cleanflight>make
|
||||||
%% build_config.c
|
%% build_config.c
|
||||||
%% battery.c
|
%% battery.c
|
||||||
%% boardalignment.c
|
%% boardalignment.c
|
||||||
%% buzzer.c
|
%% beeper.c
|
||||||
%% config.c
|
%% config.c
|
||||||
%% maths.c
|
%% maths.c
|
||||||
%% printf.c
|
%% printf.c
|
||||||
|
@ -117,7 +117,7 @@ rs/pwm_mapping.o obj/NAZE/drivers/pwm_output.o obj/NAZE/drivers/pwm_rssi.o obj/N
|
||||||
AZE/drivers/pwm_rx.o obj/NAZE/drivers/serial_softserial.o obj/NAZE/drivers/seria
|
AZE/drivers/pwm_rx.o obj/NAZE/drivers/serial_softserial.o obj/NAZE/drivers/seria
|
||||||
l_uart_common.o obj/NAZE/drivers/serial_uart_stm32f10x.o obj/NAZE/drivers/timer_
|
l_uart_common.o obj/NAZE/drivers/serial_uart_stm32f10x.o obj/NAZE/drivers/timer_
|
||||||
common.o obj/NAZE/build_config.o obj/NAZE/battery.o obj/NAZE/boardalignment.o ob
|
common.o obj/NAZE/build_config.o obj/NAZE/battery.o obj/NAZE/boardalignment.o ob
|
||||||
j/NAZE/buzzer.o obj/NAZE/config.o obj/NAZE/common/maths.o obj/NAZE/common/printf
|
j/NAZE/beeper.o obj/NAZE/config.o obj/NAZE/common/maths.o obj/NAZE/common/printf
|
||||||
.o obj/NAZE/common/typeconversion.o obj/NAZE/failsafe.o obj/NAZE/main.o obj/NAZE
|
.o obj/NAZE/common/typeconversion.o obj/NAZE/failsafe.o obj/NAZE/main.o obj/NAZE
|
||||||
/mw.o obj/NAZE/sensors_acceleration.o obj/NAZE/sensors_barometer.o obj/NAZE/sens
|
/mw.o obj/NAZE/sensors_acceleration.o obj/NAZE/sensors_barometer.o obj/NAZE/sens
|
||||||
ors_compass.o obj/NAZE/sensors_gyro.o obj/NAZE/sensors_initialisation.o obj/NAZE
|
ors_compass.o obj/NAZE/sensors_gyro.o obj/NAZE/sensors_initialisation.o obj/NAZE
|
||||||
|
|
|
@ -27,7 +27,7 @@
|
||||||
#include "sound_beeper.h"
|
#include "sound_beeper.h"
|
||||||
|
|
||||||
|
|
||||||
#ifdef BUZZER
|
#ifdef BEEPER
|
||||||
|
|
||||||
void (*systemBeepPtr)(bool onoff) = NULL;
|
void (*systemBeepPtr)(bool onoff) = NULL;
|
||||||
|
|
||||||
|
@ -52,14 +52,14 @@ static void beepInverted(bool onoff)
|
||||||
|
|
||||||
void systemBeep(bool onoff)
|
void systemBeep(bool onoff)
|
||||||
{
|
{
|
||||||
#ifdef BUZZER
|
#ifdef BEEPER
|
||||||
systemBeepPtr(onoff);
|
systemBeepPtr(onoff);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
static inline bool isBuzzerOutputInverted(void)
|
static inline bool isBeeperOutputInverted(void)
|
||||||
{
|
{
|
||||||
#ifdef BUZZER_INVERTED
|
#ifdef BEEPER_INVERTED
|
||||||
return true;
|
return true;
|
||||||
#else
|
#else
|
||||||
// Naze rev5 needs inverted beeper.
|
// Naze rev5 needs inverted beeper.
|
||||||
|
@ -69,9 +69,9 @@ static inline bool isBuzzerOutputInverted(void)
|
||||||
|
|
||||||
void beeperInit(void)
|
void beeperInit(void)
|
||||||
{
|
{
|
||||||
#ifdef BUZZER
|
#ifdef BEEPER
|
||||||
initBeeperHardware();
|
initBeeperHardware();
|
||||||
if (isBuzzerOutputInverted())
|
if (isBeeperOutputInverted())
|
||||||
systemBeepPtr = beepInverted;
|
systemBeepPtr = beepInverted;
|
||||||
else
|
else
|
||||||
systemBeepPtr = beepNormal;
|
systemBeepPtr = beepNormal;
|
||||||
|
|
|
@ -28,7 +28,7 @@
|
||||||
|
|
||||||
void initBeeperHardware(void)
|
void initBeeperHardware(void)
|
||||||
{
|
{
|
||||||
#ifdef BUZZER
|
#ifdef BEEPER
|
||||||
struct {
|
struct {
|
||||||
GPIO_TypeDef *gpio;
|
GPIO_TypeDef *gpio;
|
||||||
gpio_config_t cfg;
|
gpio_config_t cfg;
|
||||||
|
|
|
@ -27,7 +27,7 @@
|
||||||
|
|
||||||
void initBeeperHardware(void)
|
void initBeeperHardware(void)
|
||||||
{
|
{
|
||||||
#ifdef BUZZER
|
#ifdef BEEPER
|
||||||
struct {
|
struct {
|
||||||
GPIO_TypeDef *gpio;
|
GPIO_TypeDef *gpio;
|
||||||
gpio_config_t cfg;
|
gpio_config_t cfg;
|
||||||
|
|
|
@ -26,7 +26,7 @@
|
||||||
#include "config/runtime_config.h"
|
#include "config/runtime_config.h"
|
||||||
#include "config/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "io/buzzer.h"
|
#include "io/beeper.h"
|
||||||
|
|
||||||
#define DOUBLE_PAUSE_DURATION_MILLIS (LONG_PAUSE_DURATION_MILLIS * 2)
|
#define DOUBLE_PAUSE_DURATION_MILLIS (LONG_PAUSE_DURATION_MILLIS * 2)
|
||||||
#define LONG_PAUSE_DURATION_MILLIS 200
|
#define LONG_PAUSE_DURATION_MILLIS 200
|
||||||
|
@ -35,8 +35,8 @@
|
||||||
|
|
||||||
#define SHORT_CONFIRMATION_BEEP_DURATION_MILLIS (SHORT_PAUSE_DURATION_MILLIS / 2)
|
#define SHORT_CONFIRMATION_BEEP_DURATION_MILLIS (SHORT_PAUSE_DURATION_MILLIS / 2)
|
||||||
|
|
||||||
static uint8_t buzzerIsOn = 0, beepDone = 0;
|
static uint8_t beeperIsOn = 0, beepDone = 0;
|
||||||
static uint32_t buzzerLastToggleTime;
|
static uint32_t beeperLastToggleTime;
|
||||||
static void beep(uint16_t pulseMillis);
|
static void beep(uint16_t pulseMillis);
|
||||||
static void beep_code(char first, char second, char third, char pause);
|
static void beep_code(char first, char second, char third, char pause);
|
||||||
|
|
||||||
|
@ -46,20 +46,20 @@ typedef enum {
|
||||||
FAILSAFE_IDLE = 0,
|
FAILSAFE_IDLE = 0,
|
||||||
FAILSAFE_LANDING,
|
FAILSAFE_LANDING,
|
||||||
FAILSAFE_FIND_ME
|
FAILSAFE_FIND_ME
|
||||||
} failsafeBuzzerWarnings_e;
|
} failsafeBeeperWarnings_e;
|
||||||
|
|
||||||
static failsafe_t* failsafe;
|
static failsafe_t* failsafe;
|
||||||
|
|
||||||
void buzzerInit(failsafe_t *initialFailsafe)
|
void beepcodeInit(failsafe_t *initialFailsafe)
|
||||||
{
|
{
|
||||||
failsafe = initialFailsafe;
|
failsafe = initialFailsafe;
|
||||||
}
|
}
|
||||||
|
|
||||||
void buzzer(bool warn_vbat)
|
void beepcodeUpdateState(bool warn_vbat)
|
||||||
{
|
{
|
||||||
static uint8_t beeperOnBox;
|
static uint8_t beeperOnBox;
|
||||||
static uint8_t warn_noGPSfix = 0;
|
static uint8_t warn_noGPSfix = 0;
|
||||||
static failsafeBuzzerWarnings_e warn_failsafe = FAILSAFE_IDLE;
|
static failsafeBeeperWarnings_e warn_failsafe = FAILSAFE_IDLE;
|
||||||
|
|
||||||
//===================== BeeperOn via rcOptions =====================
|
//===================== BeeperOn via rcOptions =====================
|
||||||
if (rcOptions[BOXBEEPERON]) { // unconditional beeper on via AUXn switch
|
if (rcOptions[BOXBEEPERON]) { // unconditional beeper on via AUXn switch
|
||||||
|
@ -113,7 +113,7 @@ void buzzer(bool warn_vbat)
|
||||||
else if (toggleBeep > 0)
|
else if (toggleBeep > 0)
|
||||||
beep(50); // fast confirmation beep
|
beep(50); // fast confirmation beep
|
||||||
else {
|
else {
|
||||||
buzzerIsOn = 0;
|
beeperIsOn = 0;
|
||||||
BEEP_OFF;
|
BEEP_OFF;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -154,7 +154,7 @@ void beep_code(char first, char second, char third, char pause)
|
||||||
|
|
||||||
if (icnt < 3 && Duration != 0)
|
if (icnt < 3 && Duration != 0)
|
||||||
beep(Duration);
|
beep(Duration);
|
||||||
if (icnt >= 3 && (buzzerLastToggleTime < millis() - Duration)) {
|
if (icnt >= 3 && (beeperLastToggleTime < millis() - Duration)) {
|
||||||
icnt = 0;
|
icnt = 0;
|
||||||
toggleBeep = 0;
|
toggleBeep = 0;
|
||||||
}
|
}
|
||||||
|
@ -162,18 +162,18 @@ void beep_code(char first, char second, char third, char pause)
|
||||||
if (icnt < 3)
|
if (icnt < 3)
|
||||||
icnt++;
|
icnt++;
|
||||||
beepDone = 0;
|
beepDone = 0;
|
||||||
buzzerIsOn = 0;
|
beeperIsOn = 0;
|
||||||
BEEP_OFF;
|
BEEP_OFF;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static void beep(uint16_t pulseMillis)
|
static void beep(uint16_t pulseMillis)
|
||||||
{
|
{
|
||||||
if (buzzerIsOn) {
|
if (beeperIsOn) {
|
||||||
if (millis() >= buzzerLastToggleTime + pulseMillis) {
|
if (millis() >= beeperLastToggleTime + pulseMillis) {
|
||||||
buzzerIsOn = 0;
|
beeperIsOn = 0;
|
||||||
BEEP_OFF;
|
BEEP_OFF;
|
||||||
buzzerLastToggleTime = millis();
|
beeperLastToggleTime = millis();
|
||||||
if (toggleBeep >0)
|
if (toggleBeep >0)
|
||||||
toggleBeep--;
|
toggleBeep--;
|
||||||
beepDone = 1;
|
beepDone = 1;
|
||||||
|
@ -181,9 +181,9 @@ static void beep(uint16_t pulseMillis)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (millis() >= (buzzerLastToggleTime + LONG_PAUSE_DURATION_MILLIS)) { // Buzzer is off and long pause time is up -> turn it on
|
if (millis() >= (beeperLastToggleTime + LONG_PAUSE_DURATION_MILLIS)) { // Beeper is off and long pause time is up -> turn it on
|
||||||
buzzerIsOn = 1;
|
beeperIsOn = 1;
|
||||||
BEEP_ON;
|
BEEP_ON;
|
||||||
buzzerLastToggleTime = millis(); // save the time the buzer turned on
|
beeperLastToggleTime = millis(); // save the time the buzer turned on
|
||||||
}
|
}
|
||||||
}
|
}
|
|
@ -17,5 +17,5 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
void buzzer(bool warn_vbat);
|
void beepcodeUpdateState(bool warn_vbat);
|
||||||
void queueConfirmationBeep(uint8_t duration);
|
void queueConfirmationBeep(uint8_t duration);
|
|
@ -81,7 +81,7 @@ failsafe_t* failsafeInit(rxConfig_t *intialRxConfig);
|
||||||
pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init);
|
pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init);
|
||||||
void mixerInit(MultiType mixerConfiguration, motorMixer_t *customMixers, pwmOutputConfiguration_t *pwmOutputConfiguration);
|
void mixerInit(MultiType mixerConfiguration, motorMixer_t *customMixers, pwmOutputConfiguration_t *pwmOutputConfiguration);
|
||||||
void rxInit(rxConfig_t *rxConfig, failsafe_t *failsafe);
|
void rxInit(rxConfig_t *rxConfig, failsafe_t *failsafe);
|
||||||
void buzzerInit(failsafe_t *initialFailsafe);
|
void beepcodeInit(failsafe_t *initialFailsafe);
|
||||||
void gpsInit(serialConfig_t *serialConfig, gpsConfig_t *initialGpsConfig, gpsProfile_t *initialGpsProfile, pidProfile_t *pidProfile);
|
void gpsInit(serialConfig_t *serialConfig, gpsConfig_t *initialGpsConfig, gpsProfile_t *initialGpsProfile, pidProfile_t *pidProfile);
|
||||||
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, int16_t magDeclinationFromConfig);
|
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, int16_t magDeclinationFromConfig);
|
||||||
void imuInit(void);
|
void imuInit(void);
|
||||||
|
@ -199,7 +199,7 @@ void init(void)
|
||||||
mixerInit(masterConfig.mixerConfiguration, masterConfig.customMixer, pwmOutputConfiguration);
|
mixerInit(masterConfig.mixerConfiguration, masterConfig.customMixer, pwmOutputConfiguration);
|
||||||
|
|
||||||
failsafe = failsafeInit(&masterConfig.rxConfig);
|
failsafe = failsafeInit(&masterConfig.rxConfig);
|
||||||
buzzerInit(failsafe);
|
beepcodeInit(failsafe);
|
||||||
rxInit(&masterConfig.rxConfig, failsafe);
|
rxInit(&masterConfig.rxConfig, failsafe);
|
||||||
|
|
||||||
if (feature(FEATURE_GPS)) {
|
if (feature(FEATURE_GPS)) {
|
||||||
|
|
|
@ -42,7 +42,7 @@
|
||||||
#include "sensors/barometer.h"
|
#include "sensors/barometer.h"
|
||||||
#include "sensors/gyro.h"
|
#include "sensors/gyro.h"
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
#include "io/buzzer.h"
|
#include "io/beeper.h"
|
||||||
#include "io/escservo.h"
|
#include "io/escservo.h"
|
||||||
#include "flight/failsafe.h"
|
#include "flight/failsafe.h"
|
||||||
#include "flight/imu.h"
|
#include "flight/imu.h"
|
||||||
|
@ -232,7 +232,7 @@ void annexCode(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
buzzer(batteryWarningEnabled); // external buzzer routine that handles buzzer events globally now
|
beepcodeUpdateState(batteryWarningEnabled);
|
||||||
|
|
||||||
if (f.ARMED) {
|
if (f.ARMED) {
|
||||||
LED0_ON;
|
LED0_ON;
|
||||||
|
|
|
@ -25,7 +25,7 @@
|
||||||
#include "drivers/accgyro.h"
|
#include "drivers/accgyro.h"
|
||||||
#include "flight/flight.h"
|
#include "flight/flight.h"
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "io/buzzer.h"
|
#include "io/beeper.h"
|
||||||
#include "sensors/boardalignment.h"
|
#include "sensors/boardalignment.h"
|
||||||
#include "config/runtime_config.h"
|
#include "config/runtime_config.h"
|
||||||
#include "config/config.h"
|
#include "config/config.h"
|
||||||
|
@ -130,7 +130,7 @@ void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTri
|
||||||
if (InflightcalibratingA == 1) {
|
if (InflightcalibratingA == 1) {
|
||||||
AccInflightCalibrationActive = false;
|
AccInflightCalibrationActive = false;
|
||||||
AccInflightCalibrationMeasurementDone = true;
|
AccInflightCalibrationMeasurementDone = true;
|
||||||
queueConfirmationBeep(2); // buzzer to indicatiing the end of calibration
|
queueConfirmationBeep(2); // beeper to indicatiing the end of calibration
|
||||||
// recover saved values to maintain current flight behavior until new values are transferred
|
// recover saved values to maintain current flight behavior until new values are transferred
|
||||||
accelerationTrims->raw[FD_ROLL] = accZero_saved[FD_ROLL];
|
accelerationTrims->raw[FD_ROLL] = accZero_saved[FD_ROLL];
|
||||||
accelerationTrims->raw[FD_PITCH] = accZero_saved[FD_PITCH];
|
accelerationTrims->raw[FD_PITCH] = accZero_saved[FD_PITCH];
|
||||||
|
|
|
@ -25,7 +25,7 @@
|
||||||
|
|
||||||
// Battery monitoring stuff
|
// Battery monitoring stuff
|
||||||
uint8_t batteryCellCount = 3; // cell count
|
uint8_t batteryCellCount = 3; // cell count
|
||||||
uint16_t batteryWarningVoltage; // annoying buzzer after this one, battery ready to be dead
|
uint16_t batteryWarningVoltage; // annoying beeper after this one, battery ready to be dead
|
||||||
|
|
||||||
uint8_t vbat = 0; // battery voltage in 0.1V steps
|
uint8_t vbat = 0; // battery voltage in 0.1V steps
|
||||||
|
|
||||||
|
|
|
@ -29,14 +29,14 @@
|
||||||
#define BEEP_GPIO GPIOE
|
#define BEEP_GPIO GPIOE
|
||||||
#define BEEP_PIN Pin_9|Pin_13 // Red LEDs - PE9/PE13
|
#define BEEP_PIN Pin_9|Pin_13 // Red LEDs - PE9/PE13
|
||||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOE
|
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOE
|
||||||
#define BUZZER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define BARO_GPIO GPIOC
|
#define BARO_GPIO GPIOC
|
||||||
#define BARO_PIN Pin_13
|
#define BARO_PIN Pin_13
|
||||||
|
|
||||||
#define GYRO
|
#define GYRO
|
||||||
#define ACC
|
#define ACC
|
||||||
#define BUZZER
|
#define BEEPER
|
||||||
#define LED0
|
#define LED0
|
||||||
#define LED1
|
#define LED1
|
||||||
|
|
||||||
|
|
|
@ -26,7 +26,7 @@
|
||||||
|
|
||||||
|
|
||||||
#define BEEP_GPIO GPIOA
|
#define BEEP_GPIO GPIOA
|
||||||
#define BEEP_PIN Pin_12 // PA12 (Buzzer)
|
#define BEEP_PIN Pin_12 // PA12 (Beeper)
|
||||||
#define BEEP_PERIPHERAL RCC_APB2Periph_GPIOA
|
#define BEEP_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||||
|
|
||||||
#define BARO_GPIO GPIOC
|
#define BARO_GPIO GPIOC
|
||||||
|
@ -37,7 +37,7 @@
|
||||||
#define MAG
|
#define MAG
|
||||||
#define BARO
|
#define BARO
|
||||||
#define SONAR
|
#define SONAR
|
||||||
#define BUZZER
|
#define BEEPER
|
||||||
#define LED0
|
#define LED0
|
||||||
#define LED1
|
#define LED1
|
||||||
|
|
||||||
|
|
|
@ -24,7 +24,7 @@
|
||||||
#define BEEP_PIN Pin_10
|
#define BEEP_PIN Pin_10
|
||||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOB
|
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||||
|
|
||||||
#define BUZZER
|
#define BEEPER
|
||||||
#define LED0
|
#define LED0
|
||||||
|
|
||||||
#define GYRO
|
#define GYRO
|
||||||
|
|
|
@ -29,16 +29,16 @@
|
||||||
#define BEEP_GPIO GPIOE
|
#define BEEP_GPIO GPIOE
|
||||||
#define BEEP_PIN Pin_9|Pin_13 // Red LEDs - PE9/PE13
|
#define BEEP_PIN Pin_9|Pin_13 // Red LEDs - PE9/PE13
|
||||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOE
|
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOE
|
||||||
#define BUZZER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
|
|
||||||
#define BUZZER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
#define BARO_GPIO GPIOC
|
#define BARO_GPIO GPIOC
|
||||||
#define BARO_PIN Pin_13
|
#define BARO_PIN Pin_13
|
||||||
|
|
||||||
#define GYRO
|
#define GYRO
|
||||||
#define ACC
|
#define ACC
|
||||||
#define BUZZER
|
#define BEEPER
|
||||||
#define LED0
|
#define LED0
|
||||||
#define LED1
|
#define LED1
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue