1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-25 09:16:07 +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,275 @@
/*
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef _HARDWARE_POWMAN_H
#define _HARDWARE_POWMAN_H
#include "pico.h"
#include "hardware/structs/powman.h"
/** \file hardware/powman.h
* \defgroup hardware_powman hardware_powman
*
* \brief Power Management API
*
*/
// PICO_CONFIG: PARAM_ASSERTIONS_ENABLED_HARDWARE_POWMAN, Enable/disable hardware_powman assertions, type=bool, default=0, group=hardware_powman
#ifndef PARAM_ASSERTIONS_ENABLED_HARDWARE_POWMAN
#define PARAM_ASSERTIONS_ENABLED_HARDWARE_POWMAN 0
#endif
/*! \brief Use the ~32KHz low power oscillator as the powman timer source
* \ingroup hardware_powman
*/
void powman_timer_set_1khz_tick_source_lposc(void);
/*! \brief Use the low power oscillator (specifying frequency) as the powman timer source
* \ingroup hardware_powman
* \param lposc_freq_hz specify an exact lposc freq to trim it
*/
void powman_timer_set_1khz_tick_source_lposc_with_hz(uint32_t lposc_freq_hz);
/*! \brief Use the crystal oscillator as the powman timer source
* \ingroup hardware_powman
*/
void powman_timer_set_1khz_tick_source_xosc(void);
/*! \brief Use the crystal oscillator as the powman timer source
* \ingroup hardware_powman
* \param xosc_freq_hz specify a crystal frequency
*/
void powman_timer_set_1khz_tick_source_xosc_with_hz(uint32_t xosc_freq_hz);
/*! \brief Use a 1KHz external tick as the powman timer source
* \ingroup hardware_powman
* \param gpio the gpio to use. must be 12, 14, 20, 22
*/
void powman_timer_set_1khz_tick_source_gpio(uint32_t gpio);
/*! \brief Use a 1Hz external signal as the powman timer source for seconds only
* \ingroup hardware_powman
*
* Use a 1hz sync signal, such as from a gps for the seconds component of the timer.
* The milliseconds will still come from another configured source such as xosc or lposc
*
* \param gpio the gpio to use. must be 12, 14, 20, 22
*/
void powman_timer_enable_gpio_1hz_sync(uint32_t gpio);
/*! \brief Stop using 1Hz external signal as the powman timer source for seconds
* \ingroup hardware_powman
*/
void powman_timer_disable_gpio_1hz_sync(void);
/*! \brief Returns current time in ms
* \ingroup hardware_powman
*/
uint64_t powman_timer_get_ms(void);
/*! \brief Set current time in ms
* \ingroup hardware_powman
*
* \param time_ms Current time in ms
*/
void powman_timer_set_ms(uint64_t time_ms);
/*! \brief Set an alarm at an absolute time in ms
* \ingroup hardware_powman
*
* Note, the timer is stopped and then restarted as part of this function. This only controls the alarm
* if you want to use the alarm to wake up powman then you should use \ref powman_enable_alarm_wakeup_at_ms
*
* \param alarm_time_ms time at which the alarm will fire
*/
void powman_timer_enable_alarm_at_ms(uint64_t alarm_time_ms);
/*! \brief Disable the alarm
* \ingroup hardware_powman
*
* Once an alarm has fired it must be disabled to stop firing as the alarm
* comparison is alarm = alarm_time >= current_time
*/
void powman_timer_disable_alarm(void);
/*! \brief hw_set_bits helper function
* \ingroup hardware_powman
*
* \param reg register to set
* \param bits bits of register to set
* Powman needs a password for writes, to prevent accidentally writing to it.
* This function implements hw_set_bits with an appropriate password.
*/
static inline void powman_set_bits(volatile uint32_t *reg, uint32_t bits) {
invalid_params_if(HARDWARE_POWMAN, bits >> 16);
hw_set_bits(reg, POWMAN_PASSWORD_BITS | bits);
}
/*! \brief hw_clear_bits helper function
* \ingroup hardware_powman
*
* Powman needs a password for writes, to prevent accidentally writing to it.
* This function implements hw_clear_bits with an appropriate password.
*
* \param reg register to clear
* \param bits bits of register to clear
*/
static inline void powman_clear_bits(volatile uint32_t *reg, uint32_t bits) {
invalid_params_if(HARDWARE_POWMAN, bits >> 16);
hw_clear_bits(reg, POWMAN_PASSWORD_BITS | bits);
}
/*! \brief Determine if the powman timer is running
* \ingroup hardware_powman
*/
static inline bool powman_timer_is_running(void) {
return powman_hw->timer & POWMAN_TIMER_RUN_BITS;
}
/*! \brief Stop the powman timer
* \ingroup hardware_powman
*/
static inline void powman_timer_stop(void) {
powman_clear_bits(&powman_hw->timer, POWMAN_TIMER_RUN_BITS);
}
/*! \brief Start the powman timer
* \ingroup hardware_powman
*/
static inline void powman_timer_start(void) {
powman_set_bits(&powman_hw->timer, POWMAN_TIMER_RUN_BITS);
}
/*! \brief Clears the powman alarm
* \ingroup hardware_powman
*
* Note, the alarm must be disabled (see \ref powman_timer_disable_alarm) before clearing the alarm, as the alarm fires if
* the time is greater than equal to the target, so once the time has passed the alarm will always fire while enabled.
*/
static inline void powman_clear_alarm(void) {
powman_clear_bits(&powman_hw->timer, POWMAN_TIMER_ALARM_BITS);
}
/*! \brief Power domains of powman
* \ingroup hardware_powman
*/
enum powman_power_domains {
POWMAN_POWER_DOMAIN_SRAM_BANK1 = 0, ///< bank1 includes the top 256K of sram plus sram 8 and 9 (scratch x and scratch y)
POWMAN_POWER_DOMAIN_SRAM_BANK0 = 1, ///< bank0 is bottom 256K of sSRAM
POWMAN_POWER_DOMAIN_XIP_CACHE = 2, ///< XIP cache is 2x8K instances
POWMAN_POWER_DOMAIN_SWITCHED_CORE = 3, ///< Switched core logic (processors, busfabric, peris etc)
POWMAN_POWER_DOMAIN_COUNT = 4,
};
typedef uint32_t powman_power_state;
/*! \brief Get the current power state
* \ingroup hardware_powman
*/
powman_power_state powman_get_power_state(void);
/*! \brief Set the power state
* \ingroup hardware_powman
*
* Check the desired state is valid. Powman will go to the state if it is valid and there are no pending power up requests.
*
* Note that if you are turning off the switched core then this function will never return as the processor will have
* been turned off at the end.
*
* \param state the power state to go to
* \returns PICO_OK if the state is valid. Misc PICO_ERRORs are returned if not
*/
int powman_set_power_state(powman_power_state state);
#define POWMAN_POWER_STATE_NONE 0
/*! \brief Helper function modify a powman_power_state to turn a domain on
* \ingroup hardware_powman
* \param orig original state
* \param domain domain to turn on
*/
static inline powman_power_state powman_power_state_with_domain_on(powman_power_state orig, enum powman_power_domains domain) {
invalid_params_if(HARDWARE_POWMAN, domain >= POWMAN_POWER_DOMAIN_COUNT);
return orig | (1u << domain);
}
/*! \brief Helper function modify a powman_power_state to turn a domain off
* \ingroup hardware_powman
* \param orig original state
* \param domain domain to turn off
*/
static inline powman_power_state powman_power_state_with_domain_off(powman_power_state orig, enum powman_power_domains domain) {
invalid_params_if(HARDWARE_POWMAN, domain >= POWMAN_POWER_DOMAIN_COUNT);
return orig &= ~(1u << domain);
}
/*! \brief Helper function to check if a domain is on in a given powman_power_state
* \ingroup hardware_powman
* \param state powman_power_state
* \param domain domain to check is on
*/
static inline bool powman_power_state_is_domain_on(powman_power_state state, enum powman_power_domains domain) {
invalid_params_if(HARDWARE_POWMAN, domain >= POWMAN_POWER_DOMAIN_COUNT);
return state & (1u << domain);
}
/*! \brief Wake up from an alarm at a given time
* \ingroup hardware_powman
* \param alarm_time_ms time to wake up in ms
*/
void powman_enable_alarm_wakeup_at_ms(uint64_t alarm_time_ms);
/*! \brief Wake up from a gpio
* \ingroup hardware_powman
* \param gpio_wakeup_num hardware wakeup instance to use (0-3)
* \param gpio gpio to wake up from (0-47)
* \param edge true for edge sensitive, false for level sensitive
* \param high true for active high, false active low
*/
void powman_enable_gpio_wakeup(uint gpio_wakeup_num, uint32_t gpio, bool edge, bool high);
/*! \brief Disable waking up from alarm
* \ingroup hardware_powman
*/
void powman_disable_alarm_wakeup(void);
/*! \brief Disable wake up from a gpio
* \ingroup hardware_powman
* \param gpio_wakeup_num hardware wakeup instance to use (0-3)
*/
void powman_disable_gpio_wakeup(uint gpio_wakeup_num);
/*! \brief Disable all wakeup sources
* \ingroup hardware_powman
*/
void powman_disable_all_wakeups(void);
/*! \brief Configure sleep state and wakeup state
* \ingroup hardware_powman
* \param sleep_state power state powman will go to when sleeping, used to validate the wakeup state
* \param wakeup_state power state powman will go to when waking up. Note switched core and xip always power up. SRAM bank0 and bank1 can be left powered off
* \returns true if the state is valid, false if not
*/
bool powman_configure_wakeup_state(powman_power_state sleep_state, powman_power_state wakeup_state);
/*! \brief Ignore wake up when the debugger is attached
* \ingroup hardware_powman
*
* Typically, when a debugger is attached it will assert the pwrupreq signal. OpenOCD does not clear this signal, even when you quit.
* This means once you have attached a debugger powman will never go to sleep. This function lets you ignore the debugger
* pwrupreq which means you can go to sleep with a debugger attached. The debugger will error out if you go to turn off the switch core with it attached,
* as the processors have been powered off.
*
* \param ignored should the debugger power up request be ignored
*/
static inline void powman_set_debug_power_request_ignored(bool ignored) {
if (ignored)
powman_set_bits(&powman_hw->dbg_pwrcfg, 1);
else
powman_clear_bits(&powman_hw->dbg_pwrcfg, 0);
}
#endif

View file

@ -0,0 +1,259 @@
/*
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdint.h>
#include <stdio.h>
#include <inttypes.h>
#include "pico.h"
#include "hardware/gpio.h"
#include "hardware/powman.h"
#ifndef PICO_POWMAN_DEBUG
#define PICO_POWMAN_DEBUG 0
#endif
#if PICO_POWMAN_DEBUG
bool powman_debug_printf = false;
void powman_enable_debug_printf(void) {
powman_debug_printf = true;
}
#define powman_debug(format, args...) if (powman_debug_printf) printf(format, ## args)
#else
#define powman_debug(...)
#endif
static inline void powman_write(volatile uint32_t *reg, uint32_t value) {
// Write needs a password in top 16 bits
invalid_params_if(HARDWARE_POWMAN, value >> 16);
*reg = POWMAN_PASSWORD_BITS | value;
}
void powman_timer_set_ms(uint64_t time_ms) {
bool was_running = powman_timer_is_running();
if (was_running) powman_timer_stop();
powman_write(&powman_hw->set_time_15to0, time_ms & 0xffff);
powman_write(&powman_hw->set_time_31to16, (time_ms >> 16) & 0xffff);
powman_write(&powman_hw->set_time_47to32, (time_ms >> 32) & 0xffff);
powman_write(&powman_hw->set_time_63to48, (time_ms >> 48) & 0xffff);
if (was_running) powman_timer_start();
}
uint64_t powman_timer_get_ms(void) {
// Need to make sure that the upper 32 bits of the timer
// don't change, so read that first
uint32_t hi = powman_hw->read_time_upper;
uint32_t lo;
do {
// Read the lower 32 bits
lo = powman_hw->read_time_lower;
// Now read the upper 32 bits again and
// check that it hasn't incremented. If it has loop around
// and read the lower 32 bits again to get an accurate value
uint32_t next_hi = powman_hw->read_time_upper;
if (hi == next_hi) break;
hi = next_hi;
} while (true);
return ((uint64_t) hi << 32u) | lo;
}
void powman_timer_set_1khz_tick_source_lposc(void) {
powman_timer_set_1khz_tick_source_lposc_with_hz(32768);
}
void powman_timer_set_1khz_tick_source_lposc_with_hz(uint32_t lposc_freq_hz) {
bool was_running = powman_timer_is_running();
if (was_running) powman_timer_stop();
uint32_t lposc_freq_khz = lposc_freq_hz / 1000;
uint32_t lposc_freq_khz_frac16 = (lposc_freq_khz % 1000) * 65536 / 1000;
powman_write(&powman_hw->lposc_freq_khz_int, lposc_freq_khz);
powman_write(&powman_hw->lposc_freq_khz_frac, lposc_freq_khz_frac16);
powman_set_bits(&powman_hw->timer, POWMAN_TIMER_USE_LPOSC_BITS);
if (was_running) {
powman_timer_start();
while(!(powman_hw->timer & POWMAN_TIMER_USING_LPOSC_BITS));
}
}
void powman_timer_set_1khz_tick_source_xosc(void) {
powman_timer_set_1khz_tick_source_xosc_with_hz(XOSC_HZ);
}
void powman_timer_set_1khz_tick_source_xosc_with_hz(uint32_t xosc_freq_hz) {
bool was_running = powman_timer_is_running();
if (was_running) powman_timer_stop();
uint32_t xosc_freq_khz = xosc_freq_hz / 1000;
uint32_t xosc_freq_khz_frac16 = (xosc_freq_khz % 1000) * 65536 / 1000;
powman_write(&powman_hw->xosc_freq_khz_int, xosc_freq_khz);
powman_write(&powman_hw->xosc_freq_khz_frac, xosc_freq_khz_frac16);
powman_set_bits(&powman_hw->timer, POWMAN_TIMER_USE_XOSC_BITS);
if (was_running) {
powman_timer_start();
while(!(powman_hw->timer & POWMAN_TIMER_USING_XOSC_BITS));
}
}
static void powman_timer_use_gpio(uint32_t gpio, uint32_t use, uint32_t using) {
bool was_running = powman_timer_is_running();
if (was_running) powman_timer_stop();
invalid_params_if(HARDWARE_POWMAN, !((gpio == 12) || (gpio == 14) || (gpio == 20) || (gpio == 22)));
gpio_set_input_enabled(gpio, true);
powman_write(&powman_hw->ext_time_ref, gpio);
powman_set_bits(&powman_hw->timer, use);
if (was_running) {
powman_timer_start();
while(!(powman_hw->timer & using));
}
}
void powman_timer_set_1khz_tick_source_gpio(uint32_t gpio) {
// todo check if we're using the GPIO setup already?
powman_timer_use_gpio(gpio, POWMAN_TIMER_USE_GPIO_1KHZ_BITS, POWMAN_TIMER_USING_GPIO_1KHZ_BITS);
}
void powman_timer_enable_gpio_1hz_sync(uint32_t gpio) {
// todo check if we're using the GPIO setup already?
powman_timer_use_gpio(gpio, POWMAN_TIMER_USE_GPIO_1HZ_BITS, POWMAN_TIMER_USING_GPIO_1HZ_BITS);
}
void powman_timer_disable_gpio_1hz_sync(void) {
powman_clear_bits(&powman_hw->timer, POWMAN_TIMER_USE_GPIO_1HZ_BITS);
}
powman_power_state powman_get_power_state(void) {
uint32_t state_reg = powman_hw->state & POWMAN_STATE_CURRENT_BITS;
// todo we should have hardware/regs/powman.h values for these
static_assert(POWMAN_POWER_DOMAIN_SRAM_BANK1 == 0, "");
static_assert(POWMAN_POWER_DOMAIN_SRAM_BANK0 == 1, "");
static_assert(POWMAN_POWER_DOMAIN_XIP_CACHE == 2, "");
static_assert(POWMAN_POWER_DOMAIN_SWITCHED_CORE == 3, "");
static_assert(POWMAN_STATE_CURRENT_BITS == 0xf, "");
return (powman_power_state) state_reg;
}
// TODO: Should this fail to go to sleep if there is no wakeup alarm
int powman_set_power_state(powman_power_state state) {
// Clear req ignored in case it has been set
powman_clear_bits(&powman_hw->state, POWMAN_STATE_REQ_IGNORED_BITS);
powman_debug("powman: Requesting state %x\n", state);
powman_write(&powman_hw->state, (~state << POWMAN_STATE_REQ_LSB) & POWMAN_STATE_REQ_BITS);
// Has it been ignored?
if (powman_hw->state & POWMAN_STATE_REQ_IGNORED_BITS) {
powman_debug("State req ignored because of a pending pwrup req: %"PRIx32"\n", powman_hw->current_pwrup_req);
return PICO_ERROR_PRECONDITION_NOT_MET;
}
bool state_valid = (powman_hw->state & POWMAN_STATE_BAD_SW_REQ_BITS) == 0;
if (!state_valid) {
powman_debug("powman: Requested state invalid\n");
return PICO_ERROR_INVALID_ARG;
} else {
powman_debug("powman: Requested state valid\n");
}
if (!powman_power_state_is_domain_on(state, POWMAN_POWER_DOMAIN_SWITCHED_CORE)) {
// If we are turning off switched core then POWMAN_STATE_WAITING_BITS will be
// set because we are waiting for proc to go to sleep, so return ok and then the proc
// can go to sleep
// Note if the powerdown is being blocked by a pending pwrup request we will break out of this and return a failure
// Clk pow is slow so can take a few clk_pow cycles for waiting to turn up
for (int i = 0; i < 100; i++) {
if (powman_hw->state & POWMAN_STATE_WAITING_BITS) {
return PICO_OK;
}
}
// If it hasn't turned up then false
powman_debug("powman: STATE_WAITING hasn't turned up\n");
return PICO_ERROR_TIMEOUT;
}
// Wait while the state is changing then return true as we will be in the new state
powman_debug("powman: waiting for state change\n");
while(powman_hw->state & POWMAN_STATE_CHANGING_BITS) tight_loop_contents();
powman_debug("powman: state changed to %x\n", state);
return PICO_OK;
}
bool powman_configure_wakeup_state(powman_power_state sleep_state, powman_power_state wakeup_state) {
// When powman wakes up it can keep the state of the sram0 and sram1 banks. Note, it can't
// explicitly
bool valid = powman_power_state_is_domain_on(wakeup_state, POWMAN_POWER_DOMAIN_XIP_CACHE);
valid &= powman_power_state_is_domain_on(wakeup_state, POWMAN_POWER_DOMAIN_SWITCHED_CORE);
valid &= powman_power_state_is_domain_on(sleep_state, POWMAN_POWER_DOMAIN_SRAM_BANK0) ==
powman_power_state_is_domain_on(wakeup_state, POWMAN_POWER_DOMAIN_SRAM_BANK0);
valid &= powman_power_state_is_domain_on(sleep_state, POWMAN_POWER_DOMAIN_SRAM_BANK1) ==
powman_power_state_is_domain_on(wakeup_state, POWMAN_POWER_DOMAIN_SRAM_BANK1);
if (valid) {
powman_clear_bits(&powman_hw->seq_cfg, POWMAN_SEQ_CFG_HW_PWRUP_SRAM0_BITS | POWMAN_SEQ_CFG_HW_PWRUP_SRAM1_BITS);
uint32_t seq_cfg_set = 0;
if (!powman_power_state_is_domain_on(sleep_state, POWMAN_POWER_DOMAIN_SRAM_BANK0)) seq_cfg_set |= POWMAN_SEQ_CFG_HW_PWRUP_SRAM0_BITS;
if (!powman_power_state_is_domain_on(sleep_state, POWMAN_POWER_DOMAIN_SRAM_BANK1)) seq_cfg_set |= POWMAN_SEQ_CFG_HW_PWRUP_SRAM1_BITS;
powman_set_bits(&powman_hw->seq_cfg, seq_cfg_set);
}
return valid;
}
void powman_timer_enable_alarm_at_ms(uint64_t alarm_time_ms) {
powman_set_bits(&powman_hw->inte, POWMAN_INTE_TIMER_BITS);
powman_clear_bits(&powman_hw->timer, POWMAN_TIMER_ALARM_ENAB_BITS);
// Alarm must be disabled to set the alarm time
powman_write(&powman_hw->alarm_time_15to0, alarm_time_ms & 0xffff);
powman_write(&powman_hw->alarm_time_31to16, (alarm_time_ms >> 16) & 0xffff);
powman_write(&powman_hw->alarm_time_47to32, (alarm_time_ms >> 32) & 0xffff);
powman_write(&powman_hw->alarm_time_63to48, (alarm_time_ms >> 48) & 0xffff);
powman_clear_alarm();
// TODO: Assuming pwrup on alarm has no bad side effects if already powered up
powman_set_bits(&powman_hw->timer, POWMAN_TIMER_ALARM_ENAB_BITS);
}
void powman_timer_disable_alarm(void) {
powman_clear_bits(&powman_hw->inte, POWMAN_INTE_TIMER_BITS);
powman_clear_bits(&powman_hw->timer, POWMAN_TIMER_ALARM_ENAB_BITS);
}
void powman_enable_alarm_wakeup_at_ms(uint64_t alarm_time_ms) {
powman_timer_enable_alarm_at_ms(alarm_time_ms);
powman_set_bits(&powman_hw->timer, POWMAN_TIMER_PWRUP_ON_ALARM_BITS);
}
void powman_disable_alarm_wakeup(void) {
powman_timer_disable_alarm();
powman_clear_bits(&powman_hw->timer, POWMAN_TIMER_PWRUP_ON_ALARM_BITS);
}
void powman_enable_gpio_wakeup(uint gpio_wakeup_num, uint32_t gpio, bool edge, bool high) {
invalid_params_if(HARDWARE_POWMAN, gpio_wakeup_num >= count_of(powman_hw->pwrup));
// Need to make sure pad is input enabled
gpio_set_input_enabled(gpio, true);
// Set up gpio hardware for what we want
uint32_t pwrup = (edge ? POWMAN_PWRUP0_MODE_VALUE_EDGE : POWMAN_PWRUP0_MODE_VALUE_LEVEL) << POWMAN_PWRUP0_MODE_LSB;
pwrup |= (high ? POWMAN_PWRUP0_DIRECTION_BITS : 0);
pwrup |= gpio << POWMAN_PWRUP0_SOURCE_LSB;
powman_write(&powman_hw->pwrup[gpio_wakeup_num], pwrup);
// Clear the status bit in case an edge is already latched
powman_clear_bits(&powman_hw->pwrup[gpio_wakeup_num], POWMAN_PWRUP0_STATUS_BITS);
// Important to enable it separately to allow the gpio to change
powman_set_bits(&powman_hw->pwrup[gpio_wakeup_num], POWMAN_PWRUP0_ENABLE_BITS);
}
void powman_disable_gpio_wakeup(uint gpio_wakeup_num) {
invalid_params_if(HARDWARE_POWMAN, gpio_wakeup_num >= count_of(powman_hw->pwrup));
powman_clear_bits(&powman_hw->pwrup[gpio_wakeup_num], POWMAN_PWRUP0_ENABLE_BITS);
}
void powman_disable_all_wakeups(void) {
for (uint i = 0; i < count_of(powman_hw->pwrup); i++) {
powman_disable_gpio_wakeup(i);
}
powman_disable_alarm_wakeup();
}