style: add missing curly braces in if/while/for statements.

Add missing curly braces in if/while/for statements.

This is a style guideline we have that was not enforced in CI. All
issues fixed here were detected by sonarqube SCA.

Signed-off-by: Anas Nashif <anas.nashif@intel.com>
This commit is contained in:
Anas Nashif 2025-05-09 09:28:09 -04:00 committed by Benjamin Cabé
commit 2aacbcaab5
23 changed files with 80 additions and 55 deletions

View file

@ -92,8 +92,8 @@ static void arc_cluster_scm_enable(void)
/* Invalidate SCM before enabling. */
arc_cln_write_reg_nolock(ARC_CLN_CACHE_CMD,
ARC_CLN_CACHE_CMD_OP_REG_INV | ARC_CLN_CACHE_CMD_INCR);
while (arc_cln_read_reg_nolock(ARC_CLN_CACHE_STATUS) & ARC_CLN_CACHE_STATUS_BUSY)
;
while (arc_cln_read_reg_nolock(ARC_CLN_CACHE_STATUS) & ARC_CLN_CACHE_STATUS_BUSY) {
}
arc_cln_write_reg_nolock(ARC_CLN_CACHE_STATUS, ARC_CLN_CACHE_STATUS_EN);
}

View file

@ -207,24 +207,28 @@ static bool is_address_mapped(uint64_t *addr)
{
uintptr_t *phys = NULL;
if (*addr == 0U)
if (*addr == 0U) {
return false;
}
/* Check alignment. */
if ((*addr & (sizeof(uint32_t) - 1U)) != 0U)
if ((*addr & (sizeof(uint32_t) - 1U)) != 0U) {
return false;
}
return !arch_page_phys_get((void *) addr, phys);
}
static bool is_valid_jump_address(uint64_t *addr)
{
if (*addr == 0U)
if (*addr == 0U) {
return false;
}
/* Check alignment. */
if ((*addr & (sizeof(uint32_t) - 1U)) != 0U)
if ((*addr & (sizeof(uint32_t) - 1U)) != 0U) {
return false;
}
return ((*addr >= (uint64_t)__text_region_start) &&
(*addr <= (uint64_t)(__text_region_end)));
@ -266,8 +270,9 @@ static void walk_stackframe(arm64_stacktrace_cb cb, void *cookie, const struct a
if (!is_address_mapped(fp))
break;
lr = fp[1];
if (!is_valid_jump_address(&lr))
if (!is_valid_jump_address(&lr)) {
break;
}
if (!cb(cookie, lr, fp)) {
break;
}

View file

@ -52,8 +52,9 @@ static void xtensa_elf_relocate(struct llext_loader *ldr, struct llext *ext,
for (sh_ndx = 0; sh_ndx < ext->sect_cnt; sh_ndx++) {
if (ext->sect_hdrs[sh_ndx].sh_addr <= *got_entry &&
*got_entry <
ext->sect_hdrs[sh_ndx].sh_addr + ext->sect_hdrs[sh_ndx].sh_size)
ext->sect_hdrs[sh_ndx].sh_addr + ext->sect_hdrs[sh_ndx].sh_size) {
break;
}
}
if (sh_ndx == ext->sect_cnt) {

View file

@ -343,8 +343,8 @@ static int npcm_clock_control_init(const struct device *dev)
/* Load M and N values into the frequency multiplier */
priv->hfcgctrl |= BIT(NPCM_HFCGCTRL_LOAD);
/* Wait for stable */
while (sys_test_bit(priv->hfcgctrl, NPCM_HFCGCTRL_CLK_CHNG))
;
while (sys_test_bit(priv->hfcgctrl, NPCM_HFCGCTRL_CLK_CHNG)) {
}
}
/* Set all clock prescalers of core and peripherals. */

View file

@ -80,8 +80,8 @@ static int clock_control_si32_pll_on(const struct device *dev, clock_control_sub
SI32_PLL_A_select_dco_frequency_lock_mode(config->pll);
while (!(SI32_PLL_A_is_locked(config->pll) ||
SI32_PLL_A_is_saturation_low_interrupt_pending(config->pll) ||
SI32_PLL_A_is_saturation_high_interrupt_pending(config->pll)))
;
SI32_PLL_A_is_saturation_high_interrupt_pending(config->pll))) {
}
return 0;
}

View file

@ -73,8 +73,8 @@ static int counter_ra_agt_start(const struct device *dev)
reg->AGTCR = AGT_AGTCR_START_TIMER;
while (!(reg->AGTCR & BIT(R_AGTX0_AGT16_CTRL_AGTCR_TCSTF_Pos)) && likely(--timeout))
;
while (!(reg->AGTCR & BIT(R_AGTX0_AGT16_CTRL_AGTCR_TCSTF_Pos)) && likely(--timeout)) {
}
return timeout > 0 ? 0 : -EIO;
}
@ -86,8 +86,8 @@ static int counter_ra_agt_stop(const struct device *dev)
reg->AGTCR = AGT_AGTCR_STOP_TIMER;
while ((reg->AGTCR & BIT(R_AGTX0_AGT16_CTRL_AGTCR_TCSTF_Pos)) && likely(--timeout))
;
while ((reg->AGTCR & BIT(R_AGTX0_AGT16_CTRL_AGTCR_TCSTF_Pos)) && likely(--timeout)) {
}
return timeout > 0 ? 0 : -EIO;
}

View file

@ -659,8 +659,9 @@ static int dma_mcux_edma_reload(const struct device *dev, uint32_t channel,
/* Previous TCD index in circular list */
pre_idx = data->transfer_settings.write_idx - 1;
if (pre_idx >= CONFIG_DMA_TCD_QUEUE_SIZE)
if (pre_idx >= CONFIG_DMA_TCD_QUEUE_SIZE) {
pre_idx = CONFIG_DMA_TCD_QUEUE_SIZE - 1;
}
/* Configure a TCD for the transfer */
tcd = &(DEV_CFG(dev)->tcdpool[channel][data->transfer_settings.write_idx]);

View file

@ -82,12 +82,13 @@ static int dma_nxp_sdma_consume(struct sdma_channel_data *chan_data, uint32_t by
chan_data->stat.read_position += bytes;
chan_data->stat.read_position %= chan_data->capacity;
if (chan_data->stat.read_position > chan_data->stat.write_position)
if (chan_data->stat.read_position > chan_data->stat.write_position) {
chan_data->stat.free = chan_data->stat.read_position -
chan_data->stat.write_position;
else
} else {
chan_data->stat.free = chan_data->capacity -
(chan_data->stat.write_position - chan_data->stat.read_position);
}
chan_data->stat.pending_length = chan_data->capacity - chan_data->stat.free;
@ -102,12 +103,13 @@ static int dma_nxp_sdma_produce(struct sdma_channel_data *chan_data, uint32_t by
chan_data->stat.write_position += bytes;
chan_data->stat.write_position %= chan_data->capacity;
if (chan_data->stat.write_position > chan_data->stat.read_position)
if (chan_data->stat.write_position > chan_data->stat.read_position) {
chan_data->stat.pending_length = chan_data->stat.write_position -
chan_data->stat.read_position;
else
} else {
chan_data->stat.pending_length = chan_data->capacity -
(chan_data->stat.read_position - chan_data->stat.write_position);
}
chan_data->stat.free = chan_data->capacity - chan_data->stat.pending_length;
@ -389,13 +391,15 @@ static int dma_nxp_sdma_reload(const struct device *dev, uint32_t channel, uint3
chan_data = &dev_data->chan[channel];
if (!size)
if (!size) {
return 0;
}
if (chan_data->direction == MEMORY_TO_PERIPHERAL)
if (chan_data->direction == MEMORY_TO_PERIPHERAL) {
dma_nxp_sdma_produce(chan_data, size);
else
} else {
dma_nxp_sdma_consume(chan_data, size);
}
return 0;
}
@ -424,11 +428,13 @@ static bool sdma_channel_filter(const struct device *dev, int chan_id, void *par
struct sdma_dev_data *dev_data = dev->data;
/* chan 0 is reserved for boot channel */
if (chan_id == 0)
if (chan_id == 0) {
return false;
}
if (chan_id >= FSL_FEATURE_SDMA_MODULE_CHANNEL)
if (chan_id >= FSL_FEATURE_SDMA_MODULE_CHANNEL) {
return false;
}
dev_data->chan[chan_id].event_source = *((int *)param);
dev_data->chan[chan_id].index = chan_id;

View file

@ -997,11 +997,12 @@ static int espi_npcx_send_oob(const struct device *dev,
/* Write GET_OOB data into 32-bits tx buffer in little endian */
for (idx_tx_buf = 0; idx_tx_buf < sz_oob_tx/4; idx_tx_buf++,
oob_buf += 4)
oob_buf += 4) {
inst->OOBTXBUF[idx_tx_buf + 1] = oob_buf[0]
| (oob_buf[1] << 8)
| (oob_buf[2] << 16)
| (oob_buf[3] << 24);
}
/* Write remaining bytes of package */
if (sz_oob_tx % 4) {

View file

@ -274,10 +274,11 @@ static int i2s_stm32_configure(const struct device *dev, enum i2s_dir dir,
}
/* set I2S clock polarity */
if ((i2s_cfg->format & I2S_FMT_CLK_FORMAT_MASK) == I2S_FMT_BIT_CLK_INV)
if ((i2s_cfg->format & I2S_FMT_CLK_FORMAT_MASK) == I2S_FMT_BIT_CLK_INV) {
LL_I2S_SetClockPolarity(cfg->i2s, LL_I2S_POLARITY_HIGH);
else
} else {
LL_I2S_SetClockPolarity(cfg->i2s, LL_I2S_POLARITY_LOW);
}
stream->state = I2S_STATE_READY;
return 0;

View file

@ -266,8 +266,8 @@ void soc_interrupt_init(void)
wdt_regs->EWDKEYR = 0;
/* Spin and wait for reboot */
while (1)
;
while (1) {
}
} else {
/* Disable ETWD hardware reset */
gctrl_regs->GCTRL_ETWDUARTCR &= ~IT8XXX2_GCTRL_ETWD_HW_RST_EN;

View file

@ -75,8 +75,8 @@ IRAM_ATTR static void esp32_mbox_isr(const struct device *dev)
/* first of all take the ownership of the shared memory */
while (!atomic_cas(&dev_data->control->lock, ESP32_MBOX_LOCK_FREE_VAL,
dev_data->this_core_id))
;
dev_data->this_core_id)) {
}
if (dev_data->cb) {
/* For ESP32 soft mbox driver, the message parameter of the callback holds
@ -224,8 +224,8 @@ static int esp32_mbox_init(const struct device *dev)
LOG_DBG("Waiting CPU0 to sync");
while (!atomic_cas(&data->control->lock, ESP32_MBOX_LOCK_FREE_VAL,
data->this_core_id))
;
data->this_core_id)) {
}
atomic_set(&data->control->lock, ESP32_MBOX_LOCK_FREE_VAL);

View file

@ -74,8 +74,8 @@ static int afio_init(void)
#ifdef AFIO_CPSCTL
if (DT_PROP(AFIO_NODE, enable_cps)) {
gpio_compensation_config(GPIO_COMPENSATION_ENABLE);
while (gpio_compensation_flag_get() == RESET)
;
while (gpio_compensation_flag_get() == RESET) {
}
}
#endif /* AFIO_CPSCTL */

View file

@ -173,8 +173,9 @@ static int lis2dux12_sample_fetch(const struct device *dev, enum sensor_channel
#endif
case SENSOR_CHAN_ALL:
ret = chip_api->sample_fetch_accel(dev);
if (ret != 0)
if (ret != 0) {
break;
}
#if defined(CONFIG_LIS2DUX12_ENABLE_TEMP)
ret = chip_api->sample_fetch_temp(dev);
#endif

View file

@ -128,8 +128,8 @@ static int kb1200_uart_fifo_fill(const struct device *dev, const uint8_t *tx_dat
while ((size - tx_bytes) > 0) {
/* Check Tx FIFO not Full*/
while (config->ser->SERSTS & SERSTS_TX_FULL)
;
while (config->ser->SERSTS & SERSTS_TX_FULL) {
}
/* Put a character into Tx FIFO */
config->ser->SERTBUF = tx_data[tx_bytes];
tx_bytes++;
@ -276,7 +276,6 @@ static void kb1200_uart_poll_out(const struct device *dev, unsigned char c)
/* Wait Tx FIFO not Full*/
while (config->ser->SERSTS & SER_TxFull) {
;
}
/* Put a character into Tx FIFO */
config->ser->SERTBUF = c;

View file

@ -129,8 +129,8 @@ static int uart_ambiq_pm_action(const struct device *dev, enum pm_device_action
return 0;
case PM_DEVICE_ACTION_SUSPEND:
while ((get_uart(dev)->fr & PL011_FR_BUSY) != 0)
;
while ((get_uart(dev)->fr & PL011_FR_BUSY) != 0) {
}
/* Preserve UART registers*/
key = irq_lock();

View file

@ -2052,8 +2052,9 @@ static int device_wlan_pm_action(const struct device *dev, enum pm_device_action
#ifdef CONFIG_NXP_WIFI_WMM_UAPSD
|| wlan_is_wmm_uapsd_enabled()
#endif
)
) {
return -EBUSY;
}
/*
* Trigger host sleep handshake here. Before handshake is done, host is not allowed
* to enter low power mode

View file

@ -180,8 +180,9 @@ static inline bool is_el_highest_implemented(void)
curr_el = GET_EL(read_currentel());
if (curr_el < el_highest)
if (curr_el < el_highest) {
return false;
}
return true;
}

View file

@ -112,8 +112,9 @@ static inline void irq_set_priority_next_level(const struct device *dev,
const struct irq_next_level_api *api =
(const struct irq_next_level_api *)dev->api;
if (api->intr_set_priority)
if (api->intr_set_priority) {
api->intr_set_priority(dev, irq, prio, flags);
}
}
/**

View file

@ -445,8 +445,9 @@ static inline uint32_t crc_by_type(enum crc_type type, const uint8_t *src, size_
case CRC24_PGP: {
uint32_t crc = crc24_pgp_update(seed, src, len);
if (last)
if (last) {
crc &= CRC24_FINAL_VALUE_MASK;
}
return crc;
}
case CRC32_C:

View file

@ -830,13 +830,15 @@ static int wpas_add_and_config_network(struct wpa_supplicant *wpa_s,
if (params->TLS_cipher == WIFI_EAP_TLS_ECC_P384) {
if (!wpa_cli_cmd_v("set_network %d openssl_ciphers \"%s\"",
resp.network_id,
cipher_config.openssl_ciphers))
cipher_config.openssl_ciphers)) {
goto out;
}
} else if (params->TLS_cipher == WIFI_EAP_TLS_RSA_3K) {
snprintf(phase1, sizeof(phase1), "tls_suiteb=1");
if (!wpa_cli_cmd_v("set_network %d phase1 \"%s\"",
resp.network_id, &phase1[0]))
resp.network_id, &phase1[0])) {
goto out;
}
}
}

View file

@ -89,8 +89,9 @@ void test_fft_op(void)
int32_t fft_in[FFT_LENGTH];
/* Create input */
for (i = 0; i < FFT_LENGTH; i++)
for (i = 0; i < FFT_LENGTH; i++) {
fft_in[i] = FFT_LENGTH * (1 + i % 2); /* only real part */
}
printk("[Library Test] == Fast Fourier Transform on Real Data test ==\r\n");
start = k_cycle_get_32();
@ -124,12 +125,15 @@ void test_fir_blms_op(void)
int32_t fir_in[FIR_LENGTH];
int32_t fir_ref[FIR_LENGTH + FIR_M];
for (i = 0; i < FIR_M; i++)
for (i = 0; i < FIR_M; i++) {
fir_coef[i] = fir_coef_ref[i];
for (i = 0; i < FIR_LENGTH; i++)
}
for (i = 0; i < FIR_LENGTH; i++) {
fir_in[i] = fir_in_ref[i];
for (i = 0; i < FIR_LENGTH + FIR_M; i++)
}
for (i = 0; i < FIR_LENGTH + FIR_M; i++) {
fir_ref[i] = fir_ref_ref[i];
}
printk("[Library Test] == Least Mean Square (LMS) Filter for Real Data test ==\r\n");
start = k_cycle_get_32();

View file

@ -4289,8 +4289,8 @@ enum net_verdict tp_input(struct net_conn *net_conn,
conn = (void *)sys_slist_peek_head(&tcp_conns);
context = conn->context;
while (tcp_conn_close(conn, 0))
;
while (tcp_conn_close(conn, 0)) {
}
tcp_free(context);
}
tp_mem_stat();