diff --git a/src/platform/PICO/mk/RP2350.mk b/src/platform/PICO/mk/RP2350.mk
index 6f05d5f3ac..b26625e412 100644
--- a/src/platform/PICO/mk/RP2350.mk
+++ b/src/platform/PICO/mk/RP2350.mk
@@ -403,6 +403,7 @@ MCU_COMMON_SRC = \
PICO/io_pico.c \
PICO/persistent.c \
PICO/pwm_pico.c \
+ PICO/pwm_beeper_pico.c \
PICO/serial_uart_pico.c \
PICO/serial_usb_vcp_pico.c \
PICO/system.c \
diff --git a/src/platform/PICO/pwm_beeper_pico.c b/src/platform/PICO/pwm_beeper_pico.c
new file mode 100644
index 0000000000..9fae7b1fa8
--- /dev/null
+++ b/src/platform/PICO/pwm_beeper_pico.c
@@ -0,0 +1,83 @@
+/*
+ * This file is part of Betaflight.
+ *
+ * Betaflight is free software. You can redistribute this software
+ * and/or modify this software 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.
+ *
+ * Betaflight 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 this software.
+ *
+ * If not, see .
+ */
+
+#include
+#include
+#include "platform.h"
+
+#if defined(USE_BEEPER) && defined(USE_PWM_OUTPUT)
+
+#include "drivers/io.h"
+#include "drivers/io_impl.h"
+#include "hardware/gpio.h"
+#include "hardware/pwm.h"
+
+static bool beeperConfigured;
+static bool beeperEnabled;
+static int beeperGPIO;
+static uint pwmSlice;
+
+void pwmWriteBeeper(bool on)
+{
+ if (beeperConfigured) {
+ gpio_set_outover(beeperGPIO, on ? GPIO_OVERRIDE_NORMAL : GPIO_OVERRIDE_LOW);
+ pwm_set_enabled(pwmSlice, on);
+ beeperEnabled = on;
+ }
+}
+
+void pwmToggleBeeper(void)
+{
+ pwmWriteBeeper(!beeperEnabled);
+}
+
+void beeperPwmInit(const ioTag_t tag, uint16_t frequency)
+{
+ // frequency should be non-zero when calling beeperPwmInit.
+ IO_t beeperIO = IOGetByTag(tag);
+ if (beeperIO && frequency) {
+ beeperGPIO = IO_GPIOPinIdx(beeperIO);
+ IOInit(beeperIO, OWNER_BEEPER, 0);
+
+ // f = sysclk / div / wrap
+ // Max clock divide is just under 256.
+ uint16_t wrap;
+ uint32_t clock_divide = (SystemCoreClock / frequency + 0xfffe) / 0xffff; // round up
+ if (clock_divide > 255) {
+ clock_divide = 255;
+ wrap = 0xffff;
+ } else {
+ wrap = SystemCoreClock / frequency / clock_divide;
+ }
+
+ pwm_config cfg = pwm_get_default_config();
+ pwm_config_set_clkdiv_int(&cfg, clock_divide);
+ pwm_config_set_wrap(&cfg, wrap);
+ pwmSlice = pwm_gpio_to_slice_num(beeperGPIO);
+ pwm_init(pwmSlice, &cfg, false);
+ gpio_set_function(beeperGPIO, GPIO_FUNC_PWM);
+ pwm_set_gpio_level(beeperGPIO, wrap >> 1); // 50% square wave
+ beeperEnabled = false;
+ beeperConfigured = true;
+ }
+}
+
+#endif
diff --git a/src/platform/PICO/target/RP2350B/target.h b/src/platform/PICO/target/RP2350B/target.h
index 45779b72a6..55beefa129 100644
--- a/src/platform/PICO/target/RP2350B/target.h
+++ b/src/platform/PICO/target/RP2350B/target.h
@@ -201,6 +201,10 @@
// Enable 9V if/when we need it (for DVTX?)
// #define PICO_BEC_9V_ENABLE_PIN PA15
+#define USE_BEEPER
+#define BEEPER_PWM_HZ 1971
+#define BEEPER_PIN PA5
+
//#undef USE_BARO
#define USE_BARO_DPS310
#undef USE_BARO_MS5611