Merge branch 'bugfix/register_non_32bit_access_v4.2' into 'release/v4.2'

hal: avoid non-32bit access to registers (v4.2)

See merge request espressif/esp-idf!15617
This commit is contained in:
Jiang Jiang Jian
2021-11-23 07:26:31 +00:00
13 changed files with 65 additions and 62 deletions

View File

@ -65,10 +65,10 @@ static inline void dac_ll_update_output_value(dac_channel_t channel, uint8_t val
{
if (channel == DAC_CHANNEL_1) {
SENS.sar_dac_ctrl2.dac_cw_en1 = 0;
RTCIO.pad_dac[channel].dac = value;
HAL_FORCE_MODIFY_U32_REG_FIELD(RTCIO.pad_dac[channel], dac, value);
} else if (channel == DAC_CHANNEL_2) {
SENS.sar_dac_ctrl2.dac_cw_en2 = 0;
RTCIO.pad_dac[channel].dac = value;
HAL_FORCE_MODIFY_U32_REG_FIELD(RTCIO.pad_dac[channel], dac, value);
}
}

View File

@ -44,7 +44,7 @@ typedef union {
* @brief I2C interrupt event
*/
typedef enum {
I2C_INTR_EVENT_ERR,
I2C_INTR_EVENT_ERR,
I2C_INTR_EVENT_ARBIT_LOST, /*!< I2C arbition lost event */
I2C_INTR_EVENT_NACK, /*!< I2C NACK event */
I2C_INTR_EVENT_TOUT, /*!< I2C time out event */
@ -331,7 +331,7 @@ static inline void i2c_ll_set_sda_timing(i2c_dev_t *hw, int sda_sample, int sda_
*/
static inline void i2c_ll_set_txfifo_empty_thr(i2c_dev_t *hw, uint8_t empty_thr)
{
hw->fifo_conf.tx_fifo_empty_thrhd = empty_thr;
hw->fifo_conf.tx_fifo_empty_thrhd = empty_thr;
}
/**
@ -344,7 +344,7 @@ static inline void i2c_ll_set_txfifo_empty_thr(i2c_dev_t *hw, uint8_t empty_thr)
*/
static inline void i2c_ll_set_rxfifo_full_thr(i2c_dev_t *hw, uint8_t full_thr)
{
hw->fifo_conf.rx_fifo_full_thrhd = full_thr;
hw->fifo_conf.rx_fifo_full_thrhd = full_thr;
}
/**
@ -535,7 +535,7 @@ static inline void i2c_ll_write_txfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
uint32_t fifo_addr = (hw == &I2C0) ? 0x6001301c : 0x6002701c;
for(int i = 0; i < len; i++) {
WRITE_PERI_REG(fifo_addr, ptr[i]);
}
}
}
/**
@ -550,8 +550,8 @@ static inline void i2c_ll_write_txfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
static inline void i2c_ll_read_rxfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
{
for(int i = 0; i < len; i++) {
ptr[i] = hw->fifo_data.data;
}
ptr[i] = HAL_FORCE_READ_U32_REG_FIELD(hw->fifo_data, data);
}
}
/**

View File

@ -86,7 +86,7 @@ static inline mcpwm_intr_t mcpwm_ll_get_intr(mcpwm_dev_t *mcpwm)
* @param mcpwm Address of the MCPWM peripheral registers.
* @param intr Bitwise ORed interrupts to clear.
*/
static inline void mcpwm_ll_clear_intr(mcpwm_dev_t* mcpwm, mcpwm_intr_t intr)
static inline void mcpwm_ll_clear_intr(mcpwm_dev_t *mcpwm, mcpwm_intr_t intr)
{
mcpwm->int_clr.val = intr;
}
@ -101,9 +101,9 @@ static inline void mcpwm_ll_clear_intr(mcpwm_dev_t* mcpwm, mcpwm_intr_t intr)
* @param timer The timer to set the prescale, 0-2.
* @param prescale Prescale factor, 0-255.
*/
static inline void mcpwm_ll_timer_set_prescale(mcpwm_dev_t* mcpwm, int timer, uint32_t prescale)
static inline void mcpwm_ll_timer_set_prescale(mcpwm_dev_t *mcpwm, int timer, uint32_t prescale)
{
mcpwm->timer[timer].period.prescale = prescale;
HAL_FORCE_MODIFY_U32_REG_FIELD(mcpwm->timer[timer].period, prescale, prescale);
}
@ -156,8 +156,7 @@ static inline void mcpwm_ll_timer_stop(mcpwm_dev_t *mcpwm, int timer)
*/
static inline void mcpwm_ll_timer_set_period(mcpwm_dev_t *mcpwm, int timer, uint32_t period)
{
mcpwm->timer[timer].period.period = period - 1;
HAL_FORCE_MODIFY_U32_REG_FIELD(mcpwm->timer[timer].period, period, period - 1);
mcpwm->timer[timer].period.upmethod = 0;
}
@ -170,7 +169,7 @@ static inline void mcpwm_ll_timer_set_period(mcpwm_dev_t *mcpwm, int timer, uint
*/
static inline uint32_t mcpwm_ll_timer_get_period(mcpwm_dev_t *mcpwm, int timer)
{
return mcpwm->timer[timer].period.period + 1;
return HAL_FORCE_READ_U32_REG_FIELD(mcpwm->timer[timer].period, period) + 1;
}
/********************* Sync *******************/
@ -265,7 +264,7 @@ static inline void mcpwm_ll_operator_set_compare_upmethod(mcpwm_dev_t *mcpwm, in
*/
static inline uint32_t mcpwm_ll_operator_get_compare(mcpwm_dev_t *mcpwm, int op, int cmp_n)
{
return (mcpwm->channel[op].cmpr_value[cmp_n].cmpr_val);
return HAL_FORCE_READ_U32_REG_FIELD(mcpwm->channel[op].cmpr_value[cmp_n], cmpr_val);
}
/**
@ -278,7 +277,7 @@ static inline uint32_t mcpwm_ll_operator_get_compare(mcpwm_dev_t *mcpwm, int op,
*/
static inline void mcpwm_ll_operator_set_compare(mcpwm_dev_t *mcpwm, int op, int cmp_n, uint32_t compare)
{
mcpwm->channel[op].cmpr_value[cmp_n].cmpr_val = compare;
HAL_FORCE_MODIFY_U32_REG_FIELD(mcpwm->channel[op].cmpr_value[cmp_n], cmpr_val, compare);
}
/********************* Generator *******************/
@ -326,7 +325,7 @@ static inline void mcpwm_ll_gen_set_period_action(mcpwm_dev_t *mcpwm, int op, in
* @param down_action The action to take when the counter is counting down.
*/
static inline void mcpwm_ll_gen_set_cmp_action(mcpwm_dev_t *mcpwm, int op, int gen,
int cmp_n, mcpwm_output_action_t up_action, mcpwm_output_action_t down_action)
int cmp_n, mcpwm_output_action_t up_action, mcpwm_output_action_t down_action)
{
if (cmp_n == 0) {
mcpwm->channel[op].generator[gen].utea = up_action;
@ -474,7 +473,7 @@ static inline void mcpwm_ll_fault_set_oneshot_action(mcpwm_dev_t *mcpwm, int op,
* @param down_action Action to take when fault happens when counting down.
*/
static inline void mcpwm_ll_fault_set_cyc_action(mcpwm_dev_t *mcpwm, int op, int gen,
mcpwm_output_action_t up_action, mcpwm_output_action_t down_action)
mcpwm_output_action_t up_action, mcpwm_output_action_t down_action)
{
mcpwm->channel[op].tz_cfg1.cbcpulse = BIT(0); //immediately
if (gen == 0) {
@ -510,7 +509,7 @@ static inline void mcpwm_ll_deadtime_init(mcpwm_dev_t *mcpwm, int op)
* @param mode Dead zone mode to use.
*/
static inline void mcpwm_ll_set_deadtime_mode(mcpwm_dev_t *mcpwm,
int op, mcpwm_deadtime_type_t mode)
int op, mcpwm_deadtime_type_t mode)
{
#define MCPWM_LL_DEADTIME_REG_MASK (MCPWM_DT0_DEB_MODE_M | MCPWM_DT0_A_OUTSWAP_M | MCPWM_DT0_B_OUTSWAP_M | \
MCPWM_DT0_RED_INSEL_M | MCPWM_DT0_FED_INSEL_M | MCPWM_DT0_RED_OUTINVERT_M | MCPWM_DT0_FED_OUTINVERT_M | \
@ -542,7 +541,7 @@ static inline void mcpwm_ll_set_deadtime_mode(mcpwm_dev_t *mcpwm,
*/
static inline void mcpwm_ll_deadtime_set_falling_delay(mcpwm_dev_t *mcpwm, int op, uint32_t fed)
{
mcpwm->channel[op].db_fed_cfg.fed = fed;
HAL_FORCE_MODIFY_U32_REG_FIELD(mcpwm->channel[op].db_fed_cfg, fed, fed);
}
/**
@ -554,7 +553,7 @@ static inline void mcpwm_ll_deadtime_set_falling_delay(mcpwm_dev_t *mcpwm, int o
*/
static inline void mcpwm_ll_deadtime_set_rising_delay(mcpwm_dev_t *mcpwm, int op, uint32_t red)
{
mcpwm->channel[op].db_red_cfg.red = red;
HAL_FORCE_MODIFY_U32_REG_FIELD(mcpwm->channel[op].db_red_cfg, red, red);
}
/**
@ -689,7 +688,7 @@ static inline mcpwm_capture_on_edge_t mcpwm_ll_get_captured_edge(mcpwm_dev_t *mc
} else { //2
edge = mcpwm->cap_status.cap2_edge;
}
return (edge? MCPWM_NEG_EDGE: MCPWM_POS_EDGE);
return (edge ? MCPWM_NEG_EDGE : MCPWM_POS_EDGE);
}
STATIC_HAL_REG_CHECK(MCPWM, MCPWM_NEG_EDGE, BIT(0));
@ -703,7 +702,7 @@ STATIC_HAL_REG_CHECK(MCPWM, MCPWM_POS_EDGE, BIT(1));
* @param cap_edge The edge to capture, bitwise.
*/
static inline void mcpwm_ll_capture_select_edge(mcpwm_dev_t *mcpwm, int cap_sig,
mcpwm_capture_on_edge_t cap_edge)
mcpwm_capture_on_edge_t cap_edge)
{
mcpwm->cap_cfg_ch[cap_sig].mode = cap_edge;
}
@ -717,7 +716,7 @@ static inline void mcpwm_ll_capture_select_edge(mcpwm_dev_t *mcpwm, int cap_sig,
*/
static inline void mcpwm_ll_capture_set_prescale(mcpwm_dev_t *mcpwm, int cap_sig, uint32_t prescale)
{
mcpwm->cap_cfg_ch[cap_sig].prescale = prescale;
HAL_FORCE_MODIFY_U32_REG_FIELD(mcpwm->cap_cfg_ch[cap_sig], prescale, prescale);
}
/**
@ -728,7 +727,7 @@ static inline void mcpwm_ll_capture_set_prescale(mcpwm_dev_t *mcpwm, int cap_sig
*/
static inline mcpwm_intr_t mcpwm_ll_get_cap_intr_def(int bit)
{
return BIT(bit+MCPWM_CAP0_INT_RAW_S);
return BIT(bit + MCPWM_CAP0_INT_RAW_S);
}
#ifdef __cplusplus

View File

@ -20,6 +20,7 @@ extern "C" {
#include <stdbool.h>
#include "soc/rmt_struct.h"
#include "soc/rmt_caps.h"
#include "hal/hal_defs.h"
#define RMT_LL_HW_BASE (&RMT)
#define RMT_LL_MEM_BASE (&RMTMEM)
@ -87,12 +88,12 @@ static inline uint32_t rmt_ll_get_mem_blocks(rmt_dev_t *dev, uint32_t channel)
static inline void rmt_ll_set_counter_clock_div(rmt_dev_t *dev, uint32_t channel, uint32_t div)
{
dev->conf_ch[channel].conf0.div_cnt = div;
HAL_FORCE_MODIFY_U32_REG_FIELD(dev->conf_ch[channel].conf0, div_cnt, div);
}
static inline uint32_t rmt_ll_get_counter_clock_div(rmt_dev_t *dev, uint32_t channel)
{
uint32_t div = dev->conf_ch[channel].conf0.div_cnt;
uint32_t div = HAL_FORCE_READ_U32_REG_FIELD(dev->conf_ch[channel].conf0, div_cnt);
return div == 0 ? 256 : div;
}
@ -108,12 +109,12 @@ static inline void rmt_ll_enable_mem_access(rmt_dev_t *dev, bool enable)
static inline void rmt_ll_set_rx_idle_thres(rmt_dev_t *dev, uint32_t channel, uint32_t thres)
{
dev->conf_ch[channel].conf0.idle_thres = thres;
HAL_FORCE_MODIFY_U32_REG_FIELD(dev->conf_ch[channel].conf0, idle_thres, thres);
}
static inline uint32_t rmt_ll_get_rx_idle_thres(rmt_dev_t *dev, uint32_t channel)
{
return dev->conf_ch[channel].conf0.idle_thres;
return HAL_FORCE_READ_U32_REG_FIELD(dev->conf_ch[channel].conf0, idle_thres);
}
static inline void rmt_ll_set_mem_owner(rmt_dev_t *dev, uint32_t channel, uint8_t owner)
@ -143,7 +144,7 @@ static inline void rmt_ll_enable_rx_filter(rmt_dev_t *dev, uint32_t channel, boo
static inline void rmt_ll_set_rx_filter_thres(rmt_dev_t *dev, uint32_t channel, uint32_t thres)
{
dev->conf_ch[channel].conf1.rx_filter_thres = thres;
HAL_FORCE_MODIFY_U32_REG_FIELD(dev->conf_ch[channel].conf1, rx_filter_thres, thres);
}
static inline void rmt_ll_set_counter_clock_src(rmt_dev_t *dev, uint32_t channel, uint8_t src)
@ -259,14 +260,14 @@ static inline uint32_t rmt_ll_get_tx_thres_interrupt_status(rmt_dev_t *dev)
static inline void rmt_ll_set_tx_carrier_high_low_ticks(rmt_dev_t *dev, uint32_t channel, uint32_t high_ticks, uint32_t low_ticks)
{
dev->carrier_duty_ch[channel].high = high_ticks;
dev->carrier_duty_ch[channel].low = low_ticks;
HAL_FORCE_MODIFY_U32_REG_FIELD(dev->carrier_duty_ch[channel], high, high_ticks);
HAL_FORCE_MODIFY_U32_REG_FIELD(dev->carrier_duty_ch[channel], low, low_ticks);
}
static inline void rmt_ll_get_carrier_high_low_ticks(rmt_dev_t *dev, uint32_t channel, uint32_t *high_ticks, uint32_t *low_ticks)
{
*high_ticks = dev->carrier_duty_ch[channel].high;
*low_ticks = dev->carrier_duty_ch[channel].low;
*high_ticks = HAL_FORCE_READ_U32_REG_FIELD(dev->carrier_duty_ch[channel], high);
*low_ticks = HAL_FORCE_READ_U32_REG_FIELD(dev->carrier_duty_ch[channel], low);
}
static inline void rmt_ll_enable_carrier(rmt_dev_t *dev, uint32_t channel, bool enable)

View File

@ -55,7 +55,7 @@ static inline void sigmadelta_ll_set_en(gpio_sd_dev_t *hw, bool en)
*/
static inline void sigmadelta_ll_set_duty(gpio_sd_dev_t *hw, sigmadelta_channel_t channel, int8_t duty)
{
hw->channel[channel].duty = duty;
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->channel[channel], duty, (uint32_t)duty);
}
/**
@ -67,7 +67,7 @@ static inline void sigmadelta_ll_set_duty(gpio_sd_dev_t *hw, sigmadelta_channel_
*/
static inline void sigmadelta_ll_set_prescale(gpio_sd_dev_t *hw, sigmadelta_channel_t channel, uint8_t prescale)
{
hw->channel[channel].prescale = prescale;
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->channel[channel], prescale, prescale);
}
#ifdef __cplusplus

View File

@ -23,6 +23,7 @@ extern "C" {
#include <stdlib.h>
#include "hal/timer_types.h"
#include "hal/hal_defs.h"
#include "soc/timer_periph.h"
#include "soc/timer_group_struct.h"
#include "hal/hal_defs.h"
@ -53,7 +54,7 @@ static inline void timer_ll_set_divider(timg_dev_t *hw, timer_idx_t timer_num, u
}
int timer_en = hw->hw_timer[timer_num].config.enable;
hw->hw_timer[timer_num].config.enable = 0;
hw->hw_timer[timer_num].config.divider = divider;
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->hw_timer[timer_num].config, divider, divider);
hw->hw_timer[timer_num].config.enable = timer_en;
}
@ -68,7 +69,7 @@ static inline void timer_ll_set_divider(timg_dev_t *hw, timer_idx_t timer_num, u
*/
static inline void timer_ll_get_divider(timg_dev_t *hw, timer_idx_t timer_num, uint32_t *divider)
{
uint32_t d = hw->hw_timer[timer_num].config.divider;
uint32_t d = HAL_FORCE_READ_U32_REG_FIELD(hw->hw_timer[timer_num].config, divider);
if (d == 0) {
d = 65536;
} else if (d == 1) {

View File

@ -294,9 +294,9 @@ static inline void touch_ll_set_threshold(touch_pad_t touch_num, uint16_t thresh
{
touch_pad_t tp_wrap = touch_ll_num_wrap(touch_num);
if (tp_wrap & 0x1) {
SENS.touch_thresh[tp_wrap / 2].l_thresh = threshold;
HAL_FORCE_MODIFY_U32_REG_FIELD(SENS.touch_thresh[tp_wrap / 2], l_thresh, threshold);
} else {
SENS.touch_thresh[tp_wrap / 2].h_thresh = threshold;
HAL_FORCE_MODIFY_U32_REG_FIELD(SENS.touch_thresh[tp_wrap / 2], h_thresh, threshold);
}
}
@ -311,8 +311,8 @@ static inline void touch_ll_get_threshold(touch_pad_t touch_num, uint16_t *thres
touch_pad_t tp_wrap = touch_ll_num_wrap(touch_num);
if (threshold) {
*threshold = (tp_wrap & 0x1 ) ?
SENS.touch_thresh[tp_wrap / 2].l_thresh :
SENS.touch_thresh[tp_wrap / 2].h_thresh;
HAL_FORCE_READ_U32_REG_FIELD(SENS.touch_thresh[tp_wrap / 2], l_thresh) :
HAL_FORCE_READ_U32_REG_FIELD(SENS.touch_thresh[tp_wrap / 2], h_thresh) ;
}
}
@ -492,7 +492,8 @@ static inline void touch_ll_intr_clear(void)
static inline uint32_t touch_ll_read_raw_data(touch_pad_t touch_num)
{
touch_pad_t tp_wrap = touch_ll_num_wrap(touch_num);
return ((tp_wrap & 0x1) ? SENS.touch_meas[tp_wrap / 2].l_val : SENS.touch_meas[tp_wrap / 2].h_val);
return ((tp_wrap & 0x1) ? HAL_FORCE_READ_U32_REG_FIELD(SENS.touch_meas[tp_wrap / 2], l_val) :
HAL_FORCE_READ_U32_REG_FIELD(SENS.touch_meas[tp_wrap / 2], h_val));
}
/**

View File

@ -510,8 +510,8 @@ static inline void twai_ll_set_acc_filter(twai_dev_t* hw, uint32_t code, uint32_
uint32_t code_swapped = __builtin_bswap32(code);
uint32_t mask_swapped = __builtin_bswap32(mask);
for (int i = 0; i < 4; i++) {
hw->acceptance_filter.acr[i].byte = ((code_swapped >> (i * 8)) & 0xFF);
hw->acceptance_filter.amr[i].byte = ((mask_swapped >> (i * 8)) & 0xFF);
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->acceptance_filter.acr[i], byte, ((code_swapped >> (i * 8)) & 0xFF));
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->acceptance_filter.amr[i], byte, ((mask_swapped >> (i * 8)) & 0xFF));
}
hw->mode_reg.afm = single_filter;
}
@ -546,7 +546,7 @@ static inline void twai_ll_get_rx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t
{
//Copy RX buffer registers into frame
for (int i = 0; i < 13; i++) {
rx_frame->bytes[i] = hw->tx_rx_buffer[i].byte;
rx_frame->bytes[i] = HAL_FORCE_READ_U32_REG_FIELD(hw->tx_rx_buffer[i], byte);
}
}

View File

@ -77,10 +77,10 @@ static inline void dac_ll_update_output_value(dac_channel_t channel, uint8_t val
{
if (channel == DAC_CHANNEL_1) {
SENS.sar_dac_ctrl2.dac_cw_en1 = 0;
RTCIO.pad_dac[channel].dac = value;
HAL_FORCE_MODIFY_U32_REG_FIELD(RTCIO.pad_dac[channel], dac, value);
} else if (channel == DAC_CHANNEL_2) {
SENS.sar_dac_ctrl2.dac_cw_en2 = 0;
RTCIO.pad_dac[channel].dac = value;
HAL_FORCE_MODIFY_U32_REG_FIELD(RTCIO.pad_dac[channel], dac, value);
}
}

View File

@ -20,6 +20,7 @@ extern "C" {
#include <stdbool.h>
#include "soc/rmt_struct.h"
#include "soc/rmt_caps.h"
#include "hal/hal_defs.h"
#define RMT_LL_HW_BASE (&RMT)
#define RMT_LL_MEM_BASE (&RMTMEM)
@ -89,12 +90,12 @@ static inline uint32_t rmt_ll_get_mem_blocks(rmt_dev_t *dev, uint32_t channel)
static inline void rmt_ll_set_counter_clock_div(rmt_dev_t *dev, uint32_t channel, uint32_t div)
{
dev->conf_ch[channel].conf0.div_cnt = div;
HAL_FORCE_MODIFY_U32_REG_FIELD(dev->conf_ch[channel].conf0, div_cnt, div);
}
static inline uint32_t rmt_ll_get_counter_clock_div(rmt_dev_t *dev, uint32_t channel)
{
uint32_t div = dev->conf_ch[channel].conf0.div_cnt;
uint32_t div = HAL_FORCE_READ_U32_REG_FIELD(dev->conf_ch[channel].conf0, div_cnt);
return div == 0 ? 256 : div;
}
@ -110,12 +111,12 @@ static inline void rmt_ll_enable_mem_access(rmt_dev_t *dev, bool enable)
static inline void rmt_ll_set_rx_idle_thres(rmt_dev_t *dev, uint32_t channel, uint32_t thres)
{
dev->conf_ch[channel].conf0.idle_thres = thres;
HAL_FORCE_MODIFY_U32_REG_FIELD(dev->conf_ch[channel].conf0, idle_thres, thres);
}
static inline uint32_t rmt_ll_get_rx_idle_thres(rmt_dev_t *dev, uint32_t channel)
{
return dev->conf_ch[channel].conf0.idle_thres;
return HAL_FORCE_READ_U32_REG_FIELD(dev->conf_ch[channel].conf0, idle_thres);
}
static inline void rmt_ll_set_mem_owner(rmt_dev_t *dev, uint32_t channel, uint8_t owner)
@ -177,7 +178,7 @@ static inline void rmt_ll_enable_rx_filter(rmt_dev_t *dev, uint32_t channel, boo
static inline void rmt_ll_set_rx_filter_thres(rmt_dev_t *dev, uint32_t channel, uint32_t thres)
{
dev->conf_ch[channel].conf1.rx_filter_thres = thres;
HAL_FORCE_MODIFY_U32_REG_FIELD(dev->conf_ch[channel].conf1, rx_filter_thres, thres);
}
static inline void rmt_ll_set_counter_clock_src(rmt_dev_t *dev, uint32_t channel, uint8_t src)
@ -346,8 +347,8 @@ static inline void rmt_ll_set_rx_carrier_high_low_ticks(rmt_dev_t *dev, uint32_t
static inline void rmt_ll_get_carrier_high_low_ticks(rmt_dev_t *dev, uint32_t channel, uint32_t *high_ticks, uint32_t *low_ticks)
{
*high_ticks = dev->carrier_duty_ch[channel].high;
*low_ticks = dev->carrier_duty_ch[channel].low;
*high_ticks = HAL_FORCE_READ_U32_REG_FIELD(dev->carrier_duty_ch[channel], high);
*low_ticks = HAL_FORCE_READ_U32_REG_FIELD(dev->carrier_duty_ch[channel], low);
}
// This function has different meaning for TX and RX

View File

@ -55,7 +55,7 @@ static inline void sigmadelta_ll_set_en(gpio_sd_dev_t *hw, bool en)
*/
static inline void sigmadelta_ll_set_duty(gpio_sd_dev_t *hw, sigmadelta_channel_t channel, int8_t duty)
{
hw->channel[channel].duty = duty;
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->channel[channel], duty, (uint32_t)duty);
}
/**
@ -67,7 +67,7 @@ static inline void sigmadelta_ll_set_duty(gpio_sd_dev_t *hw, sigmadelta_channel_
*/
static inline void sigmadelta_ll_set_prescale(gpio_sd_dev_t *hw, sigmadelta_channel_t channel, uint8_t prescale)
{
hw->channel[channel].prescale = prescale;
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->channel[channel], prescale, prescale);
}
#ifdef __cplusplus

View File

@ -51,7 +51,7 @@ static inline void timer_ll_set_divider(timg_dev_t *hw, timer_idx_t timer_num, u
}
int timer_en = hw->hw_timer[timer_num].config.enable;
hw->hw_timer[timer_num].config.enable = 0;
hw->hw_timer[timer_num].config.divider = divider;
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->hw_timer[timer_num].config, divider, divider);
hw->hw_timer[timer_num].config.enable = timer_en;
}
@ -66,7 +66,7 @@ static inline void timer_ll_set_divider(timg_dev_t *hw, timer_idx_t timer_num, u
*/
static inline void timer_ll_get_divider(timg_dev_t *hw, timer_idx_t timer_num, uint32_t *divider)
{
uint32_t d = hw->hw_timer[timer_num].config.divider;
uint32_t d = HAL_FORCE_READ_U32_REG_FIELD(hw->hw_timer[timer_num].config, divider);
if (d == 0) {
d = 65536;
}

View File

@ -495,8 +495,8 @@ static inline void twai_ll_set_acc_filter(twai_dev_t* hw, uint32_t code, uint32_
uint32_t code_swapped = __builtin_bswap32(code);
uint32_t mask_swapped = __builtin_bswap32(mask);
for (int i = 0; i < 4; i++) {
hw->acceptance_filter.acr[i].byte = ((code_swapped >> (i * 8)) & 0xFF);
hw->acceptance_filter.amr[i].byte = ((mask_swapped >> (i * 8)) & 0xFF);
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->acceptance_filter.acr[i], byte, ((code_swapped >> (i * 8)) & 0xFF));
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->acceptance_filter.amr[i], byte, ((mask_swapped >> (i * 8)) & 0xFF));
}
hw->mode_reg.afm = single_filter;
}
@ -531,7 +531,7 @@ static inline void twai_ll_get_rx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t
{
//Copy RX buffer registers into frame
for (int i = 0; i < 13; i++) {
rx_frame->bytes[i] = hw->tx_rx_buffer[i].byte;
rx_frame->bytes[i] = HAL_FORCE_READ_U32_REG_FIELD(hw->tx_rx_buffer[i], byte);
}
}