diff --git a/make/source.mk b/make/source.mk
index 1fb79a9494..f1ebeb4fe1 100644
--- a/make/source.mk
+++ b/make/source.mk
@@ -61,6 +61,8 @@ COMMON_SRC = \
io/transponder_ir.c \
msp/msp_serial.c \
pg/adc.c \
+ pg/beeper.c \
+ pg/beeper_dev.c \
pg/bus_i2c.c \
pg/flash.c \
pg/max7456.c \
diff --git a/src/main/drivers/sound_beeper.c b/src/main/drivers/sound_beeper.c
index 2e47104efc..de976fa500 100644
--- a/src/main/drivers/sound_beeper.c
+++ b/src/main/drivers/sound_beeper.c
@@ -21,10 +21,11 @@
#include "platform.h"
#include "drivers/io.h"
+#include "drivers/pwm_output.h"
+
+#include "pg/beeper_dev.h"
#include "sound_beeper.h"
-#include "pwm_output.h"
-
#ifdef BEEPER
static IO_t beeperIO = DEFIO_IO(NONE);
diff --git a/src/main/drivers/sound_beeper.h b/src/main/drivers/sound_beeper.h
index e119aabf5f..12ba74017e 100644
--- a/src/main/drivers/sound_beeper.h
+++ b/src/main/drivers/sound_beeper.h
@@ -17,8 +17,6 @@
#pragma once
-#include "drivers/io_types.h"
-
#ifdef BEEPER
#define BEEP_TOGGLE systemBeepToggle()
#define BEEP_OFF systemBeep(false)
@@ -29,13 +27,7 @@
#define BEEP_ON do {} while (0)
#endif
-typedef struct beeperDevConfig_s {
- ioTag_t ioTag;
- uint8_t isInverted;
- uint8_t isOpenDrain;
- uint16_t frequency;
-} beeperDevConfig_t;
-
void systemBeep(bool on);
void systemBeepToggle(void);
-void beeperInit(const beeperDevConfig_t *beeperDevConfig);
+struct beeperDevConfig_s;
+void beeperInit(const struct beeperDevConfig_s *beeperDevConfig);
diff --git a/src/main/fc/config.c b/src/main/fc/config.c
index 256f3e6bde..b630b20e46 100644
--- a/src/main/fc/config.c
+++ b/src/main/fc/config.c
@@ -36,8 +36,6 @@
#include "config/config_eeprom.h"
#include "config/feature.h"
-#include "pg/pg.h"
-#include "pg/pg_ids.h"
#include "drivers/accgyro/accgyro.h"
#include "drivers/bus_spi.h"
@@ -51,7 +49,6 @@
#include "drivers/pwm_output.h"
#include "drivers/rx/rx_spi.h"
#include "drivers/sensor.h"
-#include "drivers/sound_beeper.h"
#include "drivers/system.h"
#include "drivers/timer.h"
@@ -81,6 +78,10 @@
#include "io/servos.h"
#include "io/vtx_control.h"
+#include "pg/beeper.h"
+#include "pg/pg.h"
+#include "pg/pg_ids.h"
+
#include "rx/rx.h"
#include "rx/rx_spi.h"
diff --git a/src/main/fc/config.h b/src/main/fc/config.h
index be235254b4..e3e315f45b 100644
--- a/src/main/fc/config.h
+++ b/src/main/fc/config.h
@@ -25,7 +25,6 @@
#include "drivers/flash.h"
#include "drivers/serial.h"
#include "drivers/bus_i2c.h"
-#include "drivers/sound_beeper.h"
typedef enum {
FEATURE_RX_PPM = 1 << 0,
@@ -80,7 +79,6 @@ typedef struct systemConfig_s {
PG_DECLARE(pilotConfig_t, pilotConfig);
PG_DECLARE(systemConfig_t, systemConfig);
-PG_DECLARE(beeperDevConfig_t, beeperDevConfig);
struct pidProfile_s;
extern struct pidProfile_s *currentPidProfile;
diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c
index 213bd5065b..4e9117f67f 100644
--- a/src/main/fc/fc_core.c
+++ b/src/main/fc/fc_core.c
@@ -35,6 +35,7 @@
#include "pg/pg_ids.h"
#include "drivers/light_led.h"
+#include "drivers/sound_beeper.h"
#include "drivers/system.h"
#include "drivers/time.h"
#include "drivers/transponder_ir.h"
diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c
index 53b1d66d5a..7aa6a37e4e 100644
--- a/src/main/fc/fc_init.c
+++ b/src/main/fc/fc_init.c
@@ -78,6 +78,7 @@
#include "msp/msp_serial.h"
#include "pg/adc.h"
+#include "pg/beeper_dev.h"
#include "pg/bus_i2c.h"
#include "pg/flash.h"
#include "pg/pg.h"
@@ -92,6 +93,7 @@
#include "io/beeper.h"
#include "io/displayport_max7456.h"
#include "io/displayport_rcdevice.h"
+#include "io/displayport_srxl.h"
#include "io/serial.h"
#include "io/flashfs.h"
#include "io/gps.h"
@@ -111,8 +113,6 @@
#include "io/vtx_smartaudio.h"
#include "io/vtx_tramp.h"
-#include "io/displayport_srxl.h"
-
#include "scheduler/scheduler.h"
#include "sensors/acceleration.h"
diff --git a/src/main/interface/cli.c b/src/main/interface/cli.c
index eee5eb387c..feb8bb7e38 100644
--- a/src/main/interface/cli.c
+++ b/src/main/interface/cli.c
@@ -53,8 +53,6 @@ extern uint8_t __config_end;
#include "config/config_eeprom.h"
#include "config/feature.h"
-#include "pg/pg.h"
-#include "pg/pg_ids.h"
#include "drivers/accgyro/accgyro.h"
#include "drivers/buf_writer.h"
@@ -114,7 +112,11 @@ extern uint8_t __config_end;
#include "io/vtx.h"
#include "pg/adc.h"
+#include "pg/beeper.h"
+#include "pg/beeper_dev.h"
#include "pg/bus_i2c.h"
+#include "pg/pg.h"
+#include "pg/pg_ids.h"
#include "pg/rx_pwm.h"
#include "rx/rx.h"
diff --git a/src/main/interface/settings.c b/src/main/interface/settings.c
index 624bb7a985..2d95c124a0 100644
--- a/src/main/interface/settings.c
+++ b/src/main/interface/settings.c
@@ -62,6 +62,8 @@
#include "io/vtx_rtc6705.h"
#include "pg/adc.h"
+#include "pg/beeper.h"
+#include "pg/beeper_dev.h"
#include "pg/max7456.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
diff --git a/src/main/io/beeper.c b/src/main/io/beeper.c
index 94666ca0e4..44cf0fa343 100644
--- a/src/main/io/beeper.c
+++ b/src/main/io/beeper.c
@@ -23,8 +23,6 @@
#include "common/utils.h"
#include "config/feature.h"
-#include "pg/pg.h"
-#include "pg/pg_ids.h"
#include "drivers/sound_beeper.h"
#include "drivers/time.h"
@@ -43,12 +41,11 @@
#include "io/gps.h"
#endif
+#include "pg/beeper.h"
+
#include "sensors/battery.h"
#include "sensors/sensors.h"
-
-PG_REGISTER_WITH_RESET_TEMPLATE(beeperDevConfig_t, beeperDevConfig, PG_BEEPER_DEV_CONFIG, 0);
-
#ifdef BEEPER_INVERTED
#define IS_OPEN_DRAIN false
#define IS_INVERTED true
@@ -67,13 +64,6 @@ PG_REGISTER_WITH_RESET_TEMPLATE(beeperDevConfig_t, beeperDevConfig, PG_BEEPER_DE
#define BEEPER_PWM_HZ 0
#endif
-PG_RESET_TEMPLATE(beeperDevConfig_t, beeperDevConfig,
- .isOpenDrain = IS_OPEN_DRAIN,
- .isInverted = IS_INVERTED,
- .ioTag = IO_TAG(BEEPER_PIN),
- .frequency = BEEPER_PWM_HZ
-);
-
#if FLASH_SIZE > 64
#define BEEPER_NAMES
#endif
@@ -84,11 +74,6 @@ PG_RESET_TEMPLATE(beeperDevConfig_t, beeperDevConfig,
#define BEEPER_COMMAND_STOP 0xFF
#ifdef BEEPER
-PG_REGISTER_WITH_RESET_TEMPLATE(beeperConfig_t, beeperConfig, PG_BEEPER_CONFIG, 1);
-PG_RESET_TEMPLATE(beeperConfig_t, beeperConfig,
- .dshotBeaconTone = 0
-);
-
/* Beeper Sound Sequences: (Square wave generation)
* Sequence must end with 0xFF or 0xFE. 0xFE repeats the sequence from
* start when 0xFF stops the sound when it's completed.
diff --git a/src/main/io/beeper.h b/src/main/io/beeper.h
index fa8ac88f88..f76b193b6d 100644
--- a/src/main/io/beeper.h
+++ b/src/main/io/beeper.h
@@ -51,16 +51,6 @@ typedef enum {
// BEEPER_ALL and BEEPER_PREFERENCE must remain at the bottom of this enum
} beeperMode_e;
-typedef struct beeperConfig_s {
- uint32_t beeper_off_flags;
- uint32_t preferred_beeper_off_flags;
- uint8_t dshotBeaconTone;
-} beeperConfig_t;
-
-#ifdef BEEPER
-PG_DECLARE(beeperConfig_t, beeperConfig);
-#endif
-
void beeper(beeperMode_e mode);
void beeperSilence(void);
void beeperUpdate(timeUs_t currentTimeUs);
diff --git a/src/main/pg/beeper.c b/src/main/pg/beeper.c
new file mode 100644
index 0000000000..b02689fcd5
--- /dev/null
+++ b/src/main/pg/beeper.c
@@ -0,0 +1,31 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * Cleanflight is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Cleanflight. If not, see .
+ */
+
+#include
+
+#ifdef BEEPER
+
+#include "pg/pg.h"
+#include "pg/pg_ids.h"
+
+#include "beeper.h"
+
+PG_REGISTER_WITH_RESET_TEMPLATE(beeperConfig_t, beeperConfig, PG_BEEPER_CONFIG, 1);
+PG_RESET_TEMPLATE(beeperConfig_t, beeperConfig,
+ .dshotBeaconTone = 0
+);
+#endif
diff --git a/src/main/pg/beeper.h b/src/main/pg/beeper.h
new file mode 100644
index 0000000000..55b99d102d
--- /dev/null
+++ b/src/main/pg/beeper.h
@@ -0,0 +1,29 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * Cleanflight is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Cleanflight. If not, see .
+ */
+
+#pragma once
+
+#include "pg/pg.h"
+#include "drivers/io_types.h"
+
+typedef struct beeperConfig_s {
+ uint32_t beeper_off_flags;
+ uint32_t preferred_beeper_off_flags;
+ uint8_t dshotBeaconTone;
+} beeperConfig_t;
+
+PG_DECLARE(beeperConfig_t, beeperConfig);
diff --git a/src/main/pg/beeper_dev.c b/src/main/pg/beeper_dev.c
new file mode 100644
index 0000000000..ccccab5df3
--- /dev/null
+++ b/src/main/pg/beeper_dev.c
@@ -0,0 +1,54 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * Cleanflight is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Cleanflight. If not, see .
+ */
+
+#include "platform.h"
+
+#ifdef BEEPER
+
+#include "drivers/io.h"
+#include "pg/pg.h"
+#include "pg/pg_ids.h"
+
+#include "beeper_dev.h"
+
+PG_REGISTER_WITH_RESET_TEMPLATE(beeperDevConfig_t, beeperDevConfig, PG_BEEPER_DEV_CONFIG, 0);
+
+#ifdef BEEPER_INVERTED
+#define IS_OPEN_DRAIN false
+#define IS_INVERTED true
+#else
+#define IS_OPEN_DRAIN true
+#define IS_INVERTED false
+#endif
+
+#ifdef BEEPER
+#define BEEPER_PIN BEEPER
+#ifndef BEEPER_PWM_HZ
+#define BEEPER_PWM_HZ 0
+#endif
+#else
+#define BEEPER_PIN NONE
+#define BEEPER_PWM_HZ 0
+#endif
+
+PG_RESET_TEMPLATE(beeperDevConfig_t, beeperDevConfig,
+ .isOpenDrain = IS_OPEN_DRAIN,
+ .isInverted = IS_INVERTED,
+ .ioTag = IO_TAG(BEEPER_PIN),
+ .frequency = BEEPER_PWM_HZ
+);
+#endif
diff --git a/src/main/pg/beeper_dev.h b/src/main/pg/beeper_dev.h
new file mode 100644
index 0000000000..4adef14fde
--- /dev/null
+++ b/src/main/pg/beeper_dev.h
@@ -0,0 +1,32 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * Cleanflight is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Cleanflight. If not, see .
+ */
+
+#pragma once
+
+#include "drivers/io_types.h"
+
+#include "pg/pg.h"
+#include "drivers/io_types.h"
+
+typedef struct beeperDevConfig_s {
+ ioTag_t ioTag;
+ uint8_t isInverted;
+ uint8_t isOpenDrain;
+ uint16_t frequency;
+} beeperDevConfig_t;
+
+PG_DECLARE(beeperDevConfig_t, beeperDevConfig);
diff --git a/src/main/target/ALIENFLIGHTF3/config.c b/src/main/target/ALIENFLIGHTF3/config.c
index a5f0a2632c..f04b357311 100644
--- a/src/main/target/ALIENFLIGHTF3/config.c
+++ b/src/main/target/ALIENFLIGHTF3/config.c
@@ -34,6 +34,8 @@
#include "flight/mixer.h"
#include "flight/pid.h"
+#include "pg/beeper_dev.h"
+
#include "rx/rx.h"
#include "io/serial.h"
diff --git a/src/main/target/BLUEJAYF4/config.c b/src/main/target/BLUEJAYF4/config.c
index 185883b3d9..ea689cb78d 100644
--- a/src/main/target/BLUEJAYF4/config.c
+++ b/src/main/target/BLUEJAYF4/config.c
@@ -34,6 +34,7 @@
#include "sensors/gyro.h"
#include "pg/adc.h"
+#include "pg/beeper_dev.h"
#include "hardware_revision.h"
diff --git a/src/main/target/YUPIF4/config.c b/src/main/target/YUPIF4/config.c
index 858703b63e..f6721e25fc 100644
--- a/src/main/target/YUPIF4/config.c
+++ b/src/main/target/YUPIF4/config.c
@@ -25,6 +25,7 @@
#include "fc/config.h"
#include "flight/pid.h"
#include "pg/adc.h"
+#include "pg/beeper_dev.h"
#include "telemetry/telemetry.h"
#include "hardware_revision.h"
diff --git a/src/test/unit/cli_unittest.cc b/src/test/unit/cli_unittest.cc
index 26df59d9ec..b402b117e7 100644
--- a/src/test/unit/cli_unittest.cc
+++ b/src/test/unit/cli_unittest.cc
@@ -47,6 +47,7 @@ extern "C" {
#include "io/osd.h"
#include "io/serial.h"
#include "io/vtx.h"
+ #include "pg/beeper.h"
#include "rx/rx.h"
#include "scheduler/scheduler.h"
#include "sensors/battery.h"