diff --git a/Makefile b/Makefile index 72d296851f..8e4aacdc02 100644 --- a/Makefile +++ b/Makefile @@ -136,7 +136,7 @@ COMMON_SRC = build_config.c \ drivers/serial.c \ drivers/sound_beeper.c \ drivers/system.c \ - io/buzzer.c \ + io/beeper.c \ io/gps.c \ io/gps_conversion.c \ io/ledstrip.c \ diff --git a/baseflight.uvproj b/baseflight.uvproj index 765943e863..6413e41592 100755 --- a/baseflight.uvproj +++ b/baseflight.uvproj @@ -459,9 +459,9 @@ .\src\spektrum.c - buzzer.c + beeper.c 1 - .\src\buzzer.c + .\src\beeper.c utils.c @@ -1202,9 +1202,9 @@ .\src\spektrum.c - buzzer.c + beeper.c 1 - .\src\buzzer.c + .\src\beeper.c utils.c diff --git a/docs/Autotune.md b/docs/Autotune.md index 3fc1b12376..dde3594ba3 100644 --- a/docs/Autotune.md +++ b/docs/Autotune.md @@ -19,7 +19,7 @@ Launch the multirotor. 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. @@ -27,7 +27,7 @@ PID settings will have been updated for ROLL/YAW. 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. diff --git a/docs/building in windows.md b/docs/building in windows.md index 44e01d6c80..c96aa92590 100644 --- a/docs/building in windows.md +++ b/docs/building in windows.md @@ -42,7 +42,7 @@ C:\Users\nico\Documents\GitHub\cleanflight>make %% build_config.c %% battery.c %% boardalignment.c -%% buzzer.c +%% beeper.c %% config.c %% maths.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 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 -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 /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 diff --git a/src/main/drivers/sound_beeper.c b/src/main/drivers/sound_beeper.c index b2cc0a934c..afe0aaf6ad 100644 --- a/src/main/drivers/sound_beeper.c +++ b/src/main/drivers/sound_beeper.c @@ -27,7 +27,7 @@ #include "sound_beeper.h" -#ifdef BUZZER +#ifdef BEEPER void (*systemBeepPtr)(bool onoff) = NULL; @@ -52,14 +52,14 @@ static void beepInverted(bool onoff) void systemBeep(bool onoff) { -#ifdef BUZZER +#ifdef BEEPER systemBeepPtr(onoff); #endif } -static inline bool isBuzzerOutputInverted(void) +static inline bool isBeeperOutputInverted(void) { -#ifdef BUZZER_INVERTED +#ifdef BEEPER_INVERTED return true; #else // Naze rev5 needs inverted beeper. @@ -69,9 +69,9 @@ static inline bool isBuzzerOutputInverted(void) void beeperInit(void) { -#ifdef BUZZER +#ifdef BEEPER initBeeperHardware(); - if (isBuzzerOutputInverted()) + if (isBeeperOutputInverted()) systemBeepPtr = beepInverted; else systemBeepPtr = beepNormal; diff --git a/src/main/drivers/sound_beeper_stm32f10x.c b/src/main/drivers/sound_beeper_stm32f10x.c index 6faaf7e7d4..851d2de073 100644 --- a/src/main/drivers/sound_beeper_stm32f10x.c +++ b/src/main/drivers/sound_beeper_stm32f10x.c @@ -28,7 +28,7 @@ void initBeeperHardware(void) { -#ifdef BUZZER +#ifdef BEEPER struct { GPIO_TypeDef *gpio; gpio_config_t cfg; diff --git a/src/main/drivers/sound_beeper_stm32f30x.c b/src/main/drivers/sound_beeper_stm32f30x.c index 80c8d93d0e..8a83aa3352 100644 --- a/src/main/drivers/sound_beeper_stm32f30x.c +++ b/src/main/drivers/sound_beeper_stm32f30x.c @@ -27,7 +27,7 @@ void initBeeperHardware(void) { -#ifdef BUZZER +#ifdef BEEPER struct { GPIO_TypeDef *gpio; gpio_config_t cfg; diff --git a/src/main/io/buzzer.c b/src/main/io/beeper.c similarity index 84% rename from src/main/io/buzzer.c rename to src/main/io/beeper.c index 0eea155fb7..70a42842ac 100644 --- a/src/main/io/buzzer.c +++ b/src/main/io/beeper.c @@ -26,7 +26,7 @@ #include "config/runtime_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 LONG_PAUSE_DURATION_MILLIS 200 @@ -35,8 +35,8 @@ #define SHORT_CONFIRMATION_BEEP_DURATION_MILLIS (SHORT_PAUSE_DURATION_MILLIS / 2) -static uint8_t buzzerIsOn = 0, beepDone = 0; -static uint32_t buzzerLastToggleTime; +static uint8_t beeperIsOn = 0, beepDone = 0; +static uint32_t beeperLastToggleTime; static void beep(uint16_t pulseMillis); static void beep_code(char first, char second, char third, char pause); @@ -46,20 +46,20 @@ typedef enum { FAILSAFE_IDLE = 0, FAILSAFE_LANDING, FAILSAFE_FIND_ME -} failsafeBuzzerWarnings_e; +} failsafeBeeperWarnings_e; static failsafe_t* failsafe; -void buzzerInit(failsafe_t *initialFailsafe) +void beepcodeInit(failsafe_t *initialFailsafe) { failsafe = initialFailsafe; } -void buzzer(bool warn_vbat) +void beepcodeUpdateState(bool warn_vbat) { static uint8_t beeperOnBox; static uint8_t warn_noGPSfix = 0; - static failsafeBuzzerWarnings_e warn_failsafe = FAILSAFE_IDLE; + static failsafeBeeperWarnings_e warn_failsafe = FAILSAFE_IDLE; //===================== BeeperOn via rcOptions ===================== if (rcOptions[BOXBEEPERON]) { // unconditional beeper on via AUXn switch @@ -113,7 +113,7 @@ void buzzer(bool warn_vbat) else if (toggleBeep > 0) beep(50); // fast confirmation beep else { - buzzerIsOn = 0; + beeperIsOn = 0; BEEP_OFF; } } @@ -154,7 +154,7 @@ void beep_code(char first, char second, char third, char pause) if (icnt < 3 && Duration != 0) beep(Duration); - if (icnt >= 3 && (buzzerLastToggleTime < millis() - Duration)) { + if (icnt >= 3 && (beeperLastToggleTime < millis() - Duration)) { icnt = 0; toggleBeep = 0; } @@ -162,18 +162,18 @@ void beep_code(char first, char second, char third, char pause) if (icnt < 3) icnt++; beepDone = 0; - buzzerIsOn = 0; + beeperIsOn = 0; BEEP_OFF; } } static void beep(uint16_t pulseMillis) { - if (buzzerIsOn) { - if (millis() >= buzzerLastToggleTime + pulseMillis) { - buzzerIsOn = 0; + if (beeperIsOn) { + if (millis() >= beeperLastToggleTime + pulseMillis) { + beeperIsOn = 0; BEEP_OFF; - buzzerLastToggleTime = millis(); + beeperLastToggleTime = millis(); if (toggleBeep >0) toggleBeep--; beepDone = 1; @@ -181,9 +181,9 @@ static void beep(uint16_t pulseMillis) return; } - if (millis() >= (buzzerLastToggleTime + LONG_PAUSE_DURATION_MILLIS)) { // Buzzer is off and long pause time is up -> turn it on - buzzerIsOn = 1; + if (millis() >= (beeperLastToggleTime + LONG_PAUSE_DURATION_MILLIS)) { // Beeper is off and long pause time is up -> turn it on + beeperIsOn = 1; BEEP_ON; - buzzerLastToggleTime = millis(); // save the time the buzer turned on + beeperLastToggleTime = millis(); // save the time the buzer turned on } } diff --git a/src/main/io/buzzer.h b/src/main/io/beeper.h similarity index 92% rename from src/main/io/buzzer.h rename to src/main/io/beeper.h index 4a4de4fda4..1fb713beb7 100644 --- a/src/main/io/buzzer.h +++ b/src/main/io/beeper.h @@ -17,5 +17,5 @@ #pragma once -void buzzer(bool warn_vbat); +void beepcodeUpdateState(bool warn_vbat); void queueConfirmationBeep(uint8_t duration); diff --git a/src/main/main.c b/src/main/main.c index 071c955239..a7ec86288c 100755 --- a/src/main/main.c +++ b/src/main/main.c @@ -81,7 +81,7 @@ failsafe_t* failsafeInit(rxConfig_t *intialRxConfig); pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init); void mixerInit(MultiType mixerConfiguration, motorMixer_t *customMixers, pwmOutputConfiguration_t *pwmOutputConfiguration); 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); bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, int16_t magDeclinationFromConfig); void imuInit(void); @@ -199,7 +199,7 @@ void init(void) mixerInit(masterConfig.mixerConfiguration, masterConfig.customMixer, pwmOutputConfiguration); failsafe = failsafeInit(&masterConfig.rxConfig); - buzzerInit(failsafe); + beepcodeInit(failsafe); rxInit(&masterConfig.rxConfig, failsafe); if (feature(FEATURE_GPS)) { diff --git a/src/main/mw.c b/src/main/mw.c index 76f0564d18..5f482035a7 100755 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -42,7 +42,7 @@ #include "sensors/barometer.h" #include "sensors/gyro.h" #include "sensors/battery.h" -#include "io/buzzer.h" +#include "io/beeper.h" #include "io/escservo.h" #include "flight/failsafe.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) { LED0_ON; diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 3950ea0ed4..c01e526225 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -25,7 +25,7 @@ #include "drivers/accgyro.h" #include "flight/flight.h" #include "sensors/sensors.h" -#include "io/buzzer.h" +#include "io/beeper.h" #include "sensors/boardalignment.h" #include "config/runtime_config.h" #include "config/config.h" @@ -130,7 +130,7 @@ void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTri if (InflightcalibratingA == 1) { AccInflightCalibrationActive = false; 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 accelerationTrims->raw[FD_ROLL] = accZero_saved[FD_ROLL]; accelerationTrims->raw[FD_PITCH] = accZero_saved[FD_PITCH]; diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index 1708b23a9b..b540bc3774 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -25,7 +25,7 @@ // Battery monitoring stuff 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 diff --git a/src/main/target/CHEBUZZF3/target.h b/src/main/target/CHEBUZZF3/target.h index 466c57368f..6890adb019 100644 --- a/src/main/target/CHEBUZZF3/target.h +++ b/src/main/target/CHEBUZZF3/target.h @@ -29,14 +29,14 @@ #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 BEEPER_INVERTED #define BARO_GPIO GPIOC #define BARO_PIN Pin_13 #define GYRO #define ACC -#define BUZZER +#define BEEPER #define LED0 #define LED1 diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index 934ff3011b..e3421c6e90 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -26,7 +26,7 @@ #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 BARO_GPIO GPIOC @@ -37,7 +37,7 @@ #define MAG #define BARO #define SONAR -#define BUZZER +#define BEEPER #define LED0 #define LED1 diff --git a/src/main/target/NAZE32PRO/target.h b/src/main/target/NAZE32PRO/target.h index e29ee02b2f..4779835908 100644 --- a/src/main/target/NAZE32PRO/target.h +++ b/src/main/target/NAZE32PRO/target.h @@ -24,7 +24,7 @@ #define BEEP_PIN Pin_10 #define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOB -#define BUZZER +#define BEEPER #define LED0 #define GYRO diff --git a/src/main/target/STM32F3DISCOVERY/target.h b/src/main/target/STM32F3DISCOVERY/target.h index c8e698b673..d562125b6c 100644 --- a/src/main/target/STM32F3DISCOVERY/target.h +++ b/src/main/target/STM32F3DISCOVERY/target.h @@ -29,16 +29,16 @@ #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 BEEPER_INVERTED -#define BUZZER_INVERTED +#define BEEPER_INVERTED #define BARO_GPIO GPIOC #define BARO_PIN Pin_13 #define GYRO #define ACC -#define BUZZER +#define BEEPER #define LED0 #define LED1