mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 00:05:33 +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
|
@ -0,0 +1,598 @@
|
|||
/*
|
||||
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
|
||||
*
|
||||
* SPDX-License-Identifier: BSD-3-Clause
|
||||
*/
|
||||
|
||||
#ifndef _HARDWARE_TIMER_H
|
||||
#define _HARDWARE_TIMER_H
|
||||
|
||||
#include "pico.h"
|
||||
#include "hardware/structs/timer.h"
|
||||
#include "hardware/regs/intctrl.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/** \file hardware/timer.h
|
||||
* \defgroup hardware_timer hardware_timer
|
||||
*
|
||||
* \brief Low-level hardware timer API
|
||||
*
|
||||
* This API provides medium level access to the timer HW.
|
||||
* See also \ref pico_time which provides higher levels functionality using the hardware timer.
|
||||
*
|
||||
* The timer peripheral on RP-series microcontrollers supports the following features:
|
||||
* - RP2040 single 64-bit counter, incrementing once per microsecond
|
||||
* - RP2350 two 64-bit counters, ticks generated from the tick block
|
||||
* - Latching two-stage read of counter, for race-free read over 32 bit bus
|
||||
* - Four alarms: match on the lower 32 bits of counter, IRQ on match.
|
||||
*
|
||||
* \if rp2040_specific
|
||||
* On RP2040, by default the timer uses a one microsecond reference that is generated in the Watchdog (see RP2040 Datasheet Section 4.8.2) which is derived
|
||||
* from the clk_ref.
|
||||
* \endif
|
||||
*
|
||||
* \if rp2350_specific
|
||||
* On RP2350, by default the timer uses a one microsecond reference that is generated by the tick block (see RP2350 Datasheet Section 8.5)
|
||||
* \endif
|
||||
*
|
||||
* The timer has 4 alarms, and can output a separate interrupt for each alarm. The alarms match on the lower 32 bits of the 64
|
||||
* bit counter which means they can be fired a maximum of 2^32 microseconds into the future. This is equivalent to:
|
||||
* - 2^32 ÷ 10^6: ~4295 seconds
|
||||
* - 4295 ÷ 60: ~72 minutes
|
||||
*
|
||||
* The timer is expected to be used for short sleeps, if you want a longer alarm see the \ref hardware_rtc functions.
|
||||
*
|
||||
* \subsection timer_example Example
|
||||
* \addtogroup hardware_timer
|
||||
*
|
||||
* \include hello_timer.c
|
||||
*
|
||||
* \see pico_time
|
||||
*/
|
||||
|
||||
// PICO_CONFIG: PARAM_ASSERTIONS_ENABLED_HARDWARE_TIMER, Enable/disable assertions in the hardware_timer module, type=bool, default=0, group=hardware_timer
|
||||
#ifndef PARAM_ASSERTIONS_ENABLED_HARDWARE_TIMER
|
||||
#ifdef PARAM_ASSERTIONS_ENABLED_TIMER // backwards compatibility with SDK < 2.0.0
|
||||
#define PARAM_ASSERTIONS_ENABLED_HARDWARE_TIMER PARAM_ASSERTIONS_ENABLED_TIMER
|
||||
#else
|
||||
#define PARAM_ASSERTIONS_ENABLED_HARDWARE_TIMER 0
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
* \def TIMER_NUM(timer)
|
||||
* \ingroup hardware_timer
|
||||
* \hideinitializer
|
||||
* \brief Returns the timer number for a timer instance
|
||||
*
|
||||
* Note this macro is intended to resolve at compile time, and does no parameter checking
|
||||
*/
|
||||
#ifndef TIMER_NUM
|
||||
#if NUM_GENERIC_TIMERS == 1
|
||||
#define TIMER_NUM(timer) ({ (void) (timer); 0; })
|
||||
#elif NUM_GENERIC_TIMERS == 2
|
||||
#define TIMER_NUM(timer) ((timer) == timer1_hw)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
* \def TIMER_INSTANCE(timer_num)
|
||||
* \ingroup hardware_timer
|
||||
* \hideinitializer
|
||||
* \brief Returns the timer instance with the given timer number
|
||||
*
|
||||
* Note this macro is intended to resolve at compile time, and does no parameter checking
|
||||
*/
|
||||
#ifndef TIMER_INSTANCE
|
||||
#if NUM_GENERIC_TIMERS == 1
|
||||
#define TIMER_INSTANCE(num) timer_hw
|
||||
#elif NUM_GENERIC_TIMERS == 2
|
||||
#define TIMER_INSTANCE(num) ((num) ? timer1_hw : timer0_hw)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
* \def TIMER_ALARM_IRQ_NUM(timer,alarm_num)
|
||||
* \ingroup hardware_timer
|
||||
* \hideinitializer
|
||||
* \brief Returns the \ref irq_num_t for the alarm interrupt from the given alarm on the given timer instance
|
||||
*
|
||||
* Note this macro is intended to resolve at compile time, and does no parameter checking
|
||||
*/
|
||||
#ifndef TIMER_ALARM_IRQ_NUM
|
||||
#if NUM_GENERIC_TIMERS == 1
|
||||
static_assert(TIMER_IRQ_3 == TIMER_IRQ_0 + 3, "");
|
||||
#define TIMER_ALARM_IRQ_NUM(timer, alarm_num) ({ ((void)(timer)); (TIMER_IRQ_0 + (alarm_num)); })
|
||||
#else
|
||||
static_assert(TIMER1_IRQ_3 == TIMER0_IRQ_0 + 7, "");
|
||||
#define TIMER_ALARM_IRQ_NUM(timer, alarm_num) (TIMER0_IRQ_0 + TIMER_NUM(timer) * NUM_ALARMS + (alarm_num))
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
* \def TIMER_ALARM_NUM_FROM_IRQ(irq_num)
|
||||
* \ingroup hardware_timer
|
||||
* \hideinitializer
|
||||
* \brief Returns the alarm number from an \ref irq_num_t. See \ref TIMER_INSTANCE_NUM_FROM_IRQ to get the timer instance number
|
||||
*
|
||||
* Note this macro is intended to resolve at compile time, and does no parameter checking
|
||||
*/
|
||||
#ifndef TIMER_ALARM_NUM_FROM_IRQ
|
||||
#if NUM_GENERIC_TIMERS == 1
|
||||
static_assert(TIMER_IRQ_3 == TIMER_IRQ_0 + 3, "");
|
||||
#define TIMER_ALARM_NUM_FROM_IRQ(irq_num) (((irq_num) - TIMER_IRQ_0) & 3u)
|
||||
#else
|
||||
static_assert(TIMER1_IRQ_3 == TIMER0_IRQ_0 + 7, "");
|
||||
#define TIMER_ALARM_NUM_FROM_IRQ(irq_num) (((irq_num) - TIMER0_IRQ_0) & 3u)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
* \def TIMER_NUM_FROM_IRQ(irq_num)
|
||||
* \ingroup hardware_timer
|
||||
* \hideinitializer
|
||||
* \brief Returns the alarm number from an \ref irq_num_t. See \ref TIMER_INSTANCE_NUM_FROM_IRQ to get the alarm number
|
||||
*
|
||||
* Note this macro is intended to resolve at compile time, and does no parameter checking
|
||||
*/
|
||||
#ifndef TIMER_NUM_FROM_IRQ
|
||||
#if NUM_GENERIC_TIMERS == 1
|
||||
static_assert(TIMER_IRQ_3 == TIMER_IRQ_0 + 3, "");
|
||||
#define TIMER_NUM_FROM_IRQ(irq_num) (((irq_num) - TIMER_IRQ_0) >> 2)
|
||||
#else
|
||||
static_assert(TIMER1_IRQ_3 == TIMER0_IRQ_0 + 7, "");
|
||||
#define TIMER_NUM_FROM_IRQ(irq_num) (((irq_num) - TIMER0_IRQ_0) >> 2)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// PICO_CONFIG: PICO_DEFAULT_TIMER, Timer instance number to use for RP2040-period hardware_timer APIs that assumed a single timer instance, min=0, max=1, default=0, group=hardware_timer
|
||||
|
||||
/**
|
||||
* \ingroup hardware_timer
|
||||
* \brief The default timer instance number of the timer instance used for APIs that don't take an explicit timer instance
|
||||
* \if rp2040_specific
|
||||
* On RP2040 this must be 0 as there is only one timer instance
|
||||
* \endif
|
||||
* \if rp2350_specific
|
||||
* On RP2040 this may be set to 0 or 1
|
||||
* \endif
|
||||
*/
|
||||
#ifndef PICO_DEFAULT_TIMER
|
||||
#define PICO_DEFAULT_TIMER 0
|
||||
#endif
|
||||
|
||||
/**
|
||||
* \def PICO_DEFAULT_TIMER_INSTANCE()
|
||||
* \ingroup hardware_timer
|
||||
* \hideinitializer
|
||||
* \brief Returns the default timer instance on the platform based on the setting of PICO_DEFAULT_TIMER
|
||||
*
|
||||
* Note this macro is intended to resolve at compile time, and does no parameter checking
|
||||
*/
|
||||
#ifndef PICO_DEFAULT_TIMER_INSTANCE
|
||||
#if NUM_GENERIC_TIMERS == 1
|
||||
#if PICO_DEFAULT_TIMER
|
||||
#error Setting PICO_DEFAULT_TIMER to non zero is meaningless as there is only one TIMER instance on this platform
|
||||
#endif
|
||||
#define PICO_DEFAULT_TIMER_INSTANCE() timer_hw
|
||||
#else
|
||||
#define PICO_DEFAULT_TIMER_INSTANCE() (__CONCAT(__CONCAT(timer,PICO_DEFAULT_TIMER), _hw))
|
||||
// also define timer_hw for backwards compatibility (just accesses the default instance)
|
||||
#define timer_hw PICO_DEFAULT_TIMER_INSTANCE()
|
||||
#endif
|
||||
#endif
|
||||
|
||||
static inline void check_hardware_alarm_num_param(__unused uint alarm_num) {
|
||||
invalid_params_if(HARDWARE_TIMER, alarm_num >= NUM_ALARMS);
|
||||
}
|
||||
|
||||
/*! \brief Return a 32 bit timestamp value in microseconds for a given timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* Returns the low 32 bits of the hardware timer.
|
||||
* \note This value wraps roughly every 1 hour 11 minutes and 35 seconds.
|
||||
*
|
||||
* \param timer the timer instance
|
||||
* \return the 32 bit timestamp
|
||||
* \sa time_us_32
|
||||
*/
|
||||
static inline uint32_t timer_time_us_32(timer_hw_t *timer) {
|
||||
return timer->timerawl;
|
||||
}
|
||||
|
||||
/*! \brief Return a 32 bit timestamp value in microseconds for the default timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* Returns the low 32 bits of the hardware timer.
|
||||
* \note This value wraps roughly every 1 hour 11 minutes and 35 seconds.
|
||||
*
|
||||
* \return the 32 bit timestamp
|
||||
* \sa timer_time_us_32
|
||||
*/
|
||||
static inline uint32_t time_us_32(void) {
|
||||
return timer_time_us_32(PICO_DEFAULT_TIMER_INSTANCE());
|
||||
}
|
||||
|
||||
/*! \brief Return the current 64 bit timestamp value in microseconds for a given timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* Returns the full 64 bits of the hardware timer. The \ref pico_time and other functions rely on the fact that this
|
||||
* value monotonically increases from power up. As such it is expected that this value counts upwards and never wraps
|
||||
* (we apologize for introducing a potential year 5851444 bug).
|
||||
*
|
||||
* \param timer the timer instance
|
||||
* \return the 64 bit timestamp
|
||||
* \sa time_us_64
|
||||
*/
|
||||
uint64_t timer_time_us_64(timer_hw_t *timer);
|
||||
|
||||
/*! \brief Return the current 64 bit timestamp value in microseconds for the default timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* Returns the full 64 bits of the hardware timer. The \ref pico_time and other functions rely on the fact that this
|
||||
* value monotonically increases from power up. As such it is expected that this value counts upwards and never wraps
|
||||
* (we apologize for introducing a potential year 5851444 bug).
|
||||
*
|
||||
* \return the 64 bit timestamp
|
||||
* \sa timer_time_us_64
|
||||
* */
|
||||
uint64_t time_us_64(void);
|
||||
|
||||
/*! \brief Busy wait wasting cycles for the given (32 bit) number of microseconds using the given timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* \param timer the timer instance
|
||||
* \param delay_us delay amount in microseconds
|
||||
* \sa busy_wait_us_32
|
||||
*/
|
||||
void timer_busy_wait_us_32(timer_hw_t *timer, uint32_t delay_us);
|
||||
|
||||
/*! \brief Busy wait wasting cycles for the given (32 bit) number of microseconds using the default timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* \param delay_us delay amount in microseconds
|
||||
* \sa timer_busy_wait_us_32
|
||||
*/
|
||||
void busy_wait_us_32(uint32_t delay_us);
|
||||
|
||||
/*! \brief Busy wait wasting cycles for the given (64 bit) number of microseconds using the given timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* \param timer the timer instance
|
||||
* \param delay_us delay amount in microseconds
|
||||
* \sa busy_wait_us
|
||||
*/
|
||||
void timer_busy_wait_us(timer_hw_t *timer, uint64_t delay_us);
|
||||
|
||||
/*! \brief Busy wait wasting cycles for the given (64 bit) number of microseconds using the default timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* \param delay_us delay amount in microseconds
|
||||
* \sa timer_busy_wait_us
|
||||
*/
|
||||
void busy_wait_us(uint64_t delay_us);
|
||||
|
||||
/*! \brief Busy wait wasting cycles for the given number of milliseconds using the given timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* \param timer the timer instance
|
||||
* \param delay_ms delay amount in milliseconds
|
||||
* \sa busy_wait_ms
|
||||
*/
|
||||
void timer_busy_wait_ms(timer_hw_t *timer, uint32_t delay_ms);
|
||||
|
||||
/*! \brief Busy wait wasting cycles for the given number of milliseconds using the default timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* \param delay_ms delay amount in milliseconds
|
||||
* \sa timer_busy_wait_ms
|
||||
*/
|
||||
void busy_wait_ms(uint32_t delay_ms);
|
||||
|
||||
/*! \brief Busy wait wasting cycles until after the specified timestamp using the given timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* \param timer the timer instance
|
||||
* \param t Absolute time to wait until
|
||||
* \sa busy_wait_until
|
||||
*/
|
||||
void timer_busy_wait_until(timer_hw_t *timer, absolute_time_t t);
|
||||
|
||||
/*! \brief Busy wait wasting cycles until after the specified timestamp using the default timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* \param t Absolute time to wait until
|
||||
* \sa timer_busy_wait_until
|
||||
*/
|
||||
void busy_wait_until(absolute_time_t t);
|
||||
|
||||
/*! \brief Check if the specified timestamp has been reached on the given timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* \param timer the timer instance
|
||||
* \param t Absolute time to compare against current time
|
||||
* \return true if it is now after the specified timestamp
|
||||
* \sa time_reached
|
||||
*/
|
||||
static inline bool timer_time_reached(timer_hw_t *timer, absolute_time_t t) {
|
||||
uint64_t target = to_us_since_boot(t);
|
||||
uint32_t hi_target = (uint32_t)(target >> 32u);
|
||||
uint32_t hi = timer->timerawh;
|
||||
return (hi >= hi_target && (timer->timerawl >= (uint32_t) target || hi != hi_target));
|
||||
}
|
||||
|
||||
/*! \brief Check if the specified timestamp has been reached on the default timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* \param t Absolute time to compare against current time
|
||||
* \return true if it is now after the specified timestamp
|
||||
* \sa timer_time_reached
|
||||
*/
|
||||
static inline bool time_reached(absolute_time_t t) {
|
||||
return timer_time_reached(PICO_DEFAULT_TIMER_INSTANCE(), t);
|
||||
}
|
||||
|
||||
/*! Callback function type for hardware alarms
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* \param alarm_num the hardware alarm number
|
||||
* \sa hardware_alarm_set_callback()
|
||||
*/
|
||||
typedef void (*hardware_alarm_callback_t)(uint alarm_num);
|
||||
|
||||
/*! \brief cooperatively claim the use of this hardware alarm_num on the given timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* This method hard asserts if the hardware alarm is currently claimed.
|
||||
*
|
||||
* \param timer the timer instance
|
||||
* \param alarm_num the hardware alarm to claim
|
||||
* \sa hardware_alarm_claim
|
||||
* \sa hardware_claiming
|
||||
*/
|
||||
void timer_hardware_alarm_claim(timer_hw_t *timer, uint alarm_num);
|
||||
|
||||
/*! \brief cooperatively claim the use of this hardware alarm_num on the default timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* This method hard asserts if the hardware alarm is currently claimed.
|
||||
*
|
||||
* \param alarm_num the hardware alarm to claim
|
||||
* \sa timer_hardware_alarm_claim
|
||||
* \sa hardware_claiming
|
||||
*/
|
||||
void hardware_alarm_claim(uint alarm_num);
|
||||
|
||||
/*! \brief cooperatively claim the use of a hardware alarm_num on the given timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* This method attempts to claim an unused hardware alarm
|
||||
*
|
||||
* \param timer the timer instance
|
||||
* \param required if true the function will panic if none are available
|
||||
* \return alarm_num the hardware alarm claimed or -1 if required was false, and none are available
|
||||
* \sa hardware_alarm_claim_unused
|
||||
* \sa hardware_claiming
|
||||
*/
|
||||
int timer_hardware_alarm_claim_unused(timer_hw_t *timer, bool required);
|
||||
|
||||
/*! \brief cooperatively claim the use of a hardware alarm_num on the default timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* This method attempts to claim an unused hardware alarm
|
||||
*
|
||||
* \param required if true the function will panic if none are available
|
||||
* \return alarm_num the hardware alarm claimed or -1 if required was false, and none are available
|
||||
* \sa timer_hardware_alarm_claim_unused
|
||||
* \sa hardware_claiming
|
||||
*/
|
||||
int hardware_alarm_claim_unused(bool required);
|
||||
|
||||
/*! \brief cooperatively release the claim on use of this hardware alarm_num on the given timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* \param timer the timer instance
|
||||
* \param alarm_num the hardware alarm to unclaim
|
||||
* \sa hardware_alarm_unclaim
|
||||
* \sa hardware_claiming
|
||||
*/
|
||||
void timer_hardware_alarm_unclaim(timer_hw_t *timer, uint alarm_num);
|
||||
|
||||
/*! \brief cooperatively release the claim on use of this hardware alarm_num on the default timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* \param alarm_num the hardware alarm to unclaim
|
||||
* \sa timer_hardware_alarm_unclaim
|
||||
* \sa hardware_claiming
|
||||
*/
|
||||
void hardware_alarm_unclaim(uint alarm_num);
|
||||
|
||||
/*! \brief Determine if a hardware alarm has been claimed on the given timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* \param timer the timer instance
|
||||
* \param alarm_num the hardware alarm number
|
||||
* \return true if claimed, false otherwise
|
||||
* \sa hardware_alarm_is_claimed
|
||||
* \sa hardware_alarm_claim
|
||||
*/
|
||||
bool timer_hardware_alarm_is_claimed(timer_hw_t *timer, uint alarm_num);
|
||||
|
||||
/*! \brief Determine if a hardware alarm has been claimed on the default timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* \param alarm_num the hardware alarm number
|
||||
* \return true if claimed, false otherwise
|
||||
* \sa timer_hardware_alarm_is_claimed
|
||||
* \sa hardware_alarm_claim
|
||||
*/
|
||||
bool hardware_alarm_is_claimed(uint alarm_num);
|
||||
|
||||
/*! \brief Enable/Disable a callback for a hardware alarm for a given timer instance on this core
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* This method enables/disables the alarm IRQ for the specified hardware alarm on the
|
||||
* calling core, and set the specified callback to be associated with that alarm.
|
||||
*
|
||||
* This callback will be used for the timeout set via hardware_alarm_set_target
|
||||
*
|
||||
* \note This will install the handler on the current core if the IRQ handler isn't already set.
|
||||
* Therefore the user has the opportunity to call this up from the core of their choice
|
||||
*
|
||||
* \param timer the timer instance
|
||||
* \param alarm_num the hardware alarm number
|
||||
* \param callback the callback to install, or NULL to unset
|
||||
*
|
||||
* \sa hardware_alarm_set_callback
|
||||
* \sa timer_hardware_alarm_set_target()
|
||||
*/
|
||||
void timer_hardware_alarm_set_callback(timer_hw_t *timer, uint alarm_num, hardware_alarm_callback_t callback);
|
||||
|
||||
/*! \brief Enable/Disable a callback for a hardware alarm on the default timer instance on this core
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* This method enables/disables the alarm IRQ for the specified hardware alarm on the
|
||||
* calling core, and set the specified callback to be associated with that alarm.
|
||||
*
|
||||
* This callback will be used for the timeout set via hardware_alarm_set_target
|
||||
*
|
||||
* \note This will install the handler on the current core if the IRQ handler isn't already set.
|
||||
* Therefore the user has the opportunity to call this up from the core of their choice
|
||||
*
|
||||
* \param alarm_num the hardware alarm number
|
||||
* \param callback the callback to install, or NULL to unset
|
||||
*
|
||||
* \sa timer_hardware_alarm_set_callback
|
||||
* \sa hardware_alarm_set_target()
|
||||
*/
|
||||
void hardware_alarm_set_callback(uint alarm_num, hardware_alarm_callback_t callback);
|
||||
|
||||
/**
|
||||
* \brief Set the current target for a specific hardware alarm on the given timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* This will replace any existing target
|
||||
*
|
||||
* \param timer the timer instance
|
||||
* \param alarm_num the hardware alarm number
|
||||
* \param t the target timestamp
|
||||
* \return true if the target was "missed"; i.e. it was in the past, or occurred before a future hardware timeout could be set
|
||||
* \sa hardware_alarm_set_target
|
||||
*/
|
||||
bool timer_hardware_alarm_set_target(timer_hw_t *timer, uint alarm_num, absolute_time_t t);
|
||||
|
||||
/**
|
||||
* \brief Set the current target for the specified hardware alarm on the default timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* This will replace any existing target
|
||||
*
|
||||
* \param alarm_num the hardware alarm number
|
||||
* \param t the target timestamp
|
||||
* \return true if the target was "missed"; i.e. it was in the past, or occurred before a future hardware timeout could be set
|
||||
* \sa timer_hardware_alarm_set_target
|
||||
*/
|
||||
bool hardware_alarm_set_target(uint alarm_num, absolute_time_t t);
|
||||
|
||||
/**
|
||||
* \brief Cancel an existing target (if any) for a specific hardware_alarm on the given timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* \param timer the timer instance
|
||||
* \param alarm_num the hardware alarm number
|
||||
* \sa hardware_alarm_cancel
|
||||
*/
|
||||
void timer_hardware_alarm_cancel(timer_hw_t *timer, uint alarm_num);
|
||||
|
||||
/**
|
||||
* \brief Cancel an existing target (if any) for the specified hardware_alarm on the default timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* \param alarm_num the hardware alarm number
|
||||
* \sa timer_hardware_alarm_cancel
|
||||
*/
|
||||
void hardware_alarm_cancel(uint alarm_num);
|
||||
|
||||
/**
|
||||
* \brief Force and IRQ for a specific hardware alarm on the given timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* This method will forcibly make sure the current alarm callback (if present) for the hardware
|
||||
* alarm is called from an IRQ context after this call. If an actual callback is due at the same
|
||||
* time then the callback may only be called once.
|
||||
*
|
||||
* Calling this method does not otherwise interfere with regular callback operations.
|
||||
*
|
||||
* \param timer the timer instance
|
||||
* \param alarm_num the hardware alarm number
|
||||
* \sa hardware_alarm_force_irq
|
||||
*/
|
||||
void timer_hardware_alarm_force_irq(timer_hw_t *timer, uint alarm_num);
|
||||
|
||||
/**
|
||||
* \brief Force and IRQ for a specific hardware alarm on the default timer instance
|
||||
* \ingroup hardware_timer
|
||||
*
|
||||
* This method will forcibly make sure the current alarm callback (if present) for the hardware
|
||||
* alarm is called from an IRQ context after this call. If an actual callback is due at the same
|
||||
* time then the callback may only be called once.
|
||||
*
|
||||
* Calling this method does not otherwise interfere with regular callback operations.
|
||||
*
|
||||
* \param alarm_num the hardware alarm number
|
||||
* \sa timer_hardware_alarm_force_irq
|
||||
*/
|
||||
void hardware_alarm_force_irq(uint alarm_num);
|
||||
|
||||
/**
|
||||
* \ingroup hardware_timer
|
||||
* \brief Returns the \ref irq_num_t for the alarm interrupt from the given alarm on the given timer instance
|
||||
* \param timer the timer instance
|
||||
* \param alarm_num the alarm number
|
||||
* \sa TIMER_ALARM_IRQ_NUM
|
||||
*/
|
||||
static inline uint timer_hardware_alarm_get_irq_num(timer_hw_t *timer, uint alarm_num) {
|
||||
check_hardware_alarm_num_param(alarm_num);
|
||||
return TIMER_ALARM_IRQ_NUM(timer, alarm_num);
|
||||
}
|
||||
|
||||
/**
|
||||
* \ingroup hardware_timer
|
||||
* \brief Returns the \ref irq_num_t for the alarm interrupt from the given alarm on the default timer instance
|
||||
* \param alarm_num the alarm number
|
||||
*/
|
||||
static inline uint hardware_alarm_get_irq_num(uint alarm_num) {
|
||||
return timer_hardware_alarm_get_irq_num(PICO_DEFAULT_TIMER_INSTANCE(), alarm_num);
|
||||
}
|
||||
|
||||
/**
|
||||
* \ingroup hardware_timer
|
||||
* \brief Returns the timer number for a timer instance
|
||||
*
|
||||
* \param timer the timer instance
|
||||
* \return the timer number
|
||||
* \sa TIMER_NUM
|
||||
*/
|
||||
static inline uint timer_get_index(timer_hw_t *timer) {
|
||||
return TIMER_NUM(timer);
|
||||
}
|
||||
|
||||
/**
|
||||
* \ingroup hardware_timer
|
||||
* \brief Returns the timer instance with the given timer number
|
||||
*
|
||||
* \param timer_num the timer number
|
||||
* \return the timer instance
|
||||
*/
|
||||
static inline timer_hw_t *timer_get_instance(uint timer_num) {
|
||||
invalid_params_if(HARDWARE_TIMER, timer_num >= NUM_GENERIC_TIMERS);
|
||||
return TIMER_INSTANCE(timer_num);
|
||||
}
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
#endif
|
295
lib/main/pico-sdk/rp2_common/hardware_timer/timer.c
Normal file
295
lib/main/pico-sdk/rp2_common/hardware_timer/timer.c
Normal file
|
@ -0,0 +1,295 @@
|
|||
/*
|
||||
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
|
||||
*
|
||||
* SPDX-License-Identifier: BSD-3-Clause
|
||||
*/
|
||||
|
||||
#include "hardware/timer.h"
|
||||
#include "hardware/irq.h"
|
||||
#include "hardware/sync.h"
|
||||
#include "hardware/claim.h"
|
||||
|
||||
check_hw_layout(timer_hw_t, ints, TIMER_INTS_OFFSET);
|
||||
|
||||
static hardware_alarm_callback_t alarm_callbacks[NUM_GENERIC_TIMERS][NUM_ALARMS];
|
||||
static uint32_t target_hi[NUM_GENERIC_TIMERS][NUM_ALARMS];
|
||||
static uint8_t timer_callbacks_pending[NUM_GENERIC_TIMERS];
|
||||
|
||||
static_assert(NUM_ALARMS * NUM_GENERIC_TIMERS <= 8, "");
|
||||
static uint8_t claimed[NUM_GENERIC_TIMERS];
|
||||
|
||||
void timer_hardware_alarm_claim(timer_hw_t *timer, uint alarm_num) {
|
||||
check_hardware_alarm_num_param(alarm_num);
|
||||
hw_claim_or_assert(&claimed[timer_get_index(timer)], alarm_num, "Hardware alarm %d already claimed");
|
||||
}
|
||||
|
||||
void hardware_alarm_claim(uint alarm_num) {
|
||||
timer_hardware_alarm_claim(PICO_DEFAULT_TIMER_INSTANCE(), alarm_num);
|
||||
}
|
||||
|
||||
void timer_hardware_alarm_unclaim(timer_hw_t *timer, uint alarm_num) {
|
||||
check_hardware_alarm_num_param(alarm_num);
|
||||
hw_claim_clear(&claimed[timer_get_index(timer)], alarm_num);
|
||||
}
|
||||
|
||||
void hardware_alarm_unclaim(uint alarm_num) {
|
||||
timer_hardware_alarm_unclaim(PICO_DEFAULT_TIMER_INSTANCE(), alarm_num);
|
||||
}
|
||||
|
||||
bool timer_hardware_alarm_is_claimed(timer_hw_t *timer, uint alarm_num) {
|
||||
check_hardware_alarm_num_param(alarm_num);
|
||||
return hw_is_claimed(&claimed[timer_get_index(timer)], alarm_num);
|
||||
}
|
||||
|
||||
bool hardware_alarm_is_claimed(uint alarm_num) {
|
||||
return timer_hardware_alarm_is_claimed(PICO_DEFAULT_TIMER_INSTANCE(), alarm_num);
|
||||
}
|
||||
|
||||
int timer_hardware_alarm_claim_unused(timer_hw_t *timer, bool required) {
|
||||
return hw_claim_unused_from_range(&claimed[timer_get_index(timer)], required, 0, NUM_ALARMS - 1, "No alarms available");
|
||||
}
|
||||
|
||||
int hardware_alarm_claim_unused(bool required) {
|
||||
return timer_hardware_alarm_claim_unused(PICO_DEFAULT_TIMER_INSTANCE(), required);
|
||||
}
|
||||
|
||||
/// tag::time_us_64[]
|
||||
uint64_t timer_time_us_64(timer_hw_t *timer) {
|
||||
// Need to make sure that the upper 32 bits of the timer
|
||||
// don't change, so read that first
|
||||
uint32_t hi = timer->timerawh;
|
||||
uint32_t lo;
|
||||
do {
|
||||
// Read the lower 32 bits
|
||||
lo = timer->timerawl;
|
||||
// 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 = timer->timerawh;
|
||||
if (hi == next_hi) break;
|
||||
hi = next_hi;
|
||||
} while (true);
|
||||
return ((uint64_t) hi << 32u) | lo;
|
||||
}
|
||||
/// end::time_us_64[]
|
||||
|
||||
/// \tag::busy_wait[]
|
||||
void timer_busy_wait_us_32(timer_hw_t *timer, uint32_t delay_us) {
|
||||
if (0 <= (int32_t)delay_us) {
|
||||
// we only allow 31 bits, otherwise we could have a race in the loop below with
|
||||
// values very close to 2^32
|
||||
uint32_t start = timer->timerawl;
|
||||
while (timer->timerawl - start < delay_us) {
|
||||
tight_loop_contents();
|
||||
}
|
||||
} else {
|
||||
busy_wait_us(delay_us);
|
||||
}
|
||||
}
|
||||
|
||||
void timer_busy_wait_us(timer_hw_t *timer, uint64_t delay_us) {
|
||||
uint64_t base = timer_time_us_64(timer);
|
||||
uint64_t target = base + delay_us;
|
||||
if (target < base) {
|
||||
target = (uint64_t)-1;
|
||||
}
|
||||
absolute_time_t t;
|
||||
update_us_since_boot(&t, target);
|
||||
timer_busy_wait_until(timer, t);
|
||||
}
|
||||
|
||||
void timer_busy_wait_ms(timer_hw_t *timer, uint32_t delay_ms)
|
||||
{
|
||||
if (delay_ms <= 0x7fffffffu / 1000) {
|
||||
timer_busy_wait_us_32(timer, delay_ms * 1000);
|
||||
} else {
|
||||
timer_busy_wait_us(timer, delay_ms * 1000ull);
|
||||
}
|
||||
}
|
||||
|
||||
void timer_busy_wait_until(timer_hw_t *timer, absolute_time_t t) {
|
||||
uint64_t target = to_us_since_boot(t);
|
||||
uint32_t hi_target = (uint32_t)(target >> 32u);
|
||||
uint32_t hi = timer->timerawh;
|
||||
while (hi < hi_target) {
|
||||
hi = timer->timerawh;
|
||||
tight_loop_contents();
|
||||
}
|
||||
while (hi == hi_target && timer->timerawl < (uint32_t) target) {
|
||||
hi = timer->timerawh;
|
||||
tight_loop_contents();
|
||||
}
|
||||
}
|
||||
/// \end::busy_wait[]
|
||||
|
||||
uint64_t time_us_64(void) {
|
||||
return timer_time_us_64(PICO_DEFAULT_TIMER_INSTANCE());
|
||||
}
|
||||
|
||||
void busy_wait_us_32(uint32_t delay_us) {
|
||||
timer_busy_wait_us_32(PICO_DEFAULT_TIMER_INSTANCE(), delay_us);
|
||||
}
|
||||
|
||||
void busy_wait_us(uint64_t delay_us) {
|
||||
timer_busy_wait_us(PICO_DEFAULT_TIMER_INSTANCE(), delay_us);
|
||||
}
|
||||
|
||||
void busy_wait_ms(uint32_t delay_ms)
|
||||
{
|
||||
timer_busy_wait_ms(PICO_DEFAULT_TIMER_INSTANCE(), delay_ms);
|
||||
}
|
||||
|
||||
void busy_wait_until(absolute_time_t t) {
|
||||
timer_busy_wait_until(PICO_DEFAULT_TIMER_INSTANCE(), t);
|
||||
}
|
||||
|
||||
static void hardware_alarm_irq_handler(void) {
|
||||
// Determine which timer this IRQ is for
|
||||
uint irq_num = __get_current_exception() - VTABLE_FIRST_IRQ;
|
||||
uint alarm_num = TIMER_ALARM_NUM_FROM_IRQ(irq_num);
|
||||
check_hardware_alarm_num_param(alarm_num);
|
||||
uint timer_num = TIMER_NUM_FROM_IRQ(irq_num);
|
||||
timer_hw_t *timer = timer_get_instance(timer_num);
|
||||
hardware_alarm_callback_t callback = NULL;
|
||||
|
||||
spin_lock_t *lock = spin_lock_instance(PICO_SPINLOCK_ID_TIMER);
|
||||
uint32_t save = spin_lock_blocking(lock);
|
||||
|
||||
// Clear the timer IRQ (inside lock, because we check whether we have handled the IRQ yet in alarm_set by looking at the interrupt status
|
||||
timer->intr = 1u << alarm_num;
|
||||
// Clear any forced IRQ
|
||||
hw_clear_bits(&timer->intf, 1u << alarm_num);
|
||||
|
||||
// make sure the IRQ is still valid
|
||||
if (timer_callbacks_pending[timer_num] & (1u << alarm_num)) {
|
||||
// Now check whether we have a timer event to handle that isn't already obsolete (this could happen if we
|
||||
// were already in the IRQ handler before someone else changed the timer setup
|
||||
if (timer->timerawh >= target_hi[timer_num][alarm_num]) {
|
||||
// we have reached the right high word as well as low word value
|
||||
callback = alarm_callbacks[timer_num][alarm_num];
|
||||
timer_callbacks_pending[timer_num] &= (uint8_t)~(1u << alarm_num);
|
||||
} else {
|
||||
// try again in 2^32 us
|
||||
timer->alarm[alarm_num] = timer->alarm[alarm_num]; // re-arm the timer
|
||||
}
|
||||
}
|
||||
|
||||
spin_unlock(lock, save);
|
||||
|
||||
if (callback) {
|
||||
callback(alarm_num);
|
||||
}
|
||||
}
|
||||
|
||||
void timer_hardware_alarm_set_callback(timer_hw_t *timer, uint alarm_num, hardware_alarm_callback_t callback) {
|
||||
// todo check current core owner
|
||||
// note this should probably be subsumed by irq_set_exclusive_handler anyway, since that
|
||||
// should disallow IRQ handlers on both cores
|
||||
check_hardware_alarm_num_param(alarm_num);
|
||||
uint timer_num = timer_get_index(timer);
|
||||
uint irq_num = TIMER_ALARM_IRQ_NUM(timer, alarm_num);
|
||||
spin_lock_t *lock = spin_lock_instance(PICO_SPINLOCK_ID_TIMER);
|
||||
uint32_t save = spin_lock_blocking(lock);
|
||||
if (callback) {
|
||||
if (hardware_alarm_irq_handler != irq_get_vtable_handler(irq_num)) {
|
||||
// note that set_exclusive will silently allow you to set the handler to the same thing
|
||||
// since it is idempotent, which means we don't need to worry about locking ourselves
|
||||
irq_set_exclusive_handler(irq_num, hardware_alarm_irq_handler);
|
||||
irq_set_enabled(irq_num, true);
|
||||
// Enable interrupt in block and at processor
|
||||
hw_set_bits(&timer->inte, 1u << alarm_num);
|
||||
}
|
||||
alarm_callbacks[timer_num][alarm_num] = callback;
|
||||
} else {
|
||||
alarm_callbacks[timer_num][alarm_num] = NULL;
|
||||
timer_callbacks_pending[timer_num] &= (uint8_t)~(1u << alarm_num);
|
||||
irq_remove_handler(irq_num, hardware_alarm_irq_handler);
|
||||
irq_set_enabled(irq_num, false);
|
||||
}
|
||||
spin_unlock(lock, save);
|
||||
}
|
||||
|
||||
void hardware_alarm_set_callback(uint alarm_num, hardware_alarm_callback_t callback) {
|
||||
timer_hardware_alarm_set_callback(PICO_DEFAULT_TIMER_INSTANCE(), alarm_num, callback);
|
||||
}
|
||||
|
||||
bool timer_hardware_alarm_set_target(timer_hw_t *timer, uint alarm_num, absolute_time_t target) {
|
||||
bool missed;
|
||||
uint64_t now = timer_time_us_64(timer);
|
||||
uint64_t t = to_us_since_boot(target);
|
||||
if (now >= t) {
|
||||
missed = true;
|
||||
} else {
|
||||
missed = false;
|
||||
uint timer_num = timer_get_index(timer);
|
||||
|
||||
// 1) actually set the hardware timer
|
||||
spin_lock_t *lock = spin_lock_instance(PICO_SPINLOCK_ID_TIMER);
|
||||
uint32_t save = spin_lock_blocking(lock);
|
||||
uint8_t old_timer_callbacks_pending = timer_callbacks_pending[timer_num];
|
||||
timer_callbacks_pending[timer_num] |= (uint8_t)(1u << alarm_num);
|
||||
timer->intr = 1u << alarm_num; // clear any IRQ
|
||||
timer->alarm[alarm_num] = (uint32_t) t;
|
||||
// Set the alarm. Writing time should arm it
|
||||
target_hi[timer_num][alarm_num] = (uint32_t)(t >> 32u);
|
||||
|
||||
// 2) check for races
|
||||
if (!(timer->armed & 1u << alarm_num)) {
|
||||
// not armed, so has already fired .. IRQ must be pending (we are still under lock)
|
||||
assert(timer->ints & 1u << alarm_num);
|
||||
} else {
|
||||
if (timer_time_us_64(timer) >= t) {
|
||||
// we are already at or past the right time; there is no point in us racing against the IRQ
|
||||
// we are about to generate. note however that, if there was already a timer pending before,
|
||||
// then we still let the IRQ fire, as whatever it was, is not handled by our setting missed=true here
|
||||
missed = true;
|
||||
if (timer_callbacks_pending[timer_num] != old_timer_callbacks_pending) {
|
||||
// disarm the timer
|
||||
timer->armed = 1u << alarm_num;
|
||||
// clear the IRQ...
|
||||
timer->intr = 1u << alarm_num;
|
||||
// ... including anything pending on the processor - perhaps unnecessary, but
|
||||
// our timer flag says we aren't expecting anything.
|
||||
irq_clear(timer_hardware_alarm_get_irq_num(timer, alarm_num));
|
||||
// and clear our flag so that if the IRQ handler is already active (because it is on
|
||||
// the other core) it will also skip doing anything
|
||||
timer_callbacks_pending[timer_num] = old_timer_callbacks_pending;
|
||||
}
|
||||
}
|
||||
}
|
||||
spin_unlock(lock, save);
|
||||
// note at this point any pending timer IRQ can likely run
|
||||
}
|
||||
return missed;
|
||||
}
|
||||
|
||||
bool hardware_alarm_set_target(uint alarm_num, absolute_time_t t) {
|
||||
return timer_hardware_alarm_set_target(PICO_DEFAULT_TIMER_INSTANCE(), alarm_num, t);
|
||||
}
|
||||
|
||||
void timer_hardware_alarm_cancel(timer_hw_t *timer, uint alarm_num) {
|
||||
check_hardware_alarm_num_param(alarm_num);
|
||||
|
||||
spin_lock_t *lock = spin_lock_instance(PICO_SPINLOCK_ID_TIMER);
|
||||
uint32_t save = spin_lock_blocking(lock);
|
||||
timer->armed = 1u << alarm_num;
|
||||
timer_callbacks_pending[timer_get_index(timer)] &= (uint8_t)~(1u << alarm_num);
|
||||
spin_unlock(lock, save);
|
||||
}
|
||||
|
||||
void hardware_alarm_cancel(uint alarm_num) {
|
||||
timer_hardware_alarm_cancel(PICO_DEFAULT_TIMER_INSTANCE(), alarm_num);
|
||||
}
|
||||
|
||||
void timer_hardware_alarm_force_irq(timer_hw_t *timer, uint alarm_num) {
|
||||
check_hardware_alarm_num_param(alarm_num);
|
||||
spin_lock_t *lock = spin_lock_instance(PICO_SPINLOCK_ID_TIMER);
|
||||
uint32_t save = spin_lock_blocking(lock);
|
||||
timer_callbacks_pending[timer_get_index(timer)] |= (uint8_t)(1u << alarm_num);
|
||||
spin_unlock(lock, save);
|
||||
hw_set_bits(&timer->intf, 1u << alarm_num);
|
||||
}
|
||||
|
||||
void hardware_alarm_force_irq(uint alarm_num) {
|
||||
timer_hardware_alarm_force_irq(PICO_DEFAULT_TIMER_INSTANCE(), alarm_num);
|
||||
}
|
Loading…
Add table
Add a link
Reference in a new issue