Skip to content

Commit

Permalink
Merge pull request #20747 from dylad/pr/cpu/sam0/avoid_bitfield_usage
Browse files Browse the repository at this point in the history
cpu/sam0_common: avoid bitfield usage
  • Loading branch information
dylad authored Jun 25, 2024
2 parents a3059fe + ccc155e commit 8f645a9
Show file tree
Hide file tree
Showing 19 changed files with 294 additions and 200 deletions.
11 changes: 8 additions & 3 deletions cpu/sam0_common/include/periph_cpu_common.h
Original file line number Diff line number Diff line change
Expand Up @@ -681,8 +681,13 @@ typedef enum {
static inline void sam0_set_voltage_regulator(sam0_supc_t src)
{
#ifdef REG_SUPC_VREG
SUPC->VREG.bit.SEL = src;
while (!SUPC->STATUS.bit.VREGRDY) {}
if (src == SAM0_VREG_BUCK) {
SUPC->VREG.reg |= (1 << SUPC_VREG_SEL_Pos);
}
else {
SUPC->VREG.reg &= ~(1 << SUPC_VREG_SEL_Pos);
}
while (!(SUPC->STATUS.reg & SUPC_STATUS_VREGRDY)) {}
#else
(void) src;
assert(0);
Expand Down Expand Up @@ -867,7 +872,7 @@ static inline void sercom_set_gen(void *sercom, uint8_t gclk)
static inline bool cpu_woke_from_backup(void)
{
#ifdef RSTC_RCAUSE_BACKUP
return RSTC->RCAUSE.bit.BACKUP;
return RSTC->RCAUSE.reg & RSTC_RCAUSE_BACKUP;
#else
return false;
#endif
Expand Down
13 changes: 10 additions & 3 deletions cpu/sam0_common/periph/adc.c
Original file line number Diff line number Diff line change
Expand Up @@ -190,10 +190,12 @@ static int _adc_configure(Adc *dev, adc_res_t res)
/* Set ADC resolution */
#ifdef ADC_CTRLC_RESSEL
/* Reset resolution bits in CTRLC */
dev->CTRLC.bit.RESSEL = res & 0x3;
uint32_t ctrlc = dev->CTRLC.reg;
dev->CTRLC.reg = ((ctrlc & ~ADC_CTRLC_RESSEL_Msk) | ADC_CTRLC_RESSEL(res));
#else
/* Reset resolution bits in CTRLB */
dev->CTRLB.bit.RESSEL = res & 0x3;
uint32_t ctrlb = dev->CTRLB.reg;
dev->CTRLB.reg = ((ctrlb & ~ADC_CTRLB_RESSEL_Msk) | ADC_CTRLB_RESSEL(res));
#endif

/* Set Voltage Reference */
Expand Down Expand Up @@ -317,7 +319,12 @@ static int32_t _sample(adc_t line)
| adc_channels[line].inputctrl
| (diffmode ? 0 : ADC_NEG_INPUT);
#ifdef ADC_CTRLB_DIFFMODE
dev->CTRLB.bit.DIFFMODE = diffmode;
if (diffmode) {
dev->CTRLB.reg |= ADC_CTRLB_DIFFMODE;
}
else {
dev->CTRLB.reg &= ~ADC_CTRLB_DIFFMODE;
}
#endif
_wait_syncbusy(dev);

Expand Down
6 changes: 3 additions & 3 deletions cpu/sam0_common/periph/dac.c
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ static inline void _sync(void)
#ifdef DAC_SYNCBUSY_MASK
while (DAC->SYNCBUSY.reg) {}
#else
while (DAC->STATUS.bit.SYNCBUSY) {}
while (DAC->STATUS.reg & DAC_STATUS_SYNCBUSY) {}
#endif
}

Expand Down Expand Up @@ -110,7 +110,7 @@ int8_t dac_init(dac_t line)
_dac_init_clock(line);

/* Settings can only be changed when DAC is disabled */
DAC->CTRLA.bit.ENABLE = 0;
DAC->CTRLA.reg &= ~DAC_CTRLA_ENABLE;
_sync();

#ifdef DAC_DACCTRL_ENABLE
Expand All @@ -125,7 +125,7 @@ int8_t dac_init(dac_t line)
#endif
;

Check warning on line 126 in cpu/sam0_common/periph/dac.c

View workflow job for this annotation

GitHub Actions / static-tests

semicolon is isolated from other tokens

DAC->CTRLA.bit.ENABLE = 1;
DAC->CTRLA.reg |= DAC_CTRLA_ENABLE;
_sync();

#ifdef DAC_STATUS_READY
Expand Down
14 changes: 7 additions & 7 deletions cpu/sam0_common/periph/dma.c
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,7 @@ void dma_init(void)
NVIC_EnableIRQ(DMAC_IRQn);
#endif

DMAC->CTRL.bit.DMAENABLE = 1;
DMAC->CTRL.reg |= DMAC_CTRL_DMAENABLE;
}

dma_t dma_acquire_channel(void)
Expand Down Expand Up @@ -255,11 +255,11 @@ void dma_start(dma_t dma)

#ifdef REG_DMAC_CHID
unsigned state = irq_disable();
DMAC->CHID.bit.ID = dma;
DMAC->CHID.reg = DMAC_CHID_ID(dma);
DMAC->CHCTRLA.reg = DMAC_CHCTRLA_ENABLE;
irq_restore(state);
#else
DMAC->Channel[dma].CHCTRLA.bit.ENABLE = 1;
DMAC->Channel[dma].CHCTRLA.reg |= DMAC_CHCTRLA_ENABLE;
#endif
}

Expand All @@ -274,15 +274,15 @@ void dma_cancel(dma_t dma)
DEBUG("[DMA]: Cancelling active transfer: %u\n", dma);
#ifdef REG_DMAC_CHID
unsigned state = irq_disable();
DMAC->CHID.bit.ID = dma;
DMAC->CHID.reg = DMAC_CHID_ID(dma);
/* Write zero to the enable bit */
DMAC->CHCTRLA.reg = 0;
/* Wait until the active beat is finished */
while (DMAC->CHCTRLA.bit.ENABLE) {}
while (DMAC->CHCTRLA.reg & DMAC_CHCTRLA_ENABLE) {}
irq_restore(state);
#else
DMAC->Channel[dma].CHCTRLA.bit.ENABLE = 0;
while (DMAC->Channel[dma].CHCTRLA.bit.ENABLE) {}
DMAC->Channel[dma].CHCTRLA.reg &= ~DMAC_CHCTRLA_ENABLE;
while (DMAC->Channel[dma].CHCTRLA.reg & DMAC_CHCTRLA_ENABLE) {}
#endif
}

Expand Down
4 changes: 2 additions & 2 deletions cpu/sam0_common/periph/eth.c
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ unsigned sam0_read_phy(uint8_t phy, uint8_t addr)
| GMAC_MAN_OP(PHY_READ_OP);

/* Wait for operation completion */
while (!GMAC->NSR.bit.IDLE) {}
while (!(GMAC->NSR.reg & GMAC_NSR_IDLE)) {}
/* return content of shift register */
return (GMAC->MAN.reg & GMAC_MAN_DATA_Msk);
}
Expand All @@ -148,7 +148,7 @@ void sam0_write_phy(uint8_t phy, uint8_t addr, uint16_t data)
| GMAC_MAN_CLTTO | GMAC_MAN_DATA(data);

/* Wait for operation completion */
while (!GMAC->NSR.bit.IDLE) {}
while (!(GMAC->NSR.reg & GMAC_NSR_IDLE)) {}
}

void sam0_eth_poweron(void)
Expand Down
6 changes: 3 additions & 3 deletions cpu/sam0_common/periph/flashpage.c
Original file line number Diff line number Diff line change
Expand Up @@ -58,9 +58,9 @@
static inline void wait_nvm_is_ready(void)
{
#ifdef NVMCTRL_STATUS_READY
while (!_NVMCTRL->STATUS.bit.READY) {}
while (!(_NVMCTRL->STATUS.reg & NVMCTRL_STATUS_READY)) {}
#else
while (!_NVMCTRL->INTFLAG.bit.READY) {}
while (!(_NVMCTRL->INTFLAG.reg & NVMCTRL_INTFLAG_READY)) {}
#endif
}

Expand Down Expand Up @@ -89,7 +89,7 @@ static void _lock(unsigned state)

/* cached flash contents may have changed - invalidate cache */
#ifdef CMCC
CMCC->MAINT0.bit.INVALL = 1;
CMCC->MAINT0.reg |= CMCC_MAINT0_INVALL;
#endif

irq_restore(state);
Expand Down
12 changes: 6 additions & 6 deletions cpu/sam0_common/periph/gpio.c
Original file line number Diff line number Diff line change
Expand Up @@ -242,9 +242,9 @@ void gpio_write(gpio_t pin, int value)
#ifdef MODULE_PERIPH_GPIO_IRQ

#ifdef CPU_COMMON_SAMD21
#define EIC_SYNC() while (_EIC->STATUS.bit.SYNCBUSY)
#define EIC_SYNC() while (_EIC->STATUS.reg & EIC_STATUS_SYNCBUSY)
#else
#define EIC_SYNC() while (_EIC->SYNCBUSY.bit.ENABLE)
#define EIC_SYNC() while (_EIC->SYNCBUSY.reg & EIC_SYNCBUSY_ENABLE)

Check warning on line 247 in cpu/sam0_common/periph/gpio.c

View workflow job for this annotation

GitHub Actions / static-tests

full block {} expected in the control structure
#endif

static int _exti(gpio_t pin)

Check warning on line 250 in cpu/sam0_common/periph/gpio.c

View workflow job for this annotation

GitHub Actions / static-tests

full block {} expected in the control structure
Expand Down Expand Up @@ -349,7 +349,7 @@ int gpio_init_int(gpio_t pin, gpio_mode_t mode, gpio_flank_t flank,
GCLK->CLKCTRL.reg = EIC_GCLK_ID
| GCLK_CLKCTRL_CLKEN
| GCLK_CLKCTRL_GEN(CONFIG_SAM0_GCLK_GPIO);
while (GCLK->STATUS.bit.SYNCBUSY) {}
while (GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY) {}
#else /* CPU_COMMON_SAML21 */
/* enable clocks for the EIC module */
MCLK->APBAMASK.reg |= MCLK_APBAMASK_EIC;
Expand Down Expand Up @@ -403,7 +403,7 @@ inline static void reenable_eic(gpio_eic_clock_t clock) {
| GCLK_CLKCTRL_CLKEN
| GCLK_CLKCTRL_GEN(CONFIG_SAM0_GCLK_GPIO);
}
while (GCLK->STATUS.bit.SYNCBUSY) {}
while (GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY) {}
#else
uint32_t ctrla_reg = EIC_CTRLA_ENABLE;

Expand All @@ -423,7 +423,7 @@ void gpio_pm_cb_enter(int deep)
{
#if defined(PM_SLEEPCFG_SLEEPMODE_STANDBY)
(void) deep;
unsigned mode = PM->SLEEPCFG.bit.SLEEPMODE;
unsigned mode = PM->SLEEPCFG.reg & PM_SLEEPCFG_SLEEPMODE_Msk;

if (mode == PM_SLEEPCFG_SLEEPMODE_STANDBY) {
DEBUG_PUTS("gpio: switching EIC to slow clock");
Expand All @@ -447,7 +447,7 @@ void gpio_pm_cb_leave(int deep)
#if defined(PM_SLEEPCFG_SLEEPMODE_STANDBY)
(void) deep;

if (PM->SLEEPCFG.bit.SLEEPMODE == PM_SLEEPCFG_SLEEPMODE_STANDBY) {
if ((PM->SLEEPCFG.reg & PM_SLEEPCFG_SLEEPMODE_Msk) == PM_SLEEPCFG_SLEEPMODE_STANDBY) {
DEBUG_PUTS("gpio: switching EIC to fast clock");
reenable_eic(_EIC_CLOCK_FAST);
}
Expand Down
4 changes: 2 additions & 2 deletions cpu/sam0_common/periph/gpio_ll.c
Original file line number Diff line number Diff line change
Expand Up @@ -62,12 +62,12 @@ void gpio_ll_mux(gpio_port_t port, uint8_t pin, gpio_mux_t mux)

unsigned irq_state = irq_disable();
if (mux == GPIO_MUX_DISABLED) {
apb->PINCFG[pin].bit.PMUXEN = 0;
apb->PINCFG[pin].reg &= ~PORT_PINCFG_PMUXEN;
}
else {
unsigned pmux_reg = pin >> 1;
unsigned pmux_pos = (pin & 0x01) << 2;
apb->PINCFG[pin].bit.PMUXEN = 1;
apb->PINCFG[pin].reg |= PORT_PINCFG_PMUXEN;
unsigned pmux = apb->PMUX[pmux_reg].reg;
pmux &= ~(PORT_PMUX_PMUXE_Msk << pmux_pos);
pmux |= (unsigned)mux << pmux_pos;
Expand Down
6 changes: 3 additions & 3 deletions cpu/sam0_common/periph/gpio_ll_irq.c
Original file line number Diff line number Diff line change
Expand Up @@ -121,10 +121,10 @@ static void disable_trigger(unsigned exti_num)
static void eic_sync(void)
{
#ifdef EIC_STATUS_SYNCBUSY
while (EIC_SEC->STATUS.bit.SYNCBUSY) { }
while (EIC_SEC->STATUS.reg & EIC_STATUS_SYNCBUSY) {}
#endif
#ifdef EIC_SYNCBUSY_ENABLE
while (EIC_SEC->SYNCBUSY.bit.ENABLE) { }
while (EIC_SEC->SYNCBUSY.reg & EIC_SYNCBUSY_ENABLE) {}
#endif
}

Expand All @@ -136,7 +136,7 @@ static void eic_enable_clock(void)
GCLK->CLKCTRL.reg = EIC_GCLK_ID
| GCLK_CLKCTRL_CLKEN
| GCLK_CLKCTRL_GEN(CONFIG_SAM0_GCLK_GPIO);
while (GCLK->STATUS.bit.SYNCBUSY) {}
while (GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY) {}
#endif
#ifdef MCLK_APBAMASK_EIC
MCLK->APBAMASK.reg |= MCLK_APBAMASK_EIC;
Expand Down
7 changes: 4 additions & 3 deletions cpu/sam0_common/periph/hwrng.c
Original file line number Diff line number Diff line change
Expand Up @@ -26,15 +26,16 @@
void hwrng_init(void)
{
/* Enable the MCLK */
MCLK->APBCMASK.bit.TRNG_ = 1;
MCLK->APBCMASK.reg |= MCLK_APBCMASK_TRNG;

/* Enable the TRNG */
TRNG->CTRLA.bit.ENABLE = 1;
TRNG->CTRLA.reg |= TRNG_CTRLA_ENABLE;

}

uint32_t hwrand(void)
{
while (!TRNG->INTFLAG.bit.DATARDY) {}
while (!(TRNG->INTFLAG.reg & TRNG_INTFLAG_DATARDY)) {}
return TRNG->DATA.reg;
}

Expand Down
10 changes: 5 additions & 5 deletions cpu/sam0_common/periph/i2c.c
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ static inline SercomI2cm *bus(i2c_t dev)
static void _syncbusy(SercomI2cm *dev)
{
#ifdef SERCOM_I2CM_STATUS_SYNCBUSY
while (dev->STATUS.bit.SYNCBUSY) {}
while (dev->STATUS.reg & SERCOM_I2CM_STATUS_SYNCBUSY) {}
#else
while (dev->SYNCBUSY.reg) {}
#endif
Expand All @@ -88,9 +88,9 @@ static void _reset(SercomI2cm *dev)
while (dev->CTRLA.reg & SERCOM_SPI_CTRLA_SWRST) {}

#ifdef SERCOM_I2CM_STATUS_SYNCBUSY
while (dev->STATUS.bit.SYNCBUSY) {}
while (dev->STATUS.reg & SERCOM_I2CM_STATUS_SYNCBUSY) {}
#else
while (dev->SYNCBUSY.bit.SWRST) {}
while (dev->SYNCBUSY.reg & SERCOM_I2CM_SYNCBUSY_SWRST) {}
#endif
}

Expand Down Expand Up @@ -311,7 +311,7 @@ void _i2c_poweron(i2c_t dev)
if (bus(dev) == NULL) {
return;
}
bus(dev)->CTRLA.bit.ENABLE = 1;
bus(dev)->CTRLA.reg |= SERCOM_I2CM_CTRLA_ENABLE;
_syncbusy(bus(dev));
}

Expand All @@ -322,7 +322,7 @@ void _i2c_poweroff(i2c_t dev)
if (bus(dev) == NULL) {
return;
}
bus(dev)->CTRLA.bit.ENABLE = 0;
bus(dev)->CTRLA.reg &= ~SERCOM_I2CM_CTRLA_ENABLE;
_syncbusy(bus(dev));
}

Expand Down
11 changes: 6 additions & 5 deletions cpu/sam0_common/periph/pwm.c
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@
typedef TcCount8 Tcc;
#define TCC_CTRLA_ENABLE TC_CTRLA_ENABLE
#define TCC_SYNCBUSY_CC0 TC_SYNCBUSY_CC0
#define TCC_STATUS_SYNCBUSY TC_STATUS_SYNCBUSY
#ifdef TC_SYNCBUSY_MASK
#define TCC_SYNCBUSY_MASK TC_SYNCBUSY_MASK
#endif
Expand Down Expand Up @@ -216,8 +217,8 @@ static void poweroff(pwm_t dev)
static void _tc_init(Tc *tc, pwm_mode_t mode, uint8_t prescaler, uint8_t res)
{
/* reset TC module */
tc->COUNT8.CTRLA.bit.SWRST = 1;
while (tc->COUNT8.CTRLA.bit.SWRST) {}
tc->COUNT8.CTRLA.reg |= TC_CTRLA_SWRST;
while (tc->COUNT8.CTRLA.reg & TC_CTRLA_SWRST) {}

/* set PWM mode */
switch (mode) {
Expand Down Expand Up @@ -250,7 +251,7 @@ static void _tc_init(Tc *tc, pwm_mode_t mode, uint8_t prescaler, uint8_t res)
tc->COUNT8.PER.reg = (res - 1);

#ifdef TC_STATUS_SYNCBUSY
while (tc->COUNT8.STATUS.bit.SYNCBUSY) {}
while (tc->COUNT8.STATUS.reg & TC_STATUS_SYNCBUSY) {}
#else
while (tc->COUNT8.SYNCBUSY.reg) {}
#endif
Expand Down Expand Up @@ -361,7 +362,7 @@ static void _tc_set(Tc *tc, uint8_t chan, uint16_t value)
tc->COUNT8.CC[chan].reg = value;

#ifdef TC_STATUS_SYNCBUSY
while (tc->COUNT8.STATUS.bit.SYNCBUSY) {}
while (tc->COUNT8.STATUS.reg & TC_STATUS_SYNCBUSY) {}
#else
while (tc->COUNT8.SYNCBUSY.reg & (TC_SYNCBUSY_CC0 << chan)) {}
#endif
Expand All @@ -375,7 +376,7 @@ static void _tcc_set(Tcc *tcc, uint8_t chan, uint16_t value)
#ifdef TCC_SYNCBUSY_MASK
while (tcc->SYNCBUSY.reg & (TCC_SYNCBUSY_CC0 << chan)) {}
#else
while (tcc->STATUS.bit.SYNCBUSY) {}
while (tcc->STATUS.reg & TCC_STATUS_SYNCBUSY) {}
#endif
}

Expand Down
Loading

0 comments on commit 8f645a9

Please sign in to comment.