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

Adding RP2350 SDK and target framework (#13988)

* Adding RP2350 SDK and target framework

* Spacing

* Removing board definitions
This commit is contained in:
J Blackman 2024-10-23 10:02:48 +11:00 committed by GitHub
parent 462cb05930
commit 2dd6f95aad
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
576 changed files with 435012 additions and 0 deletions

View file

@ -0,0 +1,221 @@
/*
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "hardware/flash.h"
#include "pico/bootrom.h"
#if PICO_RP2040
#include "hardware/structs/io_qspi.h"
#include "hardware/structs/ssi.h"
#else
#include "hardware/structs/qmi.h"
#endif
#define FLASH_BLOCK_ERASE_CMD 0xd8
// Standard RUID instruction: 4Bh command prefix, 32 dummy bits, 64 data bits.
#define FLASH_RUID_CMD 0x4b
#define FLASH_RUID_DUMMY_BYTES 4
#define FLASH_RUID_DATA_BYTES FLASH_UNIQUE_ID_SIZE_BYTES
#define FLASH_RUID_TOTAL_BYTES (1 + FLASH_RUID_DUMMY_BYTES + FLASH_RUID_DATA_BYTES)
//-----------------------------------------------------------------------------
// Infrastructure for reentering XIP mode after exiting for programming (take
// a copy of boot2 before XIP exit). Calling boot2 as a function works because
// it accepts a return vector in LR (and doesn't trash r4-r7). Bootrom passes
// NULL in LR, instructing boot2 to enter flash vector table's reset handler.
#if !PICO_NO_FLASH
#define BOOT2_SIZE_WORDS 64
static uint32_t boot2_copyout[BOOT2_SIZE_WORDS];
static bool boot2_copyout_valid = false;
static void __no_inline_not_in_flash_func(flash_init_boot2_copyout)(void) {
if (boot2_copyout_valid)
return;
// todo we may want the option of boot2 just being a free function in
// user RAM, e.g. if it is larger than 256 bytes
#if PICO_RP2040
const volatile uint32_t *copy_from = (uint32_t *)XIP_BASE;
#else
const volatile uint32_t *copy_from = (uint32_t *)BOOTRAM_BASE;
#endif
for (int i = 0; i < BOOT2_SIZE_WORDS; ++i)
boot2_copyout[i] = copy_from[i];
__compiler_memory_barrier();
boot2_copyout_valid = true;
}
static void __no_inline_not_in_flash_func(flash_enable_xip_via_boot2)(void) {
((void (*)(void))((intptr_t)boot2_copyout+1))();
}
#else
static void __no_inline_not_in_flash_func(flash_init_boot2_copyout)(void) {}
static void __no_inline_not_in_flash_func(flash_enable_xip_via_boot2)(void) {
// Set up XIP for 03h read on bus access (slow but generic)
rom_flash_enter_cmd_xip_fn flash_enter_cmd_xip_func = (rom_flash_enter_cmd_xip_fn)rom_func_lookup_inline(ROM_FUNC_FLASH_ENTER_CMD_XIP);
assert(flash_enter_cmd_xip_func);
flash_enter_cmd_xip_func();
}
#endif
//-----------------------------------------------------------------------------
// Actual flash programming shims (work whether or not PICO_NO_FLASH==1)
void __no_inline_not_in_flash_func(flash_range_erase)(uint32_t flash_offs, size_t count) {
#ifdef PICO_FLASH_SIZE_BYTES
hard_assert(flash_offs + count <= PICO_FLASH_SIZE_BYTES);
#endif
invalid_params_if(HARDWARE_FLASH, flash_offs & (FLASH_SECTOR_SIZE - 1));
invalid_params_if(HARDWARE_FLASH, count & (FLASH_SECTOR_SIZE - 1));
rom_connect_internal_flash_fn connect_internal_flash_func = (rom_connect_internal_flash_fn)rom_func_lookup_inline(ROM_FUNC_CONNECT_INTERNAL_FLASH);
rom_flash_exit_xip_fn flash_exit_xip_func = (rom_flash_exit_xip_fn)rom_func_lookup_inline(ROM_FUNC_FLASH_EXIT_XIP);
rom_flash_range_erase_fn flash_range_erase_func = (rom_flash_range_erase_fn)rom_func_lookup_inline(ROM_FUNC_FLASH_RANGE_ERASE);
rom_flash_flush_cache_fn flash_flush_cache_func = (rom_flash_flush_cache_fn)rom_func_lookup_inline(ROM_FUNC_FLASH_FLUSH_CACHE);
assert(connect_internal_flash_func && flash_exit_xip_func && flash_range_erase_func && flash_flush_cache_func);
flash_init_boot2_copyout();
// No flash accesses after this point
__compiler_memory_barrier();
connect_internal_flash_func();
flash_exit_xip_func();
flash_range_erase_func(flash_offs, count, FLASH_BLOCK_SIZE, FLASH_BLOCK_ERASE_CMD);
flash_flush_cache_func(); // Note this is needed to remove CSn IO force as well as cache flushing
flash_enable_xip_via_boot2();
}
void __no_inline_not_in_flash_func(flash_flush_cache)(void) {
rom_flash_flush_cache_fn flash_flush_cache_func = (rom_flash_flush_cache_fn)rom_func_lookup_inline(ROM_FUNC_FLASH_FLUSH_CACHE);
flash_flush_cache_func();
}
void __no_inline_not_in_flash_func(flash_range_program)(uint32_t flash_offs, const uint8_t *data, size_t count) {
#ifdef PICO_FLASH_SIZE_BYTES
hard_assert(flash_offs + count <= PICO_FLASH_SIZE_BYTES);
#endif
invalid_params_if(HARDWARE_FLASH, flash_offs & (FLASH_PAGE_SIZE - 1));
invalid_params_if(HARDWARE_FLASH, count & (FLASH_PAGE_SIZE - 1));
rom_connect_internal_flash_fn connect_internal_flash_func = (rom_connect_internal_flash_fn)rom_func_lookup_inline(ROM_FUNC_CONNECT_INTERNAL_FLASH);
rom_flash_exit_xip_fn flash_exit_xip_func = (rom_flash_exit_xip_fn)rom_func_lookup_inline(ROM_FUNC_FLASH_EXIT_XIP);
rom_flash_range_program_fn flash_range_program_func = (rom_flash_range_program_fn)rom_func_lookup_inline(ROM_FUNC_FLASH_RANGE_PROGRAM);
rom_flash_flush_cache_fn flash_flush_cache_func = (rom_flash_flush_cache_fn)rom_func_lookup_inline(ROM_FUNC_FLASH_FLUSH_CACHE);
assert(connect_internal_flash_func && flash_exit_xip_func && flash_range_program_func && flash_flush_cache_func);
flash_init_boot2_copyout();
__compiler_memory_barrier();
connect_internal_flash_func();
flash_exit_xip_func();
flash_range_program_func(flash_offs, data, count);
flash_flush_cache_func(); // Note this is needed to remove CSn IO force as well as cache flushing
flash_enable_xip_via_boot2();
}
//-----------------------------------------------------------------------------
// Lower-level flash access functions
#if !PICO_NO_FLASH
// Bitbanging the chip select using IO overrides, in case RAM-resident IRQs
// are still running, and the FIFO bottoms out. (the bootrom does the same)
static void __no_inline_not_in_flash_func(flash_cs_force)(bool high) {
#if PICO_RP2040
uint32_t field_val = high ?
IO_QSPI_GPIO_QSPI_SS_CTRL_OUTOVER_VALUE_HIGH :
IO_QSPI_GPIO_QSPI_SS_CTRL_OUTOVER_VALUE_LOW;
hw_write_masked(&io_qspi_hw->io[1].ctrl,
field_val << IO_QSPI_GPIO_QSPI_SS_CTRL_OUTOVER_LSB,
IO_QSPI_GPIO_QSPI_SS_CTRL_OUTOVER_BITS
);
#else
if (high) {
hw_clear_bits(&qmi_hw->direct_csr, QMI_DIRECT_CSR_ASSERT_CS0N_BITS);
} else {
hw_set_bits(&qmi_hw->direct_csr, QMI_DIRECT_CSR_ASSERT_CS0N_BITS);
}
#endif
}
void __no_inline_not_in_flash_func(flash_do_cmd)(const uint8_t *txbuf, uint8_t *rxbuf, size_t count) {
rom_connect_internal_flash_fn connect_internal_flash_func = (rom_connect_internal_flash_fn)rom_func_lookup_inline(ROM_FUNC_CONNECT_INTERNAL_FLASH);
rom_flash_exit_xip_fn flash_exit_xip_func = (rom_flash_exit_xip_fn)rom_func_lookup_inline(ROM_FUNC_FLASH_EXIT_XIP);
rom_flash_flush_cache_fn flash_flush_cache_func = (rom_flash_flush_cache_fn)rom_func_lookup_inline(ROM_FUNC_FLASH_FLUSH_CACHE);
assert(connect_internal_flash_func && flash_exit_xip_func && flash_flush_cache_func);
flash_init_boot2_copyout();
__compiler_memory_barrier();
connect_internal_flash_func();
flash_exit_xip_func();
flash_cs_force(0);
size_t tx_remaining = count;
size_t rx_remaining = count;
#if PICO_RP2040
// Synopsys SSI version
// We may be interrupted -- don't want FIFO to overflow if we're distracted.
const size_t max_in_flight = 16 - 2;
while (tx_remaining || rx_remaining) {
uint32_t flags = ssi_hw->sr;
bool can_put = flags & SSI_SR_TFNF_BITS;
bool can_get = flags & SSI_SR_RFNE_BITS;
if (can_put && tx_remaining && rx_remaining - tx_remaining < max_in_flight) {
ssi_hw->dr0 = *txbuf++;
--tx_remaining;
}
if (can_get && rx_remaining) {
*rxbuf++ = (uint8_t)ssi_hw->dr0;
--rx_remaining;
}
}
#else
// QMI version -- no need to bound FIFO contents as QMI stalls on full DIRECT_RX.
hw_set_bits(&qmi_hw->direct_csr, QMI_DIRECT_CSR_EN_BITS);
while (tx_remaining || rx_remaining) {
uint32_t flags = qmi_hw->direct_csr;
bool can_put = !(flags & QMI_DIRECT_CSR_TXFULL_BITS);
bool can_get = !(flags & QMI_DIRECT_CSR_RXEMPTY_BITS);
if (can_put && tx_remaining) {
qmi_hw->direct_tx = *txbuf++;
--tx_remaining;
}
if (can_get && rx_remaining) {
*rxbuf++ = (uint8_t)qmi_hw->direct_rx;
--rx_remaining;
}
}
hw_clear_bits(&qmi_hw->direct_csr, QMI_DIRECT_CSR_EN_BITS);
#endif
flash_cs_force(1);
flash_flush_cache_func();
flash_enable_xip_via_boot2();
}
#endif
// Use standard RUID command to get a unique identifier for the flash (and
// hence the board)
static_assert(FLASH_UNIQUE_ID_SIZE_BYTES == FLASH_RUID_DATA_BYTES, "");
void flash_get_unique_id(uint8_t *id_out) {
#if PICO_NO_FLASH
__unused uint8_t *ignore = id_out;
panic_unsupported();
#else
uint8_t txbuf[FLASH_RUID_TOTAL_BYTES] = {0};
uint8_t rxbuf[FLASH_RUID_TOTAL_BYTES] = {0};
txbuf[0] = FLASH_RUID_CMD;
flash_do_cmd(txbuf, rxbuf, FLASH_RUID_TOTAL_BYTES);
for (int i = 0; i < FLASH_RUID_DATA_BYTES; i++)
id_out[i] = rxbuf[i + 1 + FLASH_RUID_DUMMY_BYTES];
#endif
}

View file

@ -0,0 +1,128 @@
/*
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef _HARDWARE_FLASH_H
#define _HARDWARE_FLASH_H
#include "pico.h"
/** \file flash.h
* \defgroup hardware_flash hardware_flash
*
* \brief Low level flash programming and erase API
*
* Note these functions are *unsafe* if you are using both cores, and the other
* is executing from flash concurrently with the operation. In this could be the
* case, you must perform your own synchronisation to make sure that no XIP
* accesses take place during flash programming. One option is to use the
* \ref multicore_lockout functions.
*
* Likewise they are *unsafe* if you have interrupt handlers or an interrupt
* vector table in flash, so you must disable interrupts before calling in
* this case.
*
* If PICO_NO_FLASH=1 is not defined (i.e. if the program is built to run from
* flash) then these functions will make a static copy of the second stage
* bootloader in SRAM, and use this to reenter execute-in-place mode after
* programming or erasing flash, so that they can safely be called from
* flash-resident code.
*
* \subsection flash_example Example
* \include flash_program.c
*/
// PICO_CONFIG: PARAM_ASSERTIONS_ENABLED_HARDWARE_FLASH, Enable/disable assertions in the hardware_flash module, type=bool, default=0, group=hardware_flash
#ifndef PARAM_ASSERTIONS_ENABLED_HARDWARE_FLASH
#ifdef PARAM_ASSERTIONS_ENABLED_FLASH // backwards compatibility with SDK < 2.0.0
#define PARAM_ASSERTIONS_ENABLED_HARDWARE_FLASH PARAM_ASSERTIONS_ENABLED_FLASH
#else
#define PARAM_ASSERTIONS_ENABLED_HARDWARE_FLASH 0
#endif
#endif
#define FLASH_PAGE_SIZE (1u << 8)
#define FLASH_SECTOR_SIZE (1u << 12)
#define FLASH_BLOCK_SIZE (1u << 16)
#ifndef FLASH_UNIQUE_ID_SIZE_BYTES
#define FLASH_UNIQUE_ID_SIZE_BYTES 8
#endif
// PICO_CONFIG: PICO_FLASH_SIZE_BYTES, size of primary flash in bytes, type=int, default=Usually provided via board header, group=hardware_flash
#ifdef __cplusplus
extern "C" {
#endif
/*! \brief Erase areas of flash
* \ingroup hardware_flash
*
* \param flash_offs Offset into flash, in bytes, to start the erase. Must be aligned to a 4096-byte flash sector.
* \param count Number of bytes to be erased. Must be a multiple of 4096 bytes (one sector).
*
* @note Erasing a flash sector sets all the bits in all the pages in that sector to one.
* You can then "program" flash pages in the sector to turn some of the bits to zero.
* Once a bit is set to zero it can only be changed back to one by erasing the whole sector again.
*/
void flash_range_erase(uint32_t flash_offs, size_t count);
/*! \brief Program flash
* \ingroup hardware_flash
*
* \param flash_offs Flash address of the first byte to be programmed. Must be aligned to a 256-byte flash page.
* \param data Pointer to the data to program into flash
* \param count Number of bytes to program. Must be a multiple of 256 bytes (one page).
*
* @note: Programming a flash page effectively changes some of the bits from one to zero.
* The only way to change a zero bit back to one is to "erase" the whole sector that the page resides in.
* So you may need to make sure you have called flash_range_erase before calling flash_range_program.
*/
void flash_range_program(uint32_t flash_offs, const uint8_t *data, size_t count);
/*! \brief Get flash unique 64 bit identifier
* \ingroup hardware_flash
*
* Use a standard 4Bh RUID instruction to retrieve the 64 bit unique
* identifier from a flash device attached to the QSPI interface. Since there
* is a 1:1 association between the MCU and this flash, this also serves as a
* unique identifier for the board.
*
* \param id_out Pointer to an 8-byte buffer to which the ID will be written
*/
void flash_get_unique_id(uint8_t *id_out);
/*! \brief Execute bidirectional flash command
* \ingroup hardware_flash
*
* Low-level function to execute a serial command on a flash device attached
* to the QSPI interface. Bytes are simultaneously transmitted and received
* from txbuf and to rxbuf. Therefore, both buffers must be the same length,
* count, which is the length of the overall transaction. This is useful for
* reading metadata from the flash chip, such as device ID or SFDP
* parameters.
*
* The XIP cache is flushed following each command, in case flash state
* has been modified. Like other hardware_flash functions, the flash is not
* accessible for execute-in-place transfers whilst the command is in
* progress, so entering a flash-resident interrupt handler or executing flash
* code on the second core concurrently will be fatal. To avoid these pitfalls
* it is recommended that this function only be used to extract flash metadata
* during startup, before the main application begins to run: see the
* implementation of pico_get_unique_id() for an example of this.
*
* \param txbuf Pointer to a byte buffer which will be transmitted to the flash
* \param rxbuf Pointer to a byte buffer where data received from the flash will be written. txbuf and rxbuf may be the same buffer.
* \param count Length in bytes of txbuf and of rxbuf
*/
void flash_do_cmd(const uint8_t *txbuf, uint8_t *rxbuf, size_t count);
void flash_flush_cache(void);
#ifdef __cplusplus
}
#endif
#endif