mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 16:55:36 +03:00
Adding RP2350 SDK and target framework (#13988)
* Adding RP2350 SDK and target framework * Spacing * Removing board definitions
This commit is contained in:
parent
462cb05930
commit
2dd6f95aad
576 changed files with 435012 additions and 0 deletions
35
lib/main/pico-sdk/rp2_common/hardware_boot_lock/boot_lock.c
Normal file
35
lib/main/pico-sdk/rp2_common/hardware_boot_lock/boot_lock.c
Normal file
|
@ -0,0 +1,35 @@
|
|||
/*
|
||||
* Copyright (c) 2024 Raspberry Pi (Trading) Ltd.
|
||||
*
|
||||
* SPDX-License-Identifier: BSD-3-Clause
|
||||
*/
|
||||
#include "hardware/boot_lock.h"
|
||||
#include "pico/runtime_init.h"
|
||||
|
||||
#if NUM_BOOT_LOCKS > 0
|
||||
void boot_locks_reset(void) {
|
||||
GCC_Pragma("GCC unroll 1") // prevent GCC unrolling this loop which is 8 bytes per
|
||||
for (uint i = 0; i < NUM_BOOT_LOCKS; i++) {
|
||||
boot_unlock_unsafe(boot_lock_instance(i));
|
||||
}
|
||||
}
|
||||
|
||||
boot_lock_t *boot_lock_init(uint lock_num) {
|
||||
assert(lock_num < NUM_BOOT_LOCKS);
|
||||
boot_lock_t *lock = boot_lock_instance(lock_num);
|
||||
boot_unlock_unsafe(lock);
|
||||
return lock;
|
||||
}
|
||||
|
||||
#if !PICO_RUNTIME_NO_INIT_BOOT_LOCKS_RESET
|
||||
#include "hardware/sync.h"
|
||||
void __weak runtime_init_boot_locks_reset(void) {
|
||||
boot_locks_reset();
|
||||
}
|
||||
#endif
|
||||
|
||||
#if !PICO_RUNTIME_SKIP_INIT_BOOT_LOCKS_RESET
|
||||
PICO_RUNTIME_INIT_FUNC_RUNTIME(runtime_init_boot_locks_reset, PICO_RUNTIME_INIT_BOOT_LOCKS_RESET);
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -0,0 +1,144 @@
|
|||
/*
|
||||
* Copyright (c) 2024 Raspberry Pi (Trading) Ltd.
|
||||
*
|
||||
* SPDX-License-Identifier: BSD-3-Clause
|
||||
*/
|
||||
|
||||
#ifndef _HARDWARE_BOOT_LOCK_H
|
||||
#define _HARDWARE_BOOT_LOCK_H
|
||||
|
||||
#include "pico.h"
|
||||
|
||||
// PICO_CONFIG: PARAM_ASSERTIONS_ENABLED_HARDWARE_BOOT_LOCK, Enable/disable assertions in the hardware_boot_lock module, type=bool, default=0, group=hardware_boot_lock
|
||||
#ifndef PARAM_ASSERTIONS_ENABLED_HARDWARE_BOOT_LOCK
|
||||
#define PARAM_ASSERTIONS_ENABLED_HARDWARE_BOOT_LOCK 0
|
||||
#endif
|
||||
|
||||
#if NUM_BOOT_LOCKS > 0
|
||||
#include "hardware/sync.h"
|
||||
#include "hardware/structs/bootram.h"
|
||||
|
||||
/** \brief A boot lock identifier
|
||||
* \ingroup hardware_sync
|
||||
*/
|
||||
typedef volatile uint32_t boot_lock_t;
|
||||
|
||||
/*! \brief Get HW Bootlock instance from number
|
||||
* \ingroup hardware_sync
|
||||
*
|
||||
* \param lock_num Bootlock ID
|
||||
* \return The bootlock instance
|
||||
*/
|
||||
__force_inline static boot_lock_t *boot_lock_instance(uint lock_num) {
|
||||
invalid_params_if(HARDWARE_BOOT_LOCK, lock_num >= NUM_BOOT_LOCKS);
|
||||
return (boot_lock_t *) (BOOTRAM_BASE + BOOTRAM_BOOTLOCK0_OFFSET + lock_num * 4);
|
||||
}
|
||||
|
||||
/*! \brief Get HW Bootlock number from instance
|
||||
* \ingroup hardware_sync
|
||||
*
|
||||
* \param lock The Bootlock instance
|
||||
* \return The Bootlock ID
|
||||
*/
|
||||
__force_inline static uint boot_lock_get_num(boot_lock_t *lock) {
|
||||
invalid_params_if(HARDWARE_BOOT_LOCK, (uint) lock < BOOTRAM_BASE + BOOTRAM_BOOTLOCK0_OFFSET ||
|
||||
(uint) lock >= NUM_BOOT_LOCKS * sizeof(boot_lock_t) + BOOTRAM_BASE + BOOTRAM_BOOTLOCK0_OFFSET ||
|
||||
((uint) lock - BOOTRAM_BASE + BOOTRAM_BOOTLOCK0_OFFSET) % sizeof(boot_lock_t) != 0);
|
||||
return (uint) (lock - (boot_lock_t *) (BOOTRAM_BASE + BOOTRAM_BOOTLOCK0_OFFSET));
|
||||
}
|
||||
|
||||
/*! \brief Acquire a boot lock without disabling interrupts (hence unsafe)
|
||||
* \ingroup hardware_sync
|
||||
*
|
||||
* \param lock Bootlock instance
|
||||
*/
|
||||
__force_inline static void boot_lock_unsafe_blocking(boot_lock_t *lock) {
|
||||
// Note we don't do a wfe or anything, because by convention these boot_locks are VERY SHORT LIVED and NEVER BLOCK and run
|
||||
// with INTERRUPTS disabled (to ensure that)... therefore nothing on our core could be blocking us, so we just need to wait on another core
|
||||
// anyway which should be finished soon
|
||||
while (__builtin_expect(!*lock, 0)) { // read from bootlock register (tries to acquire the lock)
|
||||
tight_loop_contents();
|
||||
}
|
||||
__mem_fence_acquire();
|
||||
}
|
||||
|
||||
/*! \brief try to acquire a boot lock without disabling interrupts (hence unsafe)
|
||||
* \ingroup hardware_sync
|
||||
*
|
||||
* \param lock Bootlock instance
|
||||
*/
|
||||
__force_inline static bool boot_try_lock_unsafe(boot_lock_t *lock) {
|
||||
if (*lock) {
|
||||
__mem_fence_acquire();
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
/*! \brief Release a boot lock without re-enabling interrupts
|
||||
* \ingroup hardware_sync
|
||||
*
|
||||
* \param lock Bootlock instance
|
||||
*/
|
||||
__force_inline static void boot_unlock_unsafe(boot_lock_t *lock) {
|
||||
__mem_fence_release();
|
||||
*lock = 0; // write to bootlock register (release lock)
|
||||
}
|
||||
|
||||
/*! \brief Acquire a boot lock safely
|
||||
* \ingroup hardware_sync
|
||||
*
|
||||
* This function will disable interrupts prior to acquiring the bootlock
|
||||
*
|
||||
* \param lock Bootlock instance
|
||||
* \return interrupt status to be used when unlocking, to restore to original state
|
||||
*/
|
||||
__force_inline static uint32_t boot_lock_blocking(boot_lock_t *lock) {
|
||||
uint32_t save = save_and_disable_interrupts();
|
||||
boot_lock_unsafe_blocking(lock);
|
||||
return save;
|
||||
}
|
||||
|
||||
/*! \brief Check to see if a bootlock is currently acquired elsewhere.
|
||||
* \ingroup hardware_sync
|
||||
*
|
||||
* \param lock Bootlock instance
|
||||
*/
|
||||
inline static bool is_boot_locked(boot_lock_t *lock) {
|
||||
check_hw_size(boot_lock_t, 4);
|
||||
uint lock_num = boot_lock_get_num(lock);
|
||||
return 0 != (*(io_ro_32 *) (BOOTRAM_BASE + BOOTRAM_BOOTLOCK_STAT_OFFSET) & (1u << lock_num));
|
||||
}
|
||||
|
||||
/*! \brief Release a boot lock safely
|
||||
* \ingroup hardware_sync
|
||||
*
|
||||
* This function will re-enable interrupts according to the parameters.
|
||||
*
|
||||
* \param lock Bootlock instance
|
||||
* \param saved_irq Return value from the \ref boot_lock_blocking() function.
|
||||
*
|
||||
* \sa boot_lock_blocking()
|
||||
*/
|
||||
__force_inline static void boot_unlock(boot_lock_t *lock, uint32_t saved_irq) {
|
||||
boot_unlock_unsafe(lock);
|
||||
restore_interrupts_from_disabled(saved_irq);
|
||||
}
|
||||
|
||||
/*! \brief Initialise a boot lock
|
||||
* \ingroup hardware_sync
|
||||
*
|
||||
* The boot lock is initially unlocked
|
||||
*
|
||||
* \param lock_num The boot lock number
|
||||
* \return The boot lock instance
|
||||
*/
|
||||
boot_lock_t *boot_lock_init(uint lock_num);
|
||||
|
||||
/*! \brief Release all boot locks
|
||||
* \ingroup hardware_sync
|
||||
*/
|
||||
void boot_locks_reset(void);
|
||||
|
||||
#endif
|
||||
#endif
|
Loading…
Add table
Add a link
Reference in a new issue