diff --git a/src/main/cli/cli.c b/src/main/cli/cli.c
index bdfb9eb82b..247b6f09bd 100644
--- a/src/main/cli/cli.c
+++ b/src/main/cli/cli.c
@@ -5758,7 +5758,9 @@ static void cliDma(const char *cmdName, char* cmdline)
#if defined(USE_DMA_SPEC)
cliDmaopt(cmdName, cmdline);
#else
- cliShowParseError(cmdName);
+ UNUSED(cmdName);
+ // the only option is show, so make that the default behaviour
+ showDma();
#endif
}
#endif
diff --git a/src/main/drivers/dma_reqmap.h b/src/main/drivers/dma_reqmap.h
index 54b5335249..eda66440f0 100644
--- a/src/main/drivers/dma_reqmap.h
+++ b/src/main/drivers/dma_reqmap.h
@@ -25,7 +25,7 @@
#include "drivers/dma.h"
#include "drivers/timer.h"
-#ifdef USE_DMA
+#ifdef USE_DMA_SPEC
#include "dma_reqmap_mcu.h"
#endif
diff --git a/src/platform/PICO/dma_reqmap_mcu.c b/src/platform/PICO/dma_reqmap_mcu.c
deleted file mode 100644
index 5f9c8f3af0..0000000000
--- a/src/platform/PICO/dma_reqmap_mcu.c
+++ /dev/null
@@ -1,108 +0,0 @@
-/*
- * 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 "platform.h"
-
-#ifdef USE_DMA_SPEC
-
-#include "timer_def.h"
-#include "drivers/adc.h"
-#include "drivers/bus_spi.h"
-#include "drivers/dma_reqmap.h"
-#include "drivers/serial.h"
-#include "drivers/serial_uart.h"
-#include "drivers/serial_uart_impl.h"
-#include "pg/timerio.h"
-
-#define DMA(c) { (c), (dmaResource_t *) dma_hw->ch[c] , 0 }
-
-static dmaChannelSpec_t dmaChannelSpec[MAX_PERIPHERAL_DMA_OPTIONS] = {
- DMA(1),
- DMA(2),
- DMA(3),
- DMA(4),
- DMA(5),
- DMA(6),
- DMA(7),
- DMA(8),
- DMA(9),
- DMA(10),
- DMA(11),
- DMA(12),
-#ifdef RP2350
- DMA(13),
- DMA(14),
- DMA(15),
- DMA(16),
-#endif
-};
-
-#undef DMA
-
-const dmaChannelSpec_t *dmaGetChannelSpecByPeripheral(dmaPeripheral_e device, uint8_t index, int8_t opt)
-{
- UNUSED(device);
- UNUSED(index);
- UNUSED(opt);
- //TODO : Implementation for PICO
- return NULL;
-}
-
-dmaoptValue_t dmaoptByTag(ioTag_t ioTag)
-{
- UNUSED(ioTag);
- //TODO : Implementation for PICO
- return DMA_OPT_UNUSED;
-}
-
-const dmaChannelSpec_t *dmaGetChannelSpecByTimerValue(TIM_TypeDef *tim, uint8_t channel, dmaoptValue_t dmaopt)
-{
- //TODO : Implementation for PICO
- return NULL;
-}
-
-const dmaChannelSpec_t *dmaGetChannelSpecByTimer(const timerHardware_t *timer)
-{
- if (!timer) {
- return NULL;
- }
-
- //TODO : Implementation for PICO
- return NULL;
-}
-
-// dmaGetOptionByTimer is called by pgResetFn_timerIOConfig to find out dmaopt for pre-configured timer.
-dmaoptValue_t dmaGetOptionByTimer(const timerHardware_t *timer)
-{
- //TODO : Implementation for PICO
- return DMA_OPT_UNUSED;
-}
-
-// A variant of dmaGetOptionByTimer that looks for matching dmaTimUPRef
-dmaoptValue_t dmaGetUpOptionByTimer(const timerHardware_t *timer)
-{
- //TODO : Implementation for PICO
- return DMA_OPT_UNUSED;
-}
-
-#endif // USE_DMA_SPEC
diff --git a/src/platform/PICO/dma_reqmap_mcu.h b/src/platform/PICO/dma_reqmap_mcu.h
deleted file mode 100644
index cc04c660c1..0000000000
--- a/src/platform/PICO/dma_reqmap_mcu.h
+++ /dev/null
@@ -1,27 +0,0 @@
-/*
- * 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 .
- */
-
-#pragma once
-
-#define MAX_PERIPHERAL_DMA_OPTIONS 14
-#define MAX_TIMER_DMA_OPTIONS 22
-
-#define USE_DMA_MUX