diff --git a/src/platform/PICO/mk/PICO.mk b/src/platform/PICO/mk/PICO.mk index 54cc1f12fb..cb7cfd9379 100644 --- a/src/platform/PICO/mk/PICO.mk +++ b/src/platform/PICO/mk/PICO.mk @@ -1,6 +1,24 @@ # # Raspberry PICO Make file include # +# The top level Makefile adds $(MCU_COMMON_SRC) and $(DEVICE_STDPERIPH_SRC) to SRC collection. +# + +PICO_TRACE = 1 + +PICO_LIB_OPTIMISATION := -O2 -fuse-linker-plugin -ffast-math -fmerge-all-constants + +# This file PICO.mk is $(TARGET_PLATFORM_DIR)/mk/$(TARGET_MCU_FAMILY).mk +PICO_MK_DIR = $(TARGET_PLATFORM_DIR)/mk + +ifneq ($(PICO_TRACE),) +include $(PICO_MK_DIR)/PICO_trace.mk +endif + +RP2350_TARGETS = RP2350A RP2350B +ifneq ($(filter $(TARGET_MCU), $(RP2350_TARGETS)),) +RP2350_TARGET = $(TARGET_MCU) +endif ifeq ($(DEBUG_HARDFAULTS),PICO) CFLAGS += -DDEBUG_HARDFAULTS @@ -13,16 +31,18 @@ CMSIS_DIR := $(SDK_DIR)/rp2_common/cmsis/stub/CMSIS #STDPERIPH STDPERIPH_DIR := $(SDK_DIR) -STDPERIPH_SRC := \ + +PICO_LIB_SRC = \ + rp2_common/pico_crt0/crt0.S \ rp2_common/hardware_sync_spin_lock/sync_spin_lock.c \ rp2_common/hardware_gpio/gpio.c \ - rp2_common/pico_stdio/stdio.c \ rp2_common/hardware_uart/uart.c \ rp2_common/hardware_irq/irq.c \ rp2_common/hardware_irq/irq_handler_chain.S \ rp2_common/hardware_timer/timer.c \ rp2_common/hardware_clocks/clocks.c \ rp2_common/hardware_pll/pll.c \ + rp2_common/hardware_dma/dma.c \ rp2_common/hardware_spi/spi.c \ rp2_common/hardware_i2c/i2c.c \ rp2_common/hardware_adc/adc.c \ @@ -36,7 +56,33 @@ STDPERIPH_SRC := \ common/pico_sync/lock_core.c \ common/hardware_claim/claim.c \ common/pico_sync/critical_section.c \ - rp2_common/hardware_sync/sync.c + rp2_common/hardware_sync/sync.c \ + rp2_common/pico_bootrom/bootrom.c \ + rp2_common/pico_runtime_init/runtime_init.c \ + rp2_common/pico_runtime_init/runtime_init_clocks.c \ + rp2_common/pico_runtime_init/runtime_init_stack_guard.c \ + rp2_common/pico_runtime/runtime.c \ + rp2_common/hardware_ticks/ticks.c \ + rp2_common/hardware_xosc/xosc.c \ + common/pico_sync/sem.c \ + common/pico_time/timeout_helper.c \ + common/pico_util/datetime.c \ + common/pico_util/pheap.c \ + common/pico_util/queue.c \ + rp2350/pico_platform/platform.c \ + rp2_common/pico_atomic/atomic.c \ + rp2_common/pico_bootrom/bootrom.c \ + rp2_common/pico_bootrom/bootrom_lock.c \ + rp2_common/pico_divider/divider_compiler.c \ + rp2_common/pico_double/double_math.c \ + rp2_common/pico_flash/flash.c \ + rp2_common/pico_float/float_math.c \ + rp2_common/hardware_divider/divider.c \ + rp2_common/hardware_vreg/vreg.c \ + rp2_common/pico_standard_binary_info/standard_binary_info.c \ + rp2_common/pico_clib_interface/newlib_interface.c \ + rp2_common/pico_malloc/malloc.c \ + rp2_common/pico_stdlib/stdlib.c TINY_USB_SRC_DIR = tinyUSB/src TINYUSB_SRC := \ @@ -48,26 +94,39 @@ TINYUSB_SRC := \ $(TINY_USB_SRC_DIR)/portable/raspberrypi/rp2040/dcd_rp2040.c \ $(TINY_USB_SRC_DIR)/portable/raspberrypi/rp2040/rp2040_usb.c +# TODO which of these do we need? +TINYUSB_SRC += \ + $(TINY_USB_SRC_DIR)/class/vendor/vendor_device.c \ + $(TINY_USB_SRC_DIR)/class/net/ecm_rndis_device.c \ + $(TINY_USB_SRC_DIR)/class/net/ncm_device.c \ + $(TINY_USB_SRC_DIR)/class/dfu/dfu_rt_device.c \ + $(TINY_USB_SRC_DIR)/class/dfu/dfu_device.c \ + $(TINY_USB_SRC_DIR)/class/msc/msc_device.c \ + $(TINY_USB_SRC_DIR)/class/midi/midi_device.c \ + $(TINY_USB_SRC_DIR)/class/video/video_device.c \ + $(TINY_USB_SRC_DIR)/class/hid/hid_device.c \ + $(TINY_USB_SRC_DIR)/class/usbtmc/usbtmc_device.c \ + $(TINY_USB_SRC_DIR)/class/audio/audio_device.c + + VPATH := $(VPATH):$(STDPERIPH_DIR) -DEVICE_STDPERIPH_SRC := \ - $(STDPERIPH_SRC) \ - $(TINYUSB_SRC) - -ifeq ($(TARGET_MCU),RP2350B) +ifdef RP2350_TARGET TARGET_MCU_LIB_LOWER = rp2350 TARGET_MCU_LIB_UPPER = RP2350 endif #CMSIS VPATH := $(VPATH):$(CMSIS_DIR)/Core/Include:$(CMSIS_DIR)/Device/$(TARGET_MCU_LIB_UPPER)/Include -CMSIS_SRC := \ +CMSIS_SRC := INCLUDE_DIRS += \ $(TARGET_PLATFORM_DIR) \ $(TARGET_PLATFORM_DIR)/include \ $(TARGET_PLATFORM_DIR)/usb \ - $(TARGET_PLATFORM_DIR)/startup \ + $(TARGET_PLATFORM_DIR)/startup + +SYS_INCLUDE_DIRS = \ $(SDK_DIR)/common/pico_bit_ops_headers/include \ $(SDK_DIR)/common/pico_base_headers/include \ $(SDK_DIR)/common/boot_picoboot_headers/include \ @@ -166,25 +225,139 @@ INCLUDE_DIRS += \ $(SDK_DIR)/$(TARGET_MCU_LIB_LOWER)/hardware_structs/include \ $(LIB_MAIN_DIR)/tinyUSB/src +SYS_INCLUDE_DIRS += \ + $(SDK_DIR)/rp2350/boot_stage2/include + #Flags ARCH_FLAGS = -mthumb -mcpu=cortex-m33 -march=armv8-m.main+fp+dsp -mcmse -DEVICE_FLAGS = +# Automatically treating constants as single-precision breaks pico-sdk (-Werror=double-promotion) +# We should go through BF code and explicitly declare constants as single rather than double as required, +# rather than relying on this flag. +# ARCH_FLAGS += -fsingle-precision-constant + +PICO_STDIO_USB_FLAGS = \ + -DLIB_PICO_PRINTF=1 \ + -DLIB_PICO_PRINTF_PICO=1 \ + -DLIB_PICO_STDIO=1 \ + -DLIB_PICO_STDIO_USB=1 \ + -DCFG_TUSB_DEBUG=0 \ + -DCFG_TUSB_MCU=OPT_MCU_RP2040 \ + -DCFG_TUSB_OS=OPT_OS_PICO \ + -DLIB_PICO_FIX_RP2040_USB_DEVICE_ENUMERATION=1 \ + -DPICO_RP2040_USB_DEVICE_UFRAME_FIX=1 \ + -DPICO_STDIO_USB_CONNECT_WAIT_TIMEOUT_MS=3000 \ + -DLIB_PICO_UNIQUEID=1 + +PICO_STDIO_LD_FLAGS = \ + -Wl,--wrap=sprintf \ + -Wl,--wrap=snprintf \ + -Wl,--wrap=vsnprintf \ + -Wl,--wrap=printf \ + -Wl,--wrap=vprintf \ + -Wl,--wrap=puts \ + -Wl,--wrap=putchar \ + -Wl,--wrap=getchar + +EXTRA_LD_FLAGS += $(PICO_STDIO_LD_FLAGS) $(PICO_TRACE_LD_FLAGS) + +ifdef RP2350_TARGET + +# Q. do we need LIB_BOOT_STAGE_2_HEADERS? +# TODO review LIB_PICO options +DEVICE_FLAGS += \ + -D$(RP2350_TARGET) \ + -DPICO_RP2350_A2_SUPPORTED=1 \ + -DLIB_BOOT_STAGE2_HEADERS=1 \ + -DLIB_PICO_ATOMIC=1 \ + -DLIB_PICO_BIT_OPS=1 \ + -DLIB_PICO_BIT_OPS_PICO=1 \ + -DLIB_PICO_CLIB_INTERFACE=1 \ + -DLIB_PICO_CRT0=1 \ + -DLIB_PICO_CXX_OPTIONS=1 \ + -DLIB_PICO_DIVIDER=1 \ + -DLIB_PICO_DIVIDER_COMPILER=1 \ + -DLIB_PICO_DOUBLE=1 \ + -DLIB_PICO_DOUBLE_PICO=1 \ + -DLIB_PICO_FLOAT=1 \ + -DLIB_PICO_FLOAT_PICO=1 \ + -DLIB_PICO_FLOAT_PICO_VFP=1 \ + -DLIB_PICO_INT64_OPS=1 \ + -DLIB_PICO_INT64_OPS_COMPILER=1 \ + -DLIB_PICO_MALLOC=1 \ + -DLIB_PICO_MEM_OPS=1 \ + -DLIB_PICO_MEM_OPS_COMPILER=1 \ + -DLIB_PICO_NEWLIB_INTERFACE=1 \ + -DLIB_PICO_PLATFORM=1 \ + -DLIB_PICO_PLATFORM_COMPILER=1 \ + -DLIB_PICO_PLATFORM_PANIC=1 \ + -DLIB_PICO_PLATFORM_SECTIONS=1 \ + -DLIB_PICO_PRINTF=1 \ + -DLIB_PICO_PRINTF_PICO=1 \ + -DLIB_PICO_RUNTIME=1 \ + -DLIB_PICO_RUNTIME_INIT=1 \ + -DLIB_PICO_STANDARD_BINARY_INFO=1 \ + -DLIB_PICO_STANDARD_LINK=1 \ + -DLIB_PICO_STDIO=1 \ + -DLIB_PICO_STDIO_UART=1 \ + -DLIB_PICO_STDLIB=1 \ + -DLIB_PICO_SYNC=1 \ + -DLIB_PICO_SYNC_CRITICAL_SECTION=1 \ + -DLIB_PICO_SYNC_MUTEX=1 \ + -DLIB_PICO_SYNC_SEM=1 \ + -DLIB_PICO_TIME=1 \ + -DLIB_PICO_TIME_ADAPTER=1 \ + -DLIB_PICO_UTIL=1 \ + -DPICO_32BIT=1 \ + -DPICO_BUILD=1 \ + -DPICO_COPY_TO_RAM=0 \ + -DPICO_CXX_ENABLE_EXCEPTIONS=0 \ + -DPICO_NO_FLASH=0 \ + -DPICO_NO_HARDWARE=0 \ + -DPICO_ON_DEVICE=1 \ + -DPICO_RP2350=1 \ + -DPICO_USE_BLOCKED_RAM=0 -ifeq ($(TARGET_MCU),RP2350B) -DEVICE_FLAGS += -DRP2350B -DLIB_BOOT_STAGE2_HEADERS=1 -DLIB_PICO_ATOMIC=1 -DLIB_PICO_BIT_OPS=1 -DLIB_PICO_BIT_OPS_PICO=1 -DLIB_PICO_CLIB_INTERFACE=1 -DLIB_PICO_CRT0=1 -DLIB_PICO_CXX_OPTIONS=1 -DLIB_PICO_DIVIDER=1 -DLIB_PICO_DIVIDER_COMPILER=1 -DLIB_PICO_DOUBLE=1 -DLIB_PICO_DOUBLE_PICO=1 -DLIB_PICO_FLOAT=1 -DLIB_PICO_FLOAT_PICO=1 -DLIB_PICO_FLOAT_PICO_VFP=1 -DLIB_PICO_INT64_OPS=1 -DLIB_PICO_INT64_OPS_COMPILER=1 -DLIB_PICO_MALLOC=1 -DLIB_PICO_MEM_OPS=1 -DLIB_PICO_MEM_OPS_COMPILER=1 -DLIB_PICO_NEWLIB_INTERFACE=1 -DLIB_PICO_PLATFORM=1 -DLIB_PICO_PLATFORM_COMPILER=1 -DLIB_PICO_PLATFORM_PANIC=1 -DLIB_PICO_PLATFORM_SECTIONS=1 -DLIB_PICO_PRINTF=1 -DLIB_PICO_PRINTF_PICO=1 -DLIB_PICO_RUNTIME=1 -DLIB_PICO_RUNTIME_INIT=1 -DLIB_PICO_STANDARD_BINARY_INFO=1 -DLIB_PICO_STANDARD_LINK=1 -DLIB_PICO_STDIO=1 -DLIB_PICO_STDIO_UART=1 -DLIB_PICO_STDLIB=1 -DLIB_PICO_SYNC=1 -DLIB_PICO_SYNC_CRITICAL_SECTION=1 -DLIB_PICO_SYNC_MUTEX=1 -DLIB_PICO_SYNC_SEM=1 -DLIB_PICO_TIME=1 -DLIB_PICO_TIME_ADAPTER=1 -DLIB_PICO_UTIL=1 -DPICO_32BIT=1 -DPICO_BUILD=1 -DPICO_COPY_TO_RAM=0 -DPICO_CXX_ENABLE_EXCEPTIONS=0 -DPICO_NO_FLASH=0 -DPICO_NO_HARDWARE=0 -DPICO_ON_DEVICE=1 -DPICO_RP2350=1 -DPICO_USE_BLOCKED_RAM=0 LD_SCRIPT = $(LINKER_DIR)/pico_rp2350.ld STARTUP_SRC = PICO/startup/bs2_default_padded_checksummed.S -MCU_FLASH_SIZE = 4096 + # Override the OPTIMISE_SPEED compiler setting to save flash space on these 512KB targets. # Performance is only slightly affected but around 50 kB of flash are saved. OPTIMISE_SPEED = -O2 -STDPERIPH_SRC += \ - common/RP2350/pico_platform/platform.c +# TODO tidy up - +# we might lose some/all of pico_stdio_*, pico_printf if not using PICO_TRACE +PICO_LIB_SRC += \ + rp2_common/pico_stdio/stdio.c \ + rp2_common/pico_printf/printf.c -MCU_SRC += \ - system_RP2350.c +ifneq ($(PICO_TRACE),) +PICO_LIB_SRC += \ + rp2_common/pico_stdio_uart/stdio_uart.c +endif + +PICO_STDIO_USB_SRC = \ + rp2_common/pico_stdio_usb/stdio_usb.c \ + rp2_common/pico_stdio_usb/reset_interface.c \ + rp2_common/pico_fix/rp2040_usb_device_enumeration/rp2040_usb_device_enumeration.c \ + rp2_common/pico_bit_ops/bit_ops_aeabi.S \ + rp2_common/pico_stdio_usb/stdio_usb_descriptors.c + +# TODO check +# rp2_common/pico_stdio_usb/stdio_usb_descriptors.c \ +# vs PICO/usb/usb_descriptors.c + +PICO_LIB_SRC += $(PICO_STDIO_USB_SRC) + +# Work around https://github.com/raspberrypi/pico-sdk/issues/2451 +# by using system headers, which are more tolerant of macro redefinitions. + +SYS_INCLUDE_DIRS += \ + $(SDK_DIR)/rp2_common/pico_fix/rp2040_usb_device_enumeration/include + +# TODO use system_RP2350.c instead of writing into PICO/system.c +# MCU_COMMON_SRC += \ +# system_RP2350.c else $(error Unknown MCU for Raspberry PICO target) @@ -192,6 +365,8 @@ endif DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DPICO +DEVICE_FLAGS += $(PICO_STDIO_USB_FLAGS) + MCU_COMMON_SRC = \ drivers/accgyro/accgyro_mpu.c \ drivers/dshot_bitbang_decode.c \ @@ -213,7 +388,20 @@ MCU_COMMON_SRC = \ PICO/exti_pico.c \ PICO/config_flash.c \ PICO/serial_usb_vcp_pico.c \ - PICO/usb/usb_cdc.c \ - PICO/usb/usb_descriptors.c + PICO/usb/usb_cdc.c -DEVICE_FLAGS += +DEVICE_STDPERIPH_SRC := \ + $(PICO_LIB_SRC) \ + $(STDPERIPH_SRC) \ + $(TINYUSB_SRC) \ + $(PICO_TRACE_SRC) + +# Add a target-specific definition for PICO_LIB_TARGETS in order +# to remove -flto=auto for pico-sdk file compilation +# (to avoid problem of interaction with wrapping -Wl,wrap=...). +# Place this at the end because we require PICO_LIB_TARGETS to be expanded before setting the target + +PICO_LIB_OBJS = $(addsuffix .o, $(basename $(PICO_LIB_SRC))) +PICO_LIB_OBJS += $(addsuffix .o, $(basename $(PICO_TRACE_SRC))) +PICO_LIB_TARGETS := $(foreach pobj, $(PICO_LIB_OBJS), %/$(pobj)) +$(PICO_LIB_TARGETS): CC_DEFAULT_OPTIMISATION := $(PICO_LIB_OPTIMISATION) diff --git a/src/platform/PICO/mk/PICO_trace.mk b/src/platform/PICO/mk/PICO_trace.mk new file mode 100644 index 0000000000..41d0cb64a0 --- /dev/null +++ b/src/platform/PICO/mk/PICO_trace.mk @@ -0,0 +1,4 @@ +PICO_WRAPPED_FUNCTIONS = main +PICO_WRAPPED_FUNCTIONS += init initEEPROM isEEPROMVersionValid +PICO_TRACE_LD_FLAGS += $(foreach fn, $(PICO_WRAPPED_FUNCTIONS), -Wl,--wrap=$(fn)) +PICO_TRACE_SRC += PICO/pico_trace.c diff --git a/src/platform/PICO/pico_trace.c b/src/platform/PICO/pico_trace.c new file mode 100644 index 0000000000..49c5d6aa5f --- /dev/null +++ b/src/platform/PICO/pico_trace.c @@ -0,0 +1,25 @@ +#include "pico_trace.h" + +// Wrap main to insert the initialisation code. +extern int main(int argc, char * argv[]); +extern int REAL_FUNC(main)(int argc, char * argv[]); +int WRAPPER_FUNC(main)(int argc, char * argv[]) +{ + stdio_init_all(); + return REAL_FUNC(main)(argc, argv); +} + +#define TRACEvoidvoid(x) \ + extern void x(void);\ + extern void REAL_FUNC(x)(void); \ + void WRAPPER_FUNC(x)(void)\ + {\ + tprintf("*** enter " #x " ***");\ + REAL_FUNC(x)();\ + tprintf("*** exit " #x " ***");\ + } + +// remember to add to PICO_WRAPPED_FUNCTIONS in PICO_trace.mk +TRACEvoidvoid(init) +TRACEvoidvoid(initEEPROM) +TRACEvoidvoid(isEEPROMVersionValid) diff --git a/src/platform/PICO/pico_trace.h b/src/platform/PICO/pico_trace.h new file mode 100644 index 0000000000..78ac3799b8 --- /dev/null +++ b/src/platform/PICO/pico_trace.h @@ -0,0 +1,5 @@ +#include "pico/stdio.h" +#include "pico/platform/compiler.h" + +#define tprintf(fmt,...) do {stdio_printf(fmt, ## __VA_ARGS__); stdio_printf("\n"); } while (0) + diff --git a/src/platform/PICO/platform_mcu.h b/src/platform/PICO/platform_mcu.h index 4d386f58fd..578e151f70 100644 --- a/src/platform/PICO/platform_mcu.h +++ b/src/platform/PICO/platform_mcu.h @@ -21,7 +21,13 @@ #pragma once -#define _ADDRESSMAP_H +#include "RP2350.h" + +#include "pico.h" +#include "pico/stdlib.h" +#include "hardware/spi.h" +#include "hardware/dma.h" +#include "hardware/flash.h" #define NVIC_PriorityGroup_2 0x500 @@ -31,17 +37,6 @@ #define SPI_IO_AF_SDI_CFG 0 #define SPI_IO_CS_CFG 0 -// Register address offsets for atomic RMW aliases -#define REG_ALIAS_RW_BITS (_u(0x0) << _u(12)) -#define REG_ALIAS_XOR_BITS (_u(0x1) << _u(12)) -#define REG_ALIAS_SET_BITS (_u(0x2) << _u(12)) -#define REG_ALIAS_CLR_BITS (_u(0x3) << _u(12)) - -#include "RP2350.h" -#include "pico/stdlib.h" -#include "hardware/spi.h" -#include "hardware/dma.h" - #if defined(RP2350A) || defined(RP2350B) typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState; @@ -55,7 +50,7 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState; #define DMA_TypeDef void* #define DMA_InitTypeDef void* //#define DMA_Channel_TypeDef -#define SPI_TypeDef SPI0_Type + #define ADC_TypeDef void* #define USART_TypeDef uart_inst_t #define TIM_OCInitTypeDef void* @@ -70,9 +65,12 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState; //#define EXTI_InitTypeDef //#define IRQn_Type void* +// We have to use SPI0_Type (or void) because config will pass in SPI0, SPI1, +// which are defined in pico-sdk as SPI0_Type*. +// SPI_INST converts to the correct type for use in pico-sdk functions. +#define SPI_TypeDef SPI0_Type #define SPI_INST(spi) ((spi_inst_t *)(spi)) - #endif #define DMA_DATA_ZERO_INIT @@ -106,7 +104,6 @@ extern uint32_t systemUniqueId[3]; #define UART_TX_BUFFER_ATTRIBUTE #define UART_RX_BUFFER_ATTRIBUTE -#define MAX_SPI_PIN_SEL 4 #define SERIAL_TRAIT_PIN_CONFIG 1 #define xDMA_GetCurrDataCounter(dma_resource) (((dma_channel_hw_t *)(dma_resource))->transfer_count) diff --git a/src/platform/PICO/target/RP2350A/target.h b/src/platform/PICO/target/RP2350A/target.h new file mode 100644 index 0000000000..3c7df6607c --- /dev/null +++ b/src/platform/PICO/target/RP2350A/target.h @@ -0,0 +1,247 @@ +/* + * 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 + +#ifdef PICO_STDIO_TEST +void _bprintf(const char * format, ...); +//#define bprintf(fmt,...) _bprintf(fmt, ## __VA_ARGS__) +#define bprintf(fmt,...) do {stdio_printf(fmt, ## __VA_ARGS__); stdio_printf("\n"); } while (0) +//int __wrap_printf(const char * fmt, ...); +//#define bprintf __wrap_printf +#else +#define bprintf(fmt,...) +#endif + + +#ifndef RP2350A +#define RP2350A +#endif + +#ifndef TARGET_BOARD_IDENTIFIER +#define TARGET_BOARD_IDENTIFIER "235B" +// TODO 235A? +#endif + +#ifndef USBD_PRODUCT_STRING +#define USBD_PRODUCT_STRING "Betaflight RP2350B" +// TODO +#endif + +#define USE_IO +#define USE_UART0 +#define USE_UART1 + +#define USE_SPI +#define USE_SPI_DEVICE_0 +#define USE_SPI_DEVICE_1 + +// one of these ... +// #define USE_SPI_DMA_ENABLE_EARLY +#define USE_SPI_DMA_ENABLE_LATE + +#undef USE_SOFTSERIAL1 +#undef USE_SOFTSERIAL2 + +#define USE_VCP + +#undef USE_TRANSPONDER +#undef USE_FLASH +#undef USE_FLASH_CHIP +#undef USE_SDCARD + +#undef USE_TIMER +#undef USE_I2C +#undef USE_RCC +#undef USE_CLI +#undef USE_RX_PWM +#undef USE_RX_PPM +#undef USE_RX_SPI +#undef USE_RX_CC2500 +#undef USE_SERIAL_4WAY_BLHELI_INTERFACE +#undef USE_SERIAL_4WAY_BLHELI_BOOTLOADER +#undef USE_SERIAL_4WAY_SK_BOOTLOADER +#undef USE_MULTI_GYRO +#undef USE_BARO + +#undef USE_RANGEFINDER_HCSR04 +#undef USE_CRSF +#undef USE_TELEMETRY_CRSF +#undef USE_RX_EXPRESSLRS +#undef USE_MAX7456 +#undef USE_MAG +#undef USE_MAG_HMC5883 +#undef USE_MAG_SPI_HMC5883 +#undef USE_VTX_RTC6705 +#undef USE_VTX_RTC6705_SOFTSPI +#undef USE_RX_SX1280 +#undef USE_SRXL +#undef USE_TELEMETRY +#undef USE_OSD +#undef USE_SPEKTRUM +#undef USE_SPEKTRUM_BIND +#undef USE_MSP +#undef USE_MSP_UART +#undef USE_MSP_DISPLAYPORT +#undef USE_GPS +#undef USE_GPS_UBLOX +#undef USE_GPS_MTK +#undef USE_GPS_NMEA +#undef USE_GPS_SERIAL +#undef USE_GPS_SONAR +#undef USE_GPS_UBLOX7 +#undef USE_GPS_UBLOX8 +#undef USE_GPS_RESCUE + +#undef USE_VTX +#undef USE_VTX_TRAMP +#undef USE_VTX_SMARTAUDIO +#undef USE_SPEKTRUM_VTX_CONTROL +#undef USE_VTX_COMMON +#undef USE_FLASH +#undef USE_FLASH_CHIP +#undef USE_FLASH_M25P16 +#undef USE_FLASH_W25N01G +#undef USE_FLASH_W25N02K +#undef USE_FLASH_W25M +#undef USE_FLASH_W25M512 +#undef USE_FLASH_W25M02G +#undef USE_FLASH_W25Q128FV +#undef USE_FLASH_PY25Q128HA +#undef USE_FLASH_W25Q64FV + +#undef USE_RPM_LIMIT + +#undef USE_SERVOS +#undef USE_LED_STRIP +#undef USE_OSD +#undef USE_OSD_SD +#undef USE_OSD_HD +#undef USE_OSD_QUICK_MENU +#undef USE_GPS +#undef USE_POSITION_HOLD + +//#define FLASH_PAGE_SIZE 0x1 +#define CONFIG_IN_FLASH + +// Pico flash writes are all aligned and in batches of FLASH_PAGE_SIZE (256) +#define FLASH_CONFIG_STREAMER_BUFFER_SIZE FLASH_PAGE_SIZE +#define FLASH_CONFIG_BUFFER_TYPE uint8_t + +/* to be moved to a config file once target if working + defaults as per Laurel board for now */ + +#define LED0_PIN P25 +#undef LED1_PIN +#undef LED2_PIN + +#define SPI0_SCK_PIN P2 +#define SPI0_SDI_PIN P4 +#define SPI0_SDO_PIN P3 + +#define SPI1_SCK_PIN P26 +#define SPI1_SDI_PIN P24 +#define SPI1_SDO_PIN P27 + +#define SDCARD_CS_PIN P25 +#define FLASH_CS_PIN P25 +#define MAX7456_SPI_CS_PIN P17 + +#define GYRO_1_CS_PIN P1 +#define GYRO_2_CS_PIN NONE + +#define MAX7456_SPI_INSTANCE SPI1 +#define SDCARD_SPI_INSTANCE SPI1 +#define GYRO_1_SPI_INSTANCE SPI0 + +#define USE_GYRO +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC +#define USE_ACC_SPI_ICM42688P +//#define USE_FLASH +//#define USE_FLASH_W25Q128FV +//#define USE_MAX7456 + +/* + +SPI0_CS P1 +SPI0_SCLK P2 +SPI0_COPI P3 +SPI0_CIPO P4 +BUZZER P5 +LED0 P6 +LED1 P7 +UART1_TX P8 +UART1_RX P9 +I2C1_SDA P10 +I2C1_SCL P11 +UART0_TX P12 +UART0_RX P13 + +OSD_CS P17 + +UART2_TX P20 +UART2_RX P21 + +GYRO_INT P22 + +GYRO_CLK P23 + +SPI1_CIPO P24 +SPI1_CS P25 +SPI1_SCLK P26 +SPI1_COPI P27 + +MOTOR1 P28 +MOTOR2 P29 +MOTOR3 P30 +MOTOR4 P31 + +SPARE1 P32 +SPARE2 P33 + +UART3_TX P34 +UART3_RX P35 + +DVTX_SBUS_RX P36 +TELEM_RX P37 +LED_STRIP P38 +RGB_LED P39 + +VBAT_SENSE P40 +CURR_SENSE P41 +ADC_SPARE P42 + +I2C0_SDA P44 +I2C0_SCL P45 + +SPARE3 P47 + +*/ + +#define SPIDEV_COUNT 2 +#define MAX_SPI_PIN_SEL 4 + +#define UART_RX_BUFFER_SIZE 1024 +#define UART_TX_BUFFER_SIZE 1024 + +#define UARTHARDWARE_MAX_PINS 8 +#define UART_TRAIT_AF_PORT 1 diff --git a/src/platform/PICO/target/RP2350B/target.h b/src/platform/PICO/target/RP2350B/target.h index d28d57bd54..4b35bf6834 100644 --- a/src/platform/PICO/target/RP2350B/target.h +++ b/src/platform/PICO/target/RP2350B/target.h @@ -21,6 +21,17 @@ #pragma once +#ifdef PICO_STDIO_TEST +void _bprintf(const char * format, ...); +//#define bprintf(fmt,...) _bprintf(fmt, ## __VA_ARGS__) +#define bprintf(fmt,...) do {stdio_printf(fmt, ## __VA_ARGS__); stdio_printf("\n"); } while (0) +//int __wrap_printf(const char * fmt, ...); +//#define bprintf __wrap_printf +#else +#define bprintf(fmt,...) +#endif + + #ifndef RP2350B #define RP2350B #endif @@ -41,6 +52,10 @@ #define USE_SPI_DEVICE_0 #define USE_SPI_DEVICE_1 +// one of these ... +// #define USE_SPI_DMA_ENABLE_EARLY +#define USE_SPI_DMA_ENABLE_LATE + #undef USE_SOFTSERIAL1 #undef USE_SOFTSERIAL2 @@ -83,6 +98,7 @@ #undef USE_SPEKTRUM_BIND #undef USE_MSP #undef USE_MSP_UART +#undef USE_MSP_DISPLAYPORT #undef USE_GPS #undef USE_GPS_UBLOX #undef USE_GPS_MTK @@ -121,20 +137,22 @@ #undef USE_GPS #undef USE_POSITION_HOLD - //#define FLASH_PAGE_SIZE 0x1 #define CONFIG_IN_FLASH -#define FLASH_CONFIG_STREAMER_BUFFER_SIZE 256 +// Pico flash writes are all aligned and in batches of FLASH_PAGE_SIZE (256) +#define FLASH_CONFIG_STREAMER_BUFFER_SIZE FLASH_PAGE_SIZE #define FLASH_CONFIG_BUFFER_TYPE uint8_t -/* to be moved to a config file once target if working */ +/* to be moved to a config file once target if working + defaults as per Laurel board for now */ + #define LED0_PIN P6 #define LED1_PIN P7 -#define SPI0_SCK_PIN P5 -#define SPI0_SDI_PIN P6 -#define SPI0_SDO_PIN P7 +#define SPI0_SCK_PIN P2 +#define SPI0_SDI_PIN P4 +#define SPI0_SDO_PIN P3 #define SPI1_SCK_PIN P26 #define SPI1_SDI_PIN P24 @@ -217,8 +235,10 @@ SPARE3 P47 */ #define SPIDEV_COUNT 2 +#define MAX_SPI_PIN_SEL 6 + #define UART_RX_BUFFER_SIZE 1024 #define UART_TX_BUFFER_SIZE 1024 -#define UARTHARDWARE_MAX_PINS 4 +#define UARTHARDWARE_MAX_PINS 12 #define UART_TRAIT_AF_PORT 1