devices: constify statically initialized device pointers

It is frequent to find variable definitions like this:

```c
static const struct device *dev = DEVICE_DT_GET(...)
```

That is, module level variables that are statically initialized with a
device reference. Such value is, in most cases, never changed meaning
the variable can also be declared as const (immutable). This patch
constifies all such cases.

Signed-off-by: Gerard Marull-Paretas <gerard.marull@nordicsemi.no>
This commit is contained in:
Gerard Marull-Paretas 2022-08-17 15:37:22 +02:00 committed by Carles Cufí
parent 42b53e46aa
commit e0125d04af
48 changed files with 56 additions and 53 deletions

View file

@ -34,7 +34,7 @@ const void *x86_irq_args[NR_IRQ_VECTORS];
#include <zephyr/device.h>
#include <zephyr/drivers/interrupt_controller/intel_vtd.h>
static const struct device *vtd = DEVICE_DT_GET_ONE(intel_vt_d);
static const struct device *const vtd = DEVICE_DT_GET_ONE(intel_vt_d);
#endif /* CONFIG_INTEL_VTD_ICTL */

View file

@ -164,7 +164,7 @@ void pcie_conf_write(pcie_bdf_t bdf, unsigned int reg, uint32_t data)
#include <zephyr/drivers/interrupt_controller/intel_vtd.h>
#include <zephyr/arch/x86/acpi.h>
static const struct device *vtd = DEVICE_DT_GET_ONE(intel_vt_d);
static const struct device *const vtd = DEVICE_DT_GET_ONE(intel_vt_d);
#endif /* CONFIG_INTEL_VTD_ICTL */

View file

@ -372,7 +372,7 @@ static int adc_gd32_init(const struct device *dev)
}
#define HANDLE_SHARED_IRQ(n, active_irq) \
static const struct device *dev_##n = DEVICE_DT_INST_GET(n); \
static const struct device *const dev_##n = DEVICE_DT_INST_GET(n); \
const struct adc_gd32_config *cfg_##n = dev_##n->config; \
\
if ((cfg_##n->irq_num == active_irq) && \

View file

@ -1185,7 +1185,8 @@ bool adc_stm32_is_irq_active(ADC_TypeDef *adc)
}
#define HANDLE_IRQS(index) \
static const struct device *dev_##index = DEVICE_DT_INST_GET(index); \
static const struct device *const dev_##index = \
DEVICE_DT_INST_GET(index); \
const struct adc_stm32_cfg *cfg_##index = dev_##index->config; \
ADC_TypeDef *adc_##index = (ADC_TypeDef *)(cfg_##index->base); \
\

View file

@ -143,7 +143,8 @@ static void dma_stm32_irq_handler(const struct device *dev, uint32_t id)
#ifdef CONFIG_DMA_STM32_SHARED_IRQS
#define HANDLE_IRQS(index) \
static const struct device *dev_##index = DEVICE_DT_INST_GET(index); \
static const struct device *const dev_##index = \
DEVICE_DT_INST_GET(index); \
const struct dma_stm32_config *cfg_##index = dev_##index->config; \
DMA_TypeDef *dma_##index = (DMA_TypeDef *)(cfg_##index->base); \
\

View file

@ -26,7 +26,7 @@
*/
BUILD_ASSERT(BUF_ARRAY_CNT >= 1);
static const struct device *zephyr_flash_controller =
static const struct device *const zephyr_flash_controller =
DEVICE_DT_GET_OR_NULL(DT_CHOSEN(zephyr_flash_controller));
static uint8_t __aligned(4) test_arr[TEST_ARR_SIZE];

View file

@ -97,7 +97,7 @@ static void gpio_xlnx_ps_isr(const struct device *dev)
#define GPIO_XLNX_PS_CHILD_CONCAT(idx) DEVICE_DT_GET(idx),
#define GPIO_XLNX_PS_GEN_BANK_ARRAY(idx)\
static const struct device *gpio_xlnx_ps##idx##_banks[] = {\
static const struct device *const gpio_xlnx_ps##idx##_banks[] = {\
DT_FOREACH_CHILD_STATUS_OKAY(DT_DRV_INST(idx), GPIO_XLNX_PS_CHILD_CONCAT)\
};

View file

@ -19,7 +19,7 @@
*
* Entries will be NULL if the GPIO port is not enabled.
*/
static const struct device * const gpio_ports[] = {
static const struct device *const gpio_ports[] = {
DEVICE_DT_GET_OR_NULL(DT_NODELABEL(gpioa)),
DEVICE_DT_GET_OR_NULL(DT_NODELABEL(gpiob)),
DEVICE_DT_GET_OR_NULL(DT_NODELABEL(gpioc)),

View file

@ -22,7 +22,7 @@ BUILD_ASSERT(DT_NUM_INST_STATUS_OKAY(DT_DRV_COMPAT) == 1,
#define SD0_WP_CD_SEL_OFFSET 0x0130
#define SD1_WP_CD_SEL_OFFSET 0x0134
static const struct device *slcr = DEVICE_DT_GET(DT_INST_PHANDLE(0, syscon));
static const struct device *const slcr = DEVICE_DT_GET(DT_INST_PHANDLE(0, syscon));
static mm_reg_t base = DT_INST_REG_ADDR(0);
K_SEM_DEFINE(pinctrl_lock, 1, 1);

View file

@ -42,7 +42,7 @@ static const struct stm32_pclken lptim_clk[] = {
static const struct stm32_pclken lptim_clk[] = STM32_DT_INST_CLOCKS(0);
#endif
static const struct device *clk_ctrl = DEVICE_DT_GET(STM32_CLOCK_CONTROL_NODE);
static const struct device *const clk_ctrl = DEVICE_DT_GET(STM32_CLOCK_CONTROL_NODE);
/*
* Assumptions and limitations:

View file

@ -30,7 +30,7 @@ static int8_t value = DEFAULT_TEMPERATURE;
#if defined(CONFIG_NRF_802154_TEMPERATURE_UPDATE)
static const struct device *device = DEVICE_DT_GET(DT_NODELABEL(temp));
static const struct device *const device = DEVICE_DT_GET(DT_NODELABEL(temp));
static struct k_work_delayable dwork;
static void work_handler(struct k_work *work)

View file

@ -19,7 +19,7 @@ LOG_MODULE_REGISTER(net_otPlat_entropy, CONFIG_OPENTHREAD_L2_LOG_LEVEL);
#error OpenThread requires an entropy source for a TRNG
#endif
static const struct device *dev = DEVICE_DT_GET(DT_CHOSEN(zephyr_entropy));
static const struct device *const dev = DEVICE_DT_GET(DT_CHOSEN(zephyr_entropy));
otError otPlatEntropyGet(uint8_t *aOutput, uint16_t aOutputLength)
{

View file

@ -31,7 +31,7 @@
#if defined(CONFIG_SOC_FLASH_MCUX) || defined(CONFIG_SOC_FLASH_LPC) || \
defined(CONFIG_SOC_FLASH_STM32)
static const struct device *flash_dev = DEVICE_DT_GET(DT_CHOSEN(zephyr_flash_controller));
static const struct device *const flash_dev = DEVICE_DT_GET(DT_CHOSEN(zephyr_flash_controller));
#endif
static int cmd_read(const struct shell *shell, size_t argc, char *argv[])

View file

@ -83,7 +83,7 @@ const static struct spi_buf_set tx_bufs = {
* This is the SPI bus controller device used to exchange data with
* the SPI-based BT controller.
*/
static const struct device *spi_hci_dev = DEVICE_DT_GET(DT_BUS(HCI_SPI_NODE));
static const struct device *const spi_hci_dev = DEVICE_DT_GET(DT_BUS(HCI_SPI_NODE));
static struct spi_config spi_cfg = {
.operation = SPI_WORD_SET(8) | SPI_OP_MODE_SLAVE,
};

View file

@ -30,7 +30,7 @@
#define LOG_MODULE_NAME hci_uart
LOG_MODULE_REGISTER(LOG_MODULE_NAME);
static const struct device *hci_uart_dev =
static const struct device *const hci_uart_dev =
DEVICE_DT_GET(DT_CHOSEN(zephyr_bt_c2h_uart));
static K_THREAD_STACK_DEFINE(tx_thread_stack, CONFIG_BT_HCI_TX_STACK_SIZE);
static struct k_thread tx_thread_data;

View file

@ -37,7 +37,7 @@
#define LED0_PIN DT_PHA(LED0, gpios, pin)
#define LED0_FLAGS DT_PHA(LED0, gpios, flags)
static const struct device *led_dev = DEVICE_DT_GET(LED0_DEV);
static const struct device *const led_dev = DEVICE_DT_GET(LED0_DEV);
#endif /* LED0 */
#if DT_NODE_EXISTS(BUTTON0)
@ -45,7 +45,7 @@ static const struct device *led_dev = DEVICE_DT_GET(LED0_DEV);
#define BUTTON0_PIN DT_PHA(BUTTON0, gpios, pin)
#define BUTTON0_FLAGS DT_PHA(BUTTON0, gpios, flags)
static const struct device *button_dev = DEVICE_DT_GET(BUTTON0_DEV);
static const struct device *const button_dev = DEVICE_DT_GET(BUTTON0_DEV);
static struct k_work *button_work;
static void button_cb(const struct device *port, struct gpio_callback *cb,

View file

@ -32,9 +32,10 @@ static const struct gpio_dt_spec button_a =
GPIO_DT_SPEC_GET(DT_NODELABEL(buttona), gpios);
static const struct gpio_dt_spec button_b =
GPIO_DT_SPEC_GET(DT_NODELABEL(buttonb), gpios);
static const struct device *nvm =
static const struct device *const nvm =
DEVICE_DT_GET(DT_CHOSEN(zephyr_flash_controller));
static const struct device *pwm = DEVICE_DT_GET_ANY(nordic_nrf_sw_pwm);
static const struct device *const pwm =
DEVICE_DT_GET_ANY(nordic_nrf_sw_pwm);
static struct k_work button_work;

View file

@ -86,7 +86,7 @@ void main(void)
}
#ifdef CONFIG_LP3943
static const struct device *ledc = DEVICE_DT_GET_ONE(ti_lp3943);
static const struct device *const ledc = DEVICE_DT_GET_ONE(ti_lp3943);
if (!device_is_ready(ledc)) {
printk("Device %s is not ready\n", ledc->name);

View file

@ -29,7 +29,7 @@
#define SNVS_LP_RTC_ALARM_ID 1
static const struct gpio_dt_spec button = GPIO_DT_SPEC_GET_OR(SW0_NODE, gpios, { 0 });
static const struct device *snvs_rtc_dev = DEVICE_DT_GET(SNVS_RTC_NODE);
static const struct device *const snvs_rtc_dev = DEVICE_DT_GET(SNVS_RTC_NODE);
void main(void)
{

View file

@ -14,8 +14,8 @@
#define UPDATE_INTERVAL_S 10
static const struct device *clock0 = DEVICE_DT_GET_ONE(nordic_nrf_clock);
static const struct device *timer0 = DEVICE_DT_GET(DT_NODELABEL(timer0));
static const struct device *const clock0 = DEVICE_DT_GET_ONE(nordic_nrf_clock);
static const struct device *const timer0 = DEVICE_DT_GET(DT_NODELABEL(timer0));
static struct timeutil_sync_config sync_config;
static uint64_t counter_ref;
static struct timeutil_sync_state sync_state;

View file

@ -12,7 +12,7 @@
#include <zephyr/bluetooth/mesh.h>
static const struct device *dev_info[] = {
static const struct device *const dev_info[] = {
DEVICE_DT_GET_ONE(ti_hdc1010),
DEVICE_DT_GET_ONE(nxp_mma8652fc),
DEVICE_DT_GET_ONE(avago_apds9960),

View file

@ -23,7 +23,7 @@
#define DAC_RESOLUTION 0
#endif
static const struct device *dac_dev = DEVICE_DT_GET(DAC_NODE);
static const struct device *const dac_dev = DEVICE_DT_GET(DAC_NODE);
static const struct dac_channel_cfg dac_ch_cfg = {
.channel_id = DAC_CHANNEL_ID,

View file

@ -38,7 +38,7 @@ static const struct led_rgb black = {
struct led_rgb strip_colors[STRIP_NUM_LEDS];
static const struct device *strip = DEVICE_DT_GET_ANY(greeled_lpd8806);
static const struct device *const strip = DEVICE_DT_GET_ANY(greeled_lpd8806);
const struct led_rgb *color_at(size_t time, size_t i)
{

View file

@ -33,7 +33,7 @@ static const struct led_rgb colors[] = {
struct led_rgb pixels[STRIP_NUM_PIXELS];
static const struct device *strip = DEVICE_DT_GET(STRIP_NODE);
static const struct device *const strip = DEVICE_DT_GET(STRIP_NODE);
void main(void)
{

View file

@ -18,7 +18,7 @@
/* queue to store up to 10 messages (aligned to 4-byte boundary) */
K_MSGQ_DEFINE(uart_msgq, MSG_SIZE, 10, 4);
static const struct device *uart_dev = DEVICE_DT_GET(UART_DEVICE_NODE);
static const struct device *const uart_dev = DEVICE_DT_GET(UART_DEVICE_NODE);
/* receive buffer used in UART ISR callback */
static char rx_buf[MSG_SIZE];

View file

@ -17,7 +17,7 @@
IF_ENABLED(DT_NODE_EXISTS(ACCEL_ALIAS(i)), (DEVICE_DT_GET(ACCEL_ALIAS(i)),))
/* support up to 10 accelerometer sensors */
static const struct device *sensors[] = {LISTIFY(10, ACCELEROMETER_DEVICE, ())};
static const struct device *const sensors[] = {LISTIFY(10, ACCELEROMETER_DEVICE, ())};
static const enum sensor_channel channels[] = {
SENSOR_CHAN_ACCEL_X,

View file

@ -13,8 +13,8 @@ const uint8_t DISPLAY_OFF[4] = { CHAR_OFF, CHAR_OFF, CHAR_OFF, CHAR_OFF };
const uint8_t TEXT_Err[4] = { CHAR_E, CHAR_r, CHAR_r, CHAR_OFF };
static bool initialized;
static const struct device *expander1 = DEVICE_DT_GET(DT_NODELABEL(expander1));
static const struct device *expander2 = DEVICE_DT_GET(DT_NODELABEL(expander2));
static const struct device *const expander1 = DEVICE_DT_GET(DT_NODELABEL(expander1));
static const struct device *const expander2 = DEVICE_DT_GET(DT_NODELABEL(expander2));
static const uint8_t digits[16] = {
CHAR_0,
CHAR_1,

View file

@ -29,7 +29,7 @@ typedef void (*fsm_state)(void);
static int64_t last_mode_change;
static const struct device *sensors[] = {
static const struct device *const sensors[] = {
DEVICE_DT_GET(DT_NODELABEL(vl53l0x_l)),
DEVICE_DT_GET(DT_NODELABEL(vl53l0x_c)),
DEVICE_DT_GET(DT_NODELABEL(vl53l0x_r)),

View file

@ -59,7 +59,7 @@ static struct {
} event;
/* Entropy device */
static const struct device *dev_entropy = DEVICE_DT_GET(DT_NODELABEL(rng));
static const struct device *const dev_entropy = DEVICE_DT_GET(DT_NODELABEL(rng));
static int init_reset(void);
#if defined(CONFIG_BT_CTLR_LOW_LAT_ULL_DONE)

View file

@ -52,7 +52,7 @@ static struct {
} event;
/* Entropy device */
static const struct device *dev_entropy = DEVICE_DT_GET(DT_CHOSEN(zephyr_entropy));
static const struct device *const dev_entropy = DEVICE_DT_GET(DT_CHOSEN(zephyr_entropy));
static int init_reset(void);
#if defined(CONFIG_BT_CTLR_LOW_LAT_ULL_DONE)

View file

@ -23,7 +23,7 @@ extern const struct device __device_end[];
extern const struct device __device_SMP_start[];
#endif
static const struct device *levels[] = {
static const struct device *const levels[] = {
__device_PRE_KERNEL_1_start,
__device_PRE_KERNEL_2_start,
__device_POST_KERNEL_start,

View file

@ -46,7 +46,7 @@ static const struct busy_sim_config sim_config = {
};
static struct busy_sim_data sim_data;
static const struct device *busy_sim_dev = DEVICE_DT_GET_ONE(vnd_busy_sim);
static const struct device *const busy_sim_dev = DEVICE_DT_GET_ONE(vnd_busy_sim);
static void rng_pool_work_handler(struct k_work *work)
{

View file

@ -25,7 +25,7 @@
#define STACKSIZE 1024
#define PRIORITY 7
static const struct device *flash_dev = DEVICE_DT_GET(DT_CHOSEN(zephyr_flash_controller));
static const struct device *const flash_dev = DEVICE_DT_GET(DT_CHOSEN(zephyr_flash_controller));
static struct flash_pages_info page_info;
static int *mem;
uint8_t flash_fill_buff[FLASH_READBACK_LEN];

View file

@ -25,7 +25,7 @@
#define FXOS8700_CTRLREG2_RST_MASK 0x40
static const struct device *i2c_bus = DEVICE_DT_GET(DT_NODELABEL(i2c0));
static const struct device *const i2c_bus = DEVICE_DT_GET(DT_NODELABEL(i2c0));
/**
* Setup and enable the fxos8700 with its max sample rate and

View file

@ -31,7 +31,7 @@
/**
* @brief Global variables.
*/
static const struct device *can_dev = DEVICE_DT_GET(DT_CHOSEN(zephyr_canbus));
static const struct device *const can_dev = DEVICE_DT_GET(DT_CHOSEN(zephyr_canbus));
static struct k_sem rx_callback_sem;
static struct k_sem tx_callback_sem;

View file

@ -20,7 +20,7 @@ static bool test_end;
#include <hal/nrf_gpio.h>
static const struct device *entropy = DEVICE_DT_GET(DT_CHOSEN(zephyr_entropy));
static const struct device *const entropy = DEVICE_DT_GET(DT_CHOSEN(zephyr_entropy));
static struct onoff_manager *hf_mgr;
static uint32_t iteration;

View file

@ -27,7 +27,7 @@ struct counter_alarm_cfg alarm_cfg2;
#define DEVS_FOR_DT_COMPAT(compat) \
DT_FOREACH_STATUS_OKAY(compat, DEVICE_DT_GET_AND_COMMA)
static const struct device *devices[] = {
static const struct device *const devices[] = {
#ifdef CONFIG_COUNTER_TIMER0
/* Nordic TIMER0 may be reserved for Bluetooth */
DEVICE_DT_GET(DT_NODELABEL(timer0)),
@ -93,7 +93,7 @@ static const struct device *devices[] = {
#endif
};
static const struct device *period_devs[] = {
static const struct device *const period_devs[] = {
#ifdef CONFIG_COUNTER_MCUX_RTC
DEVS_FOR_DT_COMPAT(nxp_kinetis_rtc)
#endif

View file

@ -13,7 +13,7 @@ LOG_MODULE_REGISTER(test);
static volatile uint32_t top_cnt;
static const struct device *devices[] = {
static const struct device *const devices[] = {
#ifdef CONFIG_COUNTER_RTC0
/* Nordic RTC0 may be reserved for Bluetooth */
DEVICE_DT_GET(DT_NODELABEL(rtc0)),

View file

@ -24,7 +24,7 @@ void *exp_user_data = (void *)199;
struct counter_alarm_cfg alarm_cfg;
struct counter_alarm_cfg alarm_cfg2;
static const struct device *devices[] = {
static const struct device *const devices[] = {
DEVICE_DT_GET(DT_NODELABEL(ds3231)),
};
typedef void (*counter_test_func_t)(const struct device *dev);

View file

@ -47,7 +47,7 @@
#define EXPECTED_SIZE 256
#define CANARY 0xff
static const struct device *flash_dev = TEST_AREA_DEVICE;
static const struct device *const flash_dev = TEST_AREA_DEVICE;
static struct flash_pages_info page_info;
static uint8_t __aligned(4) expected[EXPECTED_SIZE];

View file

@ -32,7 +32,7 @@
(((((((0xff & pat) << 8) | (0xff & pat)) << 8) | \
(0xff & pat)) << 8) | (0xff & pat))
static const struct device *flash_dev = DEVICE_DT_GET(DT_CHOSEN(zephyr_flash_controller));
static const struct device *const flash_dev = DEVICE_DT_GET(DT_CHOSEN(zephyr_flash_controller));
static uint8_t test_read_buf[TEST_SIM_FLASH_SIZE];
static uint32_t p32_inc;

View file

@ -14,7 +14,7 @@
* @}
*/
static const struct device *mipi_dev = DEVICE_DT_GET(DT_ALIAS(mipi_dsi));
static const struct device *const mipi_dev = DEVICE_DT_GET(DT_ALIAS(mipi_dsi));
/**
* Test the MIPI generic APIs to test read and write API functionality

View file

@ -23,7 +23,7 @@ BUILD_ASSERT(DT_NODE_HAS_COMPAT_STATUS(CHECK_NODE, test_regulator_fixed, okay));
static const struct gpio_dt_spec reg_gpio = GPIO_DT_SPEC_GET(REGULATOR_NODE, enable_gpios);
static const struct gpio_dt_spec check_gpio = GPIO_DT_SPEC_GET(CHECK_NODE, check_gpios);
static const struct device *reg_dev = DEVICE_DT_GET(REGULATOR_NODE);
static const struct device *const reg_dev = DEVICE_DT_GET(REGULATOR_NODE);
static enum {
PC_UNCHECKED,

View file

@ -9,7 +9,7 @@
#include <zephyr/device.h>
#include <zephyr/ztest.h>
static const struct device *sdhc_dev = DEVICE_DT_GET(DT_ALIAS(sdhc0));
static const struct device *const sdhc_dev = DEVICE_DT_GET(DT_ALIAS(sdhc0));
static struct sdhc_host_props props;
static struct sdhc_io io;

View file

@ -33,7 +33,7 @@
#define TEST_DATA_ID 1
#define TEST_SECTOR_COUNT 5U
static const struct device *flash_dev = DEVICE_DT_GET(TEST_NVS_FLASH_DEV_NODE);
static const struct device *const flash_dev = DEVICE_DT_GET(TEST_NVS_FLASH_DEV_NODE);
struct nvs_fixture {
struct nvs_fs fs;

View file

@ -83,7 +83,7 @@ static int init_mock(const struct device *dev)
#define DT_DRV_COMPAT vnd_ieee802154
DEVICE_DT_INST_DEFINE(0, init_mock, NULL, NULL, NULL, POST_KERNEL, 0, &rapi);
static const struct device *radio = DEVICE_DT_INST_GET(0);
static const struct device *const radio = DEVICE_DT_INST_GET(0);
static int16_t rssi_scan_mock_max_ed;
static int rssi_scan_mock(const struct device *dev, uint16_t duration,

View file

@ -14,7 +14,7 @@
#define SECTOR_COUNT 32
#define SECTOR_SIZE 512 /* subsystem should set all cards to 512 byte blocks */
#define BUF_SIZE SECTOR_SIZE * SECTOR_COUNT
static const struct device *sdhc_dev = DEVICE_DT_GET(DT_ALIAS(sdhc0));
static const struct device *const sdhc_dev = DEVICE_DT_GET(DT_ALIAS(sdhc0));
static struct sd_card card;
static uint8_t buf[BUF_SIZE] __aligned(CONFIG_SDHC_BUFFER_ALIGNMENT);
static uint8_t check_buf[BUF_SIZE] __aligned(CONFIG_SDHC_BUFFER_ALIGNMENT);

View file

@ -24,7 +24,7 @@
#define FLASH_BASE (128*1024)
#define FLASH_AVAILABLE (FLASH_SIZE-FLASH_BASE)
static const struct device *fdev = DEVICE_DT_GET(DT_CHOSEN(zephyr_flash_controller));
static const struct device *const fdev = DEVICE_DT_GET(DT_CHOSEN(zephyr_flash_controller));
static const struct flash_driver_api *api;
static const struct flash_pages_layout *layout;
static size_t layout_size;