mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-12 19:10:32 +03:00
Removing PICO directory, to be reinstated from RP2350 branch (#14413)
This commit is contained in:
parent
62dd5f6e4c
commit
98582c0c18
8 changed files with 1 additions and 624 deletions
|
@ -43,7 +43,7 @@
|
|||
|
||||
// split ioTag bits between pin and port
|
||||
// port is encoded as +1 to avoid collision with 0x0 (false as bool)
|
||||
#ifndef DEFIO_PORT_PINS
|
||||
#ifndef DEFIO_PORT_PINS
|
||||
// pins per port
|
||||
#define DEFIO_PORT_PINS 16
|
||||
#endif
|
||||
|
|
|
@ -1,302 +0,0 @@
|
|||
/* Based on GCC ARM embedded samples.
|
||||
Defines the following symbols for use by code:
|
||||
__exidx_start
|
||||
__exidx_end
|
||||
__etext
|
||||
__data_start__
|
||||
__preinit_array_start
|
||||
__preinit_array_end
|
||||
__init_array_start
|
||||
__init_array_end
|
||||
__fini_array_start
|
||||
__fini_array_end
|
||||
__data_end__
|
||||
__bss_start__
|
||||
__bss_end__
|
||||
__end__
|
||||
end
|
||||
__HeapLimit
|
||||
__StackLimit
|
||||
__StackTop
|
||||
__stack (== StackTop)
|
||||
*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
FLASH(rx) : ORIGIN = 0x10000000, LENGTH = 4m
|
||||
RAM(rwx) : ORIGIN = 0x20000000, LENGTH = 512k
|
||||
SCRATCH_X(rwx) : ORIGIN = 0x20080000, LENGTH = 4k
|
||||
SCRATCH_Y(rwx) : ORIGIN = 0x20081000, LENGTH = 4k
|
||||
}
|
||||
|
||||
ENTRY(_entry_point)
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
.flash_begin : {
|
||||
__flash_binary_start = .;
|
||||
} > FLASH
|
||||
|
||||
/* The bootrom will enter the image at the point indicated in your
|
||||
IMAGE_DEF, which is usually the reset handler of your vector table.
|
||||
|
||||
The debugger will use the ELF entry point, which is the _entry_point
|
||||
symbol, and in our case is *different from the bootrom's entry point.*
|
||||
This is used to go back through the bootrom on debugger launches only,
|
||||
to perform the same initial flash setup that would be performed on a
|
||||
cold boot.
|
||||
*/
|
||||
|
||||
.text : {
|
||||
__logical_binary_start = .;
|
||||
KEEP (*(.vectors))
|
||||
KEEP (*(.binary_info_header))
|
||||
__binary_info_header_end = .;
|
||||
KEEP (*(.embedded_block))
|
||||
__embedded_block_end = .;
|
||||
KEEP (*(.reset))
|
||||
/* TODO revisit this now memset/memcpy/float in ROM */
|
||||
/* bit of a hack right now to exclude all floating point and time critical (e.g. memset, memcpy) code from
|
||||
* FLASH ... we will include any thing excluded here in .data below by default */
|
||||
*(.init)
|
||||
*libgcc.a:cmse_nonsecure_call.o
|
||||
*(EXCLUDE_FILE(*libgcc.a: *libc.a:*lib_a-mem*.o *libm.a:) .text*)
|
||||
*(.fini)
|
||||
/* Pull all c'tors into .text */
|
||||
*crtbegin.o(.ctors)
|
||||
*crtbegin?.o(.ctors)
|
||||
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors)
|
||||
*(SORT(.ctors.*))
|
||||
*(.ctors)
|
||||
/* Followed by destructors */
|
||||
*crtbegin.o(.dtors)
|
||||
*crtbegin?.o(.dtors)
|
||||
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors)
|
||||
*(SORT(.dtors.*))
|
||||
*(.dtors)
|
||||
|
||||
. = ALIGN(4);
|
||||
/* preinit data */
|
||||
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||
KEEP(*(SORT(.preinit_array.*)))
|
||||
KEEP(*(.preinit_array))
|
||||
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||
|
||||
. = ALIGN(4);
|
||||
/* init data */
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
KEEP(*(SORT(.init_array.*)))
|
||||
KEEP(*(.init_array))
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
|
||||
. = ALIGN(4);
|
||||
/* finit data */
|
||||
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||
*(SORT(.fini_array.*))
|
||||
*(.fini_array)
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
|
||||
*(.eh_frame*)
|
||||
. = ALIGN(4);
|
||||
} > FLASH
|
||||
|
||||
/* Note the boot2 section is optional, and should be discarded if there is
|
||||
no reference to it *inside* the binary, as it is not called by the
|
||||
bootrom. (The bootrom performs a simple best-effort XIP setup and
|
||||
leaves it to the binary to do anything more sophisticated.) However
|
||||
there is still a size limit of 256 bytes, to ensure the boot2 can be
|
||||
stored in boot RAM.
|
||||
|
||||
Really this is a "XIP setup function" -- the name boot2 is historic and
|
||||
refers to its dual-purpose on RP2040, where it also handled vectoring
|
||||
from the bootrom into the user image.
|
||||
*/
|
||||
|
||||
.boot2 : {
|
||||
__boot2_start__ = .;
|
||||
*(.boot2)
|
||||
__boot2_end__ = .;
|
||||
} > FLASH
|
||||
|
||||
ASSERT(__boot2_end__ - __boot2_start__ <= 256,
|
||||
"ERROR: Pico second stage bootloader must be no more than 256 bytes in size")
|
||||
|
||||
.rodata : {
|
||||
*(EXCLUDE_FILE(*libgcc.a: *libc.a:*lib_a-mem*.o *libm.a:) .rodata*)
|
||||
*(.srodata*)
|
||||
. = ALIGN(4);
|
||||
*(SORT_BY_ALIGNMENT(SORT_BY_NAME(.flashdata*)))
|
||||
. = ALIGN(4);
|
||||
} > FLASH
|
||||
|
||||
.ARM.extab :
|
||||
{
|
||||
*(.ARM.extab* .gnu.linkonce.armextab.*)
|
||||
} > FLASH
|
||||
|
||||
__exidx_start = .;
|
||||
.ARM.exidx :
|
||||
{
|
||||
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
|
||||
} > FLASH
|
||||
__exidx_end = .;
|
||||
|
||||
/* Machine inspectable binary information */
|
||||
. = ALIGN(4);
|
||||
__binary_info_start = .;
|
||||
.binary_info :
|
||||
{
|
||||
KEEP(*(.binary_info.keep.*))
|
||||
*(.binary_info.*)
|
||||
} > FLASH
|
||||
__binary_info_end = .;
|
||||
. = ALIGN(4);
|
||||
|
||||
.ram_vector_table (NOLOAD): {
|
||||
*(.ram_vector_table)
|
||||
} > RAM
|
||||
|
||||
.uninitialized_data (NOLOAD): {
|
||||
. = ALIGN(4);
|
||||
*(.uninitialized_data*)
|
||||
} > RAM
|
||||
|
||||
.data : {
|
||||
__data_start__ = .;
|
||||
*(vtable)
|
||||
|
||||
*(.time_critical*)
|
||||
|
||||
/* remaining .text and .rodata; i.e. stuff we exclude above because we want it in RAM */
|
||||
*(.text*)
|
||||
. = ALIGN(4);
|
||||
*(.rodata*)
|
||||
. = ALIGN(4);
|
||||
|
||||
*(.data*)
|
||||
*(.sdata*)
|
||||
|
||||
. = ALIGN(4);
|
||||
*(.after_data.*)
|
||||
. = ALIGN(4);
|
||||
/* preinit data */
|
||||
PROVIDE_HIDDEN (__mutex_array_start = .);
|
||||
KEEP(*(SORT(.mutex_array.*)))
|
||||
KEEP(*(.mutex_array))
|
||||
PROVIDE_HIDDEN (__mutex_array_end = .);
|
||||
|
||||
*(.jcr)
|
||||
. = ALIGN(4);
|
||||
} > RAM AT> FLASH
|
||||
|
||||
.tdata : {
|
||||
. = ALIGN(4);
|
||||
*(.tdata .tdata.* .gnu.linkonce.td.*)
|
||||
/* All data end */
|
||||
__tdata_end = .;
|
||||
} > RAM AT> FLASH
|
||||
PROVIDE(__data_end__ = .);
|
||||
|
||||
/* __etext is (for backwards compatibility) the name of the .data init source pointer (...) */
|
||||
__etext = LOADADDR(.data);
|
||||
|
||||
.tbss (NOLOAD) : {
|
||||
. = ALIGN(4);
|
||||
__bss_start__ = .;
|
||||
__tls_base = .;
|
||||
*(.tbss .tbss.* .gnu.linkonce.tb.*)
|
||||
*(.tcommon)
|
||||
|
||||
__tls_end = .;
|
||||
} > RAM
|
||||
|
||||
.bss (NOLOAD) : {
|
||||
. = ALIGN(4);
|
||||
__tbss_end = .;
|
||||
|
||||
*(SORT_BY_ALIGNMENT(SORT_BY_NAME(.bss*)))
|
||||
*(COMMON)
|
||||
PROVIDE(__global_pointer$ = . + 2K);
|
||||
*(.sbss*)
|
||||
. = ALIGN(4);
|
||||
__bss_end__ = .;
|
||||
} > RAM
|
||||
|
||||
.heap (NOLOAD):
|
||||
{
|
||||
__end__ = .;
|
||||
end = __end__;
|
||||
KEEP(*(.heap*))
|
||||
} > RAM
|
||||
/* historically on GCC sbrk was growing past __HeapLimit to __StackLimit, however
|
||||
to be more compatible, we now set __HeapLimit explicitly to where the end of the heap is */
|
||||
__HeapLimit = ORIGIN(RAM) + LENGTH(RAM);
|
||||
|
||||
/* Start and end symbols must be word-aligned */
|
||||
.scratch_x : {
|
||||
__scratch_x_start__ = .;
|
||||
*(.scratch_x.*)
|
||||
. = ALIGN(4);
|
||||
__scratch_x_end__ = .;
|
||||
} > SCRATCH_X AT > FLASH
|
||||
__scratch_x_source__ = LOADADDR(.scratch_x);
|
||||
|
||||
.scratch_y : {
|
||||
__scratch_y_start__ = .;
|
||||
*(.scratch_y.*)
|
||||
. = ALIGN(4);
|
||||
__scratch_y_end__ = .;
|
||||
} > SCRATCH_Y AT > FLASH
|
||||
__scratch_y_source__ = LOADADDR(.scratch_y);
|
||||
|
||||
/* .stack*_dummy section doesn't contains any symbols. It is only
|
||||
* used for linker to calculate size of stack sections, and assign
|
||||
* values to stack symbols later
|
||||
*
|
||||
* stack1 section may be empty/missing if platform_launch_core1 is not used */
|
||||
|
||||
/* by default we put core 0 stack at the end of scratch Y, so that if core 1
|
||||
* stack is not used then all of SCRATCH_X is free.
|
||||
*/
|
||||
.stack1_dummy (NOLOAD):
|
||||
{
|
||||
*(.stack1*)
|
||||
} > SCRATCH_X
|
||||
.stack_dummy (NOLOAD):
|
||||
{
|
||||
KEEP(*(.stack*))
|
||||
} > SCRATCH_Y
|
||||
|
||||
.flash_end : {
|
||||
KEEP(*(.embedded_end_block*))
|
||||
PROVIDE(__flash_binary_end = .);
|
||||
} > FLASH =0xaa
|
||||
|
||||
/* stack limit is poorly named, but historically is maximum heap ptr */
|
||||
__StackLimit = ORIGIN(RAM) + LENGTH(RAM);
|
||||
__StackOneTop = ORIGIN(SCRATCH_X) + LENGTH(SCRATCH_X);
|
||||
__StackTop = ORIGIN(SCRATCH_Y) + LENGTH(SCRATCH_Y);
|
||||
__StackOneBottom = __StackOneTop - SIZEOF(.stack1_dummy);
|
||||
__StackBottom = __StackTop - SIZEOF(.stack_dummy);
|
||||
PROVIDE(__stack = __StackTop);
|
||||
|
||||
/* picolibc and LLVM */
|
||||
PROVIDE (__heap_start = __end__);
|
||||
PROVIDE (__heap_end = __HeapLimit);
|
||||
PROVIDE( __tls_align = MAX(ALIGNOF(.tdata), ALIGNOF(.tbss)) );
|
||||
PROVIDE( __tls_size_align = (__tls_size + __tls_align - 1) & ~(__tls_align - 1));
|
||||
PROVIDE( __arm32_tls_tcb_offset = MAX(8, __tls_align) );
|
||||
|
||||
/* llvm-libc */
|
||||
PROVIDE (_end = __end__);
|
||||
PROVIDE (__llvm_libc_heap_limit = __HeapLimit);
|
||||
|
||||
/* Check if data + heap + stack exceeds RAM limit */
|
||||
ASSERT(__StackLimit >= __HeapLimit, "region RAM overflowed")
|
||||
|
||||
ASSERT( __binary_info_header_end - __logical_binary_start <= 1024, "Binary info must be in first 1024 bytes of the binary")
|
||||
ASSERT( __embedded_block_end - __logical_binary_start <= 4096, "Embedded block must be in first 4096 bytes of the binary")
|
||||
|
||||
/* todo assert on extra code */
|
||||
}
|
||||
|
|
@ -1,158 +0,0 @@
|
|||
#
|
||||
# Raspberry PICO Make file include
|
||||
#
|
||||
|
||||
ifeq ($(DEBUG_HARDFAULTS),PICO)
|
||||
CFLAGS += -DDEBUG_HARDFAULTS
|
||||
endif
|
||||
|
||||
SDK_DIR = $(LIB_MAIN_DIR)/pico-sdk
|
||||
|
||||
#CMSIS
|
||||
CMSIS_DIR := $(SDK_DIR)/rp2_common/cmsis/stub/CMSIS
|
||||
|
||||
#STDPERIPH
|
||||
STDPERIPH_DIR = $(SDK_SIR)
|
||||
STDPERIPH_SRC = \
|
||||
|
||||
|
||||
VPATH := $(VPATH):$(STDPERIPH_DIR)
|
||||
|
||||
DEVICE_STDPERIPH_SRC := \
|
||||
$(STDPERIPH_SRC) \
|
||||
$(USBCORE_SRC) \
|
||||
$(USBCDC_SRC) \
|
||||
$(USBHID_SRC) \
|
||||
$(USBMSC_SRC)
|
||||
|
||||
#CMSIS
|
||||
VPATH := $(VPATH):$(CMSIS_DIR)/Core/Include:$(CMSIS_DIR)/Device/$(TARGET_MCU)/Include
|
||||
CMSIS_SRC :=
|
||||
|
||||
#SRC
|
||||
VPATH := $(VPATH):$(STDPERIPH_DIR)
|
||||
|
||||
INCLUDE_DIRS := \
|
||||
$(INCLUDE_DIRS) \
|
||||
$(TARGET_PLATFORM_DIR) \
|
||||
$(TARGET_PLATFORM_DIR)/startup \
|
||||
$(SDK_DIR)/$(TARGET_MCU)/pico_platform/include \
|
||||
$(SDK_DIR)/$(TARGET_MCU)/hardware_regs/include \
|
||||
$(SDK_DIR)/$(TARGET_MCU)/hardware_structs/include \
|
||||
$(SDK_DIR)/common/pico_bit_ops_headers/include \
|
||||
$(SDK_DIR)/common/pico_base_headers/include \
|
||||
$(SDK_DIR)/common/boot_picoboot_headers/include \
|
||||
$(SDK_DIR)/common/pico_usb_reset_interface_headers/include \
|
||||
$(SDK_DIR)/common/pico_time/include \
|
||||
$(SDK_DIR)/common/boot_uf2_headers/include \
|
||||
$(SDK_DIR)/common/pico_divider_headers/include \
|
||||
$(SDK_DIR)/common/boot_picobin_headers/include \
|
||||
$(SDK_DIR)/common/pico_util/include \
|
||||
$(SDK_DIR)/common/pico_stdlib_headers/include \
|
||||
$(SDK_DIR)/common/hardware_claim/include \
|
||||
$(SDK_DIR)/common/pico_binary_info/include \
|
||||
$(SDK_DIR)/common/pico_sync/include \
|
||||
$(SDK_DIR)/rp2_common/pico_stdio_uart/include \
|
||||
$(SDK_DIR)/rp2_common/pico_stdio_usb/include \
|
||||
$(SDK_DIR)/rp2_common/pico_stdio_rtt/include \
|
||||
$(SDK_DIR)/rp2_common/tinyusb/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_rtc/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_boot_lock/include \
|
||||
$(SDK_DIR)/rp2_common/pico_mem_ops/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_exception/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_sync_spin_lock/include \
|
||||
$(SDK_DIR)/rp2_common/pico_runtime_init/include \
|
||||
$(SDK_DIR)/rp2_common/pico_standard_link/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_pio/include \
|
||||
$(SDK_DIR)/rp2_common/pico_platform_compiler/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_divider/include \
|
||||
$(SDK_DIR)/rp2_common/pico_bootsel_via_double_reset/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_powman/include \
|
||||
$(SDK_DIR)/rp2_common/pico_btstack/include \
|
||||
$(SDK_DIR)/rp2_common/pico_cyw43_driver/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_flash/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_ticks/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_dma/include \
|
||||
$(SDK_DIR)/rp2_common/pico_bit_ops/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_clocks/include \
|
||||
$(SDK_DIR)/rp2_common/pico_unique_id/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_dcp/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_watchdog/include \
|
||||
$(SDK_DIR)/rp2_common/pico_rand/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_hazard3/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_uart/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_interp/include \
|
||||
$(SDK_DIR)/rp2_common/pico_printf/include \
|
||||
$(SDK_DIR)/rp2_common/pico_aon_timer/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_riscv_platform_timer/include \
|
||||
$(SDK_DIR)/rp2_common/pico_double/include \
|
||||
$(SDK_DIR)/rp2_common/pico_cyw43_arch/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_vreg/include \
|
||||
$(SDK_DIR)/rp2_common/pico_mbedtls/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_spi/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_rcp/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_riscv/include \
|
||||
$(SDK_DIR)/rp2_common/pico_standard_binary_info/include \
|
||||
$(SDK_DIR)/rp2_common/pico_i2c_slave/include \
|
||||
$(SDK_DIR)/rp2_common/pico_int64_ops/include \
|
||||
$(SDK_DIR)/rp2_common/pico_sha256/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_irq/include \
|
||||
$(SDK_DIR)/rp2_common/pico_divider/include \
|
||||
$(SDK_DIR)/rp2_common/pico_flash/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_sync/include \
|
||||
$(SDK_DIR)/rp2_common/pico_bootrom/include \
|
||||
$(SDK_DIR)/rp2_common/pico_crt0/include \
|
||||
$(SDK_DIR)/rp2_common/pico_clib_interface/include \
|
||||
$(SDK_DIR)/rp2_common/pico_stdio/include \
|
||||
$(SDK_DIR)/rp2_common/pico_runtime/include \
|
||||
$(SDK_DIR)/rp2_common/pico_time_adapter/include \
|
||||
$(SDK_DIR)/rp2_common/pico_platform_panic/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_adc/include \
|
||||
$(SDK_DIR)/rp2_common/cmsis/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_pll/include \
|
||||
$(SDK_DIR)/rp2_common/pico_platform_sections/include \
|
||||
$(SDK_DIR)/rp2_common/boot_bootrom_headers/include \
|
||||
$(SDK_DIR)/rp2_common/pico_fix/include \
|
||||
$(SDK_DIR)/rp2_common/pico_lwip/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_base/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_xosc/include \
|
||||
$(SDK_DIR)/rp2_common/pico_async_context/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_pwm/include \
|
||||
$(SDK_DIR)/rp2_common/pico_stdio_semihosting/include \
|
||||
$(SDK_DIR)/rp2_common/pico_float/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_resets/include \
|
||||
$(SDK_DIR)/rp2_common/pico_cxx_options/include \
|
||||
$(SDK_DIR)/rp2_common/pico_stdlib/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_sha256/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_i2c/include \
|
||||
$(SDK_DIR)/rp2_common/pico_atomic/include \
|
||||
$(SDK_DIR)/rp2_common/pico_multicore/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_gpio/include \
|
||||
$(SDK_DIR)/rp2_common/pico_malloc/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_timer/include \
|
||||
$(CMSIS_DIR)/Core/Include \
|
||||
$(CMSIS_DIR)/Device/$(TARGET_MCU)/Include
|
||||
|
||||
#Flags
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m33 -march=armv8-m.main+fp+dsp -mfloat-abi=softfp -mcmse
|
||||
|
||||
DEVICE_FLAGS =
|
||||
|
||||
ifeq ($(TARGET_MCU),RP2350)
|
||||
DEVICE_FLAGS += -DRP2350 -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 = 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
|
||||
else
|
||||
$(error Unknown MCU for Raspberry PICO target)
|
||||
endif
|
||||
|
||||
DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DPICO
|
||||
|
||||
MCU_COMMON_SRC = \
|
||||
|
||||
|
||||
DEVICE_FLAGS +=
|
|
@ -1,67 +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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#if defined(RP2350)
|
||||
|
||||
#include "RP2350.h"
|
||||
|
||||
typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
|
||||
|
||||
#define I2C_TypeDef I2C0_Type
|
||||
//#define I2C_HandleTypeDef
|
||||
#define GPIO_TypeDef IO_BANK0_Type
|
||||
//#define GPIO_InitTypeDef
|
||||
#define TIM_TypeDef TIMER0_Type
|
||||
//#define TIM_OCInitTypeDef
|
||||
#define DMA_TypeDef DMA_Type
|
||||
//#define DMA_InitTypeDef
|
||||
//#define DMA_Channel_TypeDef
|
||||
#define SPI_TypeDef SPI0_Type
|
||||
#define ADC_TypeDef ADC_Type
|
||||
#define USART_TypeDef UART0_Type
|
||||
#define TIM_OCInitTypeDef TIMER0_Type
|
||||
#define TIM_ICInitTypeDef TIMER0_Type
|
||||
//#define TIM_OCStructInit
|
||||
//#define TIM_Cmd
|
||||
//#define TIM_CtrlPWMOutputs
|
||||
//#define TIM_TimeBaseInit
|
||||
//#define TIM_ARRPreloadConfig
|
||||
//#define SystemCoreClock
|
||||
//#define EXTI_TypeDef
|
||||
//#define EXTI_InitTypeDef
|
||||
|
||||
|
||||
#endif
|
||||
|
||||
#define DEFAULT_CPU_OVERCLOCK 0
|
||||
#define TASK_GYROPID_DESIRED_PERIOD 125 // 125us = 8kHz
|
||||
#define SCHEDULER_DELAY_LIMIT 10
|
||||
|
||||
#define IOCFG_OUT_PP 0
|
||||
#define IOCFG_OUT_OD 0
|
||||
#define IOCFG_AF_PP 0
|
||||
#define IOCFG_AF_OD 0
|
||||
#define IOCFG_IPD 0
|
||||
#define IOCFG_IPU 0
|
||||
#define IOCFG_IN_FLOATING 0
|
||||
|
|
@ -1,25 +0,0 @@
|
|||
// Padded and checksummed version of: /home/black/src/pico/hello/build/pico-sdk/src/rp2350/boot_stage2/bs2_default.bin
|
||||
|
||||
.cpu cortex-m0plus
|
||||
.thumb
|
||||
|
||||
.section .boot2, "ax"
|
||||
|
||||
.global __boot2_entry_point
|
||||
__boot2_entry_point:
|
||||
.byte 0x00, 0xb5, 0x24, 0x4b, 0x21, 0x20, 0x58, 0x60, 0x13, 0xf5, 0x40, 0x53, 0x02, 0x20, 0x98, 0x60
|
||||
.byte 0xd8, 0x60, 0x18, 0x61, 0x58, 0x61, 0x13, 0xf5, 0x0d, 0x23, 0x1f, 0x49, 0x19, 0x60, 0x18, 0x68
|
||||
.byte 0x10, 0xf0, 0x02, 0x0f, 0xfb, 0xd1, 0x35, 0x20, 0x00, 0xf0, 0x2c, 0xf8, 0x02, 0x28, 0x14, 0xd0
|
||||
.byte 0x06, 0x20, 0x58, 0x60, 0x00, 0xf0, 0x22, 0xf8, 0x98, 0x68, 0x01, 0x20, 0x58, 0x60, 0x00, 0x20
|
||||
.byte 0x58, 0x60, 0x02, 0x20, 0x58, 0x60, 0x00, 0xf0, 0x19, 0xf8, 0x98, 0x68, 0x98, 0x68, 0x98, 0x68
|
||||
.byte 0x05, 0x20, 0x00, 0xf0, 0x17, 0xf8, 0x40, 0x08, 0xfa, 0xd2, 0x31, 0xf0, 0x01, 0x01, 0x19, 0x60
|
||||
.byte 0x0e, 0x48, 0xd8, 0x60, 0x4a, 0xf2, 0xeb, 0x00, 0x58, 0x61, 0x0d, 0x48, 0x18, 0x61, 0x4f, 0xf0
|
||||
.byte 0xa0, 0x51, 0x09, 0x78, 0x20, 0xf4, 0x80, 0x50, 0x18, 0x61, 0x00, 0xbd, 0x18, 0x68, 0x80, 0x08
|
||||
.byte 0xfc, 0xd2, 0x70, 0x47, 0x00, 0xb5, 0x58, 0x60, 0x58, 0x60, 0xff, 0xf7, 0xf7, 0xff, 0x98, 0x68
|
||||
.byte 0x98, 0x68, 0x00, 0xbd, 0x00, 0x00, 0x04, 0x40, 0x41, 0x00, 0x80, 0x07, 0x02, 0x02, 0x00, 0x40
|
||||
.byte 0xa8, 0x92, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||
.byte 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||
.byte 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||
.byte 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||
.byte 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||
.byte 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
|
@ -1,69 +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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#ifndef TARGET_BOARD_IDENTIFIER
|
||||
#define TARGET_BOARD_IDENTIFIER "R235"
|
||||
#endif
|
||||
|
||||
#ifndef USBD_PRODUCT_STRING
|
||||
#define USBD_PRODUCT_STRING "Betaflight RP2350"
|
||||
#endif
|
||||
|
||||
#undef USE_DMA
|
||||
#undef USE_FLASH
|
||||
#undef USE_FLASH_CHIP
|
||||
|
||||
#undef USE_TIMER
|
||||
#undef USE_SPI
|
||||
#undef USE_I2C
|
||||
#undef USE_UART
|
||||
#undef USE_DSHOT
|
||||
#undef USE_RCC
|
||||
|
||||
#define GPIOA_BASE ((intptr_t)0x0001)
|
||||
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
#define TARGET_IO_PORTE 0xffff
|
||||
#define TARGET_IO_PORTF 0xffff
|
||||
|
||||
#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
|
||||
|
||||
#define FLASH_PAGE_SIZE 0x1000
|
||||
#define CONFIG_IN_RAM
|
||||
|
||||
#define U_ID_0 0
|
||||
#define U_ID_1 1
|
||||
#define U_ID_2 2
|
|
@ -1,2 +0,0 @@
|
|||
TARGET_MCU := RP2350
|
||||
TARGET_MCU_FAMILY := PICO
|
Loading…
Add table
Add a link
Reference in a new issue