Skip to content

Commit

Permalink
fixup! boards/adafruit-metro-m4-express: allow sharing SERCOM
Browse files Browse the repository at this point in the history
  • Loading branch information
maribu committed Nov 23, 2024
1 parent c3608b2 commit 7efd29e
Show file tree
Hide file tree
Showing 5 changed files with 41 additions and 54 deletions.
14 changes: 2 additions & 12 deletions cpu/sam0_common/include/periph_cpu_common.h
Original file line number Diff line number Diff line change
Expand Up @@ -325,16 +325,6 @@ typedef enum {
*/
typedef uint8_t sercom_t;

/**
* @brief SERCOM configuration for @ref sercom_acquire
*/
typedef struct {
uint32_t ctrla; /**< Value to write to the CTRLA register */
uint32_t ctrlb; /**< Value to write to the CTRLB register */
uint16_t baud; /**< Value to write to the BAUD register */
uint8_t gclk; /**< Generator clock */
} sercom_conf_t;

/**
* @brief IRQ callback to call on IRQs triggered by the SERCOM
*
Expand Down Expand Up @@ -362,7 +352,7 @@ Sercom *sercom_get_baseaddr(sercom_t sercom);
* @brief Acquire exclusive access to the given SERCOM, enable it, and
* configure it as specified
* @param[in] sercom The SERCOM to acquire
* @param[in] conf The configuration to apply
* @param[in] gclk Generator clock
* @param[in] irq_cb Function to call on IRQ or `NULL`
* @param[in] irq_arg Argument to pass to @p irq_cb
*
Expand All @@ -378,7 +368,7 @@ Sercom *sercom_get_baseaddr(sercom_t sercom);
* @post If @p irq_cb was `NULL`, the corresponding IRQ(s) is/are disabled
* in the NIVC. Otherwise they are enabled but masked.
*/
void sercom_acquire(sercom_t sercom, const sercom_conf_t *conf,
void sercom_acquire(sercom_t sercom, uint8_t gclk,
sercom_irq_cb_t irq_cb, void *irq_arg);

/**
Expand Down
19 changes: 13 additions & 6 deletions cpu/sam0_common/periph/i2c.c
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,11 @@ static mutex_t locks[I2C_NUMOF];
/**
* @brief Cache the configuration for faster SERCOM initialization
*/
static sercom_conf_t _configs[I2C_NUMOF];
static struct i2c_sercom_config {
uint32_t ctrla; /**< This goes into the CTRLA register */
uint32_t ctrlb; /**< This goes into the CTRLB register */
uint32_t baud; /**< This goes into the BAUD register */
} _configs[I2C_NUMOF];

static SercomI2cm *_dev(i2c_t bus)
{
Expand Down Expand Up @@ -102,9 +106,6 @@ void i2c_init(i2c_t bus)

/* Initialize mutex */
mutex_init(&locks[bus]);
_configs[bus] = (sercom_conf_t){
.gclk = i2c_config[bus].gclk_src,
};

/* Set sercom module to operate in I2C master mode and run in Standby
if user requests it */
Expand Down Expand Up @@ -160,14 +161,20 @@ void i2c_acquire(i2c_t bus)
SercomI2cm *dev = _dev(bus);

mutex_lock(&locks[bus]);
sercom_acquire(i2c_config[bus].sercom, &_configs[bus], NULL, NULL);
sercom_acquire(i2c_config[bus].sercom, i2c_config[bus].gclk_src, NULL, NULL);
dev->BAUD.reg = _configs[bus].baud;
dev->CTRLA.reg = _configs[bus].ctrla;
dev->CTRLB.reg = _configs[bus].ctrlb;
_attach_pins(bus);
_i2c_poweron(dev);

/* Force bus to IDLE state: At least on SAMD21 the SERCOM will stick in
* unknown state and never recover. Adding a timeout here would make
* I2C too slow to be sensible. */
dev->STATUS.reg = BUSSTATE_IDLE;
while (dev->STATUS.reg != BUSSTATE_IDLE) {
dev->STATUS.reg = BUSSTATE_IDLE;
_syncbusy(dev);
}

DEBUG("[i2c] acquired I2C%u, CTRLA=%x, CTRLB=%x, BAUD=%x, STATUS=%x\n",
(unsigned)bus, (unsigned)dev->CTRLA.reg, (unsigned)dev->CTRLB.reg,
Expand Down
15 changes: 2 additions & 13 deletions cpu/sam0_common/periph/sercom.c
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,7 @@ static void _wait_for_reset_to_complete(Sercom *dev)
while (dev->SPI.CTRLA.reg & SERCOM_SPI_CTRLA_SWRST) {}
}

void sercom_acquire(sercom_t sercom, const sercom_conf_t *conf,
void sercom_acquire(sercom_t sercom, uint8_t gclk,
sercom_irq_cb_t irq_cb, void *irq_arg)
{
assume((unsigned)sercom < SERCOM_NUMOF);
Expand All @@ -185,7 +185,7 @@ void sercom_acquire(sercom_t sercom, const sercom_conf_t *conf,
_cbs[sercom] = irq_cb;
_args[sercom] = irq_arg;

_sercom_clk_enable(sercom, conf->gclk);
_sercom_clk_enable(sercom, gclk);

/* A potential previous call to sercom_release() did not wait for the reset
* to be complete to not waste time. But we need to do so now, in case it
Expand All @@ -197,17 +197,6 @@ void sercom_acquire(sercom_t sercom, const sercom_conf_t *conf,
* SERCOM */
assume(!dev->SPI.CTRLA.reg);

/* Note: The BAUD register is either 8 bit (in case of SPI/I2C) or 16 bit
* wide (in case of UART). Due to conf->baud being in little endian,
* valid values for conf->baud for SPI/I2C mode will write zeros to
* the part exceeding the 8 bit BAUD field. So while this write may
* write to addresses that have no meaning, it happens to just work
* in all modes.
*/
dev->USART.BAUD.reg = conf->baud;
dev->USART.CTRLA.reg = conf->ctrla;
dev->USART.CTRLB.reg = conf->ctrlb;

if (irq_cb) {
#if SERCOM_HAS_DEDICATED_TX_ISR
NVIC_EnableIRQ(SERCOM0_2_IRQn + (sercom * 4));
Expand Down
24 changes: 13 additions & 11 deletions cpu/sam0_common/periph/spi.c
Original file line number Diff line number Diff line change
Expand Up @@ -242,32 +242,34 @@ static void _spi_acquire(spi_t bus, spi_mode_t mode, spi_clk_t clk)
clk = gclk_src;
}

sercom_conf_t conf = {};

/* configure bus clock, in synchronous mode its calculated from
* BAUD.reg = (f_ref / (2 * f_bus) - 1)
* with f_ref := CLOCK_CORECLOCK as defined by the board
* to mitigate the rounding error due to integer arithmetic, the
* equation is modified to
* BAUD.reg = ((f_ref + f_bus) / (2 * f_bus) - 1) */
conf.baud = (gclk_src + clk) / (2 * clk) - 1;
uint8_t baud = (gclk_src + clk) / (2 * clk) - 1;

/* configure device to be master and set mode and pads,
*
* NOTE: we could configure the pads already during spi_init, but for
* efficiency reason we do that here, so we can do all in one single write
* to the CTRLA register */
conf.ctrla = SERCOM_SPI_CTRLA_MODE(0x3) /* 0x3 -> master */
| SERCOM_SPI_CTRLA_DOPO(spi_config[bus].mosi_pad)
| SERCOM_SPI_CTRLA_DIPO(spi_config[bus].miso_pad)
| (mode << SERCOM_SPI_CTRLA_CPHA_Pos);
conf.ctrlb = SERCOM_SPI_CTRLB_CHSIZE(0) | SERCOM_SPI_CTRLB_RXEN;
uint32_t ctrla = SERCOM_SPI_CTRLA_MODE(0x3) /* 0x3 -> master */
| SERCOM_SPI_CTRLA_DOPO(spi_config[bus].mosi_pad)
| SERCOM_SPI_CTRLA_DIPO(spi_config[bus].miso_pad)
| (mode << SERCOM_SPI_CTRLA_CPHA_Pos);
uint32_t ctrlb = SERCOM_SPI_CTRLB_CHSIZE(0) | SERCOM_SPI_CTRLB_RXEN;

sercom_acquire(spi_config[bus].sercom, spi_config[bus].gclk_src, NULL, NULL);

conf.gclk = spi_config[bus].gclk_src;
sercom_acquire(spi_config[bus].sercom, &conf, NULL, NULL);
SercomSpi *dev = _dev(bus);
dev->CTRLA.reg = ctrla;
dev->CTRLB.reg = ctrlb;
dev->BAUD.reg = baud;

/* finally enable the device */
_enable(_dev(bus));
_enable(dev);
}

static void _spi_blocking_transfer(spi_t bus, const void *out, void *in, size_t len)
Expand Down
23 changes: 11 additions & 12 deletions cpu/sam0_common/periph/uart.c
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@
*/

#include "bitfield.h"
#include "cpu.h"
#include "modules.h"
#include "periph/gpio.h"
#include "periph/uart.h"
Expand Down Expand Up @@ -355,10 +354,6 @@ void uart_poweron(uart_t uart)

bf_set_atomic(_enabled, uart);

sercom_conf_t conf = {
.gclk = uart_config[uart].gclk_src,
};

uint32_t f_src = sam0_gclk_freq(uart_config[uart].gclk_src);

#if IS_ACTIVE(CONFIG_SAM0_UART_BAUD_FRAC)
Expand All @@ -377,7 +372,7 @@ void uart_poweron(uart_t uart)

/* set asynchronous mode w/o parity, LSB first, TX and RX pad as specified
* by the board in the periph_conf.h, x16 sampling and use internal clock */
conf.ctrla = SERCOM_USART_CTRLA_DORD
uint32_t ctrla = SERCOM_USART_CTRLA_DORD
#if IS_ACTIVE(CONFIG_SAM0_UART_BAUD_FRAC)
/* enable Asynchronous Fractional mode */
| sampr
Expand All @@ -388,40 +383,44 @@ void uart_poweron(uart_t uart)

/* Set run in standby mode if enabled */
if (uart_config[uart].flags & UART_FLAG_RUN_STANDBY) {
conf.ctrla |= SERCOM_USART_CTRLA_RUNSTDBY;
ctrla |= SERCOM_USART_CTRLA_RUNSTDBY;
}

/* calculate symbol rate */
conf.baud = _calculate_baud(symbol_rates[uart], f_src);
uint16_t baud = _calculate_baud(symbol_rates[uart], f_src);

uint32_t ctrlb = 0;
/* enable transmitter, and configure 8N1 mode */
if (gpio_is_valid(uart_config[uart].tx_pin)) {
conf.ctrlb = SERCOM_USART_CTRLB_TXEN;
ctrlb = SERCOM_USART_CTRLB_TXEN;
}

sercom_irq_cb_t irq_cb = NULL;

/* enable receiver and RX interrupt if configured */
if ((uart_ctx[uart].rx_cb) && (gpio_is_valid(uart_config[uart].rx_pin))) {
irq_cb = uart_isr;
conf.ctrlb |= SERCOM_USART_CTRLB_RXEN;
ctrlb |= SERCOM_USART_CTRLB_RXEN;

/* set wakeup receive from sleep if enabled */
if (uart_config[uart].flags & UART_FLAG_WAKEUP) {
conf.ctrlb |= SERCOM_USART_CTRLB_SFDE;
ctrlb |= SERCOM_USART_CTRLB_SFDE;
}
}

if (IS_USED(MODULE_PERIPH_UART_NONBLOCKING)) {
irq_cb = uart_isr;
}

sercom_acquire(uart_config[uart].sercom, &conf,
sercom_acquire(uart_config[uart].sercom, uart_config[uart].gclk_src,
irq_cb, (void *)(uintptr_t)uart);

_attach_pins(uart);

SercomUsart *dev = _dev(uart);
dev->CTRLA.reg = ctrla;
dev->CTRLB.reg = ctrlb;
dev->BAUD.reg = baud;
/* enable RX IRQ, if needed */
if ((uart_ctx[uart].rx_cb) && (gpio_is_valid(uart_config[uart].rx_pin))) {
dev->INTENSET.reg = SERCOM_USART_INTENSET_RXC;
Expand Down

0 comments on commit 7efd29e

Please sign in to comment.