1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 08:15:30 +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,102 @@
/*
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "pico/bootrom.h"
#include "boot/picoboot.h"
#include "boot/picobin.h"
/// \tag::table_lookup[]
void *rom_func_lookup(uint32_t code) {
return rom_func_lookup_inline(code);
}
#pragma GCC diagnostic push
// diagnostic: GCC thinks near-zero value is a null pointer member access, but it's not
#pragma GCC diagnostic ignored "-Warray-bounds"
void *rom_data_lookup(uint32_t code) {
#if PICO_RP2040
rom_table_lookup_fn rom_table_lookup = (rom_table_lookup_fn) rom_hword_as_ptr(BOOTROM_TABLE_LOOKUP_OFFSET);
uint16_t *data_table = (uint16_t *) rom_hword_as_ptr(BOOTROM_DATA_TABLE_OFFSET);
return rom_table_lookup(data_table, code);
#else
rom_table_lookup_fn rom_table_lookup = (rom_table_lookup_fn) (uintptr_t)*(uint16_t*)(BOOTROM_TABLE_LOOKUP_OFFSET);
return rom_table_lookup(code, RT_FLAG_DATA);
#endif
}
#pragma GCC diagnostic pop
/// \end::table_lookup[]
bool rom_funcs_lookup(uint32_t *table, unsigned int count) {
bool ok = true;
for (unsigned int i = 0; i < count; i++) {
table[i] = (uintptr_t) rom_func_lookup(table[i]);
if (!table[i]) ok = false;
}
return ok;
}
void __attribute__((noreturn)) rom_reset_usb_boot(uint32_t usb_activity_gpio_pin_mask, uint32_t disable_interface_mask) {
#ifdef ROM_FUNC_RESET_USB_BOOT
rom_reset_usb_boot_fn func = (rom_reset_usb_boot_fn) rom_func_lookup(ROM_FUNC_RESET_USB_BOOT);
func(usb_activity_gpio_pin_mask, disable_interface_mask);
#elif defined(ROM_FUNC_REBOOT)
uint32_t flags = disable_interface_mask;
if (usb_activity_gpio_pin_mask) {
flags |= BOOTSEL_FLAG_GPIO_PIN_SPECIFIED;
// the parameter is actually the gpio number, but we only care if BOOTSEL_FLAG_GPIO_PIN_SPECIFIED
usb_activity_gpio_pin_mask = (uint32_t)__builtin_ctz(usb_activity_gpio_pin_mask);
}
rom_reboot(REBOOT2_FLAG_REBOOT_TYPE_BOOTSEL | REBOOT2_FLAG_NO_RETURN_ON_SUCCESS, 10, flags, usb_activity_gpio_pin_mask);
__builtin_unreachable();
#else
panic_unsupported();
#endif
}
#if !PICO_RP2040
bool rom_get_boot_random(uint32_t out[4]) {
uint32_t result[5];
rom_get_sys_info_fn func = (rom_get_sys_info_fn) rom_func_lookup_inline(ROM_FUNC_GET_SYS_INFO);
if (5 == func(result, count_of(result), SYS_INFO_BOOT_RANDOM)) {
for(uint i=0;i<4;i++) {
out[i] = result[i+1];
}
return true;
}
return false;
}
int rom_add_flash_runtime_partition(uint32_t start_offset, uint32_t size, uint32_t permissions) {
if ((start_offset) & 4095 || (size & 4095)) return PICO_ERROR_BAD_ALIGNMENT;
if (!size || start_offset + size > 32 * 1024 * 1024) return PICO_ERROR_INVALID_ARG;
if (permissions & ~PICOBIN_PARTITION_PERMISSIONS_BITS) return PICO_ERROR_INVALID_ARG;
void **ptr = (void **)rom_data_lookup(ROM_DATA_PARTITION_TABLE_PTR);
assert(ptr);
assert(*ptr);
struct pt {
struct {
uint8_t partition_count;
uint8_t permission_partition_count; // >= partition_count and includes any regions added at runtime
bool loaded;
};
uint32_t unpartitioned_space_permissions_and_flags;
resident_partition_t partitions[PARTITION_TABLE_MAX_PARTITIONS];
} *pt = (struct pt *)*ptr;
assert(pt->loaded); // even if empty it should have been populated by the bootrom
if (pt->permission_partition_count < pt->partition_count) pt->permission_partition_count = pt->partition_count;
if (pt->permission_partition_count < PARTITION_TABLE_MAX_PARTITIONS) {
pt->partitions[pt->permission_partition_count].permissions_and_location = permissions |
((start_offset / 4096) << PICOBIN_PARTITION_LOCATION_FIRST_SECTOR_LSB) |
((start_offset + size - 4096) / 4096) << PICOBIN_PARTITION_LOCATION_LAST_SECTOR_LSB;
pt->partitions[pt->permission_partition_count].permissions_and_flags = permissions;
return pt->permission_partition_count++;
}
return PICO_ERROR_INSUFFICIENT_RESOURCES;
}
#endif

View file

@ -0,0 +1,21 @@
/*
* Copyright (c) 2024 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "pico/bootrom/lock.h"
#include "pico/runtime_init.h"
#if PICO_BOOTROM_LOCKING_ENABLED
#if !PICO_RUNTIME_NO_INIT_BOOTROM_LOCKING_ENABLE
#include "hardware/sync.h"
void __weak runtime_init_bootrom_locking_enable(void) {
bootrom_acquire_lock_blocking(BOOTROM_LOCK_ENABLE);
}
#endif
#if !PICO_RUNTIME_SKIP_INIT_BOOTROM_LOCKING_ENABLE
PICO_RUNTIME_INIT_FUNC_RUNTIME(runtime_init_bootrom_locking_enable, PICO_RUNTIME_INIT_BOOTROM_LOCKING_ENABLE);
#endif
#endif

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,69 @@
/*
* Copyright (c) 2024 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef _PICO_BOOTROM_LOCK_H
#define _PICO_BOOTROM_LOCK_H
#include "hardware/boot_lock.h"
#include "pico/bootrom_constants.h"
// PICO_CONFIG: PICO_BOOTROM_LOCKING_ENABLED, Enable/disable locking for bootrom functions that use shared resources. If this flag is enabled bootrom lock checking is turned on and BOOT locks are taken around the relevant bootrom functions, type=bool, default=1, group=pico_bootrom
#ifndef PICO_BOOTROM_LOCKING_ENABLED
#if NUM_BOOT_LOCKS > 0
#define PICO_BOOTROM_LOCKING_ENABLED 1
#endif
#endif
/**
* \brief Try to acquire a bootrom lock
*
* If PICO_BOOTROM_LOCKING_ENABLED is false, this method returns true immediately
*
* \param lock_num the lock numbers - BOOTROM_LOCK_SHA_256, BOOTROM_LOCK_FLASH_OP or BOOTROM_LOCK_OTP
* \return true if the lock was acquired
*/
static inline bool bootrom_try_acquire_lock(uint lock_num) {
#if PICO_BOOTROM_LOCKING_ENABLED
// unsafe as this is a long term lock (so no irq disable)
return boot_try_lock_unsafe(boot_lock_instance(lock_num));
#else
(void)lock_num;
return true;
#endif
}
/**
* \brief Acquire a bootrom lock. If the lock is unavailable, block until it is available
*
* If PICO_BOOTROM_LOCKING_ENABLED is false, this method does nothing
*
* \param lock_num the lock numbers - BOOTROM_LOCK_SHA_256, BOOTROM_LOCK_FLASH_OP or BOOTROM_LOCK_OTP
*/
static inline void bootrom_acquire_lock_blocking(uint lock_num) {
#if PICO_BOOTROM_LOCKING_ENABLED
// unsafe as this is a long term lock (so no irq disable)
boot_lock_unsafe_blocking(boot_lock_instance(lock_num));
#else
(void)lock_num;
#endif
}
/**
* \brief Release a bootrom lock
*
* If PICO_BOOTROM_LOCKING_ENABLED is false, this method does nothing
*
* \param lock_num the lock numbers - BOOTROM_LOCK_SHA_256, BOOTROM_LOCK_FLASH_OP or BOOTROM_LOCK_OTP
*/
static inline void bootrom_release_lock(uint lock_num) {
#if PICO_BOOTROM_LOCKING_ENABLED
boot_unlock_unsafe(boot_lock_instance(lock_num));
#else
(void)lock_num;
#endif
}
#endif

View file

@ -0,0 +1,50 @@
/*
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef _PICO_BOOTROM_SF_TABLE_H
#define _PICO_BOOTROM_SF_TABLE_H
// NOTE THESE FUNCTION IMPLEMENTATIONS MATCH THE BEHAVIOR DESCRIBED IN THE BOOTROM SECTION OF THE RP2040 DATASHEET
#define SF_TABLE_FADD 0x00
#define SF_TABLE_FSUB 0x04
#define SF_TABLE_FMUL 0x08
#define SF_TABLE_FDIV 0x0c
#define SF_TABLE_FCMP_FAST 0x10
#define SF_TABLE_FCMP_FAST_FLAGS 0x14
#define SF_TABLE_FSQRT 0x18
#define SF_TABLE_FLOAT2INT 0x1c
#define SF_TABLE_FLOAT2FIX 0x20
#define SF_TABLE_FLOAT2UINT 0x24
#define SF_TABLE_FLOAT2UFIX 0x28
#define SF_TABLE_INT2FLOAT 0x2c
#define SF_TABLE_FIX2FLOAT 0x30
#define SF_TABLE_UINT2FLOAT 0x34
#define SF_TABLE_UFIX2FLOAT 0x38
#define SF_TABLE_FCOS 0x3c
#define SF_TABLE_FSIN 0x40
#define SF_TABLE_FTAN 0x44
#define SF_TABLE_V3_FSINCOS 0x48
#define SF_TABLE_FEXP 0x4c
#define SF_TABLE_FLN 0x50
#define SF_TABLE_V1_SIZE 0x54
#define SF_TABLE_FCMP_BASIC 0x54
#define SF_TABLE_FATAN2 0x58
#define SF_TABLE_INT642FLOAT 0x5c
#define SF_TABLE_FIX642FLOAT 0x60
#define SF_TABLE_UINT642FLOAT 0x64
#define SF_TABLE_UFIX642FLOAT 0x68
#define SF_TABLE_FLOAT2INT64 0x6c
#define SF_TABLE_FLOAT2FIX64 0x70
#define SF_TABLE_FLOAT2UINT64 0x74
#define SF_TABLE_FLOAT2UFIX64 0x78
#define SF_TABLE_FLOAT2DOUBLE 0x7c
#define SF_TABLE_V2_SIZE 0x80
#endif

View file

@ -0,0 +1,8 @@
/*
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
// new location; this file kept for backwards compatibility
#include "boot/bootrom_constants.h"