1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-14 20:10:18 +03:00

PICO changes (#14105)

* PICO changes
* Spelling corrected in API v2
* Corrected as per @ledvinap - granted will be generated in future.
* As per @tstibor
* Correction and comment as per @ledvinap
This commit is contained in:
Jay Blackman 2024-12-26 14:53:27 +11:00 committed by GitHub
parent d244239f39
commit 01d862f803
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
17 changed files with 1742 additions and 371 deletions

View file

@ -0,0 +1,108 @@
/*
* 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/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include "platform.h"
#ifdef USE_SPI
#include "common/maths.h"
#include "drivers/bus.h"
#include "drivers/bus_spi.h"
#include "drivers/bus_spi_impl.h"
#include "drivers/exti.h"
#include "drivers/io.h"
#include "hardware/spi.h"
#include "hardware/gpio.h"
static uint16_t spiDivisorToBRbits(spi_inst_t *instance, uint16_t divisor)
{
UNUSED(instance);
divisor = constrain(divisor, 2, 256);
return 0;
}
static void spiSetDivisorBRreg(spi_inst_t *instance, uint16_t divisor)
{
//TODO: implement
UNUSED(instance);
UNUSED(divisor);
}
void spiInitDevice(SPIDevice device)
{
//TODO: implement
UNUSED(device);
}
void spiInternalResetDescriptors(busDevice_t *bus)
{
//TODO: implement
UNUSED(bus);
}
void spiInternalResetStream(dmaChannelDescriptor_t *descriptor)
{
//TODO: implement
UNUSED(descriptor);
}
static bool spiInternalReadWriteBufPolled(spi_inst_t *instance, const uint8_t *txData, uint8_t *rxData, int len)
{
//TODO: implement
UNUSED(instance);
UNUSED(txData);
UNUSED(rxData);
UNUSED(len);
return true;
}
void spiInternalInitStream(const extDevice_t *dev, bool preInit)
{
//TODO: implement
UNUSED(dev);
UNUSED(preInit);
}
void spiInternalStartDMA(const extDevice_t *dev)
{
//TODO: implement
UNUSED(dev);
}
void spiInternalStopDMA (const extDevice_t *dev)
{
//TODO: implement
UNUSED(dev);
}
// DMA transfer setup and start
void spiSequenceStart(const extDevice_t *dev)
{
//TODO: implement
UNUSED(dev);
}
#endif

View file

@ -0,0 +1,231 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are 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.
*
* Cleanflight and Betaflight are distributed in the hope that they
* 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
// DEFIO_PORT_<port>_USED_MASK is bitmask of used pins on target
// DEFIO_PORT_<port>_USED_COUNT is count of used pins on target
#if defined(RP2350A)
#define DEFIO_PORT_A_USED_COUNT 30
#elif defined(RP2350B)
#define DEFIO_PORT_A_USED_COUNT 48
#else
#error "Unsupported target MCU type for PICO"
#endif
#define DEFIO_PORT_A_OFFSET (0)
// DEFIO_GPIOID__<port> maps to port index
#define DEFIO_GPIOID__A 0
// DEFIO_TAG__P<port><pin> will expand to TAG if defined for target, error is triggered otherwise
// DEFIO_TAG_E__P<port><pin> will expand to TAG if defined, to NONE otherwise (usefull for tables that are CPU-specific)
// DEFIO_REC__P<port><pin> will expand to ioRec* (using DEFIO_REC_INDEX(idx))
#define DEFIO_TAG__PA0 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 0)
#define DEFIO_TAG__PA1 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 1)
#define DEFIO_TAG__PA2 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 2)
#define DEFIO_TAG__PA3 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 3)
#define DEFIO_TAG__PA4 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 4)
#define DEFIO_TAG__PA5 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 5)
#define DEFIO_TAG__PA6 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 6)
#define DEFIO_TAG__PA7 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 7)
#define DEFIO_TAG__PA8 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 8)
#define DEFIO_TAG__PA9 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 9)
#define DEFIO_TAG__PA10 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 10)
#define DEFIO_TAG__PA11 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 11)
#define DEFIO_TAG__PA12 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 12)
#define DEFIO_TAG__PA13 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 13)
#define DEFIO_TAG__PA14 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 14)
#define DEFIO_TAG__PA15 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 15)
#define DEFIO_TAG__PA16 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 16)
#define DEFIO_TAG__PA17 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 17)
#define DEFIO_TAG__PA18 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 18)
#define DEFIO_TAG__PA19 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 19)
#define DEFIO_TAG__PA20 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 20)
#define DEFIO_TAG__PA21 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 21)
#define DEFIO_TAG__PA22 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 22)
#define DEFIO_TAG__PA23 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 23)
#define DEFIO_TAG__PA24 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 24)
#define DEFIO_TAG__PA25 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 25)
#define DEFIO_TAG__PA26 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 26)
#define DEFIO_TAG__PA27 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 27)
#define DEFIO_TAG__PA28 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 28)
#define DEFIO_TAG__PA29 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 29)
#if defined(RP2350B)
#define DEFIO_TAG__PA30 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 30)
#define DEFIO_TAG__PA31 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 31)
#define DEFIO_TAG__PA32 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 32)
#define DEFIO_TAG__PA33 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 33)
#define DEFIO_TAG__PA34 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 34)
#define DEFIO_TAG__PA35 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 35)
#define DEFIO_TAG__PA36 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 36)
#define DEFIO_TAG__PA37 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 37)
#define DEFIO_TAG__PA38 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 38)
#define DEFIO_TAG__PA39 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 39)
#define DEFIO_TAG__PA40 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 40)
#define DEFIO_TAG__PA41 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 41)
#define DEFIO_TAG__PA42 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 42)
#define DEFIO_TAG__PA43 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 43)
#define DEFIO_TAG__PA44 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 44)
#define DEFIO_TAG__PA45 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 45)
#define DEFIO_TAG__PA46 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 46)
#define DEFIO_TAG__PA47 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 47)
#endif
#define DEFIO_TAG_E__PA0 DEFIO_TAG__PA0
#define DEFIO_TAG_E__PA1 DEFIO_TAG__PA1
#define DEFIO_TAG_E__PA2 DEFIO_TAG__PA2
#define DEFIO_TAG_E__PA3 DEFIO_TAG__PA3
#define DEFIO_TAG_E__PA4 DEFIO_TAG__PA4
#define DEFIO_TAG_E__PA5 DEFIO_TAG__PA5
#define DEFIO_TAG_E__PA6 DEFIO_TAG__PA6
#define DEFIO_TAG_E__PA7 DEFIO_TAG__PA7
#define DEFIO_TAG_E__PA8 DEFIO_TAG__PA8
#define DEFIO_TAG_E__PA9 DEFIO_TAG__PA9
#define DEFIO_TAG_E__PA10 DEFIO_TAG__PA10
#define DEFIO_TAG_E__PA11 DEFIO_TAG__PA11
#define DEFIO_TAG_E__PA12 DEFIO_TAG__PA12
#define DEFIO_TAG_E__PA13 DEFIO_TAG__PA13
#define DEFIO_TAG_E__PA14 DEFIO_TAG__PA14
#define DEFIO_TAG_E__PA15 DEFIO_TAG__PA15
#define DEFIO_TAG_E__PA16 DEFIO_TAG__PA16
#define DEFIO_TAG_E__PA17 DEFIO_TAG__PA17
#define DEFIO_TAG_E__PA18 DEFIO_TAG__PA18
#define DEFIO_TAG_E__PA19 DEFIO_TAG__PA19
#define DEFIO_TAG_E__PA20 DEFIO_TAG__PA20
#define DEFIO_TAG_E__PA21 DEFIO_TAG__PA21
#define DEFIO_TAG_E__PA22 DEFIO_TAG__PA22
#define DEFIO_TAG_E__PA23 DEFIO_TAG__PA23
#define DEFIO_TAG_E__PA24 DEFIO_TAG__PA24
#define DEFIO_TAG_E__PA25 DEFIO_TAG__PA25
#define DEFIO_TAG_E__PA26 DEFIO_TAG__PA26
#define DEFIO_TAG_E__PA27 DEFIO_TAG__PA27
#define DEFIO_TAG_E__PA28 DEFIO_TAG__PA28
#define DEFIO_TAG_E__PA29 DEFIO_TAG__PA29
#if defined(RP2350B)
#define DEFIO_TAG_E__PA30 DEFIO_TAG__PA30
#define DEFIO_TAG_E__PA31 DEFIO_TAG__PA31
#define DEFIO_TAG_E__PA32 DEFIO_TAG__PA32
#define DEFIO_TAG_E__PA33 DEFIO_TAG__PA33
#define DEFIO_TAG_E__PA34 DEFIO_TAG__PA34
#define DEFIO_TAG_E__PA35 DEFIO_TAG__PA35
#define DEFIO_TAG_E__PA36 DEFIO_TAG__PA36
#define DEFIO_TAG_E__PA37 DEFIO_TAG__PA37
#define DEFIO_TAG_E__PA38 DEFIO_TAG__PA38
#define DEFIO_TAG_E__PA39 DEFIO_TAG__PA39
#define DEFIO_TAG_E__PA40 DEFIO_TAG__PA40
#define DEFIO_TAG_E__PA41 DEFIO_TAG__PA41
#define DEFIO_TAG_E__PA42 DEFIO_TAG__PA42
#define DEFIO_TAG_E__PA43 DEFIO_TAG__PA43
#define DEFIO_TAG_E__PA44 DEFIO_TAG__PA44
#define DEFIO_TAG_E__PA45 DEFIO_TAG__PA45
#define DEFIO_TAG_E__PA46 DEFIO_TAG__PA46
#define DEFIO_TAG_E__PA47 DEFIO_TAG__PA47
#else
#define DEFIO_TAG_E__PA30 DEFIO_TAG_A__NONE
#define DEFIO_TAG_E__PA31 DEFIO_TAG_A__NONE
#define DEFIO_TAG_E__PA32 DEFIO_TAG_A__NONE
#define DEFIO_TAG_E__PA33 DEFIO_TAG_A__NONE
#define DEFIO_TAG_E__PA34 DEFIO_TAG_A__NONE
#define DEFIO_TAG_E__PA35 DEFIO_TAG_A__NONE
#define DEFIO_TAG_E__PA36 DEFIO_TAG_A__NONE
#define DEFIO_TAG_E__PA37 DEFIO_TAG_A__NONE
#define DEFIO_TAG_E__PA38 DEFIO_TAG_A__NONE
#define DEFIO_TAG_E__PA39 DEFIO_TAG_A__NONE
#define DEFIO_TAG_E__PA40 DEFIO_TAG_A__NONE
#define DEFIO_TAG_E__PA41 DEFIO_TAG_A__NONE
#define DEFIO_TAG_E__PA42 DEFIO_TAG_A__NONE
#define DEFIO_TAG_E__PA43 DEFIO_TAG_A__NONE
#define DEFIO_TAG_E__PA44 DEFIO_TAG_A__NONE
#define DEFIO_TAG_E__PA45 DEFIO_TAG_A__NONE
#define DEFIO_TAG_E__PA46 DEFIO_TAG_A__NONE
#define DEFIO_TAG_E__PA47 DEFIO_TAG_A__NONE
#endif
#define DEFIO_REC__PA0 DEFIO_REC_INDEXED(0)
#define DEFIO_REC__PA1 DEFIO_REC_INDEXED(1)
#define DEFIO_REC__PA2 DEFIO_REC_INDEXED(2)
#define DEFIO_REC__PA3 DEFIO_REC_INDEXED(3)
#define DEFIO_REC__PA4 DEFIO_REC_INDEXED(4)
#define DEFIO_REC__PA5 DEFIO_REC_INDEXED(5)
#define DEFIO_REC__PA6 DEFIO_REC_INDEXED(6)
#define DEFIO_REC__PA7 DEFIO_REC_INDEXED(7)
#define DEFIO_REC__PA8 DEFIO_REC_INDEXED(8)
#define DEFIO_REC__PA9 DEFIO_REC_INDEXED(9)
#define DEFIO_REC__PA10 DEFIO_REC_INDEXED(10)
#define DEFIO_REC__PA11 DEFIO_REC_INDEXED(11)
#define DEFIO_REC__PA12 DEFIO_REC_INDEXED(12)
#define DEFIO_REC__PA13 DEFIO_REC_INDEXED(13)
#define DEFIO_REC__PA14 DEFIO_REC_INDEXED(14)
#define DEFIO_REC__PA15 DEFIO_REC_INDEXED(15)
#define DEFIO_REC__PA16 DEFIO_REC_INDEXED(16)
#define DEFIO_REC__PA17 DEFIO_REC_INDEXED(17)
#define DEFIO_REC__PA18 DEFIO_REC_INDEXED(18)
#define DEFIO_REC__PA19 DEFIO_REC_INDEXED(19)
#define DEFIO_REC__PA20 DEFIO_REC_INDEXED(20)
#define DEFIO_REC__PA21 DEFIO_REC_INDEXED(21)
#define DEFIO_REC__PA22 DEFIO_REC_INDEXED(22)
#define DEFIO_REC__PA23 DEFIO_REC_INDEXED(23)
#define DEFIO_REC__PA24 DEFIO_REC_INDEXED(24)
#define DEFIO_REC__PA25 DEFIO_REC_INDEXED(25)
#define DEFIO_REC__PA26 DEFIO_REC_INDEXED(26)
#define DEFIO_REC__PA27 DEFIO_REC_INDEXED(27)
#define DEFIO_REC__PA28 DEFIO_REC_INDEXED(28)
#define DEFIO_REC__PA29 DEFIO_REC_INDEXED(29)
#if defined(RP2350B)
#define DEFIO_REC__PA30 DEFIO_REC_INDEXED(30)
#define DEFIO_REC__PA31 DEFIO_REC_INDEXED(31)
#define DEFIO_REC__PA32 DEFIO_REC_INDEXED(32)
#define DEFIO_REC__PA33 DEFIO_REC_INDEXED(33)
#define DEFIO_REC__PA34 DEFIO_REC_INDEXED(34)
#define DEFIO_REC__PA35 DEFIO_REC_INDEXED(35)
#define DEFIO_REC__PA36 DEFIO_REC_INDEXED(36)
#define DEFIO_REC__PA37 DEFIO_REC_INDEXED(37)
#define DEFIO_REC__PA38 DEFIO_REC_INDEXED(38)
#define DEFIO_REC__PA39 DEFIO_REC_INDEXED(39)
#define DEFIO_REC__PA40 DEFIO_REC_INDEXED(40)
#define DEFIO_REC__PA41 DEFIO_REC_INDEXED(41)
#define DEFIO_REC__PA42 DEFIO_REC_INDEXED(42)
#define DEFIO_REC__PA43 DEFIO_REC_INDEXED(43)
#define DEFIO_REC__PA44 DEFIO_REC_INDEXED(44)
#define DEFIO_REC__PA45 DEFIO_REC_INDEXED(45)
#define DEFIO_REC__PA46 DEFIO_REC_INDEXED(46)
#define DEFIO_REC__PA47 DEFIO_REC_INDEXED(47)
#endif
// DEFIO_IO_USED_COUNT is number of io pins supported on target
#if defined(RP2350A)
#define DEFIO_IO_USED_COUNT 30
#elif defined(RP2350B)
#define DEFIO_IO_USED_COUNT 48
#endif
// DEFIO_PORT_USED_LIST - comma separated list of bitmask for all used ports.
// DEFIO_PORT_OFFSET_LIST - comma separated list of port offsets (count of pins before this port)
// unused ports on end of list are skipped
#define DEFIO_PORT_USED_COUNT 1
#define DEFIO_PORT_USED_LIST DEFIO_PORT_A_USED_MASK
#define DEFIO_PORT_OFFSET_LIST DEFIO_PORT_A_OFFSET
#define DEFIO_PIN_USED_COUNT DEFIO_PORT_A_USED_COUNT

111
src/platform/PICO/io_pico.c Normal file
View file

@ -0,0 +1,111 @@
/*
* 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/>.
*/
#include "platform.h"
#include "drivers/io.h"
#include "drivers/io_impl.h"
#include "common/utils.h"
#include "hardware/gpio.h"
// initialize all ioRec_t structures from ROM
// currently only bitmask is used, this may change in future
void IOInitGlobal(void)
{
ioRec_t *ioRec = ioRecs;
for (unsigned pin = 0; pin < DEFIO_PIN_USED_COUNT; pin++) {
ioRec->pin = pin;
ioRec++;
}
}
uint32_t IO_EXTI_Line(IO_t io)
{
UNUSED(io);
return 0;
}
bool IORead(IO_t io)
{
if (!io) {
return false;
}
return gpio_get(IO_Pin(io));
}
void IOWrite(IO_t io, bool hi)
{
if (!io) {
return;
}
gpio_put(IO_Pin(io), hi);
}
void IOHi(IO_t io)
{
if (!io) {
return;
}
gpio_put(IO_Pin(io), 1);
}
void IOLo(IO_t io)
{
if (!io) {
return;
}
gpio_put(IO_Pin(io), 0);
}
void IOToggle(IO_t io)
{
if (!io) {
return;
}
gpio_put(IO_Pin(io), !gpio_get(IO_Pin(io)));
}
void IOConfigGPIO(IO_t io, ioConfig_t cfg)
{
if (!io) {
return;
}
gpio_set_dir(IO_Pin(io), (cfg & 0x01));
}
IO_t IOGetByTag(ioTag_t tag)
{
const int portIdx = DEFIO_TAG_GPIOID(tag);
const int pinIdx = DEFIO_TAG_PIN(tag);
if (portIdx < 0 || portIdx >= DEFIO_PORT_USED_COUNT) {
return NULL;
}
if (pinIdx >= DEFIO_PIN_USED_COUNT) {
return NULL;
}
return &ioRecs[pinIdx];
}

View file

@ -1,132 +1,61 @@
/* Based on GCC ARM embedded samples. /* Specify the memory areas */
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 MEMORY
{ {
FLASH(rx) : ORIGIN = 0x10000000, LENGTH = 4m FLASH_X (rx) : ORIGIN = 0x10000000, LENGTH = 16K
RAM(rwx) : ORIGIN = 0x20000000, LENGTH = 512k FLASH_CONFIG (r) : ORIGIN = 0x10004000, LENGTH = 16K
FLASH (rx) : ORIGIN = 0x10008000, LENGTH = 992K
RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 512K
SCRATCH_X(rwx) : ORIGIN = 0x20080000, LENGTH = 4k SCRATCH_X(rwx) : ORIGIN = 0x20080000, LENGTH = 4k
SCRATCH_Y(rwx) : ORIGIN = 0x20081000, LENGTH = 4k SCRATCH_Y(rwx) : ORIGIN = 0x20081000, LENGTH = 4k
} }
ENTRY(_entry_point) REGION_ALIAS("STACKRAM", RAM)
REGION_ALIAS("FASTRAM", RAM)
REGION_ALIAS("MOVABLE_FLASH", FLASH)
/* Entry Point */
ENTRY(Reset_Handler)
/* Highest address of the user mode stack */
_estack = ORIGIN(STACKRAM) + LENGTH(STACKRAM) - 8; /* Reserve 2 x 4bytes for info across reset */
/* Base address where the config is stored. */
__config_start = ORIGIN(FLASH_CONFIG);
__config_end = ORIGIN(FLASH_CONFIG) + LENGTH(FLASH_CONFIG);
/* Generate a link error if heap and stack don't fit into RAM */
_Min_Heap_Size = 0; /* required amount of heap */
_Min_Stack_Size = 0x800; /* required amount of stack */
/* Define output sections */
SECTIONS SECTIONS
{ {
.flash_begin : { /* The startup code goes first into FLASH_X */
__flash_binary_start = .; .isr_vector :
} > FLASH {
. = ALIGN(512);
PROVIDE (isr_vector_table_base = .);
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} >FLASH_X
/* The bootrom will enter the image at the point indicated in your /* The program code and other data goes into FLASH */
IMAGE_DEF, which is usually the reset handler of your vector table. .text :
{
. = ALIGN(4);
*(.text) /* .text sections (code) */
*(.text*) /* .text* sections (code) */
*(.rodata) /* .rodata sections (constants, strings, etc.) */
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
*(.glue_7) /* glue arm to thumb code */
*(.glue_7t) /* glue thumb to arm code */
*(.eh_frame)
The debugger will use the ELF entry point, which is the _entry_point KEEP (*(.init))
symbol, and in our case is *different from the bootrom's entry point.* KEEP (*(.fini))
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); . = ALIGN(4);
/* preinit data */ _etext = .; /* define a global symbols at end of code */
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 } >FLASH
.ARM.extab : .ARM.extab :
@ -134,169 +63,180 @@ SECTIONS
*(.ARM.extab* .gnu.linkonce.armextab.*) *(.ARM.extab* .gnu.linkonce.armextab.*)
} >FLASH } >FLASH
.ARM :
{
__exidx_start = .; __exidx_start = .;
.ARM.exidx : *(.ARM.exidx*) __exidx_end = .;
{
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
} >FLASH } >FLASH
__exidx_end = .;
/* Machine inspectable binary information */ .pg_registry :
. = ALIGN(4);
__binary_info_start = .;
.binary_info :
{ {
KEEP(*(.binary_info.keep.*)) PROVIDE_HIDDEN (__pg_registry_start = .);
*(.binary_info.*) KEEP (*(.pg_registry))
KEEP (*(SORT(.pg_registry.*)))
PROVIDE_HIDDEN (__pg_registry_end = .);
} >FLASH } >FLASH
__binary_info_end = .;
.pg_resetdata :
{
PROVIDE_HIDDEN (__pg_resetdata_start = .);
KEEP (*(.pg_resetdata))
PROVIDE_HIDDEN (__pg_resetdata_end = .);
} >FLASH
/* used by the startup to initialize data */
_sidata = LOADADDR(.data);
/* Initialized data sections goes into RAM, load LMA copy after code */
.data :
{
. = ALIGN(4); . = ALIGN(4);
_sdata = .; /* create a global symbol at data start */
.ram_vector_table (NOLOAD): { *(.data) /* .data sections */
*(.ram_vector_table) *(.data*) /* .data* sections */
} > 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); . = ALIGN(4);
*(.after_data.*) _edata = .; /* define a global symbol at data end */
. = 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 } >RAM AT >FLASH
.tdata : { /* Uninitialized data section */
. = ALIGN(4); . = ALIGN(4);
*(.tdata .tdata.* .gnu.linkonce.td.*) .bss (NOLOAD) :
/* All data end */ {
__tdata_end = .; /* This is used by the startup in order to initialize the .bss secion */
} > RAM AT> FLASH _sbss = .; /* define a global symbol at bss start */
PROVIDE(__data_end__ = .); __bss_start__ = _sbss;
*(.bss)
/* __etext is (for backwards compatibility) the name of the .data init source pointer (...) */ *(SORT_BY_ALIGNMENT(.bss*))
__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) *(COMMON)
PROVIDE(__global_pointer$ = . + 2K);
*(.sbss*)
. = ALIGN(4); . = ALIGN(4);
__bss_end__ = .; _ebss = .; /* define a global symbol at bss end */
__bss_end__ = _ebss;
} >RAM } >RAM
.heap (NOLOAD): /* Uninitialized data section */
. = ALIGN(4);
.sram2 (NOLOAD) :
{ {
__end__ = .; /* This is used by the startup in order to initialize the .sram2 secion */
end = __end__; _ssram2 = .; /* define a global symbol at sram2 start */
KEEP(*(.heap*)) __sram2_start__ = _ssram2;
*(.sram2)
*(SORT_BY_ALIGNMENT(.sram2*))
. = ALIGN(4);
_esram2 = .; /* define a global symbol at sram2 end */
__sram2_end__ = _esram2;
} >RAM } >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 */ /* used during startup to initialized fastram_data */
.scratch_x : { _sfastram_idata = LOADADDR(.fastram_data);
__scratch_x_start__ = .;
*(.scratch_x.*)
. = ALIGN(4);
__scratch_x_end__ = .;
} > SCRATCH_X AT > FLASH
__scratch_x_source__ = LOADADDR(.scratch_x);
.scratch_y : { /* Initialized FAST_DATA section for unsuspecting developers */
__scratch_y_start__ = .; .fastram_data :
*(.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*) . = ALIGN(4);
} > SCRATCH_X _sfastram_data = .; /* create a global symbol at data start */
.stack_dummy (NOLOAD): *(.fastram_data) /* .data sections */
*(.fastram_data*) /* .data* sections */
. = ALIGN(4);
_efastram_data = .; /* define a global symbol at data end */
} >FASTRAM AT >FLASH
. = ALIGN(4);
.fastram_bss (NOLOAD) :
{ {
KEEP(*(.stack*)) _sfastram_bss = .;
} > SCRATCH_Y __fastram_bss_start__ = _sfastram_bss;
*(.fastram_bss)
*(SORT_BY_ALIGNMENT(.fastram_bss*))
.flash_end : { . = ALIGN(4);
KEEP(*(.embedded_end_block*)) _efastram_bss = .;
PROVIDE(__flash_binary_end = .); __fastram_bss_end__ = _efastram_bss;
} > FLASH =0xaa } >FASTRAM
/* stack limit is poorly named, but historically is maximum heap ptr */ /* used during startup to initialized dmaram_data */
__StackLimit = ORIGIN(RAM) + LENGTH(RAM); _sdmaram_idata = LOADADDR(.dmaram_data);
__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 */ . = ALIGN(32);
PROVIDE (__heap_start = __end__); .dmaram_data :
PROVIDE (__heap_end = __HeapLimit); {
PROVIDE( __tls_align = MAX(ALIGNOF(.tdata), ALIGNOF(.tbss)) ); PROVIDE(dmaram_start = .);
PROVIDE( __tls_size_align = (__tls_size + __tls_align - 1) & ~(__tls_align - 1)); _sdmaram = .;
PROVIDE( __arm32_tls_tcb_offset = MAX(8, __tls_align) ); _dmaram_start__ = _sdmaram;
_sdmaram_data = .; /* create a global symbol at data start */
*(.dmaram_data) /* .data sections */
*(.dmaram_data*) /* .data* sections */
. = ALIGN(32);
_edmaram_data = .; /* define a global symbol at data end */
} >RAM AT >FLASH
/* llvm-libc */ . = ALIGN(32);
PROVIDE (_end = __end__); .dmaram_bss (NOLOAD) :
PROVIDE (__llvm_libc_heap_limit = __HeapLimit); {
_sdmaram_bss = .;
__dmaram_bss_start__ = _sdmaram_bss;
*(.dmaram_bss)
*(SORT_BY_ALIGNMENT(.dmaram_bss*))
. = ALIGN(32);
_edmaram_bss = .;
__dmaram_bss_end__ = _edmaram_bss;
} >RAM
/* Check if data + heap + stack exceeds RAM limit */ . = ALIGN(32);
ASSERT(__StackLimit >= __HeapLimit, "region RAM overflowed") .DMA_RAM (NOLOAD) :
{
KEEP(*(.DMA_RAM))
PROVIDE(dmaram_end = .);
_edmaram = .;
_dmaram_end__ = _edmaram;
} >RAM
ASSERT( __binary_info_header_end - __logical_binary_start <= 1024, "Binary info must be in first 1024 bytes of the binary") .DMA_RW_AXI (NOLOAD) :
ASSERT( __embedded_block_end - __logical_binary_start <= 4096, "Embedded block must be in first 4096 bytes of the binary") {
. = ALIGN(32);
PROVIDE(dmarwaxi_start = .);
_sdmarwaxi = .;
_dmarwaxi_start__ = _sdmarwaxi;
KEEP(*(.DMA_RW_AXI))
PROVIDE(dmarwaxi_end = .);
_edmarwaxi = .;
_dmarwaxi_end__ = _edmarwaxi;
} >RAM
/* todo assert on extra code */ .persistent_data (NOLOAD) :
{
__persistent_data_start__ = .;
*(.persistent_data)
. = ALIGN(4);
__persistent_data_end__ = .;
} >RAM
/* User_heap_stack section, used to check that there is enough RAM left */
_heap_stack_end = ORIGIN(STACKRAM)+LENGTH(STACKRAM) - 8; /* 8 bytes to allow for alignment */
_heap_stack_begin = _heap_stack_end - _Min_Stack_Size - _Min_Heap_Size;
. = _heap_stack_begin;
._user_heap_stack :
{
. = ALIGN(4);
PROVIDE ( end = . );
PROVIDE ( _end = . );
. = . + _Min_Heap_Size;
. = . + _Min_Stack_Size;
. = ALIGN(4);
} >STACKRAM = 0xa5
/* Remove information from the standard libraries */
/DISCARD/ :
{
libc.a ( * )
libm.a ( * )
libgcc.a ( * )
} }
.ARM.attributes 0 : { *(.ARM.attributes) }
}

View file

@ -12,9 +12,23 @@ SDK_DIR = $(LIB_MAIN_DIR)/pico-sdk
CMSIS_DIR := $(SDK_DIR)/rp2_common/cmsis/stub/CMSIS CMSIS_DIR := $(SDK_DIR)/rp2_common/cmsis/stub/CMSIS
#STDPERIPH #STDPERIPH
STDPERIPH_DIR = $(SDK_SIR) STDPERIPH_DIR := $(SDK_DIR)/rp2_common
STDPERIPH_SRC = \ STDPERIPH_SRC := \
pico_clib_interface/newlib_interface.c \
hardware_sync_spin_lock/sync_spin_lock.c \
hardware_gpio/gpio.c \
pico_stdio/stdio.c \
hardware_uart/uart.c \
hardware_irq/irq.c \
hardware_timer/timer.c \
hardware_clocks/clocks.c \
hardware_pll/pll.c \
hardware_spi/spi.c \
hardware_i2c/i2c.c \
hardware_adc/adc.c \
hardware_pio/pio.c \
hardware_watchdog/watchdog.c \
hardware_flash/flash.c
VPATH := $(VPATH):$(STDPERIPH_DIR) VPATH := $(VPATH):$(STDPERIPH_DIR)
@ -25,20 +39,19 @@ DEVICE_STDPERIPH_SRC := \
$(USBHID_SRC) \ $(USBHID_SRC) \
$(USBMSC_SRC) $(USBMSC_SRC)
ifeq ($(TARGET_MCU),RP2350B)
TARGET_MCU_LIB_LOWER = rp2350
TARGET_MCU_LIB_UPPER = RP2350
endif
#CMSIS #CMSIS
VPATH := $(VPATH):$(CMSIS_DIR)/Core/Include:$(CMSIS_DIR)/Device/$(TARGET_MCU)/Include VPATH := $(VPATH):$(CMSIS_DIR)/Core/Include:$(CMSIS_DIR)/Device/$(TARGET_MCU_LIB_UPPER)/Include
CMSIS_SRC := CMSIS_SRC := \
#SRC
VPATH := $(VPATH):$(STDPERIPH_DIR)
INCLUDE_DIRS := \ INCLUDE_DIRS += \
$(INCLUDE_DIRS) \
$(TARGET_PLATFORM_DIR) \ $(TARGET_PLATFORM_DIR) \
$(TARGET_PLATFORM_DIR)/startup \ $(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_bit_ops_headers/include \
$(SDK_DIR)/common/pico_base_headers/include \ $(SDK_DIR)/common/pico_base_headers/include \
$(SDK_DIR)/common/boot_picoboot_headers/include \ $(SDK_DIR)/common/boot_picoboot_headers/include \
@ -131,21 +144,31 @@ INCLUDE_DIRS := \
$(SDK_DIR)/rp2_common/pico_malloc/include \ $(SDK_DIR)/rp2_common/pico_malloc/include \
$(SDK_DIR)/rp2_common/hardware_timer/include \ $(SDK_DIR)/rp2_common/hardware_timer/include \
$(CMSIS_DIR)/Core/Include \ $(CMSIS_DIR)/Core/Include \
$(CMSIS_DIR)/Device/$(TARGET_MCU)/Include $(CMSIS_DIR)/Device/$(TARGET_MCU_LIB_UPPER)/Include \
$(SDK_DIR)/$(TARGET_MCU_LIB_LOWER)/pico_platform/include \
$(SDK_DIR)/$(TARGET_MCU_LIB_LOWER)/hardware_regs/include \
$(SDK_DIR)/$(TARGET_MCU_LIB_LOWER)/hardware_structs/include
#Flags #Flags
ARCH_FLAGS = -mthumb -mcpu=cortex-m33 -march=armv8-m.main+fp+dsp -mfloat-abi=softfp -mcmse ARCH_FLAGS = -mthumb -mcpu=cortex-m33 -march=armv8-m.main+fp+dsp -mfloat-abi=softfp -mcmse
DEVICE_FLAGS = DEVICE_FLAGS =
ifeq ($(TARGET_MCU),RP2350) ifeq ($(TARGET_MCU),RP2350B)
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 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 LD_SCRIPT = $(LINKER_DIR)/pico_rp2350.ld
STARTUP_SRC = startup/bs2_default_padded_checksummed.S STARTUP_SRC = PICO/startup/bs2_default_padded_checksummed.S
MCU_FLASH_SIZE = 4096 MCU_FLASH_SIZE = 4096
# Override the OPTIMISE_SPEED compiler setting to save flash space on these 512KB targets. # 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. # Performance is only slightly affected but around 50 kB of flash are saved.
OPTIMISE_SPEED = -O2 OPTIMISE_SPEED = -O2
STDPERIPH_SRC += \
common/RP2350/pico_platform/platform.c
MCU_SRC += \
system_RP2350.c
else else
$(error Unknown MCU for Raspberry PICO target) $(error Unknown MCU for Raspberry PICO target)
endif endif
@ -153,6 +176,13 @@ endif
DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DPICO DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DPICO
MCU_COMMON_SRC = \ MCU_COMMON_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/dshot_bitbang_decode.c \
drivers/inverter.c \
drivers/bus_spi.c \
PICO/system.c \
PICO/io_pico.c \
PICO/bus_spi_pico.c \
PICO/serial_uart_pico.c
DEVICE_FLAGS += DEVICE_FLAGS +=

View file

@ -0,0 +1,9 @@
// AUTOGENERATED FROM PICO_CONFIG_HEADER_FILES and then PICO_<PLATFORM>_CONFIG_HEADER_FILES
// DO NOT EDIT!
// based on PICO_CONFIG_HEADER_FILES:
#include "cmsis/rename_exceptions.h"
// based on PICO_RP2350_ARM_S_CONFIG_HEADER_FILES:

View file

@ -0,0 +1,287 @@
/*
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
/** \file platform.h
* \defgroup pico_platform pico_platform
*
* \brief Macros and definitions (and functions when included by non assembly code) for the RP2 family device / architecture
* to provide a common abstraction over low level compiler / platform specifics
*
* This header may be included by assembly code
*/
#ifndef _PICO_PLATFORM_H
#define _PICO_PLATFORM_H
#ifndef _PICO_H
#error pico/platform.h should not be included directly; include pico.h instead
#endif
#include "pico/platform/compiler.h"
#include "pico/platform/sections.h"
#include "pico/platform/panic.h"
#include "hardware/regs/addressmap.h"
#include "hardware/regs/sio.h"
#ifdef __riscv
#include "hardware/regs/rvcsr.h"
#endif
// PICO_CONFIG: PICO_RP2350A, Whether the current board has an RP2350 in an A (30 GPIO) package, type=bool, default=Usually provided via board header, group=pico_platform
#if 0 // make tooling checks happy
#define PICO_RP2350A 0
#endif
// PICO_CONFIG: PICO_RP2350_A2_SUPPORTED, Whether to include any specific software support for RP2350 A2 revision, type=bool, default=1, advanced=true, group=pico_platform
#ifndef PICO_RP2350_A2_SUPPORTED
#define PICO_RP2350_A2_SUPPORTED 1
#endif
// PICO_CONFIG: PICO_STACK_SIZE, Minimum amount of stack space reserved in the linker script for each core. See also PICO_CORE1_STACK_SIZE, min=0x100, default=0x800, advanced=true, group=pico_platform
#ifndef PICO_STACK_SIZE
#define PICO_STACK_SIZE _u(0x800)
#endif
// PICO_CONFIG: PICO_HEAP_SIZE, Minimum amount of heap space reserved by the linker script, min=0x100, default=0x800, advanced=true, group=pico_platform
#ifndef PICO_HEAP_SIZE
#define PICO_HEAP_SIZE _u(0x800)
#endif
// PICO_CONFIG: PICO_NO_RAM_VECTOR_TABLE, Enable/disable the RAM vector table, type=bool, default=0, advanced=true, group=pico_platform
#ifndef PICO_NO_RAM_VECTOR_TABLE
#define PICO_NO_RAM_VECTOR_TABLE 0
#endif
#ifndef PICO_RAM_VECTOR_TABLE_SIZE
#define PICO_RAM_VECTOR_TABLE_SIZE (VTABLE_FIRST_IRQ + NUM_IRQS)
#endif
// PICO_CONFIG: PICO_USE_STACK_GUARDS, Enable/disable stack guards, type=bool, default=0, advanced=true, group=pico_platform
#ifndef PICO_USE_STACK_GUARDS
#define PICO_USE_STACK_GUARDS 0
#endif
// PICO_CONFIG: PICO_CLKDIV_ROUND_NEAREST, True if floating point clock divisors should be rounded to the nearest possible clock divisor by default rather than rounding down, type=bool, default=1, group=pico_platform
#ifndef PICO_CLKDIV_ROUND_NEAREST
#define PICO_CLKDIV_ROUND_NEAREST 1
#endif
#ifndef __ASSEMBLER__
/*! \brief No-op function for the body of tight loops
* \ingroup pico_platform
*
* No-op function intended to be called by any tight hardware polling loop. Using this ubiquitously
* makes it much easier to find tight loops, but also in the future \#ifdef-ed support for lockup
* debugging might be added
*/
static __force_inline void tight_loop_contents(void) {}
/*! \brief Helper method to busy-wait for at least the given number of cycles
* \ingroup pico_platform
*
* This method is useful for introducing very short delays.
*
* This method busy-waits in a tight loop for the given number of system clock cycles. The total wait time is only accurate to within 2 cycles,
* and this method uses a loop counter rather than a hardware timer, so the method will always take longer than expected if an
* interrupt is handled on the calling core during the busy-wait; you can of course disable interrupts to prevent this.
*
* You can use \ref clock_get_hz(clk_sys) to determine the number of clock cycles per second if you want to convert an actual
* time duration to a number of cycles.
*
* \param minimum_cycles the minimum number of system clock cycles to delay for
*/
static inline void busy_wait_at_least_cycles(uint32_t minimum_cycles) {
pico_default_asm_volatile (
#ifdef __riscv
// Note the range is halved on RISC-V due to signed comparison (no carry flag)
".option push\n"
".option norvc\n" // force 32 bit addi, so branch prediction guaranteed
".p2align 2\n"
"1: \n"
"addi %0, %0, -2 \n"
"bgez %0, 1b\n"
".option pop"
#else
"1: subs %0, #3\n"
"bcs 1b\n"
#endif
: "+r" (minimum_cycles) : : "cc", "memory"
);
}
// PICO_CONFIG: PICO_NO_FPGA_CHECK, Remove the FPGA platform check for small code size reduction, type=bool, default=1, advanced=true, group=pico_runtime
#ifndef PICO_NO_FPGA_CHECK
#define PICO_NO_FPGA_CHECK 1
#endif
// PICO_CONFIG: PICO_NO_SIM_CHECK, Remove the SIM platform check for small code size reduction, type=bool, default=1, advanced=true, group=pico_runtime
#ifndef PICO_NO_SIM_CHECK
#define PICO_NO_SIM_CHECK 1
#endif
#if PICO_NO_FPGA_CHECK
static inline bool running_on_fpga(void) {return false;}
#else
bool running_on_fpga(void);
#endif
#if PICO_NO_SIM_CHECK
static inline bool running_in_sim(void) {return false;}
#else
bool running_in_sim(void);
#endif
/*! \brief Execute a breakpoint instruction
* \ingroup pico_platform
*/
static __force_inline void __breakpoint(void) {
#ifdef __riscv
__asm ("ebreak");
#else
pico_default_asm_volatile ("bkpt #0" : : : "memory");
#endif
}
/*! \brief Get the current core number
* \ingroup pico_platform
*
* \return The core number the call was made from
*/
__force_inline static uint get_core_num(void) {
return (*(uint32_t *) (SIO_BASE + SIO_CPUID_OFFSET));
}
/*! \brief Get the current exception level on this core
* \ingroup pico_platform
*
* On Cortex-M this is the exception number defined in the architecture
* reference, which is equal to VTABLE_FIRST_IRQ + irq num if inside an
* interrupt handler. (VTABLE_FIRST_IRQ is defined in platform_defs.h).
*
* On Hazard3, this function returns VTABLE_FIRST_IRQ + irq num if inside of
* an external IRQ handler (or a fault from such a handler), and 0 otherwise,
* generally aligning with the Cortex-M values.
*
* \return the exception number if the CPU is handling an exception, or 0 otherwise
*/
static __force_inline uint __get_current_exception(void) {
#ifdef __riscv
uint32_t meicontext;
pico_default_asm_volatile (
"csrr %0, %1\n"
: "=r" (meicontext) : "i" (RVCSR_MEICONTEXT_OFFSET)
);
if (meicontext & RVCSR_MEICONTEXT_NOIRQ_BITS) {
return 0;
} else {
return VTABLE_FIRST_IRQ + (
(meicontext & RVCSR_MEICONTEXT_IRQ_BITS) >> RVCSR_MEICONTEXT_IRQ_LSB
);
}
#else
uint exception;
pico_default_asm_volatile (
"mrs %0, ipsr\n"
"uxtb %0, %0\n"
: "=l" (exception)
);
return exception;
#endif
}
/*! \brief Return true if executing in the NonSecure state (Arm-only)
* \ingroup pico_platform
*
* \return True if currently executing in the NonSecure state on an Arm processor
*/
__force_inline static bool pico_processor_state_is_nonsecure(void) {
#ifndef __riscv
// todo add a define to disable NS checking at all?
// IDAU-Exempt addresses return S=1 when tested in the Secure state,
// whereas executing a tt in the NonSecure state will always return S=0.
uint32_t tt;
pico_default_asm_volatile (
"movs %0, #0\n"
"tt %0, %0\n"
: "=r" (tt) : : "cc"
);
return !(tt & (1u << 22));
#else
// NonSecure is an Arm concept, there is nothing meaningful to return
// here. Note it's not possible in general to detect whether you are
// executing in U-mode as, for example, M-mode is classically
// virtualisable in U-mode.
return false;
#endif
}
#define host_safe_hw_ptr(x) ((uintptr_t)(x))
#define native_safe_hw_ptr(x) host_safe_hw_ptr(x)
/*! \brief Returns the RP2350 chip revision number
* \ingroup pico_platform
* @return the RP2350 chip revision number (1 for B0/B1, 2 for B2)
*/
uint8_t rp2350_chip_version(void);
/*! \brief Returns the RP2040 chip revision number for compatibility
* \ingroup pico_platform
* @return 2 RP2040 errata fixed in B2 are fixed in RP2350
*/
static inline uint8_t rp2040_chip_version(void) {
return 2;
}
/*! \brief Returns the RP2040 rom version number
* \ingroup pico_platform
* @return the RP2040 rom version number (1 for RP2040-B0, 2 for RP2040-B1, 3 for RP2040-B2)
*/
static inline uint8_t rp2040_rom_version(void) {
GCC_Pragma("GCC diagnostic push")
GCC_Pragma("GCC diagnostic ignored \"-Warray-bounds\"")
return *(uint8_t*)0x13;
GCC_Pragma("GCC diagnostic pop")
}
/*! \brief Multiply two integers using an assembly `MUL` instruction
* \ingroup pico_platform
*
* This multiplies a by b using multiply instruction using the ARM mul instruction regardless of values (the compiler
* might otherwise choose to perform shifts/adds), i.e. this is a 1 cycle operation.
*
* \param a the first operand
* \param b the second operand
* \return a * b
*/
__force_inline static int32_t __mul_instruction(int32_t a, int32_t b) {
#ifdef __riscv
__asm ("mul %0, %0, %1" : "+r" (a) : "r" (b) : );
#else
pico_default_asm ("muls %0, %1" : "+l" (a) : "l" (b) : "cc");
#endif
return a;
}
/*! \brief multiply two integer values using the fastest method possible
* \ingroup pico_platform
*
* Efficiently multiplies value a by possibly constant value b.
*
* If b is known to be constant and not zero or a power of 2, then a mul instruction is used rather than gcc's default
* which is often a slow combination of shifts and adds. If b is a power of 2 then a single shift is of course preferable
* and will be used
*
* \param a the first operand
* \param b the second operand
* \return a * b
*/
#define __fast_mul(a, b) __builtin_choose_expr(__builtin_constant_p(b) && !__builtin_constant_p(a), \
(__builtin_popcount(b) >= 2 ? __mul_instruction(a,b) : (a)*(b)), \
(a)*(b))
#endif // __ASSEMBLER__
#endif

View file

@ -0,0 +1,19 @@
/*
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
// ---------------------------------------
// THIS FILE IS AUTOGENERATED; DO NOT EDIT
// ---------------------------------------
#ifndef _PICO_VERSION_H
#define _PICO_VERSION_H
#define PICO_SDK_VERSION_MAJOR 2
#define PICO_SDK_VERSION_MINOR 1
#define PICO_SDK_VERSION_REVISION 0
#define PICO_SDK_VERSION_STRING "2.1.0"
#endif

View file

@ -21,26 +21,46 @@
#pragma once #pragma once
#if defined(RP2350) #define _ADDRESSMAP_H
#define NVIC_PriorityGroup_2 0x500
#define SPI_IO_AF_CFG 0
#define SPI_IO_AF_SCK_CFG_HIGH 0
#define SPI_IO_AF_SCK_CFG_LOW 0
#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 "RP2350.h"
#include "pico/stdlib.h"
#include "hardware/spi.h"
#if defined(RP2350A) || defined(RP2350B)
typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState; typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
#define I2C_TypeDef I2C0_Type #define I2C_TypeDef i2c0_hw
//#define I2C_HandleTypeDef //#define I2C_HandleTypeDef
#define GPIO_TypeDef IO_BANK0_Type #define GPIO_TypeDef io_bank0_hw_t
//#define GPIO_InitTypeDef //#define GPIO_InitTypeDef
#define TIM_TypeDef TIMER0_Type #define TIM_TypeDef void*
//#define TIM_OCInitTypeDef //#define TIM_OCInitTypeDef
#define DMA_TypeDef DMA_Type #define DMA_TypeDef void*
//#define DMA_InitTypeDef //#define DMA_InitTypeDef
//#define DMA_Channel_TypeDef //#define DMA_Channel_TypeDef
#define SPI_TypeDef SPI0_Type #define SPI_TypeDef spi_inst_t
#define ADC_TypeDef ADC_Type #define ADC_TypeDef void*
#define USART_TypeDef UART0_Type #define USART_TypeDef uart_inst_t
#define TIM_OCInitTypeDef TIMER0_Type #define TIM_OCInitTypeDef void*
#define TIM_ICInitTypeDef TIMER0_Type #define TIM_ICInitTypeDef void*
//#define TIM_OCStructInit //#define TIM_OCStructInit
//#define TIM_Cmd //#define TIM_Cmd
//#define TIM_CtrlPWMOutputs //#define TIM_CtrlPWMOutputs
@ -49,19 +69,24 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
//#define SystemCoreClock //#define SystemCoreClock
//#define EXTI_TypeDef //#define EXTI_TypeDef
//#define EXTI_InitTypeDef //#define EXTI_InitTypeDef
//#define IRQn_Type void*
#endif #endif
#define DMA_DATA_ZERO_INIT
#define DMA_DATA
#define STATIC_DMA_DATA_AUTO static
#define DEFAULT_CPU_OVERCLOCK 0 #define DEFAULT_CPU_OVERCLOCK 0
#define TASK_GYROPID_DESIRED_PERIOD 125 // 125us = 8kHz #define TASK_GYROPID_DESIRED_PERIOD 125 // 125us = 8kHz
#define SCHEDULER_DELAY_LIMIT 10 #define SCHEDULER_DELAY_LIMIT 10
#define IOCFG_OUT_PP 0 #define IO_CONFIG(mode, speed, pupd) ((mode) | ((speed) << 2) | ((pupd) << 5))
#define IOCFG_OUT_OD 0
#define IOCFG_OUT_PP IO_CONFIG(GPIO_OUT, 0, 0)
#define IOCFG_OUT_OD IO_CONFIG(GPIO_OUT, 0, 0)
#define IOCFG_AF_PP 0 #define IOCFG_AF_PP 0
#define IOCFG_AF_OD 0 #define IOCFG_AF_OD 0
#define IOCFG_IPD 0 #define IOCFG_IPD IO_CONFIG(GPIO_IN, 0, 0)
#define IOCFG_IPU 0 #define IOCFG_IPU IO_CONFIG(GPIO_IN, 0, 0)
#define IOCFG_IN_FLOATING 0 #define IOCFG_IN_FLOATING IO_CONFIG(GPIO_IN, 0, 0)

View file

@ -0,0 +1,125 @@
/*
* 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
// Configuration constants
#define UART_TX_BUFFER_ATTRIBUTE // NONE
#define UART_RX_BUFFER_ATTRIBUTE // NONE
#define UARTHARDWARE_MAX_PINS 3
#ifndef UART_RX_BUFFER_SIZE
#define UART_RX_BUFFER_SIZE 256
#endif
#ifndef UART_TX_BUFFER_SIZE
#ifdef USE_MSP_DISPLAYPORT
#define UART_TX_BUFFER_SIZE 1280
#else
#define UART_TX_BUFFER_SIZE 256
#endif
#endif
// compressed index of UART/LPUART. Direct index into uartDevice[]
typedef enum {
UARTDEV_INVALID = -1,
#ifdef USE_UART0
UARTDEV_0,
#endif
#ifdef USE_UART1
UARTDEV_1,
#endif
UARTDEV_COUNT
} uartDeviceIdx_e;
typedef struct uartPinDef_s {
ioTag_t pin;
} uartPinDef_t;
typedef struct uartHardware_s {
serialPortIdentifier_e identifier;
uart_inst_t* reg;
uartPinDef_t rxPins[UARTHARDWARE_MAX_PINS];
uartPinDef_t txPins[UARTHARDWARE_MAX_PINS];
uint8_t irqn;
volatile uint8_t *txBuffer;
volatile uint8_t *rxBuffer;
uint16_t txBufferSize;
uint16_t rxBufferSize;
} uartHardware_t;
extern const uartHardware_t uartHardware[UARTDEV_COUNT];
// uartDevice_t is an actual device instance.
// XXX Instances are allocated for uarts defined by USE_UARTx atm.
typedef enum {
TX_PIN_ACTIVE,
TX_PIN_MONITOR,
TX_PIN_IGNORE
} txPinState_t;
// TODO: merge uartPort_t and uartDevice_t
typedef struct uartDevice_s {
uartPort_t port;
const uartHardware_t *hardware;
uartPinDef_t rx;
uartPinDef_t tx;
volatile uint8_t *rxBuffer;
volatile uint8_t *txBuffer;
txPinState_t txPinState;
} uartDevice_t;
extern uartDevice_t uartDevice[UARTDEV_COUNT]; // indexed by uartDeviceIdx_e;
uartDeviceIdx_e uartDeviceIdxFromIdentifier(serialPortIdentifier_e identifier);
uartDevice_t* uartDeviceFromIdentifier(serialPortIdentifier_e identifier);
extern const struct serialPortVTable uartVTable[];
uartPort_t *serialUART(uartDevice_t *uart, uint32_t baudRate, portMode_e mode, portOptions_e options);
void uartConfigureExternalPinInversion(uartPort_t *uartPort);
void uartReconfigure(uartPort_t *uartPort);
void uartConfigureDma(uartDevice_t *uartdev);
void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor);
bool checkUsartTxOutput(uartPort_t *s);
void uartTxMonitor(uartPort_t *s);
#define UART_BUFFER(type, n, rxtx) type volatile uint8_t uart ## n ## rxtx ## xBuffer[UART_ ## rxtx ## X_BUFFER_SIZE]
#define UART_BUFFERS_EXTERN(n) \
UART_BUFFER(extern, n, R); \
UART_BUFFER(extern, n, T); struct dummy_s \
/**/
#ifdef USE_UART0
UART_BUFFERS_EXTERN(0);
#endif
#ifdef USE_UART1
UART_BUFFERS_EXTERN(1);
#endif
#undef UART_BUFFERS_EXTERN

View file

@ -0,0 +1,205 @@
/*
* 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/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#ifdef USE_UART
#include "drivers/system.h"
#include "drivers/io.h"
#include "drivers/serial.h"
#include "drivers/serial_uart.h"
#include "drivers/serial_impl.h"
#include "serial_uart_impl.h"
#include "hardware/uart.h"
#include "hardware/irq.h"
const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART0
{
.identifier = SERIAL_PORT_UART0,
.reg = uart0,
.rxPins = {
{ DEFIO_TAG_E(PA1) },
{ DEFIO_TAG_E(PA17) },
},
.txPins = {
{ DEFIO_TAG_E(PA0) },
{ DEFIO_TAG_E(PA16) },
},
.irqn = UART0_IRQ,
.txBuffer = uart0TxBuffer,
.rxBuffer = uart0RxBuffer,
.txBufferSize = sizeof(uart0TxBuffer),
.rxBufferSize = sizeof(uart0RxBuffer),
},
#endif
#ifdef USE_UART1
{
.identifier = SERIAL_PORT_UART1,
.reg = uart1,
.rxPins = {
{ DEFIO_TAG_E(PA5) },
{ DEFIO_TAG_E(PA9) },
{ DEFIO_TAG_E(PA25) },
},
.txPins = {
{ DEFIO_TAG_E(PA4) },
{ DEFIO_TAG_E(PA20) },
{ DEFIO_TAG_E(PA24) },
},
.irqn = UART1_IRQ,
.txBuffer = uart1TxBuffer,
.rxBuffer = uart1RxBuffer,
.txBufferSize = sizeof(uart1TxBuffer),
.rxBufferSize = sizeof(uart1RxBuffer),
},
#endif
};
static void uartIrqHandler(uartPort_t *s)
{
if ((uart_get_hw(s->USARTx)->imsc & UART_UARTIMSC_RXIM_BITS) != 0) {
while (uart_is_readable(s->USARTx)) {
const uint8_t ch = uart_getc(s->USARTx);
if (s->port.rxCallback) {
s->port.rxCallback(ch, s->port.rxCallbackData);
} else {
s->port.rxBuffer[s->port.rxBufferHead] = ch;
s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
}
}
}
if ((uart_get_hw(s->USARTx)->imsc & UART_UARTIMSC_TXIM_BITS) != 0) {
while (uart_is_writable(s->USARTx)) {
if (s->port.txBufferTail != s->port.txBufferHead) {
uart_putc(s->USARTx, s->port.txBuffer[s->port.txBufferTail]);
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
} else {
uart_set_irqs_enabled(s->USARTx, true, false);
break;
}
}
}
}
static void on_uart0(void)
{
uartIrqHandler(&uartDevice[UARTDEV_0].port);
}
static void on_uart1(void)
{
uartIrqHandler(&uartDevice[UARTDEV_1].port);
}
uartPort_t *serialUART(uartDevice_t *uartdev, uint32_t baudRate, portMode_e mode, portOptions_e options)
{
UNUSED(options);
uartPort_t *s = &uartdev->port;
const uartHardware_t *hardware = uartdev->hardware;
s->port.vTable = uartVTable;
s->port.baudRate = baudRate;
s->port.rxBuffer = hardware->rxBuffer;
s->port.txBuffer = hardware->txBuffer;
s->port.rxBufferSize = hardware->rxBufferSize;
s->port.txBufferSize = hardware->txBufferSize;
s->USARTx = hardware->reg;
IO_t txIO = IOGetByTag(uartdev->tx.pin);
IO_t rxIO = IOGetByTag(uartdev->rx.pin);
const serialPortIdentifier_e identifier = s->port.identifier;
const int ownerIndex = serialOwnerIndex(identifier);
const resourceOwner_e ownerTxRx = serialOwnerTxRx(identifier); // rx is always +1
IOInit(txIO, ownerTxRx, ownerIndex);
IOInit(txIO, ownerTxRx, ownerIndex);
uart_init(hardware->reg, baudRate);
if ((mode & MODE_TX) && txIO) {
IOInit(txIO, ownerTxRx, ownerIndex);
gpio_set_function(IO_Pin(txIO), GPIO_FUNC_UART);
}
if ((mode & MODE_RX) && rxIO) {
IOInit(rxIO, ownerTxRx + 1, ownerIndex);
gpio_set_function(IO_Pin(rxIO), GPIO_FUNC_UART);
}
uart_set_hw_flow(hardware->reg, false, false);
uart_set_format(hardware->reg, 8, 1, UART_PARITY_NONE);
uart_set_fifo_enabled(hardware->reg, false);
irq_set_exclusive_handler(hardware->irqn, hardware->irqn == UART0_IRQ ? on_uart0 : on_uart1);
irq_set_enabled(hardware->irqn, true);
if ((mode & MODE_RX) && rxIO) {
uart_set_irqs_enabled(hardware->reg, true, false);
}
return s;
}
// called from platform-specific uartReconfigure
void uartConfigureExternalPinInversion(uartPort_t *uartPort)
{
#if !defined(USE_INVERTER)
UNUSED(uartPort);
#else
const bool inverted = uartPort->port.options & SERIAL_INVERTED;
enableInverter(uartPort->port.identifier, inverted);
#endif
}
void uartTryStartTx(uartPort_t *s)
{
if (s->port.txBufferTail == s->port.txBufferHead) {
return;
}
uart_set_irqs_enabled(s->USARTx, uart_get_hw(s->USARTx)->imsc & UART_UARTIMSC_RXIM_BITS, true);
}
void uartReconfigure(uartPort_t *s)
{
uart_deinit(s->USARTx);
uart_init(s->USARTx, s->port.baudRate);
uart_set_format(s->USARTx, 8, 1, UART_PARITY_NONE);
uart_set_fifo_enabled(s->USARTx, false);
uartConfigureExternalPinInversion(s);
}
#endif /* USE_UART */

132
src/platform/PICO/system.c Normal file
View file

@ -0,0 +1,132 @@
/*
* 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/>.
*/
#include "platform.h"
#include <stdint.h>
#include "hardware/timer.h"
#include "hardware/clocks.h"
int main(int argc, char * argv[]);
void Reset_Handler(void);
void Default_Handler(void);
// cycles per microsecond
static uint32_t usTicks = 0;
void (* const vector_table[])() __attribute__((section(".vectors"))) = {
(void (*)())0x20000000, // Initial Stack Pointer
Reset_Handler, // Interrupt Handler for reset
Default_Handler, // Default handler for other interrupts
};
uint32_t SystemCoreClock; /* System Clock Frequency (Core Clock)*/
void SystemCoreClockUpdate (void)
{
SystemCoreClock = clock_get_hz(clk_sys);
}
void __attribute__((constructor)) SystemInit (void)
{
SystemCoreClockUpdate();
}
void Reset_Handler(void)
{
// Initialize data segments
extern uint32_t _sdata, _edata, _sidata;
uint32_t *src = &_sidata;
uint32_t *dst = &_sdata;
while (dst < &_edata) {
*dst++ = *src++;
}
// Clear bss segment
extern uint32_t _sbss, _ebss;
dst = &_sbss;
while (dst < &_ebss) {
*dst++ = 0;
}
usTicks = clock_get_hz(clk_sys) / 1000000;
// Call main function
main(0, 0);
}
void Default_Handler(void)
{
while (1); // Infinite loop on default handler
}
void systemReset(void)
{
//TODO: implement
}
void systemInit(void)
{
//TODO: implement
}
// Return system uptime in milliseconds (rollover in 49 days)
uint32_t millis(void)
{
//TODO: correction required?
return time_us_32() / 1000;
}
// Return system uptime in micros
uint32_t micros(void)
{
return time_us_32();
}
uint32_t microsISR(void)
{
return micros();
}
void delayMicroseconds(uint32_t us)
{
uint32_t now = micros();
while (micros() - now < us);
}
void delay(uint32_t ms)
{
while (ms--) {
delayMicroseconds(1000);
}
}
uint32_t getCycleCounter(void)
{
return time_us_32();
}
uint32_t clockMicrosToCycles(uint32_t micros)
{
return micros / usTicks;
}

View file

@ -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

View file

@ -1,2 +0,0 @@
TARGET_MCU := RP2350
TARGET_MCU_FAMILY := PICO

View file

@ -0,0 +1,212 @@
/*
* 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 RP2350B
#define RP2350B
#endif
#ifndef TARGET_BOARD_IDENTIFIER
#define TARGET_BOARD_IDENTIFIER "235B"
#endif
#ifndef USBD_PRODUCT_STRING
#define USBD_PRODUCT_STRING "Betaflight RP2350B"
#endif
#define USE_IO
#define USE_UART0
#define USE_UART1
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#undef USE_SOFTSERIAL1
#undef USE_SOFTSERIAL2
#undef USE_VCP
#undef USE_TRANSPONDER
#undef USE_DMA
#undef USE_FLASH
#undef USE_FLASH_CHIP
#undef USE_SDCARD
#undef USE_TIMER
#undef USE_I2C
#undef USE_UART
#undef USE_DSHOT
#undef USE_RCC
#undef USE_CLI
#undef USE_PWM_OUTPUT
#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_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
#define FLASH_PAGE_SIZE 0x1000
#define CONFIG_IN_RAM
#define U_ID_0 0
#define U_ID_1 1
#define U_ID_2 2
/* to be moved to a config file once target if working */
#define LED0_PIN PA6
#define LED1_PIN PA7
#define SPI0_SCK_PIN PA5
#define SPI0_SDI_PIN PA6
#define SPI0_SDO_PIN PA7
#define SPI1_SCK_PIN PA26
#define SPI1_SDI_PIN PA24
#define SPI1_SDO_PIN PA27
#define SDCARD_CS_PIN PA25
#define FLASH_CS_PIN PA25
#define MAX7456_SPI_CS_PIN PA17
#define GYRO_1_CS_PIN PA1
#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
*/

View file

@ -0,0 +1,8 @@
TARGET_MCU := RP2350B
TARGET_MCU_FAMILY := PICO
DEVICE_FLAGS += \
-DPICO_RP2350B=1 \
-DPICO_RP2350_A2_SUPPORTED=1 \
-DPICO_FLASH_SPI_CLKDIV=2 \
-DPICO_BOOT_STAGE2_CHOOSE_W25Q080=1