SDK 1.3.0 release

See release notes for details

Co-authored-by: Brian Cooke <bdscooke@gmail.com>
Co-authored-by: Luke Wren <wren6991@gmail.com>
Co-authored-by: Uri Shaked <uri@urishaked.com>
Co-authored-by: Zapta <zapta@users.noreply.github.com>
Co-authored-by: Andrew Scheller <andrew.scheller@raspberrypi.com>
Co-authored-by: Liam Fraser <liam@raspberrypi.com>
Co-authored-by: Gabriel Wang <embedded_zhuoran@Hotmail.com>
Co-authored-by: Matias Silva <matita.martins@gmail.com>
Co-authored-by: dp111 <19616418+dp111@users.noreply.github.com>
Co-authored-by: Leonardo La Rocca <46094699+leoli51@users.noreply.github.com>
Co-authored-by: Mahyar Koshkouei <mk@deltabeard.com>
Co-authored-by: Brian Starkey <stark3y@gmail.com>
Co-authored-by: Philip Howard <github@gadgetoid.com>
Co-authored-by: Mike Causer <mcauser@gmail.com>
Co-authored-by: Martino Facchin <m.facchin@arduino.cc>
Co-authored-by: ZodiusInfuser <christopher.parrott2@gmail.com>
Co-authored-by: Manuel Wick <manuel@matronix.de>
Co-authored-by: Matias Silva <git@matiasilva.com>
Co-authored-by: Robert Pafford <19439938+rjp5th@users.noreply.github.com>
Co-authored-by: Alasdair Allan <alasdair@raspberrypi.com>
Co-authored-by: Engineer_Will <646689853@qq.com>
Co-authored-by: Garatronic <31109090+garatronic@users.noreply.github.com>
This commit is contained in:
Graham Sanderson
2021-11-01 14:20:54 -05:00
committed by GitHub
parent bfcbefafc5
commit 2062372d20
158 changed files with 7125 additions and 1483 deletions

View File

@ -72,5 +72,6 @@ endif()
set(CMAKE_EXECUTABLE_SUFFIX "${CMAKE_EXECUTABLE_SUFFIX}" PARENT_SCOPE)
pico_add_doxygen(${CMAKE_CURRENT_LIST_DIR})
pico_add_doxygen_exclude(${CMAKE_CURRENT_LIST_DIR}/cmsis)
pico_promote_common_scope_vars()

View File

@ -4,7 +4,7 @@
if (DEFINED ENV{PICO_DEFAULT_BOOT_STAGE2_FILE})
set(PICO_DEFAULT_BOOT_STAGE2_FILE $ENV{PICO_DEFAULT_BOOT_STAGE2_FILE})
message("Using PICO_DEFAULT_BOOT_STAGE2_FILE from environment ('${PICO_DEFAULT_BOOT_STAGE2_FILE}')")
elif (PICO_DEFAULT_BOOT_STAGE2_FILE)
elseif (PICO_DEFAULT_BOOT_STAGE2_FILE)
# explicitly set, so cache it
set(PICO_DEFAULT_BOOT_STAGE2_FILE "${PICO_DEFAULT_BOOT_STAGE2_FILE}" CACHE STRING "boot stage 2 source file" FORCE)
endif()
@ -25,6 +25,7 @@ endif()
if (NOT EXISTS ${PICO_DEFAULT_BOOT_STAGE2_FILE})
message(FATAL_ERROR "Specified boot stage 2 source '${PICO_DEFAULT_BOOT_STAGE2_FILE}' does not exist.")
endif()
pico_register_common_scope_var(PICO_DEFAULT_BOOT_STAGE2_FILE)
# needed by function below
set(PICO_BOOT_STAGE2_DIR "${CMAKE_CURRENT_LIST_DIR}" CACHE INTERNAL "")
@ -98,3 +99,9 @@ endmacro()
pico_define_boot_stage2(bs2_default ${PICO_DEFAULT_BOOT_STAGE2_FILE})
# Create a new boot stage 2 target using the default implementation for the current build (PICO_BOARD derived)
function(pico_clone_default_boot_stage2 NAME)
pico_define_boot_stage2(${NAME} ${PICO_DEFAULT_BOOT_STAGE2_FILE})
endfunction()
pico_promote_common_scope_vars()

View File

@ -19,7 +19,7 @@
* The RP2040 has an internal analogue-digital converter (ADC) with the following features:
* - SAR ADC
* - 500 kS/s (Using an independent 48MHz clock)
* - 12 bit (9.5 ENOB)
* - 12 bit (8.7 ENOB)
* - 5 input mux:
* - 4 inputs that are available on package pins shared with GPIO[29:26]
* - 1 input is dedicated to the internal temperature sensor
@ -28,7 +28,7 @@
* - DMA interface
*
* Although there is only one ADC you can specify the input to it using the adc_select_input() function.
* In round robin mode (adc_rrobin()) will use that input and move to the next one after a read.
* In round robin mode (adc_set_round_robin()), the ADC will use that input and move to the next one after a read.
*
* User ADC inputs are on 0-3 (GPIO 26-29), the temperature sensor is on input 4.
*
@ -62,7 +62,7 @@ void adc_init(void);
/*! \brief Initialise the gpio for use as an ADC pin
* \ingroup hardware_adc
*
* Prepare a GPIO for use with ADC, by disabling all digital functions.
* Prepare a GPIO for use with ADC by disabling all digital functions.
*
* \param gpio The GPIO number to use. Allowable GPIO numbers are 26 to 29 inclusive.
*/
@ -167,7 +167,7 @@ static inline void adc_set_clkdiv(float clkdiv) {
/*! \brief Setup the ADC FIFO
* \ingroup hardware_adc
*
* FIFO is 4 samples long, if a conversion is completed and the FIFO is full the result is dropped.
* FIFO is 4 samples long, if a conversion is completed and the FIFO is full, the result is dropped.
*
* \param en Enables write each conversion result to the FIFO
* \param dreq_en Enable DMA requests when FIFO contains data
@ -193,7 +193,7 @@ static inline void adc_set_clkdiv(float clkdiv) {
/*! \brief Check FIFO empty state
* \ingroup hardware_adc
*
* \return Returns true if the fifo is empty
* \return Returns true if the FIFO is empty
*/
static inline bool adc_fifo_is_empty(void) {
return !!(adc_hw->fcs & ADC_FCS_EMPTY_BITS);
@ -231,7 +231,7 @@ static inline uint16_t adc_fifo_get_blocking(void) {
/*! \brief Drain the ADC FIFO
* \ingroup hardware_adc
*
* Will wait for any conversion to complete then drain the FIFO discarding any results.
* Will wait for any conversion to complete then drain the FIFO, discarding any results.
*/
static inline void adc_fifo_drain(void) {
// Potentially there is still a conversion in progress -- wait for this to complete before draining

View File

@ -55,6 +55,11 @@ extern "C" {
#define check_hw_layout(type, member, offset) static_assert(offsetof(type, member) == (offset), "hw offset mismatch")
#define check_hw_size(type, size) static_assert(sizeof(type) == (size), "hw size mismatch")
// PICO_CONFIG: PARAM_ASSERTIONS_ENABLED_ADDRESS_ALIAS, Enable/disable assertions in memory address aliasing macros, type=bool, default=0, group=hardware_base
#ifndef PARAM_ASSERTIONS_ENABLED_ADDRESS_ALIAS
#define PARAM_ASSERTIONS_ENABLED_ADDRESS_ALIAS 0
#endif
typedef volatile uint32_t io_rw_32;
typedef const volatile uint32_t io_ro_32;
typedef volatile uint32_t io_wo_32;
@ -68,15 +73,44 @@ typedef volatile uint8_t io_wo_8;
typedef volatile uint8_t *const ioptr;
typedef ioptr const const_ioptr;
// A non-functional (empty) helper macro to help IDEs follow links from the autogenerated
// hardware struct headers in hardware/structs/xxx.h to the raw register definitions
// in hardware/regs/xxx.h. A preprocessor define such as TIMER_TIMEHW_OFFSET (a timer register offset)
// is not generally clickable (in an IDE) if placed in a C comment, so _REG_(TIMER_TIMEHW_OFFSET) is
// included outside of a comment instead
#define _REG_(x)
// Helper method used by hw_alias macros to optionally check input validity
#define hw_alias_check_addr(addr) ((uintptr_t)(addr))
// can't use the following impl as it breaks existing static declarations using hw_alias, so would be a backwards incompatibility
//static __force_inline uint32_t hw_alias_check_addr(volatile void *addr) {
// uint32_t rc = (uintptr_t)addr;
// invalid_params_if(ADDRESS_ALIAS, rc < 0x40000000); // catch likely non HW pointer types
// return rc;
//}
// Helper method used by xip_alias macros to optionally check input validity
static __force_inline uint32_t xip_alias_check_addr(const void *addr) {
uint32_t rc = (uintptr_t)addr;
valid_params_if(ADDRESS_ALIAS, rc >= XIP_MAIN_BASE && rc < XIP_NOALLOC_BASE);
return rc;
}
// Untyped conversion alias pointer generation macros
#define hw_set_alias_untyped(addr) ((void *)(REG_ALIAS_SET_BITS | (uintptr_t)(addr)))
#define hw_clear_alias_untyped(addr) ((void *)(REG_ALIAS_CLR_BITS | (uintptr_t)(addr)))
#define hw_xor_alias_untyped(addr) ((void *)(REG_ALIAS_XOR_BITS | (uintptr_t)(addr)))
#define hw_set_alias_untyped(addr) ((void *)(REG_ALIAS_SET_BITS | hw_alias_check_addr(addr)))
#define hw_clear_alias_untyped(addr) ((void *)(REG_ALIAS_CLR_BITS | hw_alias_check_addr(addr)))
#define hw_xor_alias_untyped(addr) ((void *)(REG_ALIAS_XOR_BITS | hw_alias_check_addr(addr)))
#define xip_noalloc_alias_untyped(addr) ((void *)(XIP_NOALLOC_BASE | xip_alias_check_addr(addr)))
#define xip_nocache_alias_untyped(addr) ((void *)(XIP_NOCACHE_BASE | xip_alias_check_addr(addr)))
#define xip_nocache_noalloc_alias_untyped(addr) ((void *)(XIP_NOCACHE_NOALLOC_BASE | xip_alias_check_addr(addr)))
// Typed conversion alias pointer generation macros
#define hw_set_alias(p) ((typeof(p))hw_set_alias_untyped(p))
#define hw_clear_alias(p) ((typeof(p))hw_clear_alias_untyped(p))
#define hw_xor_alias(p) ((typeof(p))hw_xor_alias_untyped(p))
#define xip_noalloc_alias(p) ((typeof(p))xip_noalloc_alias_untyped(p))
#define xip_nocache_alias(p) ((typeof(p))xip_nocache_alias_untyped(p))
#define xip_nocache_noalloc_alias(p) ((typeof(p))xip_nocache_noalloc_alias_untyped(p))
/*! \brief Atomically set the specified bits to 1 in a HW register
* \ingroup hardware_base

View File

@ -18,6 +18,7 @@ static_assert(__builtin_offsetof(dma_hw_t, ch[1].ctrl_trig) == DMA_CH1_CTRL_TRIG
static_assert(NUM_DMA_CHANNELS <= 16, "");
static uint16_t _claimed;
static uint8_t _timer_claimed;
void dma_channel_claim(uint channel) {
check_dma_channel_param(channel);
@ -44,6 +45,25 @@ bool dma_channel_is_claimed(uint channel) {
return hw_is_claimed((uint8_t *) &_claimed, channel);
}
void dma_timer_claim(uint timer) {
check_dma_timer_param(timer);
hw_claim_or_assert(&_timer_claimed, timer, "DMA timer %d is already claimed");
}
void dma_timer_unclaim(uint timer) {
check_dma_timer_param(timer);
hw_claim_clear(&_timer_claimed, timer);
}
int dma_claim_unused_timer(bool required) {
return hw_claim_unused_from_range(&_timer_claimed, required, 0, NUM_DMA_TIMERS-1, "No DMA timers are available");
}
bool dma_timer_is_claimed(uint timer) {
check_dma_timer_param(timer);
return hw_is_claimed(&_timer_claimed, timer);
}
#ifndef NDEBUG
void print_dma_ctrl(dma_channel_hw_t *channel) {

View File

@ -54,6 +54,10 @@ static inline void check_dma_channel_param(__unused uint channel) {
#endif
}
static inline void check_dma_timer_param(__unused uint timer_num) {
valid_params_if(DMA, timer_num < NUM_DMA_TIMERS);
}
inline static dma_channel_hw_t *dma_channel_hw_addr(uint channel) {
check_dma_channel_param(channel);
return &dma_hw->ch[channel];
@ -715,6 +719,71 @@ inline static void dma_sniffer_disable(void) {
dma_hw->sniff_ctrl = 0;
}
/*! \brief Mark a dma timer as used
* \ingroup hardware_dma
*
* Method for cooperative claiming of hardware. Will cause a panic if the timer
* is already claimed. Use of this method by libraries detects accidental
* configurations that would fail in unpredictable ways.
*
* \param timer the dma timer
*/
void dma_timer_claim(uint timer);
/*! \brief Mark a dma timer as no longer used
* \ingroup hardware_dma
*
* Method for cooperative claiming of hardware.
*
* \param timer the dma timer to release
*/
void dma_timer_unclaim(uint timer);
/*! \brief Claim a free dma timer
* \ingroup hardware_dma
*
* \param required if true the function will panic if none are available
* \return the dma timer number or -1 if required was false, and none were free
*/
int dma_claim_unused_timer(bool required);
/*! \brief Determine if a dma timer is claimed
* \ingroup hardware_dma
*
* \param timer the dma timer
* \return true if the timer is claimed, false otherwise
* \see dma_timer_claim
*/
bool dma_timer_is_claimed(uint timer);
/*! \brief Set the divider for the given DMA timer
* \ingroup hardware_dma
*
* The timer will run at the system_clock_freq * numerator / denominator, so this is the speed
* that data elements will be transferred at via a DMA channel using this timer as a DREQ
*
* \param timer the dma timer
* \param numerator the fraction's numerator
* \param denominator the fraction's denominator
*/
static inline void dma_timer_set_fraction(uint timer, uint16_t numerator, uint16_t denominator) {
check_dma_timer_param(timer);
dma_hw->timer[timer] = (((uint32_t)numerator) << DMA_TIMER0_X_LSB) | (((uint32_t)denominator) << DMA_TIMER0_Y_LSB);
}
/*! \brief Return the DREQ number for a given DMA timer
* \ingroup hardware_dma
*
* \param timer_num DMA timer number 0-3
*/
static inline uint dma_get_timer_dreq(uint timer_num) {
static_assert(DREQ_DMA_TIMER1 == DREQ_DMA_TIMER0 + 1, "");
static_assert(DREQ_DMA_TIMER2 == DREQ_DMA_TIMER0 + 2, "");
static_assert(DREQ_DMA_TIMER3 == DREQ_DMA_TIMER0 + 3, "");
check_dma_timer_param(timer_num);
return DREQ_DMA_TIMER0 + timer_num;
}
#ifndef NDEBUG
void print_dma_ctrl(dma_channel_hw_t *channel);
#endif

View File

@ -16,7 +16,7 @@
*
* Methods for setting processor exception handlers
*
* Exceptions are identified by a \ref exception_num which is a number from -15 to -1; these are the numbers relative to
* Exceptions are identified by a \ref exception_number which is a number from -15 to -1; these are the numbers relative to
* the index of the first IRQ vector in the vector table. (i.e. vector table index is exception_num plus 16)
*
* There is one set of exception handlers per core, so the exception handlers for each core as set by these methods are independent.
@ -85,11 +85,11 @@ exception_handler_t exception_set_exclusive_handler(enum exception_number num, e
* prior to the call to exception_set_exclusive_handler(), so that exception_set_exclusive_handler()
* may be called again in the future.
*
* \param num Exception number \ref exception_nums
* \param num Exception number \ref exception_number
* \param original_handler The original handler returned from \ref exception_set_exclusive_handler
* \see exception_set_exclusive_handler()
*/
void exception_restore_handler(enum exception_number, exception_handler_t original_handler);
void exception_restore_handler(enum exception_number num, exception_handler_t original_handler);
/*! \brief Get the current exception handler for the specified exception from the currently installed vector table
* of the execution core

View File

@ -50,7 +50,7 @@ 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)
void (*flash_enter_cmd_xip)(void) = (void(*)(void))rom_func_lookup(rom_table_code('C', 'X'));
rom_flash_enter_cmd_xip_fn flash_enter_cmd_xip = (rom_flash_enter_cmd_xip_fn)rom_func_lookup_inline(ROM_FUNC_FLASH_ENTER_CMD_XIP);
assert(flash_enter_cmd_xip);
flash_enter_cmd_xip();
}
@ -66,11 +66,10 @@ void __no_inline_not_in_flash_func(flash_range_erase)(uint32_t flash_offs, size_
#endif
invalid_params_if(FLASH, flash_offs & (FLASH_SECTOR_SIZE - 1));
invalid_params_if(FLASH, count & (FLASH_SECTOR_SIZE - 1));
void (*connect_internal_flash)(void) = (void(*)(void))rom_func_lookup(rom_table_code('I', 'F'));
void (*flash_exit_xip)(void) = (void(*)(void))rom_func_lookup(rom_table_code('E', 'X'));
void (*flash_range_erase)(uint32_t, size_t, uint32_t, uint8_t) =
(void(*)(uint32_t, size_t, uint32_t, uint8_t))rom_func_lookup(rom_table_code('R', 'E'));
void (*flash_flush_cache)(void) = (void(*)(void))rom_func_lookup(rom_table_code('F', 'C'));
rom_connect_internal_flash_fn connect_internal_flash = (rom_connect_internal_flash_fn)rom_func_lookup_inline(ROM_FUNC_CONNECT_INTERNAL_FLASH);
rom_flash_exit_xip_fn flash_exit_xip = (rom_flash_exit_xip_fn)rom_func_lookup_inline(ROM_FUNC_FLASH_EXIT_XIP);
rom_flash_range_erase_fn flash_range_erase = (rom_flash_range_erase_fn)rom_func_lookup_inline(ROM_FUNC_FLASH_RANGE_ERASE);
rom_flash_flush_cache_fn flash_flush_cache = (rom_flash_flush_cache_fn)rom_func_lookup_inline(ROM_FUNC_FLASH_FLUSH_CACHE);
assert(connect_internal_flash && flash_exit_xip && flash_range_erase && flash_flush_cache);
flash_init_boot2_copyout();
@ -90,11 +89,10 @@ void __no_inline_not_in_flash_func(flash_range_program)(uint32_t flash_offs, con
#endif
invalid_params_if(FLASH, flash_offs & (FLASH_PAGE_SIZE - 1));
invalid_params_if(FLASH, count & (FLASH_PAGE_SIZE - 1));
void (*connect_internal_flash)(void) = (void(*)(void))rom_func_lookup(rom_table_code('I', 'F'));
void (*flash_exit_xip)(void) = (void(*)(void))rom_func_lookup(rom_table_code('E', 'X'));
void (*flash_range_program)(uint32_t, const uint8_t*, size_t) =
(void(*)(uint32_t, const uint8_t*, size_t))rom_func_lookup(rom_table_code('R', 'P'));
void (*flash_flush_cache)(void) = (void(*)(void))rom_func_lookup(rom_table_code('F', 'C'));
rom_connect_internal_flash_fn connect_internal_flash = (rom_connect_internal_flash_fn)rom_func_lookup_inline(ROM_FUNC_CONNECT_INTERNAL_FLASH);
rom_flash_exit_xip_fn flash_exit_xip = (rom_flash_exit_xip_fn)rom_func_lookup_inline(ROM_FUNC_FLASH_EXIT_XIP);
rom_flash_range_program_fn flash_range_program = (rom_flash_range_program_fn)rom_func_lookup_inline(ROM_FUNC_FLASH_RANGE_PROGRAM);
rom_flash_flush_cache_fn flash_flush_cache = (rom_flash_flush_cache_fn)rom_func_lookup_inline(ROM_FUNC_FLASH_FLUSH_CACHE);
assert(connect_internal_flash && flash_exit_xip && flash_range_program && flash_flush_cache);
flash_init_boot2_copyout();
@ -124,9 +122,9 @@ static void __no_inline_not_in_flash_func(flash_cs_force)(bool high) {
}
void __no_inline_not_in_flash_func(flash_do_cmd)(const uint8_t *txbuf, uint8_t *rxbuf, size_t count) {
void (*connect_internal_flash)(void) = (void(*)(void))rom_func_lookup(rom_table_code('I', 'F'));
void (*flash_exit_xip)(void) = (void(*)(void))rom_func_lookup(rom_table_code('E', 'X'));
void (*flash_flush_cache)(void) = (void(*)(void))rom_func_lookup(rom_table_code('F', 'C'));
rom_connect_internal_flash_fn connect_internal_flash = (rom_connect_internal_flash_fn)rom_func_lookup_inline(ROM_FUNC_CONNECT_INTERNAL_FLASH);
rom_flash_exit_xip_fn flash_exit_xip = (rom_flash_exit_xip_fn)rom_func_lookup_inline(ROM_FUNC_FLASH_EXIT_XIP);
rom_flash_flush_cache_fn flash_flush_cache = (rom_flash_flush_cache_fn)rom_func_lookup_inline(ROM_FUNC_FLASH_FLUSH_CACHE);
assert(connect_internal_flash && flash_exit_xip && flash_flush_cache);
flash_init_boot2_copyout();
__compiler_memory_barrier();

View File

@ -142,7 +142,7 @@ static void gpio_irq_handler(void) {
io_irq_ctrl_hw_t *irq_ctrl_base = get_core_num() ?
&iobank0_hw->proc1_irq_ctrl : &iobank0_hw->proc0_irq_ctrl;
for (uint gpio = 0; gpio < NUM_BANK0_GPIOS; gpio++) {
io_rw_32 *status_reg = &irq_ctrl_base->ints[gpio / 8];
io_ro_32 *status_reg = &irq_ctrl_base->ints[gpio / 8];
uint events = (*status_reg >> 4 * (gpio % 8)) & 0xf;
if (events) {
// TODO: If both cores care about this event then the second core won't get the irq?

View File

@ -178,6 +178,12 @@ enum gpio_drive_strength {
*/
void gpio_set_function(uint gpio, enum gpio_function fn);
/*! \brief Determine current GPIO function
* \ingroup hardware_gpio
*
* \param gpio GPIO number
* \return Which GPIO function is currently selected from list \ref gpio_function
*/
enum gpio_function gpio_get_function(uint gpio);
/*! \brief Select up and down pulls on specific GPIO
@ -401,7 +407,7 @@ void gpio_acknowledge_irq(uint gpio, uint32_t events);
/*! \brief Initialise a GPIO for (enabled I/O and set func to GPIO_FUNC_SIO)
* \ingroup hardware_gpio
*
* Clear the output enable (i.e. set to input)
* Clear the output enable (i.e. set to input).
* Clear any output value.
*
* \param gpio GPIO number
@ -411,7 +417,7 @@ void gpio_init(uint gpio);
/*! \brief Initialise multiple GPIOs (enabled I/O and set func to GPIO_FUNC_SIO)
* \ingroup hardware_gpio
*
* Clear the output enable (i.e. set to input)
* Clear the output enable (i.e. set to input).
* Clear any output value.
*
* \param gpio_mask Mask with 1 bit per GPIO number to initialize

View File

@ -115,16 +115,18 @@ void i2c_set_slave_mode(i2c_inst_t *i2c, bool slave, uint8_t addr) {
invalid_params_if(I2C, addr >= 0x80); // 7-bit addresses
invalid_params_if(I2C, i2c_reserved_addr(addr));
i2c->hw->enable = 0;
uint32_t ctrl_set_if_master = I2C_IC_CON_MASTER_MODE_BITS | I2C_IC_CON_IC_SLAVE_DISABLE_BITS;
uint32_t ctrl_set_if_slave = I2C_IC_CON_RX_FIFO_FULL_HLD_CTRL_BITS;
if (slave) {
hw_clear_bits(&i2c->hw->con,
I2C_IC_CON_MASTER_MODE_BITS |
I2C_IC_CON_IC_SLAVE_DISABLE_BITS
hw_write_masked(&i2c->hw->con,
ctrl_set_if_slave,
ctrl_set_if_master | ctrl_set_if_slave
);
i2c->hw->sar = addr;
} else {
hw_set_bits(&i2c->hw->con,
I2C_IC_CON_MASTER_MODE_BITS |
I2C_IC_CON_IC_SLAVE_DISABLE_BITS
hw_write_masked(&i2c->hw->con,
ctrl_set_if_master,
ctrl_set_if_master | ctrl_set_if_slave
);
}
i2c->hw->enable = 1;

View File

@ -10,6 +10,7 @@
#include "pico.h"
#include "pico/time.h"
#include "hardware/structs/i2c.h"
#include "hardware/regs/dreq.h"
// PICO_CONFIG: PARAM_ASSERTIONS_ENABLED_I2C, Enable/disable assertions in the I2C module, type=bool, default=0, group=hardware_i2c
#ifndef PARAM_ASSERTIONS_ENABLED_I2C
@ -26,10 +27,12 @@ extern "C" {
* I2C Controller API
*
* The I2C bus is a two-wire serial interface, consisting of a serial data line SDA and a serial clock SCL. These wires carry
* information between the devices connected to the bus. Each device is recognized by a unique address and can operate as
* information between the devices connected to the bus. Each device is recognized by a unique 7-bit address and can operate as
* either a “transmitter” or “receiver”, depending on the function of the device. Devices can also be considered as masters or
* slaves when performing data transfers. A master is a device that initiates a data transfer on the bus and generates the
* clock signals to permit that transfer. At that time, any device addressed is considered a slave.
* clock signals to permit that transfer. The first byte in the data transfer always contains the 7-bit address and
* a read/write bit in the LSB position. This API takes care of toggling the read/write bit. After this, any device addressed
* is considered a slave.
*
* This API allows the controller to be set up as a master or a slave using the \ref i2c_set_slave_mode function.
*
@ -154,7 +157,7 @@ static inline i2c_hw_t *i2c_get_hw(i2c_inst_t *i2c) {
* \ingroup hardware_i2c
*
* \param i2c Either \ref i2c0 or \ref i2c1
* \param addr Address of device to write to
* \param addr 7-bit address of device to write to
* \param src Pointer to data to send
* \param len Length of data in bytes to send
* \param nostop If true, master retains control of the bus at the end of the transfer (no Stop is issued),
@ -171,7 +174,7 @@ int i2c_write_blocking_until(i2c_inst_t *i2c, uint8_t addr, const uint8_t *src,
* \ingroup hardware_i2c
*
* \param i2c Either \ref i2c0 or \ref i2c1
* \param addr Address of device to read from
* \param addr 7-bit address of device to read from
* \param dst Pointer to buffer to receive data
* \param len Length of data in bytes to receive
* \param nostop If true, master retains control of the bus at the end of the transfer (no Stop is issued),
@ -185,7 +188,7 @@ int i2c_read_blocking_until(i2c_inst_t *i2c, uint8_t addr, uint8_t *dst, size_t
* \ingroup hardware_i2c
*
* \param i2c Either \ref i2c0 or \ref i2c1
* \param addr Address of device to write to
* \param addr 7-bit address of device to write to
* \param src Pointer to data to send
* \param len Length of data in bytes to send
* \param nostop If true, master retains control of the bus at the end of the transfer (no Stop is issued),
@ -207,7 +210,7 @@ int i2c_write_timeout_per_char_us(i2c_inst_t *i2c, uint8_t addr, const uint8_t *
* \ingroup hardware_i2c
*
* \param i2c Either \ref i2c0 or \ref i2c1
* \param addr Address of device to read from
* \param addr 7-bit address of device to read from
* \param dst Pointer to buffer to receive data
* \param len Length of data in bytes to receive
* \param nostop If true, master retains control of the bus at the end of the transfer (no Stop is issued),
@ -226,7 +229,7 @@ int i2c_read_timeout_per_char_us(i2c_inst_t *i2c, uint8_t addr, uint8_t *dst, si
* \ingroup hardware_i2c
*
* \param i2c Either \ref i2c0 or \ref i2c1
* \param addr Address of device to write to
* \param addr 7-bit address of device to write to
* \param src Pointer to data to send
* \param len Length of data in bytes to send
* \param nostop If true, master retains control of the bus at the end of the transfer (no Stop is issued),
@ -239,12 +242,12 @@ int i2c_write_blocking(i2c_inst_t *i2c, uint8_t addr, const uint8_t *src, size_t
* \ingroup hardware_i2c
*
* \param i2c Either \ref i2c0 or \ref i2c1
* \param addr Address of device to read from
* \param addr 7-bit address of device to read from
* \param dst Pointer to buffer to receive data
* \param len Length of data in bytes to receive
* \param nostop If true, master retains control of the bus at the end of the transfer (no Stop is issued),
* and the next transfer will begin with a Restart rather than a Start.
* \return Number of bytes read, or PICO_ERROR_GENERIC if address not acknowledged, no device present.
* \return Number of bytes read, or PICO_ERROR_GENERIC if address not acknowledged or no device present.
*/
int i2c_read_blocking(i2c_inst_t *i2c, uint8_t addr, uint8_t *dst, size_t len, bool nostop);
@ -309,6 +312,19 @@ static inline void i2c_read_raw_blocking(i2c_inst_t *i2c, uint8_t *dst, size_t l
}
}
/*! \brief Return the DREQ to use for pacing transfers to/from a particular I2C instance
* \ingroup hardware_i2c
*
* \param i2c Either \ref i2c0 or \ref i2c1
* \param is_tx true for sending data to the I2C instance, false for receiving data from the I2C instance
*/
static inline uint i2c_get_dreq(i2c_inst_t *i2c, bool is_tx) {
static_assert(DREQ_I2C0_RX == DREQ_I2C0_TX + 1, "");
static_assert(DREQ_I2C1_RX == DREQ_I2C1_TX + 1, "");
static_assert(DREQ_I2C1_TX == DREQ_I2C0_TX + 2, "");
return DREQ_I2C0_TX + i2c_hw_index(i2c) * 2 + !is_tx;
}
#ifdef __cplusplus
}
#endif

View File

@ -8,12 +8,12 @@
#define _HARDWARE_IRQ_H_
// These two config items are also used by assembler, so keeping separate
// PICO_CONFIG: PICO_MAX_SHARED_IRQ_HANDLERS, Maximum Number of shared IRQ handers, default=4, advanced=true, group=hardware_irq
// PICO_CONFIG: PICO_MAX_SHARED_IRQ_HANDLERS, Maximum number of shared IRQ handlers, default=4, advanced=true, group=hardware_irq
#ifndef PICO_MAX_SHARED_IRQ_HANDLERS
#define PICO_MAX_SHARED_IRQ_HANDLERS 4u
#endif
// PICO_CONFIG: PICO_DISABLE_SHARED_IRQ_HANDLERS, Disable shared IRQ handers, type=bool, default=0, group=hardware_irq
// PICO_CONFIG: PICO_DISABLE_SHARED_IRQ_HANDLERS, Disable shared IRQ handlers, type=bool, default=0, group=hardware_irq
#ifndef PICO_DISABLE_SHARED_IRQ_HANDLERS
#define PICO_DISABLE_SHARED_IRQ_HANDLERS 0
#endif
@ -37,13 +37,13 @@
* On the RP2040, only the lower 26 IRQ signals are connected on the NVIC; IRQs 26 to 31 are tied to zero (never firing).
*
* There is one NVIC per core, and each core's NVIC has the same hardware interrupt lines routed to it, with the exception of the IO interrupts
* where there is one IO interrupt per bank, per core. These are completely independent, so for example, processor 0 can be
* where there is one IO interrupt per bank, per core. These are completely independent, so, for example, processor 0 can be
* interrupted by GPIO 0 in bank 0, and processor 1 by GPIO 1 in the same bank.
*
* \note That all IRQ APIs affect the executing core only (i.e. the core calling the function).
*
* \note You should not enable the same (shared) IRQ number on both cores, as this will lead to race conditions
* or starvation of one of the cores. Additionally don't forget that disabling interrupts on one core does not disable interrupts
* or starvation of one of the cores. Additionally, don't forget that disabling interrupts on one core does not disable interrupts
* on the other core.
*
* There are three different ways to set handlers for an IRQ:
@ -53,7 +53,7 @@
* you will not be able to change it using the above APIs at runtime). Using this method can cause link conflicts at runtime, and offers no runtime performance benefit (i.e, it should not generally be used).
*
* \note If an IRQ is enabled and fires with no handler installed, a breakpoint will be hit and the IRQ number will
* be in r0.
* be in register r0.
*
* \section interrupt_nums Interrupt Numbers
*
@ -119,7 +119,11 @@ extern "C" {
*/
typedef void (*irq_handler_t)(void);
/*! \brief Set specified interrupts priority
static inline void check_irq_param(__unused uint num) {
invalid_params_if(IRQ, num >= NUM_IRQS);
}
/*! \brief Set specified interrupt's priority
* \ingroup hardware_irq
*
* \param num Interrupt number
@ -133,6 +137,21 @@ typedef void (*irq_handler_t)(void);
*/
void irq_set_priority(uint num, uint8_t hardware_priority);
/*! \brief Get specified interrupt's priority
* \ingroup hardware_irq
*
* Numerically-lower values indicate a higher priority. Hardware priorities
* range from 0 (highest priority) to 255 (lowest priority) though only the
* top 2 bits are significant on ARM Cortex-M0+. To make it easier to specify
* higher or lower priorities than the default, all IRQ priorities are
* initialized to PICO_DEFAULT_IRQ_PRIORITY by the SDK runtime at startup.
* PICO_DEFAULT_IRQ_PRIORITY defaults to 0x80
*
* \param num Interrupt number
* \return the IRQ priority
*/
uint irq_get_priority(uint num);
/*! \brief Enable or disable a specific interrupt on the executing core
* \ingroup hardware_irq
*
@ -245,7 +264,7 @@ static inline void irq_clear(uint int_num) {
*((volatile uint32_t *) (PPB_BASE + M0PLUS_NVIC_ICPR_OFFSET)) = (1u << ((uint32_t) (int_num & 0x1F)));
}
/*! \brief Force an interrupt to pending on the executing core
/*! \brief Force an interrupt to be pending on the executing core
* \ingroup hardware_irq
*
* This should generally not be used for IRQs connected to hardware.

View File

@ -33,10 +33,6 @@ static void set_raw_irq_handler_and_unlock(uint num, irq_handler_t handler, uint
spin_unlock(spin_lock_instance(PICO_SPINLOCK_ID_IRQ), save);
}
static inline void check_irq_param(__unused uint num) {
invalid_params_if(IRQ, num >= NUM_IRQS);
}
void irq_set_enabled(uint num, bool enabled) {
check_irq_param(num);
irq_set_mask_enabled(1u << num, enabled);
@ -63,7 +59,7 @@ void irq_set_pending(uint num) {
*((io_rw_32 *) (PPB_BASE + M0PLUS_NVIC_ISPR_OFFSET)) = 1u << num;
}
#if PICO_MAX_SHARED_IRQ_HANDLERS
#if !PICO_DISABLE_SHARED_IRQ_HANDLERS
// limited by 8 bit relative links (and reality)
static_assert(PICO_MAX_SHARED_IRQ_HANDLERS >= 1 && PICO_MAX_SHARED_IRQ_HANDLERS < 0x7f, "");
@ -92,11 +88,13 @@ extern struct irq_handler_chain_slot {
} irq_handler_chain_slots[PICO_MAX_SHARED_IRQ_HANDLERS];
static int8_t irq_hander_chain_free_slot_head;
#endif
static inline bool is_shared_irq_raw_handler(irq_handler_t raw_handler) {
return (uintptr_t)raw_handler - (uintptr_t)irq_handler_chain_slots < sizeof(irq_handler_chain_slots);
}
#else
#define is_shared_irq_raw_handler(h) false
#endif
irq_handler_t irq_get_vtable_handler(uint num) {
check_irq_param(num);
@ -133,6 +131,7 @@ irq_handler_t irq_get_exclusive_handler(uint num) {
}
#if !PICO_DISABLE_SHARED_IRQ_HANDLERS
static uint16_t make_branch(uint16_t *from, void *to) {
uint32_t ui_from = (uint32_t)from;
uint32_t ui_to = (uint32_t)to;
@ -160,37 +159,36 @@ static inline void *resolve_branch(uint16_t *inst) {
// GCC produces horrible code for subtraction of pointers here, and it was bugging me
static inline int8_t slot_diff(struct irq_handler_chain_slot *to, struct irq_handler_chain_slot *from) {
static_assert(sizeof(struct irq_handler_chain_slot) == 12, "");
int32_t result;
int32_t result = 0xaaaa;
// return (to - from);
// note this implementation has limited range, but is fine for plenty more than -128->127 result
asm (".syntax unified\n"
"subs %1, %2\n"
"adcs %1, %1\n" // * 2 (and + 1 if negative for rounding)
"ldr %0, =0xaaaa\n"
"muls %0, %1\n"
"lsrs %0, 20\n"
: "=l" (result), "+l" (to)
: "l" (from)
:
);
: "+l" (result), "+l" (to)
: "l" (from)
:
);
return (int8_t)result;
}
static inline int8_t get_slot_index(struct irq_handler_chain_slot *slot) {
return slot_diff(slot, irq_handler_chain_slots);
}
#endif
void irq_add_shared_handler(uint num, irq_handler_t handler, uint8_t order_priority) {
check_irq_param(num);
#if PICO_DISABLE_SHARED_IRQ_HANDLERS
#endif
#if PICO_NO_RAM_VECTOR_TABLE || !PICO_MAX_SHARED_IRQ_HANDLERS
#if PICO_NO_RAM_VECTOR_TABLE
panic_unsupported()
#elif PICO_DISABLE_SHARED_IRQ_HANDLERS
irq_set_exclusive_handler(num, handler);
#else
spin_lock_t *lock = spin_lock_instance(PICO_SPINLOCK_ID_IRQ);
uint32_t save = spin_lock_blocking(lock);
hard_assert(irq_hander_chain_free_slot_head >= 0);
hard_assert(irq_hander_chain_free_slot_head >= 0); // we must have a slot
struct irq_handler_chain_slot *slot = &irq_handler_chain_slots[irq_hander_chain_free_slot_head];
int8_t slot_index = irq_hander_chain_free_slot_head;
irq_hander_chain_free_slot_head = slot->link;
@ -261,7 +259,7 @@ void irq_remove_handler(uint num, irq_handler_t handler) {
uint32_t save = spin_lock_blocking(lock);
irq_handler_t vtable_handler = get_vtable()[16 + num];
if (vtable_handler != __unhandled_user_irq && vtable_handler != handler) {
#if !PICO_DISABLE_SHARED_IRQ_HANDLERS && PICO_MAX_SHARED_IRQ_HANDLERS
#if !PICO_DISABLE_SHARED_IRQ_HANDLERS
if (is_shared_irq_raw_handler(vtable_handler)) {
// This is a bit tricky, as an executing IRQ handler doesn't take a lock.
@ -361,7 +359,15 @@ void irq_set_priority(uint num, uint8_t hardware_priority) {
*p = (*p & ~(0xffu << (8 * (num & 3u)))) | (((uint32_t) hardware_priority) << (8 * (num & 3u)));
}
#if !PICO_DISABLE_SHARED_IRQ_HANDLERS && PICO_MAX_SHARED_IRQ_HANDLERS
uint irq_get_priority(uint num) {
check_irq_param(num);
// note that only 32 bit reads are supported
io_rw_32 *p = (io_rw_32 *)((PPB_BASE + M0PLUS_NVIC_IPR0_OFFSET) + (num & ~3u));
return (uint8_t)(*p >> (8 * (num & 3u)));
}
#if !PICO_DISABLE_SHARED_IRQ_HANDLERS
// used by irq_handler_chain.S to remove the last link in a handler chain after it executes
// note this must be called only with the last slot in a chain (and during the exception)
void irq_add_tail_to_free_list(struct irq_handler_chain_slot *slot) {
@ -397,8 +403,11 @@ void irq_add_tail_to_free_list(struct irq_handler_chain_slot *slot) {
void irq_init_priorities() {
#if PICO_DEFAULT_IRQ_PRIORITY != 0
for (uint irq = 0; irq < NUM_IRQS; irq++) {
irq_set_priority(irq, PICO_DEFAULT_IRQ_PRIORITY);
static_assert(!(NUM_IRQS & 3), "");
uint32_t prio4 = (PICO_DEFAULT_IRQ_PRIORITY & 0xff) * 0x1010101u;
io_rw_32 * p = (io_rw_32 *)(PPB_BASE + M0PLUS_NVIC_IPR0_OFFSET);
for (uint i = 0; i < NUM_IRQS / 4; i++) {
*p++ = prio4;
}
#endif
}

View File

@ -4,7 +4,7 @@
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "hardware/platform_defs.h"
#include "pico.h"
#include "hardware/irq.h"
#if !PICO_DISABLE_SHARED_IRQ_HANDLERS

View File

@ -25,7 +25,7 @@
* Programmable I/O (PIO) API
*
* A programmable input/output block (PIO) is a versatile hardware interface which
* can support a number of different IO standards. There are two PIO blocks in the RP2040
* can support a number of different IO standards. There are two PIO blocks in the RP2040.
*
* Each PIO is programmable in the same sense as a processor: the four state machines independently
* execute short, sequential programs, to manipulate GPIOs and transfer data. Unlike a general
@ -436,14 +436,19 @@ static inline void pio_gpio_init(PIO pio, uint pin) {
gpio_set_function(pin, pio == pio0 ? GPIO_FUNC_PIO0 : GPIO_FUNC_PIO1);
}
/*! \brief Return the DREQ to use for pacing transfers to a particular state machine
/*! \brief Return the DREQ to use for pacing transfers to/from a particular state machine FIFO
* \ingroup hardware_pio
*
* \param pio The PIO instance; either \ref pio0 or \ref pio1
* \param sm State machine index (0..3)
* \param is_tx true for sending data to the state machine, false for received data from the state machine
* \param is_tx true for sending data to the state machine, false for receiving data from the state machine
*/
static inline uint pio_get_dreq(PIO pio, uint sm, bool is_tx) {
static_assert(DREQ_PIO0_TX1 == DREQ_PIO0_TX0 + 1, "");
static_assert(DREQ_PIO0_TX2 == DREQ_PIO0_TX0 + 2, "");
static_assert(DREQ_PIO0_TX3 == DREQ_PIO0_TX0 + 3, "");
static_assert(DREQ_PIO0_RX0 == DREQ_PIO0_TX0 + NUM_PIO_STATE_MACHINES, "");
static_assert(DREQ_PIO1_RX0 == DREQ_PIO1_TX0 + NUM_PIO_STATE_MACHINES, "");
check_pio_param(pio);
check_sm_param(sm);
return sm + (is_tx ? 0 : NUM_PIO_STATE_MACHINES) + (pio == pio0 ? DREQ_PIO0_TX0 : DREQ_PIO1_TX0);

View File

@ -9,7 +9,18 @@
#include "pico.h"
// PICO_CONFIG: PARAM_ASSERTIONS_ENABLED_PIO_INSTRUCTIONS, Enable/disable assertions in the PIO instructions, type=bool, default=0, group=hardware_pio
/** \brief PIO instruction encoding
* \defgroup pio_instructions pio_instructions
* \ingroup hardware_pio
*
* Functions for generating PIO instruction encodings programmatically. In debug builds
*`PARAM_ASSERTIONS_ENABLED_PIO_INSTRUCTIONS` can be set to 1 to enable validation of encoding function
* parameters.
*
* For fuller descriptions of the instructions in question see the "RP2040 Datasheet"
*/
// PICO_CONFIG: PARAM_ASSERTIONS_ENABLED_PIO_INSTRUCTIONS, Enable/disable assertions in the PIO instructions, type=bool, default=0, group=pio_instructions
#ifndef PARAM_ASSERTIONS_ENABLED_PIO_INSTRUCTIONS
#define PARAM_ASSERTIONS_ENABLED_PIO_INSTRUCTIONS 0
#endif
@ -44,6 +55,12 @@ enum pio_instr_bits {
#define _PIO_INVALID_MOV_DEST 0u
#endif
/*! \brief Enumeration of values to pass for source/destination args for instruction encoding functions
* \ingroup pio_instructions
*
* \note Not all values are suitable for all functions. Validity is only checked in debug mode when
* `PARAM_ASSERTIONS_ENABLED_PIO_INSTRUCTIONS` is 1
*/
enum pio_src_dest {
pio_pins = 0u,
pio_x = 1u,
@ -58,11 +75,11 @@ enum pio_src_dest {
pio_exec_out = 7u | _PIO_INVALID_IN_SRC | _PIO_INVALID_SET_DEST | _PIO_INVALID_MOV_SRC | _PIO_INVALID_MOV_DEST,
};
inline static uint _pio_major_instr_bits(uint instr) {
static inline uint _pio_major_instr_bits(uint instr) {
return instr & 0xe000u;
}
inline static uint _pio_encode_instr_and_args(enum pio_instr_bits instr_bits, uint arg1, uint arg2) {
static inline uint _pio_encode_instr_and_args(enum pio_instr_bits instr_bits, uint arg1, uint arg2) {
valid_params_if(PIO_INSTRUCTIONS, arg1 <= 0x7);
#if PARAM_ASSERTIONS_ENABLED(PIO_INSTRUCTIONS)
uint32_t major = _pio_major_instr_bits(instr_bits);
@ -75,100 +92,388 @@ inline static uint _pio_encode_instr_and_args(enum pio_instr_bits instr_bits, ui
return instr_bits | (arg1 << 5u) | (arg2 & 0x1fu);
}
inline static uint _pio_encode_instr_and_src_dest(enum pio_instr_bits instr_bits, enum pio_src_dest dest, uint value) {
static inline uint _pio_encode_instr_and_src_dest(enum pio_instr_bits instr_bits, enum pio_src_dest dest, uint value) {
return _pio_encode_instr_and_args(instr_bits, dest & 7u, value);
}
inline static uint pio_encode_delay(uint cycles) {
/*! \brief Encode just the delay slot bits of an instruction
* \ingroup pio_instructions
*
* \note This function does not return a valid instruction encoding; instead it returns an encoding of the delay
* slot suitable for `OR`ing with the result of an encoding function for an actual instruction. Care should be taken when
* combining the results of this function with the results of \ref pio_encode_sideset and \ref pio_encode_sideset_opt
* as they share the same bits within the instruction encoding.
*
* \param cycles the number of cycles 0-31 (or less if side set is being used)
* \return the delay slot bits to be ORed with an instruction encoding
*/
static inline uint pio_encode_delay(uint cycles) {
// note that the maximum cycles will be smaller if sideset_bit_count > 0
valid_params_if(PIO_INSTRUCTIONS, cycles <= 0x1f);
return cycles << 8u;
}
inline static uint pio_encode_sideset(uint sideset_bit_count, uint value) {
/*! \brief Encode just the side set bits of an instruction (in non optional side set mode)
* \ingroup pio_instructions
*
* \note This function does not return a valid instruction encoding; instead it returns an encoding of the side set bits
* suitable for `OR`ing with the result of an encoding function for an actual instruction. Care should be taken when
* combining the results of this function with the results of \ref pio_encode_delay as they share the same bits
* within the instruction encoding.
*
* \param sideset_bit_count number of side set bits as would be specified via `.sideset` in pioasm
* \param value the value to sideset on the pins
* \return the side set bits to be ORed with an instruction encoding
*/
static inline uint pio_encode_sideset(uint sideset_bit_count, uint value) {
valid_params_if(PIO_INSTRUCTIONS, sideset_bit_count >= 1 && sideset_bit_count <= 5);
valid_params_if(PIO_INSTRUCTIONS, value <= ((1u << sideset_bit_count) - 1));
return value << (13u - sideset_bit_count);
}
inline static uint pio_encode_sideset_opt(uint sideset_bit_count, uint value) {
/*! \brief Encode just the side set bits of an instruction (in optional -`opt` side set mode)
* \ingroup pio_instructions
*
* \note This function does not return a valid instruction encoding; instead it returns an encoding of the side set bits
* suitable for `OR`ing with the result of an encoding function for an actual instruction. Care should be taken when
* combining the results of this function with the results of \ref pio_encode_delay as they share the same bits
* within the instruction encoding.
*
* \param sideset_bit_count number of side set bits as would be specified via `.sideset <n> opt` in pioasm
* \param value the value to sideset on the pins
* \return the side set bits to be ORed with an instruction encoding
*/
static inline uint pio_encode_sideset_opt(uint sideset_bit_count, uint value) {
valid_params_if(PIO_INSTRUCTIONS, sideset_bit_count >= 1 && sideset_bit_count <= 4);
valid_params_if(PIO_INSTRUCTIONS, value <= ((1u << sideset_bit_count) - 1));
return 0x1000u | value << (12u - sideset_bit_count);
}
inline static uint pio_encode_jmp(uint addr) {
/*! \brief Encode an unconditional JMP instruction
* \ingroup pio_instructions
*
* This is the equivalent of `JMP <addr>`
*
* \param addr The target address 0-31 (an absolute address within the PIO instruction memory)
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_jmp(uint addr) {
return _pio_encode_instr_and_args(pio_instr_bits_jmp, 0, addr);
}
inline static uint _pio_encode_irq(bool relative, uint irq) {
/*! \brief Encode a conditional JMP if scratch X zero instruction
* \ingroup pio_instructions
*
* This is the equivalent of `JMP !X <addr>`
*
* \param addr The target address 0-31 (an absolute address within the PIO instruction memory)
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_jmp_not_x(uint addr) {
return _pio_encode_instr_and_args(pio_instr_bits_jmp, 1, addr);
}
/*! \brief Encode a conditional JMP if scratch X non-zero (and post-decrement X) instruction
* \ingroup pio_instructions
*
* This is the equivalent of `JMP X-- <addr>`
*
* \param addr The target address 0-31 (an absolute address within the PIO instruction memory)
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_jmp_x_dec(uint addr) {
return _pio_encode_instr_and_args(pio_instr_bits_jmp, 2, addr);
}
/*! \brief Encode a conditional JMP if scratch Y zero instruction
* \ingroup pio_instructions
*
* This is the equivalent of `JMP !Y <addr>`
*
* \param addr The target address 0-31 (an absolute address within the PIO instruction memory)
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_jmp_not_y(uint addr) {
return _pio_encode_instr_and_args(pio_instr_bits_jmp, 3, addr);
}
/*! \brief Encode a conditional JMP if scratch Y non-zero (and post-decrement Y) instruction
* \ingroup pio_instructions
*
* This is the equivalent of `JMP Y-- <addr>`
*
* \param addr The target address 0-31 (an absolute address within the PIO instruction memory)
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_jmp_y_dec(uint addr) {
return _pio_encode_instr_and_args(pio_instr_bits_jmp, 4, addr);
}
/*! \brief Encode a conditional JMP if scratch X not equal scratch Y instruction
* \ingroup pio_instructions
*
* This is the equivalent of `JMP X!=Y <addr>`
*
* \param addr The target address 0-31 (an absolute address within the PIO instruction memory)
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_jmp_x_ne_y(uint addr) {
return _pio_encode_instr_and_args(pio_instr_bits_jmp, 5, addr);
}
/*! \brief Encode a conditional JMP if input pin high instruction
* \ingroup pio_instructions
*
* This is the equivalent of `JMP PIN <addr>`
*
* \param addr The target address 0-31 (an absolute address within the PIO instruction memory)
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_jmp_pin(uint addr) {
return _pio_encode_instr_and_args(pio_instr_bits_jmp, 6, addr);
}
/*! \brief Encode a conditional JMP if output shift register not empty instruction
* \ingroup pio_instructions
*
* This is the equivalent of `JMP !OSRE <addr>`
*
* \param addr The target address 0-31 (an absolute address within the PIO instruction memory)
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_jmp_not_osre(uint addr) {
return _pio_encode_instr_and_args(pio_instr_bits_jmp, 7, addr);
}
static inline uint _pio_encode_irq(bool relative, uint irq) {
valid_params_if(PIO_INSTRUCTIONS, irq <= 7);
return (relative ? 0x10u : 0x0u) | irq;
}
inline static uint pio_encode_wait_gpio(bool polarity, uint pin) {
return _pio_encode_instr_and_args(pio_instr_bits_wait, 0u | (polarity ? 4u : 0u), pin);
/*! \brief Encode a WAIT for GPIO pin instruction
* \ingroup pio_instructions
*
* This is the equivalent of `WAIT <polarity> GPIO <gpio>`
*
* \param polarity true for `WAIT 1`, false for `WAIT 0`
* \param gpio The real GPIO number 0-31
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_wait_gpio(bool polarity, uint gpio) {
return _pio_encode_instr_and_args(pio_instr_bits_wait, 0u | (polarity ? 4u : 0u), gpio);
}
inline static uint pio_encode_wait_pin(bool polarity, uint pin) {
/*! \brief Encode a WAIT for pin instruction
* \ingroup pio_instructions
*
* This is the equivalent of `WAIT <polarity> PIN <pin>`
*
* \param polarity true for `WAIT 1`, false for `WAIT 0`
* \param pin The pin number 0-31 relative to the executing SM's input pin mapping
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_wait_pin(bool polarity, uint pin) {
return _pio_encode_instr_and_args(pio_instr_bits_wait, 1u | (polarity ? 4u : 0u), pin);
}
inline static uint pio_encode_wait_irq(bool polarity, bool relative, uint irq) {
/*! \brief Encode a WAIT for IRQ instruction
* \ingroup pio_instructions
*
* This is the equivalent of `WAIT <polarity> IRQ <irq> <relative>`
*
* \param polarity true for `WAIT 1`, false for `WAIT 0`
* \param relative true for a `WAIT IRQ <irq> REL`, false for regular `WAIT IRQ <irq>`
* \param irq the irq number 0-7
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_wait_irq(bool polarity, bool relative, uint irq) {
valid_params_if(PIO_INSTRUCTIONS, irq <= 7);
return _pio_encode_instr_and_args(pio_instr_bits_wait, 2u | (polarity ? 4u : 0u), _pio_encode_irq(relative, irq));
}
inline static uint pio_encode_in(enum pio_src_dest src, uint value) {
/*! \brief Encode an IN instruction
* \ingroup pio_instructions
*
* This is the equivalent of `IN <src>, <count>`
*
* \param src The source to take data from
* \param count The number of bits 1-32
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_in(enum pio_src_dest src, uint count) {
valid_params_if(PIO_INSTRUCTIONS, !(src & _PIO_INVALID_IN_SRC));
return _pio_encode_instr_and_src_dest(pio_instr_bits_in, src, value);
return _pio_encode_instr_and_src_dest(pio_instr_bits_in, src, count);
}
inline static uint pio_encode_out(enum pio_src_dest dest, uint value) {
/*! \brief Encode an OUT instruction
* \ingroup pio_instructions
*
* This is the equivalent of `OUT <src>, <count>`
*
* \param dest The destination to write data to
* \param count The number of bits 1-32
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_out(enum pio_src_dest dest, uint count) {
valid_params_if(PIO_INSTRUCTIONS, !(dest & _PIO_INVALID_OUT_DEST));
return _pio_encode_instr_and_src_dest(pio_instr_bits_out, dest, value);
return _pio_encode_instr_and_src_dest(pio_instr_bits_out, dest, count);
}
inline static uint pio_encode_push(bool if_full, bool block) {
/*! \brief Encode a PUSH instruction
* \ingroup pio_instructions
*
* This is the equivalent of `PUSH <if_full>, <block>`
*
* \param if_full true for `PUSH IF_FULL ...`, false for `PUSH ...`
* \param block true for `PUSH ... BLOCK`, false for `PUSH ...`
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_push(bool if_full, bool block) {
return _pio_encode_instr_and_args(pio_instr_bits_push, (if_full ? 2u : 0u) | (block ? 1u : 0u), 0);
}
inline static uint pio_encode_pull(bool if_empty, bool block) {
/*! \brief Encode a PULL instruction
* \ingroup pio_instructions
*
* This is the equivalent of `PULL <if_empty>, <block>`
*
* \param if_empty true for `PULL IF_EMPTY ...`, false for `PULL ...`
* \param block true for `PULL ... BLOCK`, false for `PULL ...`
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_pull(bool if_empty, bool block) {
return _pio_encode_instr_and_args(pio_instr_bits_pull, (if_empty ? 2u : 0u) | (block ? 1u : 0u), 0);
}
inline static uint pio_encode_mov(enum pio_src_dest dest, enum pio_src_dest src) {
/*! \brief Encode a MOV instruction
* \ingroup pio_instructions
*
* This is the equivalent of `MOV <dest>, <src>`
*
* \param dest The destination to write data to
* \param src The source to take data from
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_mov(enum pio_src_dest dest, enum pio_src_dest src) {
valid_params_if(PIO_INSTRUCTIONS, !(dest & _PIO_INVALID_MOV_DEST));
valid_params_if(PIO_INSTRUCTIONS, !(src & _PIO_INVALID_MOV_SRC));
return _pio_encode_instr_and_src_dest(pio_instr_bits_mov, dest, src & 7u);
}
inline static uint pio_encode_mov_not(enum pio_src_dest dest, enum pio_src_dest src) {
/*! \brief Encode a MOV instruction with bit invert
* \ingroup pio_instructions
*
* This is the equivalent of `MOV <dest>, ~<src>`
*
* \param dest The destination to write inverted data to
* \param src The source to take data from
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_mov_not(enum pio_src_dest dest, enum pio_src_dest src) {
valid_params_if(PIO_INSTRUCTIONS, !(dest & _PIO_INVALID_MOV_DEST));
valid_params_if(PIO_INSTRUCTIONS, !(src & _PIO_INVALID_MOV_SRC));
return _pio_encode_instr_and_src_dest(pio_instr_bits_mov, dest, (1u << 3u) | (src & 7u));
}
inline static uint pio_encode_mov_reverse(enum pio_src_dest dest, enum pio_src_dest src) {
/*! \brief Encode a MOV instruction with bit reverse
* \ingroup pio_instructions
*
* This is the equivalent of `MOV <dest>, ::<src>`
*
* \param dest The destination to write bit reversed data to
* \param src The source to take data from
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_mov_reverse(enum pio_src_dest dest, enum pio_src_dest src) {
valid_params_if(PIO_INSTRUCTIONS, !(dest & _PIO_INVALID_MOV_DEST));
valid_params_if(PIO_INSTRUCTIONS, !(src & _PIO_INVALID_MOV_SRC));
return _pio_encode_instr_and_src_dest(pio_instr_bits_mov, dest, (2u << 3u) | (src & 7u));
}
inline static uint pio_encode_irq_set(bool relative, uint irq) {
/*! \brief Encode a IRQ SET instruction
* \ingroup pio_instructions
*
* This is the equivalent of `IRQ SET <irq> <relative>`
*
* \param relative true for a `IRQ SET <irq> REL`, false for regular `IRQ SET <irq>`
* \param irq the irq number 0-7
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_irq_set(bool relative, uint irq) {
return _pio_encode_instr_and_args(pio_instr_bits_irq, 0, _pio_encode_irq(relative, irq));
}
inline static uint pio_encode_irq_clear(bool relative, uint irq) {
/*! \brief Encode a IRQ WAIT instruction
* \ingroup pio_instructions
*
* This is the equivalent of `IRQ WAIT <irq> <relative>`
*
* \param relative true for a `IRQ WAIT <irq> REL`, false for regular `IRQ WAIT <irq>`
* \param irq the irq number 0-7
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_irq_wait(bool relative, uint irq) {
return _pio_encode_instr_and_args(pio_instr_bits_irq, 1, _pio_encode_irq(relative, irq));
}
/*! \brief Encode a IRQ CLEAR instruction
* \ingroup pio_instructions
*
* This is the equivalent of `IRQ CLEAR <irq> <relative>`
*
* \param relative true for a `IRQ CLEAR <irq> REL`, false for regular `IRQ CLEAR <irq>`
* \param irq the irq number 0-7
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_irq_clear(bool relative, uint irq) {
return _pio_encode_instr_and_args(pio_instr_bits_irq, 2, _pio_encode_irq(relative, irq));
}
inline static uint pio_encode_set(enum pio_src_dest dest, uint value) {
/*! \brief Encode a SET instruction
* \ingroup pio_instructions
*
* This is the equivalent of `SET <dest>, <value>`
*
* \param dest The destination to apply the value to
* \param value The value 0-31
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_set(enum pio_src_dest dest, uint value) {
valid_params_if(PIO_INSTRUCTIONS, !(dest & _PIO_INVALID_SET_DEST));
return _pio_encode_instr_and_src_dest(pio_instr_bits_set, dest, value);
}
inline static uint pio_encode_nop(void) {
/*! \brief Encode a NOP instruction
* \ingroup pio_instructions
*
* This is the equivalent of `NOP` which is itself encoded as `MOV y, y`
*
* \return The instruction encoding with 0 delay and no side set value
* \see pio_encode_delay, pio_encode_sideset, pio_encode_sideset_opt
*/
static inline uint pio_encode_nop(void) {
return pio_encode_mov(pio_y, pio_y);
}

View File

@ -9,6 +9,7 @@
#include "pico.h"
#include "hardware/structs/pwm.h"
#include "hardware/regs/dreq.h"
#ifdef __cplusplus
extern "C" {
@ -26,7 +27,7 @@ extern "C" {
*
* The RP2040 PWM block has 8 identical slices. Each slice can drive two PWM output signals, or
* measure the frequency or duty cycle of an input signal. This gives a total of up to 16 controllable
* PWM outputs. All 30 GPIOs can be driven by the PWM block
* PWM outputs. All 30 GPIOs can be driven by the PWM block.
*
* The PWM hardware functions by continuously comparing the input value to a free-running counter. This produces a
* toggling output where the amount of time spent at the high output level is proportional to the input value. The fraction of
@ -116,21 +117,21 @@ static inline void pwm_config_set_phase_correct(pwm_config *c, bool phase_correc
* before passing them on to the PWM counter.
*/
static inline void pwm_config_set_clkdiv(pwm_config *c, float div) {
c->div = (uint32_t)(div * (float)(1u << PWM_CH1_DIV_INT_LSB));
c->div = (uint32_t)(div * (float)(1u << PWM_CH0_DIV_INT_LSB));
}
/** \brief Set PWM clock divider in a PWM configuration
* \ingroup hardware_pwm
*
* \param c PWM configuration struct to modify
* \param div integer value to reduce counting rate by. Must be greater than or equal to 1.
* \param div Integer value to reduce counting rate by. Must be greater than or equal to 1.
*
* If the divide mode is free-running, the PWM counter runs at clk_sys / div.
* Otherwise, the divider reduces the rate of events seen on the B pin input (level or edge)
* before passing them on to the PWM counter.
*/
static inline void pwm_config_set_clkdiv_int(pwm_config *c, uint div) {
c->div = div << PWM_CH1_DIV_INT_LSB;
c->div = div << PWM_CH0_DIV_INT_LSB;
}
/** \brief Set PWM counting mode in a PWM configuration
@ -201,7 +202,7 @@ static inline void pwm_init(uint slice_num, pwm_config *c, bool start) {
/** \brief Get a set of default values for PWM configuration
* \ingroup hardware_pwm
*
* PWM config is free running at system clock speed, no phase correction, wrapping at 0xffff,
* PWM config is free-running at system clock speed, no phase correction, wrapping at 0xffff,
* with standard polarities for channels A and B.
*
* \return Set of default values.
@ -239,7 +240,7 @@ static inline void pwm_set_wrap(uint slice_num, uint16_t wrap) {
/** \brief Set the current PWM counter compare value for one channel
* \ingroup hardware_pwm
*
* Set the value of the PWM counter compare value, for either channel A or channel B
* Set the value of the PWM counter compare value, for either channel A or channel B.
*
* The counter compare register is double-buffered in hardware. This means
* that, when the PWM is running, a write to the counter compare values does
@ -263,7 +264,7 @@ static inline void pwm_set_chan_level(uint slice_num, uint chan, uint16_t level)
/** \brief Set PWM counter compare values
* \ingroup hardware_pwm
*
* Set the value of the PWM counter compare values, A and B
* Set the value of the PWM counter compare values, A and B.
*
* The counter compare register is double-buffered in hardware. This means
* that, when the PWM is running, a write to the counter compare values does
@ -284,7 +285,7 @@ static inline void pwm_set_both_levels(uint slice_num, uint16_t level_a, uint16_
* \ingroup hardware_pwm
*
* Look up the correct slice (0 to 7) and channel (A or B) for a given GPIO, and update the corresponding
* counter-compare field.
* counter compare field.
*
* This PWM slice should already have been configured and set running. Also be careful of multiple GPIOs
* mapping to the same slice and channel (if GPIOs have a difference of 16).
@ -309,7 +310,7 @@ static inline void pwm_set_gpio_level(uint gpio, uint16_t level) {
* Get current value of PWM counter
*
* \param slice_num PWM slice number
* \return Current value of PWM counter
* \return Current value of the PWM counter
*/
static inline uint16_t pwm_get_counter(uint slice_num) {
check_slice_num_param(slice_num);
@ -367,7 +368,7 @@ static inline void pwm_retard_count(uint slice_num) {
/** \brief Set PWM clock divider using an 8:4 fractional value
* \ingroup hardware_pwm
*
* Set the clock divider. Counter increment will be on sysclock divided by this value, taking in to account the gating.
* Set the clock divider. Counter increment will be on sysclock divided by this value, taking into account the gating.
*
* \param slice_num PWM slice number
* \param integer 8 bit integer part of the clock divider
@ -382,7 +383,7 @@ static inline void pwm_set_clkdiv_int_frac(uint slice_num, uint8_t integer, uint
/** \brief Set PWM clock divider
* \ingroup hardware_pwm
*
* Set the clock divider. Counter increment will be on sysclock divided by this value, taking in to account the gating.
* Set the clock divider. Counter increment will be on sysclock divided by this value, taking into account the gating.
*
* \param slice_num PWM slice number
* \param divider Floating point clock divider, 1.f <= value < 256.f
@ -441,8 +442,28 @@ static inline void pwm_set_phase_correct(uint slice_num, bool phase_correct) {
/** \brief Enable/Disable PWM
* \ingroup hardware_pwm
*
* When a PWM is disabled, it halts its counter, and the output pins are left
* high or low depending on exactly when the counter is halted. When
* re-enabled the PWM resumes immediately from where it left off.
*
* If the PWM's output pins need to be low when halted:
*
* - The counter compare can be set to zero whilst the PWM is enabled, and
* then the PWM disabled once both pins are seen to be low
*
* - The GPIO output overrides can be used to force the actual pins low
*
* - The PWM can be run for one cycle (i.e. enabled then immediately disabled)
* with a TOP of 0, count of 0 and counter compare of 0, to force the pins
* low when the PWM has already been halted. The same method can be used
* with a counter compare value of 1 to force a pin high.
*
* Note that, when disabled, the PWM can still be advanced one count at a time
* by pulsing the PH_ADV bit in its CSR. The output pins transition as though
* the PWM were enabled.
*
* \param slice_num PWM slice number
* \param enabled true to enable the specified PWM, false to disable
* \param enabled true to enable the specified PWM, false to disable.
*/
static inline void pwm_set_enabled(uint slice_num, bool enabled) {
check_slice_num_param(slice_num);
@ -461,7 +482,7 @@ static inline void pwm_set_mask_enabled(uint32_t mask) {
/*! \brief Enable PWM instance interrupt
* \ingroup hardware_pwm
*
* Used to enable a single PWM instance interrupt
* Used to enable a single PWM instance interrupt.
*
* \param slice_num PWM block to enable/disable
* \param enabled true to enable, false to disable
@ -492,7 +513,7 @@ static inline void pwm_set_irq_mask_enabled(uint32_t slice_mask, bool enabled) {
}
}
/*! \brief Clear single PWM channel interrupt
/*! \brief Clear a single PWM channel interrupt
* \ingroup hardware_pwm
*
* \param slice_num PWM slice number
@ -519,6 +540,18 @@ static inline void pwm_force_irq(uint slice_num) {
pwm_hw->intf = 1u << slice_num;
}
/*! \brief Return the DREQ to use for pacing transfers to a particular PWM slice
* \ingroup hardware_pwm
*
* \param slice_num PWM slice number
*/
static inline uint pwm_get_dreq(uint slice_num) {
static_assert(DREQ_PWM_WRAP1 == DREQ_PWM_WRAP0 + 1, "");
static_assert(DREQ_PWM_WRAP7 == DREQ_PWM_WRAP0 + 7, "");
check_slice_num_param(slice_num);
return DREQ_PWM_WRAP0 + slice_num;
}
#ifdef __cplusplus
}
#endif

View File

@ -10,6 +10,7 @@
#include "pico.h"
#include "pico/time.h"
#include "hardware/structs/spi.h"
#include "hardware/regs/dreq.h"
// PICO_CONFIG: PARAM_ASSERTIONS_ENABLED_SPI, Enable/disable assertions in the SPI module, type=bool, default=0, group=hardware_spi
#ifndef PARAM_ASSERTIONS_ENABLED_SPI
@ -337,6 +338,19 @@ int spi_write16_blocking(spi_inst_t *spi, const uint16_t *src, size_t len);
*/
int spi_read16_blocking(spi_inst_t *spi, uint16_t repeated_tx_data, uint16_t *dst, size_t len);
/*! \brief Return the DREQ to use for pacing transfers to/from a particular SPI instance
* \ingroup hardware_spi
*
* \param spi SPI instance specifier, either \ref spi0 or \ref spi1
* \param is_tx true for sending data to the SPI instance, false for receiving data from the SPI instance
*/
static inline uint spi_get_dreq(spi_inst_t *spi, bool is_tx) {
static_assert(DREQ_SPI0_RX == DREQ_SPI0_TX + 1, "");
static_assert(DREQ_SPI1_RX == DREQ_SPI1_TX + 1, "");
static_assert(DREQ_SPI1_TX == DREQ_SPI0_TX + 2, "");
return DREQ_SPI0_TX + spi_get_index(spi) * 2 + !is_tx;
}
#ifdef __cplusplus
}
#endif

View File

@ -9,6 +9,7 @@
#include "pico.h"
#include "hardware/structs/uart.h"
#include "hardware/regs/dreq.h"
// PICO_CONFIG: PARAM_ASSERTIONS_ENABLED_UART, Enable/disable assertions in the UART module, type=bool, default=0, group=hardware_uart
#ifndef PARAM_ASSERTIONS_ENABLED_UART
@ -205,12 +206,17 @@ static inline void uart_set_format(uart_inst_t *uart, uint data_bits, uint stop_
* this function.
*
* \param uart UART instance. \ref uart0 or \ref uart1
* \param rx_has_data If true an interrupt will be fired when the RX FIFO contain data.
* \param rx_has_data If true an interrupt will be fired when the RX FIFO contains data.
* \param tx_needs_data If true an interrupt will be fired when the TX FIFO needs data.
*/
static inline void uart_set_irq_enables(uart_inst_t *uart, bool rx_has_data, bool tx_needs_data) {
// Both UARTRXINTR (RX) and UARTRTINTR (RX timeout) interrupts are
// required for rx_has_data. RX asserts when >=4 characters are in the RX
// FIFO (for RXIFLSEL=0). RT asserts when there are >=1 characters and no
// more have been received for 32 bit periods.
uart_get_hw(uart)->imsc = (bool_to_bit(tx_needs_data) << UART_UARTIMSC_TXIM_LSB) |
(bool_to_bit(rx_has_data) << UART_UARTIMSC_RXIM_LSB);
(bool_to_bit(rx_has_data) << UART_UARTIMSC_RXIM_LSB) |
(bool_to_bit(rx_has_data) << UART_UARTIMSC_RTIM_LSB);
if (rx_has_data) {
// Set minimum threshold
hw_write_masked(&uart_get_hw(uart)->ifls, 0 << UART_UARTIFLS_RXIFLSEL_LSB,
@ -321,7 +327,7 @@ static inline void uart_read_blocking(uart_inst_t *uart, uint8_t *dst, size_t le
/*! \brief Write single character to UART for transmission.
* \ingroup hardware_uart
*
* This function will block until all the character has been sent
* This function will block until the entire character has been sent
*
* \param uart UART instance. \ref uart0 or \ref uart1
* \param c The character to send
@ -407,7 +413,7 @@ static inline void uart_set_break(uart_inst_t *uart, bool en) {
*/
void uart_set_translate_crlf(uart_inst_t *uart, bool translate);
/*! \brief Wait for the default UART'S TX fifo to be drained
/*! \brief Wait for the default UART's TX FIFO to be drained
* \ingroup hardware_uart
*/
static inline void uart_default_tx_wait_blocking(void) {
@ -427,6 +433,19 @@ static inline void uart_default_tx_wait_blocking(void) {
*/
bool uart_is_readable_within_us(uart_inst_t *uart, uint32_t us);
/*! \brief Return the DREQ to use for pacing transfers to/from a particular UART instance
* \ingroup hardware_uart
*
* \param uart UART instance. \ref uart0 or \ref uart1
* \param is_tx true for sending data to the UART instance, false for receiving data from the UART instance
*/
static inline uint uart_get_dreq(uart_inst_t *uart, bool is_tx) {
static_assert(DREQ_UART0_RX == DREQ_UART0_TX + 1, "");
static_assert(DREQ_UART1_RX == DREQ_UART1_TX + 1, "");
static_assert(DREQ_UART1_TX == DREQ_UART0_TX + 2, "");
return DREQ_UART0_TX + uart_get_index(uart) * 2 + !is_tx;
}
#ifdef __cplusplus
}
#endif

View File

@ -8,6 +8,7 @@
#define _HARDWARE_WATCHDOG_H
#include "pico.h"
#include "hardware/structs/watchdog.h"
/** \file hardware/watchdog.h
* \defgroup hardware_watchdog hardware_watchdog
@ -66,6 +67,11 @@ void watchdog_update(void);
*
* By default the SDK assumes a 12MHz XOSC and sets the \ref watchdog_start_tick appropriately.
*
* This method sets a marker in the watchdog scratch register 4 that is checked by \ref watchdog_enable_caused_reboot.
* If the device is subsequently reset via a call to watchdog_reboot (including for example by dragging a UF2
* onto the RPI-RP2), then this value will be cleared, and so \ref watchdog_enable_caused_reboot will
* return false.
*
* \param delay_ms Number of milliseconds before watchdog will reboot without watchdog_update being called. Maximum of 0x7fffff, which is approximately 8.3 seconds
* \param pause_on_debug If the watchdog should be paused when the debugger is stepping through code
*/
@ -75,11 +81,30 @@ void watchdog_enable(uint32_t delay_ms, bool pause_on_debug);
* \brief Did the watchdog cause the last reboot?
* \ingroup hardware_watchdog
*
* @return true if the watchdog timer or a watchdog force caused the last reboot
* @return false there has been no watchdog reboot since run has been
* @return true If the watchdog timer or a watchdog force caused the last reboot
* @return false If there has been no watchdog reboot since the last power on reset. A power on reset is typically caused by a power cycle or the run pin (reset button) being toggled.
*/
bool watchdog_caused_reboot(void);
/**
* \brief Did watchdog_enable cause the last reboot?
* \ingroup hardware_watchdog
*
* Perform additional checking along with \ref watchdog_caused_reboot to determine if a watchdog timeout initiated by
* \ref watchdog_enable caused the last reboot.
*
* This method checks for a special value in watchdog scratch register 4 placed there by \ref watchdog_enable.
* This would not be present if a watchdog reset is initiated by \ref watchdog_reboot or by the RP2040 bootrom
* (e.g. dragging a UF2 onto the RPI-RP2 drive).
*
* @return true If the watchdog timer or a watchdog force caused (see \reg watchdog_caused_reboot) the last reboot
* and the watchdog reboot happened after \ref watchdog_enable was called
* @return false If there has been no watchdog reboot since the last power on reset, or the watchdog reboot was not caused
* by a watchdog timeout after \ref watchdog_enable was called.
* A power on reset is typically caused by a power cycle or the run pin (reset button) being toggled.
*/
bool watchdog_enable_caused_reboot(void);
/**
* @brief Returns the number of microseconds before the watchdog will reboot the chip.
* \ingroup hardware_watchdog

View File

@ -49,25 +49,28 @@ void _watchdog_enable(uint32_t delay_ms, bool pause_on_debug) {
hw_clear_bits(&watchdog_hw->ctrl, dbg_bits);
}
if (!delay_ms) delay_ms = 50;
if (!delay_ms) {
hw_set_bits(&watchdog_hw->ctrl, WATCHDOG_CTRL_TRIGGER_BITS);
} else {
// Note, we have x2 here as the watchdog HW currently decrements twice per tick
load_value = delay_ms * 1000 * 2;
// Note, we have x2 here as the watchdog HW currently decrements twice per tick
load_value = delay_ms * 1000 * 2;
if (load_value > 0xffffffu)
load_value = 0xffffffu;
if (load_value > 0xffffffu)
load_value = 0xffffffu;
watchdog_update();
watchdog_update();
hw_set_bits(&watchdog_hw->ctrl, WATCHDOG_CTRL_ENABLE_BITS);
hw_set_bits(&watchdog_hw->ctrl, WATCHDOG_CTRL_ENABLE_BITS);
}
}
// end::watchdog_enable[]
#define WATCHDOG_NON_REBOOT_MAGIC 0x6ab73121
void watchdog_enable(uint32_t delay_ms, bool pause_on_debug) {
// This watchdog enable doesn't reboot so clear scratch register
// with magic word to jump into code
watchdog_hw->scratch[4] = 0;
// update scratch[4] to distinguish from magic used for reboot to specific address, or 0 used to reboot
// into regular flash path
watchdog_hw->scratch[4] = WATCHDOG_NON_REBOOT_MAGIC;
_watchdog_enable(delay_ms, pause_on_debug);
}
@ -96,4 +99,8 @@ void watchdog_reboot(uint32_t pc, uint32_t sp, uint32_t delay_ms) {
bool watchdog_caused_reboot(void) {
// If any reason bits are set this is true
return watchdog_hw->reason;
}
bool watchdog_enable_caused_reboot(void) {
return watchdog_hw->reason && watchdog_hw->scratch[4] == WATCHDOG_NON_REBOOT_MAGIC;
}

View File

@ -13,8 +13,8 @@
#include "hardware/regs/xosc.h"
#include "hardware/xosc.h"
#if XOSC_MHZ < 1 || XOSC_MHZ > 15
#error XOSC_MHZ must be in the range 1-15
#if XOSC_MHZ < 1 || XOSC_MHZ > 50
#error XOSC_MHZ must be in the range 1-50
#endif
#define STARTUP_DELAY (((((XOSC_MHZ * MHZ) / 1000) + 128) / 256) * PICO_XOSC_STARTUP_DELAY_MULTIPLIER)

View File

@ -9,6 +9,8 @@
.thumb
#include "pico/asm_helper.S"
#include "pico/bootrom.h"
__pre_init __aeabi_bits_init, 00010
.macro bits_section name
@ -24,10 +26,10 @@ __pre_init __aeabi_bits_init, 00010
.equ BITS_FUNC_COUNT, 4
.align 4
aeabi_bits_funcs:
.word rom_table_code('P','3') // popcount32
.word rom_table_code('L','3') // clz32
.word rom_table_code('T','3') // ctz32
.word rom_table_code('R','3') // reverse32
.word ROM_FUNC_POPCOUNT32
.word ROM_FUNC_CLZ32
.word ROM_FUNC_CTZ32
.word ROM_FUNC_REVERSE32
aeabi_bits_funcs_end:
.section .text

View File

@ -16,9 +16,7 @@ typedef void *(*rom_table_lookup_fn)(uint16_t *table, uint32_t code);
#define rom_hword_as_ptr(rom_address) (void *)(uintptr_t)(*(uint16_t *)rom_address)
void *rom_func_lookup(uint32_t code) {
rom_table_lookup_fn rom_table_lookup = (rom_table_lookup_fn) rom_hword_as_ptr(0x18);
uint16_t *func_table = (uint16_t *) rom_hword_as_ptr(0x14);
return rom_table_lookup(func_table, code);
return rom_func_lookup_inline(code);
}
void *rom_data_lookup(uint32_t code) {

View File

@ -12,8 +12,60 @@
/** \file bootrom.h
* \defgroup pico_bootrom pico_bootrom
* Access to functions and data in the RP2040 bootrom
*
* This header may be included by assembly code
*/
// ROM FUNCTIONS
#define ROM_FUNC_POPCOUNT32 ROM_TABLE_CODE('P', '3')
#define ROM_FUNC_REVERSE32 ROM_TABLE_CODE('R', '3')
#define ROM_FUNC_CLZ32 ROM_TABLE_CODE('L', '3')
#define ROM_FUNC_CTZ32 ROM_TABLE_CODE('T', '3')
#define ROM_FUNC_MEMSET ROM_TABLE_CODE('M', 'S')
#define ROM_FUNC_MEMSET4 ROM_TABLE_CODE('S', '4')
#define ROM_FUNC_MEMCPY ROM_TABLE_CODE('M', 'C')
#define ROM_FUNC_MEMCPY44 ROM_TABLE_CODE('C', '4')
#define ROM_FUNC_RESET_USB_BOOT ROM_TABLE_CODE('U', 'B')
#define ROM_FUNC_CONNECT_INTERNAL_FLASH ROM_TABLE_CODE('I', 'F')
#define ROM_FUNC_FLASH_EXIT_XIP ROM_TABLE_CODE('E', 'X')
#define ROM_FUNC_FLASH_RANGE_ERASE ROM_TABLE_CODE('R', 'E')
#define ROM_FUNC_FLASH_RANGE_PROGRAM ROM_TABLE_CODE('R', 'P')
#define ROM_FUNC_FLASH_FLUSH_CACHE ROM_TABLE_CODE('F', 'C')
#define ROM_FUNC_FLASH_ENTER_CMD_XIP ROM_TABLE_CODE('C', 'X')
/*! \brief Return a bootrom lookup code based on two ASCII characters
* \ingroup pico_bootrom
*
* These codes are uses to lookup data or function addresses in the bootrom
*
* \param c1 the first character
* \param c2 the second character
* \return the 'code' to use in rom_func_lookup() or rom_data_lookup()
*/
#define ROM_TABLE_CODE(c1, c2) ((c1) | ((c2) << 8))
#ifndef __ASSEMBLER__
// ROM FUNCTION SIGNATURES
typedef uint32_t (*rom_popcount32_fn)(uint32_t);
typedef uint32_t (*rom_reverse32_fn)(uint32_t);
typedef uint32_t (*rom_clz32_fn)(uint32_t);
typedef uint32_t (*rom_ctz32_fn)(uint32_t);
typedef uint8_t *(*rom_memset_fn)(uint8_t *, uint8_t, uint32_t);
typedef uint32_t *(*rom_memset4_fn)(uint32_t *, uint8_t, uint32_t);
typedef uint32_t *(*rom_memcpy_fn)(uint8_t *, const uint8_t *, uint32_t);
typedef uint32_t *(*rom_memcpy44_fn)(uint32_t *, const uint32_t *, uint32_t);
typedef void __attribute__((noreturn)) (*rom_reset_usb_boot_fn)(uint32_t, uint32_t);
typedef rom_reset_usb_boot_fn reset_usb_boot_fn; // kept for backwards compatibility
typedef void (*rom_connect_internal_flash_fn)(void);
typedef void (*rom_flash_exit_xip_fn)(void);
typedef void (*rom_flash_range_erase_fn)(uint32_t, size_t, uint32_t, uint8_t);
typedef void (*rom_flash_range_program_fn)(uint32_t, const uint8_t*, size_t);
typedef void (*rom_flash_flush_cache_fn)(void);
typedef void (*rom_flash_enter_cmd_xip_fn)(void);
#ifdef __cplusplus
extern "C" {
#endif
@ -22,13 +74,13 @@ extern "C" {
* \ingroup pico_bootrom
*
* These codes are uses to lookup data or function addresses in the bootrom
*
*
* \param c1 the first character
* \param c2 the second character
* \return the 'code' to use in rom_func_lookup() or rom_data_lookup()
*/
static inline uint32_t rom_table_code(uint8_t c1, uint8_t c2) {
return (((uint)c2) << 8u) | (uint)c1;
return ROM_TABLE_CODE((uint32_t) c1, (uint32_t) c2);
}
/*!
@ -60,7 +112,24 @@ void *rom_data_lookup(uint32_t code);
*/
bool rom_funcs_lookup(uint32_t *table, unsigned int count);
typedef void __attribute__((noreturn)) (*reset_usb_boot_fn)(uint32_t, uint32_t);
// Bootrom function: rom_table_lookup
// Returns the 32 bit pointer into the ROM if found or NULL otherwise.
typedef void *(*rom_table_lookup_fn)(uint16_t *table, uint32_t code);
// Convert a 16 bit pointer stored at the given rom address into a 32 bit pointer
#define rom_hword_as_ptr(rom_address) (void *)(uintptr_t)(*(uint16_t *)rom_address)
/*!
* \brief Lookup a bootrom function by code. This method is forceably inlined into the caller for FLASH/RAM sensitive code usage
* \ingroup pico_bootrom
* \param code the code
* \return a pointer to the function, or NULL if the code does not match any bootrom function
*/
static __force_inline void *rom_func_lookup_inline(uint32_t code) {
rom_table_lookup_fn rom_table_lookup = (rom_table_lookup_fn) rom_hword_as_ptr(0x18);
uint16_t *func_table = (uint16_t *) rom_hword_as_ptr(0x14);
return rom_table_lookup(func_table, code);
}
/*!
* \brief Reboot the device into BOOTSEL mode
@ -81,7 +150,7 @@ typedef void __attribute__((noreturn)) (*reset_usb_boot_fn)(uint32_t, uint32_t);
*/
static inline void __attribute__((noreturn)) reset_usb_boot(uint32_t usb_activity_gpio_pin_mask,
uint32_t disable_interface_mask) {
reset_usb_boot_fn func = (reset_usb_boot_fn) rom_func_lookup(rom_table_code('U', 'B'));
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);
}
@ -89,4 +158,5 @@ static inline void __attribute__((noreturn)) reset_usb_boot(uint32_t usb_activit
}
#endif
#endif // !__ASSEMBLER__
#endif

View File

@ -43,8 +43,7 @@ static const uint32_t magic_token[] = {
static uint32_t __uninitialized_ram(magic_location)[count_of(magic_token)];
/*! \brief Check for double reset and enter BOOTSEL mode if detected
* \ingroup pico_bootsel_via_double_reset
/* Check for double reset and enter BOOTSEL mode if detected
*
* This function is registered to run automatically before main(). The
* algorithm is:

View File

@ -21,6 +21,7 @@ if (NOT TARGET pico_divider)
target_link_libraries(pico_divider_hardware_explicit INTERFACE
pico_divider_headers
hardware_divider
hardware_regs
)

View File

@ -413,6 +413,7 @@ y64:
lsls r3,#16
orrs r3,r4
str r3,[r7,#SIO_DIV_UDIVIDEND_OFFSET] @ y1=(r0<<16)+(((ui32)y)>>16);
str r2,[r7,#SIO_DIV_UDIVISOR_OFFSET] @ must set divisor again, as we do not save/restore regs at all in IRQs if not dirty
wait_div 1
uxth r4,r0
ldr r3,[r7,#SIO_DIV_REMAINDER_OFFSET] @ r1=y1-q1*x; 0<=r1<x
@ -420,6 +421,7 @@ y64:
lsls r3,#16
orrs r3,r4
str r3,[r7,#SIO_DIV_UDIVIDEND_OFFSET] @ y1=(r0<<16)+(((ui32)y)>>16);
str r2,[r7,#SIO_DIV_UDIVISOR_OFFSET] @ must set divisor again, as we do not save/restore regs at all in IRQs if not dirty
wait_div 3
movs r3,#0
lsls r4,r5,#16 @ quotient=(q0<<32)+(q1<<16)+q2

View File

@ -83,7 +83,7 @@ __check_nan_d2:
.macro table_tail_call SF_TABLE_OFFSET
push {r3, r4}
#if PICO_DOUBLE_SUPPORT_ROM_V1
#if PICO_DOUBLE_SUPPORT_ROM_V1 && PICO_RP2040_B0_SUPPORTED
#ifndef NDEBUG
movs r3, #0
mov ip, r3
@ -99,12 +99,12 @@ __check_nan_d2:
push {r3, r4}
ldr r3, =sd_table
ldr r3, [r3, #\SF_TABLE_OFFSET]
#if PICO_DOUBLE_SUPPORT_ROM_V1
#if PICO_DOUBLE_SUPPORT_ROM_V1 && PICO_RP2040_B0_SUPPORTED
mov ip, pc
#endif
str r3, [sp, #4]
pop {r3, pc}
#if PICO_DOUBLE_SUPPORT_ROM_V1
#if PICO_DOUBLE_SUPPORT_ROM_V1 && PICO_RP2040_B0_SUPPORTED
.byte \SF_TABLE_OFFSET, 0xdf
.word \shim
#endif
@ -733,7 +733,7 @@ sincos_shim_bootstrap:
push {r2, r3, r4}
movs r3, #0x13
ldrb r3, [r3]
#if PICO_DOUBLE_SUPPORT_ROM_V1
#if PICO_DOUBLE_SUPPORT_ROM_V1 && PICO_RP2040_B0_SUPPORTED
cmp r3, #1
bne 1f
ldr r3, =dsincos_shim

View File

@ -12,16 +12,18 @@
// IT IS ***NOT*** SAFE TO CALL THESE FUNCTION POINTERS FROM ARBITRARY CODE
uint32_t sd_table[SF_TABLE_V2_SIZE / 2];
#if !PICO_DOUBLE_SUPPORT_ROM_V1
#if !(PICO_DOUBLE_SUPPORT_ROM_V1 && PICO_RP2040_B0_SUPPORTED)
static __attribute__((noreturn)) void missing_double_func_shim(void) {
panic("missing double function");
}
#endif
extern void double_table_shim_on_use_helper(void);
void __attribute__((weak)) *sf_clz_func;
void __aeabi_double_init(void) {
int rom_version = rp2040_rom_version();
#if PICO_DOUBLE_SUPPORT_ROM_V1
#if PICO_DOUBLE_SUPPORT_ROM_V1 && PICO_RP2040_B0_SUPPORTED
if (rom_version == 1) {
// this is a little tricky.. we only want to pull in a shim if the corresponding function
@ -63,4 +65,6 @@ void __aeabi_double_init(void) {
// we use the unused entry for SINCOS
sd_table[SF_TABLE_V3_FSINCOS / 4] = (uintptr_t) double_table_shim_on_use_helper;
}
sf_clz_func = rom_func_lookup(ROM_FUNC_CLZ32);
}

View File

@ -41,11 +41,25 @@ typedef int64_t i64;
#define DUNPACK(x,e,m) e=((x)>>52)&0x7ff,m=((x)&0x000fffffffffffffULL)|0x0010000000000000ULL
#define DUNPACKS(x,s,e,m) s=((x)>>63),DUNPACK((x),(e),(m))
_Pragma("GCC diagnostic push")
_Pragma("GCC diagnostic ignored \"-Wstrict-aliasing\"")
typedef union {
double d;
ui64 ix;
} double_ui64;
static inline double ui642double(ui64 ix) {
double_ui64 tmp;
tmp.ix = ix;
return tmp.d;
}
static inline ui64 double2ui64(double d) {
double_ui64 tmp;
tmp.d = d;
return tmp.ix;
}
static inline bool disnan(double x) {
ui64 ix=*(ui64*)&x;
ui64 ix= double2ui64(x);
// checks the top bit of the low 32 bit of the NAN, but it I think that is ok
return ((uint32_t)(ix >> 31)) > 0xffe00000u;
}
@ -59,17 +73,17 @@ static inline bool disnan(double x) {
#endif
static inline int dgetsignexp(double x) {
ui64 ix=*(ui64*)&x;
ui64 ix=double2ui64(x);
return (ix>>52)&0xfff;
}
static inline int dgetexp(double x) {
ui64 ix=*(ui64*)&x;
ui64 ix=double2ui64(x);
return (ix>>52)&0x7ff;
}
static inline double dldexp(double x,int de) {
ui64 ix=*(ui64*)&x,iy;
ui64 ix=double2ui64(x),iy;
int e;
e=dgetexp(x);
if(e==0||e==0x7ff) return x;
@ -77,7 +91,7 @@ static inline double dldexp(double x,int de) {
if(e<=0) iy=ix&0x8000000000000000ULL; // signed zero for underflow
else if(e>=0x7ff) iy=(ix&0x8000000000000000ULL)|0x7ff0000000000000ULL; // signed infinity on overflow
else iy=ix+((ui64)de<<52);
return *(double*)&iy;
return ui642double(iy);
}
double WRAPPER_FUNC(ldexp)(double x, int de) {
@ -87,9 +101,9 @@ double WRAPPER_FUNC(ldexp)(double x, int de) {
static inline double dcopysign(double x,double y) {
ui64 ix=*(ui64*)&x,iy=*(ui64*)&y;
ui64 ix=double2ui64(x),iy=double2ui64(y);
ix=((ix&0x7fffffffffffffffULL)|(iy&0x8000000000000000ULL));
return *(double*)&ix;
return ui642double(ix);
}
double WRAPPER_FUNC(copysign)(double x, double y) {
@ -104,7 +118,7 @@ static inline int dispinf(double x) { return dgetsignexp(x)==0x7ff; }
static inline int disminf(double x) { return dgetsignexp(x)==0xfff; }
static inline int disint(double x) {
ui64 ix=*(ui64*)&x,m;
ui64 ix=double2ui64(x),m;
int e=dgetexp(x);
if(e==0) return 1; // 0 is an integer
e-=0x3ff; // remove exponent bias
@ -117,7 +131,7 @@ static inline int disint(double x) {
}
static inline int disoddint(double x) {
ui64 ix=*(ui64*)&x,m;
ui64 ix=double2ui64(x),m;
int e=dgetexp(x);
e-=0x3ff; // remove exponent bias
if(e<0) return 0; // |x|<1; 0 is not odd
@ -130,24 +144,24 @@ static inline int disoddint(double x) {
}
static inline int disstrictneg(double x) {
ui64 ix=*(ui64*)&x;
ui64 ix=double2ui64(x);
if(diszero(x)) return 0;
return ix>>63;
}
static inline int disneg(double x) {
ui64 ix=*(ui64*)&x;
ui64 ix=double2ui64(x);
return ix>>63;
}
static inline double dneg(double x) {
ui64 ix=*(ui64*)&x;
ui64 ix=double2ui64(x);
ix^=0x8000000000000000ULL;
return *(double*)&ix;
return ui642double(ix);
}
static inline int dispo2(double x) {
ui64 ix=*(ui64*)&x;
ui64 ix=double2ui64(x);
if(diszero(x)) return 0;
if(disinf(x)) return 0;
ix&=0x000fffffffffffffULL;
@ -164,33 +178,33 @@ static inline double dnan_or(double x) {
double WRAPPER_FUNC(trunc)(double x) {
check_nan_d1(x);
ui64 ix=*(ui64*)&x,m;
ui64 ix=double2ui64(x),m;
int e=dgetexp(x);
e-=0x3ff; // remove exponent bias
if(e<0) { // |x|<1
ix&=0x8000000000000000ULL;
return *(double*)&ix;
return ui642double(ix);
}
e=52-e; // bit position in mantissa with significance 1
if(e<=0) return x; // |x| large, so must be an integer
m=(1ULL<<e)-1; // mask for bits of significance <1
ix&=~m;
return *(double*)&ix;
return ui642double(ix);
}
double WRAPPER_FUNC(round)(double x) {
check_nan_d1(x);
ui64 ix=*(ui64*)&x,m;
ui64 ix=double2ui64(x),m;
int e=dgetexp(x);
e-=0x3ff; // remove exponent bias
if(e<-1) { // |x|<0.5
ix&=0x8000000000000000ULL;
return *(double*)&ix;
return ui642double(ix);
}
if(e==-1) { // 0.5<=|x|<1
ix&=0x8000000000000000ULL;
ix|=0x3ff0000000000000ULL; // ±1
return *(double*)&ix;
return ui642double(ix);
}
e=52-e; // bit position in mantissa with significance 1, <=52
if(e<=0) return x; // |x| large, so must be an integer
@ -198,16 +212,16 @@ double WRAPPER_FUNC(round)(double x) {
ix+=m;
m=m+m-1; // mask for bits of significance <1
ix&=~m;
return *(double*)&ix;
return ui642double(ix);
}
double WRAPPER_FUNC(floor)(double x) {
check_nan_d1(x);
ui64 ix=*(ui64*)&x,m;
ui64 ix=double2ui64(x),m;
int e=dgetexp(x);
if(e==0) { // x==0
ix&=0x8000000000000000ULL;
return *(double*)&ix;
return ui642double(ix);
}
e-=0x3ff; // remove exponent bias
if(e<0) { // |x|<1, not zero
@ -219,16 +233,16 @@ double WRAPPER_FUNC(floor)(double x) {
m=(1ULL<<e)-1; // mask for bit of significance <1
if(disneg(x)) ix+=m; // add 1-ε to magnitude if negative
ix&=~m; // truncate
return *(double*)&ix;
return ui642double(ix);
}
double WRAPPER_FUNC(ceil)(double x) {
check_nan_d1(x);
ui64 ix=*(ui64*)&x,m;
ui64 ix=double2ui64(x),m;
int e=dgetexp(x);
if(e==0) { // x==0
ix&=0x8000000000000000ULL;
return *(double*)&ix;
return ui642double(ix);
}
e-=0x3ff; // remove exponent bias
if(e<0) { // |x|<1, not zero
@ -240,7 +254,7 @@ double WRAPPER_FUNC(ceil)(double x) {
m=(1ULL<<e)-1; // mask for bit of significance <1
if(!disneg(x)) ix+=m; // add 1-ε to magnitude if positive
ix&=~m; // truncate
return *(double*)&ix;
return ui642double(ix);
}
double WRAPPER_FUNC(asin)(double x) {
@ -549,7 +563,7 @@ static i64 drem_0(i64 mx,i64 my,int e,int*pquo) {
double WRAPPER_FUNC(fmod)(double x,double y) {
check_nan_d2(x, y);
ui64 ix=*(ui64*)&x,iy=*(ui64*)&y;
ui64 ix=double2ui64(x),iy=double2ui64(y);
int sx,ex,ey;
i64 mx,my;
DUNPACKS(ix,sx,ex,mx);
@ -568,7 +582,7 @@ double WRAPPER_FUNC(fmod)(double x,double y) {
double WRAPPER_FUNC(remquo)(double x,double y,int*quo) {
check_nan_d2(x, y);
ui64 ix=*(ui64*)&x,iy=*(ui64*)&y;
ui64 ix=double2ui64(x),iy=double2ui64(y);
int sx,sy,ex,ey,q;
i64 mx,my;
DUNPACKS(ix,sx,ex,mx);
@ -609,5 +623,4 @@ double WRAPPER_FUNC(drem)(double x,double y) { check_nan_d2(x, y); return remquo
double WRAPPER_FUNC(remainder)(double x,double y) { check_nan_d2(x, y); return remquo(x,y,0); }
_Pragma("GCC diagnostic pop") // strict-aliasing
_Pragma("GCC diagnostic pop") // conversion

View File

@ -63,7 +63,7 @@ regular_func double_table_shim_on_use_helper
str r0, [sp, #12]
pop {r0-r2, pc}
#if PICO_DOUBLE_SUPPORT_ROM_V1
#if PICO_DOUBLE_SUPPORT_ROM_V1 && PICO_RP2040_B0_SUPPORTED
// Note that the V1 ROM has no double support, so this is basically the identical
// library, and shim inter-function calls do not bother to redirect back thru the
// wrapper functions
@ -1218,11 +1218,6 @@ double_section dcordic_rot_step
mov r9,r3
bx r14
ret_dzero:
movs r0,#0
movs r1,#0
bx r14
@ convert packed double in r0:r1 to signed/unsigned 32/64-bit integer/fixed-point value in r0:r1 [with r2 places after point], with rounding towards -Inf
@ fixed-point versions only work with reasonable values in r2 because of the way dunpacks works
@ -1264,7 +1259,7 @@ regular_func double2fix64_shim
eors r1,r1,r0 @ generate extreme fixed-point values
pop {r15}
double_section double2uint64_shim
double_section double2uint64_shim
regular_func double2uint64_shim
movs r2,#0 @ and fall through
regular_func double2ufix64_shim
@ -1288,7 +1283,12 @@ d2fix:
asrs r3,r1,#31
ldr r4, =d2fix_a
bx r4
ret_dzero:
movs r0,#0
movs r1,#0
bx r14
.weak d2fix_a // weak because it exists in float code too
regular_func d2fix_a
@ here
@ -2181,4 +2181,4 @@ dtab_exp:
.word 0x40000000, 0x00000000 @ log 1+2^-32 Q62
#endif
#endif

View File

@ -22,16 +22,21 @@ static void hw_enumeration_fix_force_ls_j(void);
static void hw_enumeration_fix_finish(void);
void rp2040_usb_device_enumeration_fix(void) {
// After coming out of reset, the hardware expects 800us of LS_J (linestate J) time
// before it will move to the connected state. However on a hub that broadcasts packets
// for other devices this isn't the case. The plan here is to wait for the end of the bus
// reset, force an LS_J for 1ms and then switch control back to the USB phy. Unfortunately
// this requires us to use GPIO15 as there is no other way to force the input path.
// We only need to force DP as DM can be left at zero. It will be gated off by GPIO
// logic if it isn't func selected.
#if PICO_RP2040_B0_SUPPORTED || PICO_RP2040_B1_SUPPORTED
// Actually check for B0/B1 h/w
if (rp2040_chip_version() == 1) {
// After coming out of reset, the hardware expects 800us of LS_J (linestate J) time
// before it will move to the connected state. However on a hub that broadcasts packets
// for other devices this isn't the case. The plan here is to wait for the end of the bus
// reset, force an LS_J for 1ms and then switch control back to the USB phy. Unfortunately
// this requires us to use GPIO15 as there is no other way to force the input path.
// We only need to force DP as DM can be left at zero. It will be gated off by GPIO
// logic if it isn't func selected.
// Wait SE0 phase will call force ls_j phase which will call finish phase
hw_enumeration_fix_wait_se0();
// Wait SE0 phase will call force ls_j phase which will call finish phase
hw_enumeration_fix_wait_se0();
}
#endif
}
static inline uint8_t hw_line_state(void) {

View File

@ -80,7 +80,7 @@ __check_nan_f2:
#endif
.macro table_tail_call SF_TABLE_OFFSET
#if PICO_FLOAT_SUPPORT_ROM_V1
#if PICO_FLOAT_SUPPORT_ROM_V1 && PICO_RP2040_B0_SUPPORTED
#ifndef NDEBUG
movs r3, #0
mov ip, r3
@ -94,11 +94,11 @@ __check_nan_f2:
.macro shimmable_table_tail_call SF_TABLE_OFFSET shim
ldr r3, =sf_table
ldr r3, [r3, #\SF_TABLE_OFFSET]
#if PICO_FLOAT_SUPPORT_ROM_V1
#if PICO_FLOAT_SUPPORT_ROM_V1 && PICO_RP2040_B0_SUPPORTED
mov ip, pc
#endif
bx r3
#if PICO_FLOAT_SUPPORT_ROM_V1
#if PICO_FLOAT_SUPPORT_ROM_V1 && PICO_RP2040_B0_SUPPORTED
.byte \SF_TABLE_OFFSET, 0xdf
.word \shim
#endif
@ -584,13 +584,13 @@ wrapper_func __aeabi_f2d
float_wrapper_section srqtf
wrapper_func_f1 sqrtf
#if PICO_FLOAT_SUPPORT_ROM_V1
#if PICO_FLOAT_SUPPORT_ROM_V1 && PICO_RP2040_B0_SUPPORTED
// check for negative
asrs r1, r0, #23
bmi 1f
#endif
table_tail_call SF_TABLE_FSQRT
#if PICO_FLOAT_SUPPORT_ROM_V1
#if PICO_FLOAT_SUPPORT_ROM_V1 && PICO_RP2040_B0_SUPPORTED
1:
mvns r0, r1
cmp r0, #255

View File

@ -11,9 +11,9 @@
// NOTE THIS FUNCTION TABLE IS NOT PUBLIC OR NECESSARILY COMPLETE...
// IT IS ***NOT*** SAFE TO CALL THESE FUNCTION POINTERS FROM ARBITRARY CODE
uint32_t sf_table[SF_TABLE_V2_SIZE / 2];
void *sf_clz_func;
void __attribute__((weak)) *sf_clz_func;
#if !PICO_FLOAT_SUPPORT_ROM_V1
#if !(PICO_FLOAT_SUPPORT_ROM_V1 && PICO_RP2040_B0_SUPPORTED)
static __attribute__((noreturn)) void missing_float_func_shim(void) {
panic("");
}
@ -22,7 +22,7 @@ static __attribute__((noreturn)) void missing_float_func_shim(void) {
void __aeabi_float_init(void) {
int rom_version = rp2040_rom_version();
void *rom_table = rom_data_lookup(rom_table_code('S', 'F'));
#if PICO_FLOAT_SUPPORT_ROM_V1
#if PICO_FLOAT_SUPPORT_ROM_V1 && PICO_RP2040_B0_SUPPORTED
if (rom_version == 1) {
memcpy(&sf_table, rom_table, SF_TABLE_V1_SIZE);
extern void float_table_shim_on_use_helper(void);
@ -66,5 +66,5 @@ void __aeabi_float_init(void) {
assert(*((uint8_t *)(rom_table-2)) * 4 >= SF_TABLE_V2_SIZE);
memcpy(&sf_table, rom_table, SF_TABLE_V2_SIZE);
}
sf_clz_func = rom_func_lookup(rom_table_code('L', '3'));
sf_clz_func = rom_func_lookup(ROM_FUNC_CLZ32);
}

View File

@ -39,11 +39,25 @@ typedef int32_t i32;
#define FUNPACK(x,e,m) e=((x)>>23)&0xff,m=((x)&0x007fffff)|0x00800000
#define FUNPACKS(x,s,e,m) s=((x)>>31),FUNPACK((x),(e),(m))
_Pragma("GCC diagnostic push")
_Pragma("GCC diagnostic ignored \"-Wstrict-aliasing\"")
typedef union {
float f;
ui32 ix;
} float_ui32;
static inline float ui322float(ui32 ix) {
float_ui32 tmp;
tmp.ix = ix;
return tmp.f;
}
static inline ui32 float2ui32(float f) {
float_ui32 tmp;
tmp.f = f;
return tmp.ix;
}
static inline bool fisnan(float x) {
ui32 ix=*(ui32*)&x;
ui32 ix=float2ui32(x);
return ix * 2 > 0xff000000u;
}
@ -56,17 +70,17 @@ static inline bool fisnan(float x) {
#endif
static inline int fgetsignexp(float x) {
ui32 ix=*(ui32*)&x;
ui32 ix=float2ui32(x);
return (ix>>23)&0x1ff;
}
static inline int fgetexp(float x) {
ui32 ix=*(ui32*)&x;
ui32 ix=float2ui32(x);
return (ix>>23)&0xff;
}
static inline float fldexp(float x,int de) {
ui32 ix=*(ui32*)&x,iy;
ui32 ix=float2ui32(x),iy;
int e;
e=fgetexp(x);
if(e==0||e==0xff) return x;
@ -74,7 +88,7 @@ static inline float fldexp(float x,int de) {
if(e<=0) iy=ix&0x80000000; // signed zero for underflow
else if(e>=0xff) iy=(ix&0x80000000)|0x7f800000ULL; // signed infinity on overflow
else iy=ix+((ui32)de<<23);
return *(float*)&iy;
return ui322float(iy);
}
float WRAPPER_FUNC(ldexpf)(float x, int de) {
@ -83,9 +97,9 @@ float WRAPPER_FUNC(ldexpf)(float x, int de) {
}
static inline float fcopysign(float x,float y) {
ui32 ix=*(ui32*)&x,iy=*(ui32*)&y;
ui32 ix=float2ui32(x),iy=float2ui32(y);
ix=((ix&0x7fffffff)|(iy&0x80000000));
return *(float*)&ix;
return ui322float(ix);
}
float WRAPPER_FUNC(copysignf)(float x, float y) {
@ -101,7 +115,7 @@ static inline int fispinf(float x) { return fgetsignexp(x)==0xff; }
static inline int fisminf(float x) { return fgetsignexp(x)==0x1ff; }
static inline int fisint(float x) {
ui32 ix=*(ui32*)&x,m;
ui32 ix=float2ui32(x),m;
int e=fgetexp(x);
if(e==0) return 1; // 0 is an integer
e-=0x7f; // remove exponent bias
@ -114,7 +128,7 @@ static inline int fisint(float x) {
}
static inline int fisoddint(float x) {
ui32 ix=*(ui32*)&x,m;
ui32 ix=float2ui32(x),m;
int e=fgetexp(x);
e-=0x7f; // remove exponent bias
if(e<0) return 0; // |x|<1; 0 is not odd
@ -127,24 +141,24 @@ static inline int fisoddint(float x) {
}
static inline int fisstrictneg(float x) {
ui32 ix=*(ui32*)&x;
ui32 ix=float2ui32(x);
if(fiszero(x)) return 0;
return ix>>31;
}
static inline int fisneg(float x) {
ui32 ix=*(ui32*)&x;
ui32 ix=float2ui32(x);
return ix>>31;
}
static inline float fneg(float x) {
ui32 ix=*(ui32*)&x;
ui32 ix=float2ui32(x);
ix^=0x80000000;
return *(float*)&ix;
return ui322float(ix);
}
static inline int fispo2(float x) {
ui32 ix=*(ui32*)&x;
ui32 ix=float2ui32(x);
if(fiszero(x)) return 0;
if(fisinf(x)) return 0;
ix&=0x007fffff;
@ -161,33 +175,33 @@ static inline float fnan_or(float x) {
float WRAPPER_FUNC(truncf)(float x) {
check_nan_f1(x);
ui32 ix=*(ui32*)&x,m;
ui32 ix=float2ui32(x),m;
int e=fgetexp(x);
e-=0x7f; // remove exponent bias
if(e<0) { // |x|<1
ix&=0x80000000;
return *(float*)&ix;
return ui322float(ix);
}
e=23-e; // bit position in mantissa with significance 1
if(e<=0) return x; // |x| large, so must be an integer
m=(1<<e)-1; // mask for bits of significance <1
ix&=~m;
return *(float*)&ix;
return ui322float(ix);
}
float WRAPPER_FUNC(roundf)(float x) {
check_nan_f1(x);
ui32 ix=*(ui32*)&x,m;
ui32 ix=float2ui32(x),m;
int e=fgetexp(x);
e-=0x7f; // remove exponent bias
if(e<-1) { // |x|<0.5
ix&=0x80000000;
return *(float*)&ix;
return ui322float(ix);
}
if(e==-1) { // 0.5<=|x|<1
ix&=0x80000000;
ix|=0x3f800000; // ±1
return *(float*)&ix;
return ui322float(ix);
}
e=23-e; // bit position in mantissa with significance 1, <=23
if(e<=0) return x; // |x| large, so must be an integer
@ -195,16 +209,16 @@ float WRAPPER_FUNC(roundf)(float x) {
ix+=m;
m=m+m-1; // mask for bits of significance <1
ix&=~m;
return *(float*)&ix;
return ui322float(ix);
}
float WRAPPER_FUNC(floorf)(float x) {
check_nan_f1(x);
ui32 ix=*(ui32*)&x,m;
ui32 ix=float2ui32(x),m;
int e=fgetexp(x);
if(e==0) { // x==0
ix&=0x80000000;
return *(float*)&ix;
return ui322float(ix);
}
e-=0x7f; // remove exponent bias
if(e<0) { // |x|<1, not zero
@ -216,16 +230,16 @@ float WRAPPER_FUNC(floorf)(float x) {
m=(1<<e)-1; // mask for bit of significance <1
if(fisneg(x)) ix+=m; // add 1-ε to magnitude if negative
ix&=~m; // truncate
return *(float*)&ix;
return ui322float(ix);
}
float WRAPPER_FUNC(ceilf)(float x) {
check_nan_f1(x);
ui32 ix=*(ui32*)&x,m;
ui32 ix=float2ui32(x),m;
int e=fgetexp(x);
if(e==0) { // x==0
ix&=0x80000000;
return *(float*)&ix;
return ui322float(ix);
}
e-=0x7f; // remove exponent bias
if(e<0) { // |x|<1, not zero
@ -237,7 +251,7 @@ float WRAPPER_FUNC(ceilf)(float x) {
m=(1<<e)-1; // mask for bit of significance <1
if(!fisneg(x)) ix+=m; // add 1-ε to magnitude if positive
ix&=~m; // truncate
return *(float*)&ix;
return ui322float(ix);
}
float WRAPPER_FUNC(asinf)(float x) {
@ -505,7 +519,7 @@ static i32 frem_0(i32 mx,i32 my,int e,int*pquo) {
float WRAPPER_FUNC(fmodf)(float x,float y) {
check_nan_f2(x,y);
ui32 ix=*(ui32*)&x,iy=*(ui32*)&y;
ui32 ix=float2ui32(x),iy=float2ui32(y);
int sx,ex,ey;
i32 mx,my;
FUNPACKS(ix,sx,ex,mx);
@ -526,7 +540,7 @@ float WRAPPER_FUNC(fmodf)(float x,float y) {
float WRAPPER_FUNC(remquof)(float x,float y,int*quo) {
check_nan_f2(x,y);
ui32 ix=*(ui32*)&x,iy=*(ui32*)&y;
ui32 ix=float2ui32(x),iy=float2ui32(y);
int sx,sy,ex,ey,q;
i32 mx,my;
FUNPACKS(ix,sx,ex,mx);
@ -567,5 +581,4 @@ float WRAPPER_FUNC(dremf)(float x,float y) { check_nan_f2(x,y); return remquof(x
float WRAPPER_FUNC(remainderf)(float x,float y) { check_nan_f2(x,y); return remquof(x,y,0); }
_Pragma("GCC diagnostic pop") // strict-aliasing
_Pragma("GCC diagnostic pop") // conversion

View File

@ -6,7 +6,7 @@
#include "pico/asm_helper.S"
#if PICO_FLOAT_SUPPORT_ROM_V1
#if PICO_FLOAT_SUPPORT_ROM_V1 && PICO_RP2040_B0_SUPPORTED
.syntax unified
.cpu cortex-m0plus
.thumb

View File

@ -9,6 +9,7 @@
.thumb
#include "pico/asm_helper.S"
#include "pico/bootrom.h"
__pre_init __aeabi_mem_init, 00001
@ -34,10 +35,10 @@ __pre_init __aeabi_mem_init, 00001
.align 2
aeabi_mem_funcs:
.word rom_table_code('M','S')
.word rom_table_code('M','C')
.word rom_table_code('S','4')
.word rom_table_code('C','4')
.word ROM_FUNC_MEMSET
.word ROM_FUNC_MEMCPY
.word ROM_FUNC_MEMSET4
.word ROM_FUNC_MEMCPY44
aeabi_mem_funcs_end:
.section .text
@ -58,20 +59,20 @@ regular_func __aeabi_mem_init
mem_section aeabi_memset_memcpy
wrapper_func __aeabi_memset
// args are backwards
eors r0, r1
eors r1, r0
eors r0, r1
// 2nd/3rd args are reversed
eors r2, r1
eors r1, r2
eors r2, r1
ldr r3, =aeabi_mem_funcs
ldr r3, [r3, #MEMSET]
bx r3
wrapper_func __aeabi_memset4
wrapper_func __aeabi_memset8
// args are backwards
eors r0, r1
eors r1, r0
eors r0, r1
// 2nd/3rd args are reversed
eors r2, r1
eors r1, r2
eors r2, r1
ldr r3, =aeabi_mem_funcs
ldr r3, [r3, #MEMSET4]
bx r3

View File

@ -17,7 +17,7 @@ extern "C" {
/** \file multicore.h
* \defgroup pico_multicore pico_multicore
* Adds support for running code on the second processor core (core1)
* Adds support for running code on the second processor core (core 1)
*
* \subsection multicore_example Example
* \addtogroup pico_multicore
@ -33,95 +33,155 @@ extern "C" {
#endif
#endif
/*! \brief Reset Core 1
/*! \brief Reset core 1
* \ingroup pico_multicore
*
* This function can be used to reset core 1 into its initial state (ready for launching code against via \ref multicore_launch_core1 and similar methods)
*
* \note this function should only be called from core 0
*/
void multicore_reset_core1(void);
/*! \brief Run code on core 1
* \ingroup pico_multicore
*
* Reset core1 and enter the given function on core 1 using the default core 1 stack (below core 0 stack)
* Wake up (a previously reset) core 1 and enter the given function on core 1 using the default core 1 stack (below core 0 stack).
*
* \param entry Function entry point, this function should not return.
* core 1 must previously have been reset either as a result of a system reset or by calling \ref multicore_reset_core1
*
* core 1 will use the same vector table as core 0
*
* \param entry Function entry point
* \see multicore_reset_core1
*/
void multicore_launch_core1(void (*entry)(void));
/*! \brief Launch code on core 1 with stack
* \ingroup pico_multicore
*
* Reset core1 and enter the given function on core 1 using the passed stack for core 1
* Wake up (a previously reset) core 1 and enter the given function on core 1 using the passed stack for core 1
*
* core 1 must previously have been reset either as a result of a system reset or by calling \ref multicore_reset_core1
*
* core 1 will use the same vector table as core 0
*
* \param entry Function entry point
* \param stack_bottom The bottom (lowest address) of the stack
* \param stack_size_bytes The size of the stack in bytes (must be a multiple of 4)
* \see multicore_reset_core1
*/
void multicore_launch_core1_with_stack(void (*entry)(void), uint32_t *stack_bottom, size_t stack_size_bytes);
/*! \brief Launch code on core 1 with no stack protection
* \ingroup pico_multicore
*
* Reset core1 and enter the given function using the passed sp as the initial stack pointer.
* This is a bare bones functions that does not provide a stack guard even if USE_STACK_GUARDS is defined
* Wake up (a previously reset) core 1 and start it executing with a specific entry point, stack pointer
* and vector table.
*
* This is a low level function that does not provide a stack guard even if USE_STACK_GUARDS is defined
*
* core 1 must previously have been reset either as a result of a system reset or by calling \ref multicore_reset_core1
*
* \param entry Function entry point
* \param sp Pointer to the top of the core 1 stack
* \param vector_table address of the vector table to use for core 1
* \see multicore_reset_core1
*/
void multicore_launch_core1_raw(void (*entry)(void), uint32_t *sp, uint32_t vector_table);
/*!
* \defgroup multicore_fifo fifo
* \ingroup pico_multicore
* \brief Functions for inter-core FIFO
* \brief Functions for the inter-core FIFOs
*
* The RP2040 contains two FIFOs for passing data, messages or ordered events between the two cores. Each FIFO is 32 bits
* wide, and 8 entries deep. One of the FIFOs can only be written by core 0, and read by core 1. The other can only be written
* by core 1, and read by core 0.
*
* \note The inter-core FIFOs are a very precious resource and are frequently used for SDK functionality (e.g. during
* core 1 launch or by the \ref multicore_lockout functions). Additionally they are often required for the exclusive use
* of an RTOS (e.g. FreeRTOS SMP). For these reasons it is suggested that you do not use the FIFO for your own purposes
* unless none of the above concerns apply; the majority of cases for transferring data between cores can be eqaully
* well handled by using a \ref queue
*/
/*! \brief Check the read FIFO to see if there is data waiting
/*! \brief Check the read FIFO to see if there is data available (sent by the other core)
* \ingroup multicore_fifo
*
* See the note in the \ref multicore_fifo section for considerations regarding use of the inter-core FIFOs
*
* \return true if the FIFO has data in it, false otherwise
*/
static inline bool multicore_fifo_rvalid(void) {
return !!(sio_hw->fifo_st & SIO_FIFO_ST_VLD_BITS);
}
/*! \brief Check the write FIFO to see if it is ready for more data
/*! \brief Check the write FIFO to see if it has space for more data
* \ingroup multicore_fifo
*
* See the note in the \ref multicore_fifo section for considerations regarding use of the inter-core FIFOs
*
* @return true if the FIFO has room for more data, false otherwise
*/
static inline bool multicore_fifo_wready(void) {
return !!(sio_hw->fifo_st & SIO_FIFO_ST_RDY_BITS);
}
/*! \brief Push data on to the FIFO.
/*! \brief Push data on to the write FIFO (data to the other core).
* \ingroup multicore_fifo
*
* This function will block until there is space for the data to be sent.
* Use multicore_fifo_wready() to check if it is possible to write to the
* FIFO if you don't want to block.
*
* See the note in the \ref multicore_fifo section for considerations regarding use of the inter-core FIFOs
*
* \param data A 32 bit value to push on to the FIFO
*/
void multicore_fifo_push_blocking(uint32_t data);
/*! \brief Push data on to the write FIFO (data to the other core) with timeout.
* \ingroup multicore_fifo
*
* This function will block until there is space for the data to be sent
* or the timeout is reached
*
* \param data A 32 bit value to push on to the FIFO
* \param timeout_us the timeout in microseconds
* \return true if the data was pushed, false if the timeout occurred before data could be pushed
*/
bool multicore_fifo_push_timeout_us(uint32_t data, uint64_t timeout_us);
/*! \brief Pop data from the FIFO.
/*! \brief Pop data from the read FIFO (data from the other core).
* \ingroup multicore_fifo
*
* This function will block until there is data ready to be read
* Use multicore_fifo_rvalid() to check if data is ready to be read if you don't
* want to block.
*
* \return 32 bit unsigned data from the FIFO.
* See the note in the \ref multicore_fifo section for considerations regarding use of the inter-core FIFOs
*
* \return 32 bit data from the read FIFO.
*/
uint32_t multicore_fifo_pop_blocking(void);
bool multicore_fifo_pop_timeout_us(uint64_t timeout_us, uint32_t *out);
/*! \brief Flush any data in the incoming FIFO
/*! \brief Pop data from the read FIFO (data from the other core) with timeout.
* \ingroup multicore_fifo
*
* This function will block until there is data ready to be read or the timeout is reached
*
* See the note in the \ref multicore_fifo section for considerations regarding use of the inter-core FIFOs
*
* \param timeout_us the timeout in microseconds
* \param out the location to store the popped data if available
* \return true if the data was popped and a value copied into `out`, false if the timeout occurred before data could be popped
*/
bool multicore_fifo_pop_timeout_us(uint64_t timeout_us, uint32_t *out);
/*! \brief Discard any data in the read FIFO
* \ingroup multicore_fifo
*
* See the note in the \ref multicore_fifo section for considerations regarding use of the inter-core FIFOs
*/
static inline void multicore_fifo_drain(void) {
while (multicore_fifo_rvalid())
@ -133,38 +193,117 @@ static inline void multicore_fifo_drain(void) {
*
* Note that this only clears an interrupt that was caused by the ROE or WOF flags.
* To clear the VLD flag you need to use one of the 'pop' or 'drain' functions.
*
* See the note in the \ref multicore_fifo section for considerations regarding use of the inter-core FIFOs
*
* \see multicore_fifo_get_status
*/
static inline void multicore_fifo_clear_irq(void) {
// Write any value to clear the error flags
sio_hw->fifo_st = 0xff;
}
/*! \brief Get FIFO status
/*! \brief Get FIFO statuses
* \ingroup multicore_fifo
*
* \return The status as a bitfield
* \return The statuses as a bitfield
*
* Bit | Description
* ----|------------
* 3 | Sticky flag indicating the RX FIFO was read when empty. This read was ignored by the FIFO.
* 2 | Sticky flag indicating the TX FIFO was written when full. This write was ignored by the FIFO.
* 3 | Sticky flag indicating the RX FIFO was read when empty (ROE). This read was ignored by the FIFO.
* 2 | Sticky flag indicating the TX FIFO was written when full (WOF). This write was ignored by the FIFO.
* 1 | Value is 1 if this cores TX FIFO is not full (i.e. if FIFO_WR is ready for more data)
* 0 | Value is 1 if this cores RX FIFO is not empty (i.e. if FIFO_RD is valid)
*
* See the note in the \ref multicore_fifo section for considerations regarding use of the inter-core FIFOs
*
*/
static inline uint32_t multicore_fifo_get_status(void) {
return sio_hw->fifo_st;
}
// call this from the lockout victim thread
/*!
* \defgroup multicore_lockout lockout
* \ingroup pico_multicore
* \brief Functions to enable one core to force the other core to pause execution in a known state.
*
* Sometimes it is useful to enter a critical section on both cores at once. On a single
* core system a critical section can trivially be entered by disabling interrupts, however on a multi-core
* system that is not sufficient, and unless the other core is polling in some way, then it will need to be interrupted
* in order to cooperatively enter a blocked state.
*
* These "lockout" functions use the inter core FIFOs to cause an interrupt on one core from the other, and manage
* waiting for the other core to enter the "locked out" state.
*
* The usage is that the "victim" core ... i.e the core that can be "locked out" by the other core calls
* \ref multicore_lockout_victim_init to hook the FIFO interrupt. Note that either or both cores may do this.
*
* \note When "locked out" the victim core is paused (it is actually executing a tight loop with code in RAM) and has interrupts disabled.
* This makes the lockout functions suitable for use by code that wants to write to flash (at which point no code may be executing
* from flash)
*
* The core which wishes to lockout the other core calls \ref multicore_lockout_start_blocking or
* \ref multicore_lockout_start_timeout_us to interrupt the other "victim" core and wait for it to be in a
* "locked out" state. Once the lockout is no longer needed it calls \ref multicore_lockout_end_blocking or
* \ref multicore_lockout_end_timeout_us to release the lockout and wait for confirmation.
*
* \note Because multicore lockout uses the intercore FIFOs, the FIFOs <b>cannot</b> be used for any other purpose
*/
/*! \brief Initialize the current core such that it can be a "victim" of lockout (i.e. forced to pause in a known state by the other core)
* \ingroup multicore_lockout
*
* This code hooks the intercore FIFO IRQ, and the FIFO may not be used for any other purpose after this.
*/
void multicore_lockout_victim_init(void);
// start locking out the other core (it will be
bool multicore_lockout_start_timeout_us(uint64_t timeout_us);
/*! \brief Request the other core to pause in a known state and wait for it to do so
* \ingroup multicore_lockout
*
* The other (victim) core must have previously executed \ref multicore_lockout_victim_init()
*
* \note multicore_lockout_start_ functions are not nestable, and must be paired with a call to a corresponding
* \ref multicore_lockout_end_blocking
*/
void multicore_lockout_start_blocking(void);
bool multicore_lockout_end_timeout_us(uint64_t timeout_us);
/*! \brief Request the other core to pause in a known state and wait up to a time limit for it to do so
* \ingroup multicore_lockout
*
* The other core must have previously executed \ref multicore_lockout_victim_init()
*
* \note multicore_lockout_start_ functions are not nestable, and must be paired with a call to a corresponding
* \ref multicore_lockout_end_blocking
*
* \param timeout_us the timeout in microseconds
* \return true if the other core entered the locked out state within the timeout, false otherwise
*/
bool multicore_lockout_start_timeout_us(uint64_t timeout_us);
/*! \brief Release the other core from a locked out state amd wait for it to acknowledge
* \ingroup multicore_lockout
*
* \note The other core must previously have been "locked out" by calling a `multicore_lockout_start_` function
* from this core
*/
void multicore_lockout_end_blocking(void);
/*! \brief Release the other core from a locked out state amd wait up to a time limit for it to acknowledge
* \ingroup multicore_lockout
*
* The other core must previously have been "locked out" by calling a `multicore_lockout_start_` function
* from this core
*
* \note be very careful using small timeout values, as a timeout here will leave the "lockout" functionality
* in a bad state. It is probably preferable to use \ref multicore_lockout_end_blocking anyway as if you have
* already waited for the victim core to enter the lockout state, then the victim core will be ready to exit
* the lockout state very quickly.
*
* \param timeout_us the timeout in microseconds
* \return true if the other core successfully exited locked out state within the timeout, false otherwise
*/
bool multicore_lockout_end_timeout_us(uint64_t timeout_us);
#ifdef __cplusplus
}
#endif

View File

@ -126,22 +126,32 @@ void multicore_launch_core1(void (*entry)(void)) {
}
void multicore_launch_core1_raw(void (*entry)(void), uint32_t *sp, uint32_t vector_table) {
const uint32_t cmd_sequence[] = {0, 0, 1, (uintptr_t) vector_table, (uintptr_t) sp, (uintptr_t) entry};
// Allow for the fact that the caller may have already enabled the FIFO IRQ for their
// own purposes (expecting FIFO content after core 1 is launched). We must disable
// the IRQ during the handshake, then restore afterwards.
bool enabled = irq_is_enabled(SIO_IRQ_PROC0);
irq_set_enabled(SIO_IRQ_PROC0, false);
// Values to be sent in order over the FIFO from core 0 to core 1
//
// vector_table is value for VTOR register
// sp is initial stack pointer (SP)
// entry is the initial program counter (PC) (don't forget to set the thumb bit!)
const uint32_t cmd_sequence[] =
{0, 0, 1, (uintptr_t) vector_table, (uintptr_t) sp, (uintptr_t) entry};
uint seq = 0;
do {
uint cmd = cmd_sequence[seq];
// we drain before sending a 0
// Always drain the READ FIFO (from core 1) before sending a 0
if (!cmd) {
multicore_fifo_drain();
__sev(); // core 1 may be waiting for fifo space
// Execute a SEV as core 1 may be waiting for FIFO space via WFE
__sev();
}
multicore_fifo_push_blocking(cmd);
uint32_t response = multicore_fifo_pop_blocking();
// move to next state on correct response otherwise start over
// Move to next state on correct response (echo-d value) otherwise start over
seq = cmd == response ? seq + 1 : 0;
} while (seq < count_of(cmd_sequence));
@ -176,7 +186,7 @@ static void __isr __not_in_flash_func(multicore_lockout_handler)(void) {
static void check_lockout_mutex_init(void) {
// use known available lock - we only need it briefly
uint32_t save = hw_claim_lock();
if (!mutex_is_initialzed(&lockout_mutex)) {
if (!mutex_is_initialized(&lockout_mutex)) {
mutex_init(&lockout_mutex);
}
hw_claim_unlock(save);
@ -237,7 +247,7 @@ void multicore_lockout_start_blocking() {
}
static bool multicore_lockout_end_block_until(absolute_time_t until) {
assert(mutex_is_initialzed(&lockout_mutex));
assert(mutex_is_initialized(&lockout_mutex));
if (!mutex_enter_block_until(&lockout_mutex, until)) {
return false;
}

View File

@ -4,13 +4,7 @@
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "hardware/platform_defs.h"
#include "pico/config.h"
#define WRAPPER_FUNC_NAME(x) __wrap_##x
#define SECTION_NAME(x) .text.##x
#define RAM_SECTION_NAME(x) .time_critical.##x
#define rom_table_code(c1, c2) ((c1) | ((c2) << 8))
#include "pico.h"
// do not put align in here as it is used mid function sometimes
.macro regular_func x

View File

@ -7,91 +7,304 @@
#ifndef _PICO_PLATFORM_H_
#define _PICO_PLATFORM_H_
/** \file platform.h
* \defgroup pico_platform pico_platform
*
* Macros and definitions (and functions when included by non assembly code) for the RP2 family device / architecture
* to provide a common abstraction over low level compiler / platform specifics.
*
* This header may be included by assembly code
*/
#include "hardware/platform_defs.h"
// Marker for builds targeting the RP2040
#define PICO_RP2040 1
// PICO_CONFIG: PICO_STACK_SIZE, Stack Size, min=0x100, default=0x800, advanced=true, group=pico_platform
#ifndef PICO_STACK_SIZE
#define PICO_STACK_SIZE _u(0x800)
#endif
// PICO_CONFIG: PICO_HEAP_SIZE, Heap size to reserve, min=0x100, default=0x800, advanced=true, group=pico_platform
#ifndef PICO_HEAP_SIZE
#define PICO_HEAP_SIZE _u(0x800)
#endif
// PICO_CONFIG: PICO_NO_RAM_VECTOR_TABLE, Enable/disable the RAM vector table, type=bool, default=0, advanced=true, group=pico_platform
#ifndef PICO_NO_RAM_VECTOR_TABLE
#define PICO_NO_RAM_VECTOR_TABLE 0
#endif
// PICO_CONFIG: PICO_RP2040_B0_SUPPORTED, Whether to include any specific software support for RP2040 B0 revision, type=bool, default=1, advanced=true, group=pico_platform
#ifndef PICO_RP2040_B0_SUPPORTED
#define PICO_RP2040_B0_SUPPORTED 1
#endif
// PICO_CONFIG: PICO_FLOAT_SUPPORT_ROM_V1, Include float support code for RP2040 B0 when that chip revision is supported , type=bool, default=1, advanced=true, group=pico_platform
#ifndef PICO_FLOAT_SUPPORT_ROM_V1
#define PICO_FLOAT_SUPPORT_ROM_V1 1
#endif
// PICO_CONFIG: PICO_DOUBLE_SUPPORT_ROM_V1, Include double support code for RP2040 B0 when that chip revision is supported , type=bool, default=1, advanced=true, group=pico_platform
#ifndef PICO_DOUBLE_SUPPORT_ROM_V1
#define PICO_DOUBLE_SUPPORT_ROM_V1 1
#endif
// PICO_CONFIG: PICO_RP2040_B1_SUPPORTED, Whether to include any specific software support for RP2040 B1 revision, type=bool, default=1, advanced=true, group=pico_platform
#ifndef PICO_RP2040_B1_SUPPORTED
#define PICO_RP2040_B1_SUPPORTED 1
#endif
// PICO_CONFIG: PICO_RP2040_B2_SUPPORTED, Whether to include any specific software support for RP2040 B2 revision, type=bool, default=1, advanced=true, group=pico_platform
#ifndef PICO_RP2040_B2_SUPPORTED
#define PICO_RP2040_B2_SUPPORTED 1
#endif
// --- remainder of file is not included by assembly code ---
#ifndef __ASSEMBLER__
#include <sys/cdefs.h>
#include "pico/types.h"
#include "hardware/platform_defs.h"
#ifdef __cplusplus
extern "C" {
#endif
/** \file platform.h
* \defgroup pico_platform pico_platform
* Compiler definitions for the selected PICO_PLATFORM
*/
/*! \brief Marker for an interrupt handler
* \ingroup pico_platform
* For example an IRQ handler function called my_interrupt_handler:
*
* void __isr my_interrupt_handler(void) {
*/
#define __isr
// Section naming macros
/*! \brief Section attribute macro for placement in RAM after the `.data` section
* \ingroup pico_platform
*
* For example a 400 element `uint32_t` array placed after the .data section
*
* uint32_t __after_data("my_group_name") a_big_array[400];
*
* The section attribute is `.after_data.<group>`
*
* \param group a string suffix to use in the section name to distinguish groups that can be linker
* garbage-collected independently
*/
#define __after_data(group) __attribute__((section(".after_data." group)))
/*! \brief Section attribute macro for placement not in flash (i.e in RAM)
* \ingroup pico_platform
*
* For example a 3 element `uint32_t` array placed in RAM (even though it is `static const`)
*
* static const uint32_t __not_in_flash("my_group_name") an_array[3];
*
* The section attribute is `.time_critical.<group>`
*
* \param group a string suffix to use in the section name to distinguish groups that can be linker
* garbage-collected independently
*/
#define __not_in_flash(group) __attribute__((section(".time_critical." group)))
/*! \brief Section attribute macro for placement in the SRAM bank 4 (known as "scratch X")
* \ingroup pico_platform
*
* Scratch X is commonly used for critical data and functions accessed only by one core (when only
* one core is accessing the RAM bank, there is no opportunity for stalls)
*
* For example a `uint32_t` variable placed in "scratch X"
*
* uint32_t __scratch_x("my_group_name") foo = 23;
*
* The section attribute is `.scratch_x.<group>`
*
* \param group a string suffix to use in the section name to distinguish groups that can be linker
* garbage-collected independently
*/
#define __scratch_x(group) __attribute__((section(".scratch_x." group)))
/*! \brief Section attribute macro for placement in the SRAM bank 5 (known as "scratch Y")
* \ingroup pico_platform
*
* Scratch Y is commonly used for critical data and functions accessed only by one core (when only
* one core is accessing the RAM bank, there is no opportunity for stalls)
*
* For example a `uint32_t` variable placed in "scratch Y"
*
* uint32_t __scratch_y("my_group_name") foo = 23;
*
* The section attribute is `.scratch_y.<group>`
*
* \param group a string suffix to use in the section name to distinguish groups that can be linker
* garbage-collected independently
*/
#define __scratch_y(group) __attribute__((section(".scratch_y." group)))
/*! \brief Section attribute macro for data that is to be left uninitialized
* \ingroup pico_platform
*
* Data marked this way will retain its value across a reset (normally uninitialized data - in the .bss
* section) is initialized to zero during runtime initialization
*
* For example a `uint32_t` foo that will retain its value if the program is restarted by reset.
*
* uint32_t __uninitialized_ram("my_group_name") foo;
*
* The section attribute is `.uninitialized_ram.<group>`
*
* \param group a string suffix to use in the section name to distinguish groups that can be linker
* garbage-collected independently
*/
#define __uninitialized_ram(group) __attribute__((section(".uninitialized_ram." #group))) group
// For use with PICO_COPY_TO_RAM:
/*! \brief Section attribute macro for placement in flash even in a COPY_TO_RAM binary
* \ingroup pico_platform
*
* For example a `uint32_t` variable explicitly placed in flash (it will hard fault if you attempt to write it!)
*
* uint32_t __in_flash("my_group_name") foo = 23;
*
* The section attribute is `.flashdata.<group>`
*
* \param group a string suffix to use in the section name to distinguish groups that can be linker
* garbage-collected independently
*/
#define __in_flash(group) __attribute__((section(".flashdata" group)))
/**
/*! \brief Indicates a function should not be stored in flash
* \ingroup pico_platform
*
* Decorates a function name, such that the function will execute from RAM (assuming it is not inlined
* into a flash function by the compiler)
*
* For example a function called my_func taking an int parameter:
*
* void __not_in_flash_func(my_func)(int some_arg) {
*
* The function is placed in the `.time_critical.<func_name>` linker section
*
* \see __no_inline_not_in_flash_func
*/
#define __not_in_flash_func(func_name) __not_in_flash(__STRING(func_name)) func_name
/**
* Historical synonym for __not_in_flash_func()
/*! \brief Indicates a function is time/latency critical and should not run from flash
* \ingroup pico_platform
*
* Decorates a function name, such that the function will execute from RAM (assuming it is not inlined
* into a flash function by the compiler) to avoid possible flash latency. Currently this macro is identical
* in implementation to `__not_in_flash_func`, however the semantics are distinct and a `__time_critical_func`
* may in the future be treated more specially to reduce the overhead when calling such function from a flash
* function.
*
* For example a function called my_func taking an int parameter:
*
* void __time_critical(my_func)(int some_arg) {
*
* The function is placed in the `.time_critical.<func_name>` linker section
*
* \see __not_in_flash_func
*/
#define __time_critical_func(func_name) __not_in_flash_func(func_name)
/**
/*! \brief Indicate a function should not be stored in flash and should not be inlined
* \ingroup pico_platform
*
* Decorates a function name, such that the function will execute from RAM, explicitly marking it as
* noinline to prevent it being inlined into a flash function by the compiler
*
* For example a function called my_func taking an int parameter:
*
* void __no_inline_not_in_flash_func(my_func)(int some_arg) {
*
* The function is placed in the `.time_critical.<func_name>` linker section
*/
#define __no_inline_not_in_flash_func(func_name) __noinline __not_in_flash_func(func_name)
#define __packed_aligned __packed __aligned(4)
#if defined(__GNUC__) && __GNUC__ < 7
/*! \brief Attribute to force inlining of a function regardless of optimization level
* \ingroup pico_platform
*
* For example my_function here will always be inlined:
*
* int __force_inline my_function(int x) {
*
*/
#if defined(__GNUC__) && __GNUC__ <= 7
#define __force_inline inline __always_inline
#else
#define __force_inline __always_inline
#endif
/*! \brief Macro to determine the number of elements in an array
* \ingroup pico_platform
*/
#ifndef count_of
#define count_of(a) (sizeof(a)/sizeof((a)[0]))
#endif
/*! \brief Macro to return the maximum of two comparable values
* \ingroup pico_platform
*/
#ifndef MAX
#define MAX(a, b) ((a)>(b)?(a):(b))
#endif
/*! \brief Macro to return the minimum of two comparable values
* \ingroup pico_platform
*/
#ifndef MIN
#define MIN(a, b) ((b)>(a)?(a):(b))
#endif
/**
* Execute a breakpoint instruction
/*! \brief Execute a breakpoint instruction
* \ingroup pico_platform
*/
static inline void __breakpoint(void) {
__asm__("bkpt #0");
}
/**
* Ensure that the compiler does not move memory access across this method call
/*! \brief Ensure that the compiler does not move memory access across this method call
* \ingroup pico_platform
*
* For example in the following code:
*
* *some_memory_location = var_a;
* __compiler_memory_barrier();
* uint32_t var_b = *some_other_memory_location
*
* The compiler will not move the load from `some_other_memory_location` above the memory barrier (which it otherwise
* might - even above the memory store!)
*/
__force_inline static void __compiler_memory_barrier(void) {
__asm__ volatile ("" : : : "memory");
}
// return a 32 bit handle for a raw ptr; DMA chaining for example embeds pointers in 32 bit values
// which of course does not work if we're running the code natively on a 64 bit platforms. Therefore
// we provide this macro which allows that code to provide a 64->32 bit mapping in host mode
/*! \brief Macro for converting memory addresses to 32 bit addresses suitable for DMA
* \ingroup pico_platform
*
* This is just a cast to `uintptr_t` on the RP2040, however you may want to use this when developing code
* that also runs in "host" mode. If the host mode is 64 bit and you are embedding data pointers
* in other data (e.g. DMA chaining), then there is a need in "host" mode to convert a 64 bit native
* pointer to a 32 bit value for storage, which can be done using this macro.
*/
#define host_safe_hw_ptr(x) ((uintptr_t)(x))
#define native_safe_hw_ptr(x) host_safe_hw_ptr(x)
/**
* Panic (see panic()) with the message "Unsupported".
/*! \brief Panics with the message "Unsupported"
* \ingroup pico_platform
* \see panic
*/
void __attribute__((noreturn)) panic_unsupported(void);
/**
* Panic with a message. An attempt is made to output the message to all registered STDOUT drivers
/*! \brief Displays a panic message and halts execution
* \ingroup pico_platform
*
* An attempt is made to output the message to all registered STDOUT drivers
* after which this method executes a BKPT instruction.
*
* @param fmt format string (printf-like)
@ -110,36 +323,34 @@ static inline bool running_on_fpga(void) {return false;}
bool running_on_fpga(void);
#endif
/**
* @return the RP2040 chip revision number
/*! \brief Returns the RP2040 chip revision number
* \ingroup pico_platform
* @return the RP2040 chip revision number (1 for B0/B1, 2 for B2)
*/
uint8_t rp2040_chip_version(void);
/**
* @return the RP2040 rom version number
/*! \brief Returns the RP2040 rom version number
* \ingroup pico_platform
* @return the RP2040 rom version number (1 for RP2040-B0, 2 for RP2040-B1, 3 for RP2040-B2)
*/
static inline uint8_t rp2040_rom_version(void) {
return *(uint8_t*)0x13;
}
/**
* Empty function intended to be called by any tight hardware polling loop. using this ubiquitously
/*! \brief No-op function for the body of tight loops
* \ingroup pico_platform
*
* Np-op function intended to be called by any tight hardware polling loop. Using this ubiquitously
* makes it much easier to find tight loops, but also in the future \#ifdef-ed support for lockup
* debugging might be added
*/
static inline void tight_loop_contents(void) {}
static __force_inline void tight_loop_contents(void) {}
/**
* Helper macro for making chain DMA code portable to PICO_PLATFORM=host. The problem here is
* that embedded pointers in the data are only 32 bit, which is a problem if the host
* system is 64 bit. This macro is zero cost on the actual device, but in host mode
* it provides a 64->32 bit mapping
*/
#define native_safe_hw_ptr(x) ((uintptr_t)(x))
/**
* Multiplies a by b using multiply instruction using the ARM mul instruction regardless of values;
* i.e. this is a 1 cycle operation.
/*! \brief Multiply two integers using an assembly `MUL` instruction
* \ingroup pico_platform
*
* This multiplies a by b using multiply instruction using the ARM mul instruction regardless of values (the compiler
* might otherwise choose to perform shifts/adds), i.e. this is a 1 cycle operation.
*
* \param a the first operand
* \param b the second operand
@ -150,10 +361,14 @@ __force_inline static int32_t __mul_instruction(int32_t a, int32_t b) {
return a;
}
/**
* Efficiently Multiplies value a by possibly constant value b.
/*! \brief multiply two integer values using the fastest method possible
* \ingroup pico_platform
*
* Efficiently multiplies value a by possibly constant value b.
*
* If b is known to be constant and not zero or a power of 2, then a mul instruction is used rather than gcc's default
* which is often a slow combination of shifts and adds
* which is often a slow combination of shifts and adds. If b is a power of 2 then a single shift is of course preferable
* and will be used
*
* \param a the first operand
* \param b the second operand
@ -163,18 +378,34 @@ __force_inline static int32_t __mul_instruction(int32_t a, int32_t b) {
(__builtin_popcount(b) >= 2 ? __mul_instruction(a,b) : (a)*(b)), \
(a)*(b))
#define WRAPPER_FUNC(x) __wrap_ ## x
#define REAL_FUNC(x) __real_ ## x
/*! \brief Utility macro to assert two types are equivalent.
* \ingroup pico_platform
*
* This macro can be useful in other macros along with `typeof` to assert that two parameters are of equivalent type
* (or that a single parameter is of an expected type)
*/
#define __check_type_compatible(type_a, type_b) static_assert(__builtin_types_compatible_p(type_a, type_b), __STRING(type_a) " is not compatible with " __STRING(type_b));
/**
* Get the current exception level on this core
/*! \brief Get the current exception level on this core
* \ingroup pico_platform
*
* \return the exception number if the CPU is handling an exception, or 0 otherwise
*/
uint __get_current_exception(void);
#define WRAPPER_FUNC(x) __wrap_ ## x
#define REAL_FUNC(x) __real_ ## x
#ifdef __cplusplus
}
#endif
#else // __ASSEMBLER__
#define WRAPPER_FUNC_NAME(x) __wrap_##x
#define SECTION_NAME(x) .text.##x
#define RAM_SECTION_NAME(x) .time_critical.##x
#endif // !__ASSEMBLER__
#endif

View File

@ -20,16 +20,18 @@
#include "pico/mutex.h"
#include "pico/time.h"
#if LIB_PICO_PRINTF_PICO
#include "pico/printf.h"
#else
#define weak_raw_printf printf
#define weak_raw_vprintf vprintf
#endif
#if PICO_ENTER_USB_BOOT_ON_EXIT
#include "pico/bootrom.h"
#endif
#ifndef PICO_NO_RAM_VECTOR_TABLE
#define PICO_NO_RAM_VECTOR_TABLE 0
#endif
extern char __StackLimit; /* Set by linker. */
uint32_t __attribute__((section(".ram_vector_table"))) ram_vector_table[48];
@ -113,15 +115,27 @@ void runtime_init(void) {
hw_clear_alias(padsbank0_hw)->io[28] = hw_clear_alias(padsbank0_hw)->io[29] = PADS_BANK0_GPIO0_IE_BITS;
#endif
extern mutex_t __mutex_array_start;
extern mutex_t __mutex_array_end;
// this is an array of either mutex_t or recursive_mutex_t (i.e. not necessarily the same size)
// however each starts with a lock_core_t, and the spin_lock is initialized to address 1 for a recursive
// spinlock and 0 for a regular one.
// the first function pointer, not the address of it.
for (mutex_t *m = &__mutex_array_start; m < &__mutex_array_end; m++) {
if (m->recursion_state) {
recursive_mutex_init(m);
static_assert(!(sizeof(mutex_t)&3), "");
static_assert(!(sizeof(recursive_mutex_t)&3), "");
static_assert(!offsetof(mutex_t, core), "");
static_assert(!offsetof(recursive_mutex_t, core), "");
extern lock_core_t __mutex_array_start;
extern lock_core_t __mutex_array_end;
for (lock_core_t *l = &__mutex_array_start; l < &__mutex_array_end; ) {
if (l->spin_lock) {
assert(1 == (uintptr_t)l->spin_lock); // indicator for a recursive mutex
recursive_mutex_t *rm = (recursive_mutex_t *)l;
recursive_mutex_init(rm);
l = &rm[1].core; // next
} else {
mutex_t *m = (mutex_t *)l;
mutex_init(m);
l = &m[1].core; // next
}
}
@ -230,7 +244,7 @@ extern void __attribute__((noreturn)) __printflike(1, 0) PICO_PANIC_FUNCTION(__u
// Use a forwarding method here as it is a little simpler than renaming the symbol as it is used from assembler
void __attribute__((naked, noreturn)) __printflike(1, 0) panic(__unused const char *fmt, ...) {
// if you get an undefined reference here, you didn't define your PICO_PANIC_FUNCTION!
asm (
__asm (
"push {lr}\n"
#if !PICO_PANIC_FUNCTION_EMPTY
"bl " __XSTRING(PICO_PANIC_FUNCTION) "\n"

View File

@ -79,6 +79,10 @@ if (NOT TARGET pico_standard_link)
# boot_stage2 will be linked if PICO_NO_FLASH would be defined to 0
target_link_libraries(pico_standard_link INTERFACE $<$<NOT:$<IF:$<STREQUAL:$<TARGET_PROPERTY:PICO_TARGET_BINARY_TYPE>,no_flash>,1,$<AND:$<BOOL:${PICO_NO_FLASH}>,$<STREQUAL:,$<TARGET_PROPERTY:PICO_TARGET_BINARY_TYPE>>>>>:$<IF:$<BOOL:$<TARGET_PROPERTY:PICO_TARGET_BOOT_STAGE2>>,$<TARGET_PROPERTY:PICO_TARGET_BOOT_STAGE2>,bs2_default>_library>)
# PICO_CMAKE_CONFIG: PICO_USE_DEFAULT_MAX_PAGE_SIZE, Don't shrink linker max page to 4096, type=bool, default=0, advanced=true, group=pico_standard_link
if (NOT PICO_USE_DEFAULT_MAX_PAGE_SIZE)
target_link_options(pico_standard_link INTERFACE "LINKER:-z,max-page-size=4096")
endif()
# done in compiler now
#target_link_options(pico_standard_link INTERFACE "LINKER:--build-id=none")

View File

@ -4,12 +4,11 @@
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "pico.h"
#include "hardware/regs/m0plus.h"
#include "hardware/platform_defs.h"
#include "hardware/regs/addressmap.h"
#include "hardware/regs/sio.h"
#include "pico/binary_info/defs.h"
#include "pico/config.h"
#ifdef NDEBUG
#ifndef COLLAPSE_IRQS

View File

@ -49,6 +49,9 @@ typedef struct stdio_driver stdio_driver_t;
* Call this method once you have set up your clocks to enable the stdio support for UART, USB
* and semihosting based on the presence of the respective libraries in the binary.
*
* When stdio_usb is configured, this method can be optionally made to block, waiting for a connection
* via the variables specified in \ref stdio_usb_init (i.e. \ref PICO_STDIO_USB_CONNECT_WAIT_TIMEOUT_MS)
*
* \see stdio_uart, stdio_usb, stdio_semihosting
*/
void stdio_init_all(void);
@ -74,7 +77,7 @@ int getchar_timeout_us(uint32_t timeout_us);
/*! \brief Adds or removes a driver from the list of active drivers used for input/output
* \ingroup pico_stdio
*
* \note this method should always be called on an initialized driver
* \note this method should always be called on an initialized driver and is not re-entrant
* \param driver the driver
* \param enabled true to add, false to remove
*/
@ -100,6 +103,16 @@ void stdio_filter_driver(stdio_driver_t *driver);
*/
void stdio_set_translate_crlf(stdio_driver_t *driver, bool translate);
/*! \brief putchar variant that skips any CR/LF conversion if enabled
* \ingroup pico_stdio
*/
int putchar_raw(int c);
/*! \brief puts variant that skips any CR/LF conversion if enabled
* \ingroup pico_stdio
*/
int puts_raw(const char *s);
#ifdef __cplusplus
}
#endif

View File

@ -10,7 +10,9 @@
#include "pico.h"
#include "pico/mutex.h"
#if LIB_PICO_PRINTF_PICO
#include "pico/printf.h"
#endif
#include "pico/stdio.h"
#include "pico/stdio/driver.h"
#include "pico/time.h"
@ -53,12 +55,15 @@ void stdout_serialize_end(void) {
}
#else
static bool print_serialize_begin(void) {
static bool stdout_serialize_begin(void) {
return true;
}
static void print_serialize_end(void) {
static void stdout_serialize_end(void) {
}
#endif
static void stdio_out_chars_no_crlf(stdio_driver_t *driver, const char *s, int len) {
driver->out_chars(s, len);
}
static void stdio_out_chars_crlf(stdio_driver_t *driver, const char *s, int len) {
#if PICO_STDIO_ENABLE_CRLF_SUPPORT
@ -89,7 +94,7 @@ static void stdio_out_chars_crlf(stdio_driver_t *driver, const char *s, int len)
#endif
}
static bool stdio_put_string(const char *s, int len, bool newline) {
static bool stdio_put_string(const char *s, int len, bool newline, bool no_cr) {
bool serialized = stdout_serialize_begin();
if (!serialized) {
#if PICO_STDIO_IGNORE_NESTED_STDOUT
@ -97,13 +102,14 @@ static bool stdio_put_string(const char *s, int len, bool newline) {
#endif
}
if (len == -1) len = (int)strlen(s);
void (*out_func)(stdio_driver_t *, const char *, int) = no_cr ? stdio_out_chars_no_crlf : stdio_out_chars_crlf;
for (stdio_driver_t *driver = drivers; driver; driver = driver->next) {
if (!driver->out_chars) continue;
if (filter && filter != driver) continue;
stdio_out_chars_crlf(driver, s, len);
out_func(driver, s, len);
if (newline) {
const char c = '\n';
stdio_out_chars_crlf(driver, &c, 1);
out_func(driver, &c, 1);
}
}
if (serialized) {
@ -134,13 +140,26 @@ static int stdio_get_until(char *buf, int len, absolute_time_t until) {
int WRAPPER_FUNC(putchar)(int c) {
char cc = (char)c;
stdio_put_string(&cc, 1, false);
stdio_put_string(&cc, 1, false, false);
return c;
}
int WRAPPER_FUNC(puts)(const char *s) {
int len = (int)strlen(s);
stdio_put_string(s, len, true);
stdio_put_string(s, len, true, false);
stdio_flush();
return len;
}
int putchar_raw(int c) {
char cc = (char)c;
stdio_put_string(&cc, 1, false, true);
return c;
}
int puts_raw(const char *s) {
int len = (int)strlen(s);
stdio_put_string(s, len, true, true);
stdio_flush();
return len;
}
@ -154,7 +173,7 @@ int _read(int handle, char *buffer, int length) {
int _write(int handle, char *buffer, int length) {
if (handle == 1) {
stdio_put_string(buffer, length, false);
stdio_put_string(buffer, length, false, false);
return length;
}
return -1;
@ -243,7 +262,7 @@ int __printflike(1, 0) WRAPPER_FUNC(printf)(const char* format, ...)
return ret;
}
void stdio_init_all() {
void stdio_init_all(void) {
// todo add explicit custom, or registered although you can call stdio_enable_driver explicitly anyway
// These are well known ones
#if LIB_PICO_STDIO_UART

View File

@ -18,7 +18,7 @@
// );
//}
static void __attribute__((naked)) semihosting_putc(char c) {
static void __attribute__((naked)) semihosting_putc(__unused const char *c) {
__asm (
"mov r1, r0\n"
@ -30,8 +30,8 @@ static void __attribute__((naked)) semihosting_putc(char c) {
static void stdio_semihosting_out_chars(const char *buf, int length) {
for (uint i = 0; i <length; i++) {
semihosting_putc(buf[i]);
for (int i = 0; i < length; i++) {
semihosting_putc(&buf[i]);
}
}

View File

@ -14,5 +14,6 @@ if (TARGET tinyusb_device_unmarked)
pico_stdio
pico_time
pico_unique_id
pico_usb_reset_interface_headers
)
endif()

View File

@ -54,6 +54,16 @@
#define PICO_STDIO_USB_RESET_MAGIC_BAUD_RATE 1200
#endif
// PICO_CONFIG: PICO_STDIO_USB_CONNECT_WAIT_TIMEOUT_MS, Maximum number of milliseconds to wait during initialization for a CDC connection from the host (negative means indefinite) during initialization, default=0, group=pico_stdio_usb
#ifndef PICO_STDIO_USB_CONNECT_WAIT_TIMEOUT_MS
#define PICO_STDIO_USB_CONNECT_WAIT_TIMEOUT_MS 0
#endif
// PICO_CONFIG: PICO_STDIO_USB_POST_CONNECT_WAIT_DELAY_MS, Number of extra milliseconds to wait when using PICO_STDIO_USB_CONNECT_WAIT_TIMEOUT_MS after a host CDC connection is detected (some host terminals seem to sometimes lose transmissions sent right after connection), default=50, group=pico_stdio_usb
#ifndef PICO_STDIO_USB_POST_CONNECT_WAIT_DELAY_MS
#define PICO_STDIO_USB_POST_CONNECT_WAIT_DELAY_MS 50
#endif
// PICO_CONFIG: PICO_STDIO_USB_RESET_BOOTSEL_ACTIVITY_LED, Optionally define a pin to use as bootloader activity LED when BOOTSEL mode is entered via USB (either VIA_BAUD_RATE or VIA_VENDOR_INTERFACE), type=int, min=0, max=29, group=pico_stdio_usb
// PICO_CONFIG: PICO_STDIO_USB_RESET_BOOTSEL_FIXED_ACTIVITY_LED, Whether the pin specified by PICO_STDIO_USB_RESET_BOOTSEL_ACTIVITY_LED is fixed or can be modified by picotool over the VENDOR USB interface, type=bool, default=0, group=pico_stdio_usb
@ -94,10 +104,22 @@ extern "C" {
extern stdio_driver_t stdio_usb;
/*! \brief Explicitly initialize USB stdio and add it to the current set of stdin drivers
* \ingroup pico_stdio_uart
* \ingroup pico_stdio_usb
*
* \ref PICO_STDIO_USB_CONNECT_WAIT_TIMEOUT_MS can be set to cause this method to wait for a CDC connection
* from the host before returning, which is useful if you don't want any initial stdout output to be discarded
* before the connection is established.
*
* \return true if the USB CDC was initialized, false if an error occurred
*/
bool stdio_usb_init(void);
/*! \brief Check if there is an active stdio CDC connection to a host
* \ingroup pico_stdio_usb
*
* \return true if stdio is connected over CDC
*/
bool stdio_usb_connected(void);
#ifdef __cplusplus
}
#endif

View File

@ -7,17 +7,7 @@
#ifndef _PICO_STDIO_USB_RESET_INTERFACE_H
#define _PICO_STDIO_USB_RESET_INTERFACE_H
// We use VENDOR, 0, 0 for PICOBOOT, so lets use VENDOR, 0, 1 for RESET
// definitions have been moved here
#include "pico/usb_reset_interface.h"
// VENDOR sub-class for the reset interface
#define RESET_INTERFACE_SUBCLASS 0x00
// VENDOR protocol for the reset interface
#define RESET_INTERFACE_PROTOCOL 0x01
// CONTROL requests:
// reset to BOOTSEL
#define RESET_REQUEST_BOOTSEL 0x01
// regular flash boot
#define RESET_REQUEST_FLASH 0x02
#endif

View File

@ -38,7 +38,7 @@ static uint16_t resetd_open(uint8_t __unused rhport, tusb_desc_interface_t const
}
// Support for parameterized reset via vendor interface control request
static bool resetd_control_xfer_cb(uint8_t rhport, uint8_t stage, tusb_control_request_t const * request) {
static bool resetd_control_xfer_cb(uint8_t __unused rhport, uint8_t stage, tusb_control_request_t const * request) {
// nothing to do with DATA & ACK stage
if (stage != CONTROL_STAGE_SETUP) return true;

View File

@ -41,10 +41,10 @@ static void stdio_usb_out_chars(const char *buf, int length) {
if (tud_cdc_connected()) {
for (int i = 0; i < length;) {
int n = length - i;
int avail = tud_cdc_write_available();
int avail = (int) tud_cdc_write_available();
if (n > avail) n = avail;
if (n) {
int n2 = tud_cdc_write(buf + i, n);
int n2 = (int) tud_cdc_write(buf + i, (uint32_t)n);
tud_task();
tud_cdc_write_flush();
i += n2;
@ -73,7 +73,7 @@ int stdio_usb_in_chars(char *buf, int length) {
}
int rc = PICO_ERROR_NO_DATA;
if (tud_cdc_connected() && tud_cdc_available()) {
int count = tud_cdc_read(buf, length);
int count = (int) tud_cdc_read(buf, (uint32_t) length);
rc = count ? count : PICO_ERROR_NO_DATA;
}
mutex_exit(&stdio_usb_mutex);
@ -103,9 +103,29 @@ bool stdio_usb_init(void) {
bool rc = add_alarm_in_us(PICO_STDIO_USB_TASK_INTERVAL_US, timer_task, NULL, true);
if (rc) {
stdio_set_driver_enabled(&stdio_usb, true);
#if PICO_STDIO_USB_CONNECT_WAIT_TIMEOUT_MS
#if PICO_STDIO_USB_CONNECT_WAIT_TIMEOUT_MS > 0
absolute_time_t until = make_timeout_time_ms(PICO_STDIO_USB_CONNECT_WAIT_TIMEOUT_MS);
#else
absolute_time_t until = at_the_end_of_time;
#endif
do {
if (stdio_usb_connected()) {
#if PICO_STDIO_USB_POST_CONNECT_WAIT_DELAY_MS != 0
sleep_ms(PICO_STDIO_USB_POST_CONNECT_WAIT_DELAY_MS);
#endif
break;
}
sleep_ms(10);
} while (!time_reached(until));
#endif
}
return rc;
}
bool stdio_usb_connected(void) {
return tud_cdc_connected();
}
#else
#include "pico/stdio_usb.h"
#warning stdio USB was configured, but is being disabled as TinyUSB is explicitly linked

View File

@ -143,7 +143,7 @@ const uint16_t *tud_descriptor_string_cb(uint8_t index, __unused uint16_t langid
}
// first byte is length (including header), second byte is string type
desc_str[0] = (TUSB_DESC_STRING << 8) | (2 * len + 2);
desc_str[0] = (uint16_t) ((TUSB_DESC_STRING << 8) | (2 * len + 2));
return desc_str;
}

View File

@ -7,6 +7,8 @@
#ifndef _PICO_UNIQUE_ID_H_
#define _PICO_UNIQUE_ID_H_
#include "pico.h"
#ifdef __cplusplus
extern "C" {
#endif

View File

@ -15,12 +15,13 @@ elseif (NOT EXISTS ${PICO_TINYUSB_PATH}/${TINYUSB_TEST_PATH})
endif()
if (EXISTS ${PICO_TINYUSB_PATH}/${TINYUSB_TEST_PATH})
message("TinyUSB available at ${PICO_TINYUSB_PATH}/${TINYUSB_TEST_PATH}; adding USB support.")
message("TinyUSB available at ${PICO_TINYUSB_PATH}/${TINYUSB_TEST_PATH}; enabling build support for USB.")
pico_register_common_scope_var(PICO_TINYUSB_PATH)
set(BOARD pico_sdk)
include(${PICO_TINYUSB_PATH}/hw/bsp/rp2040/family.cmake)
set(FAMILY rp2040)
include(${PICO_TINYUSB_PATH}/hw/bsp/family_support.cmake)
add_library(tinyusb_common INTERFACE)
target_link_libraries(tinyusb_common INTERFACE tinyusb_common_base)