From 56b1c95d299491277bdbf3b908d2c4ad080bf6c4 Mon Sep 17 00:00:00 2001 From: Sara Touqan Date: Tue, 29 Apr 2025 17:14:10 +0300 Subject: [PATCH 1/4] drivers: sdhc: Support SDHC SDIO driver for STM32 This commit introduces support for the SDHC driver on STM32, enabling functionality APIs for SDHC host controllers. Signed-off-by: Sara Touqan Signed-off-by: Mohammad Odeh --- drivers/sdhc/CMakeLists.txt | 1 + drivers/sdhc/Kconfig | 1 + drivers/sdhc/Kconfig.stm32 | 21 + drivers/sdhc/sdhc_stm32.c | 797 ++++++++++++++++++++++++++++++++++++ 4 files changed, 820 insertions(+) create mode 100644 drivers/sdhc/Kconfig.stm32 create mode 100644 drivers/sdhc/sdhc_stm32.c diff --git a/drivers/sdhc/CMakeLists.txt b/drivers/sdhc/CMakeLists.txt index 07b9834289b21..8ad9a7718b55c 100644 --- a/drivers/sdhc/CMakeLists.txt +++ b/drivers/sdhc/CMakeLists.txt @@ -16,4 +16,5 @@ zephyr_library_sources_ifdef(CONFIG_SDHC_RENESAS_RA sdhc_renesas_ra.c) zephyr_library_sources_ifdef(CONFIG_SDHC_MAX32 sdhc_max32.c) zephyr_library_sources_ifdef(CONFIG_SDHC_AMBIQ sdhc_ambiq.c) zephyr_library_sources_ifdef(CONFIG_XLNX_SDHC xlnx_sdhc.c) +zephyr_library_sources_ifdef(CONFIG_SDHC_STM32_SDIO sdhc_stm32.c) endif() diff --git a/drivers/sdhc/Kconfig b/drivers/sdhc/Kconfig index dc59cd37f501d..726f73830922b 100644 --- a/drivers/sdhc/Kconfig +++ b/drivers/sdhc/Kconfig @@ -21,6 +21,7 @@ source "drivers/sdhc/Kconfig.renesas_ra" source "drivers/sdhc/Kconfig.max32" source "drivers/sdhc/Kconfig.ambiq" source "drivers/sdhc/Kconfig.xlnx" +source "drivers/sdhc/Kconfig.stm32" config SDHC_INIT_PRIORITY int "SDHC driver init priority" diff --git a/drivers/sdhc/Kconfig.stm32 b/drivers/sdhc/Kconfig.stm32 new file mode 100644 index 0000000000000..01b5f4ac81d9d --- /dev/null +++ b/drivers/sdhc/Kconfig.stm32 @@ -0,0 +1,21 @@ +# Copyright (c) 2025 EXALT Technologies. +# SPDX-License-Identifier: Apache-2.0 + +config SDHC_STM32_SDIO + bool "STM32 SDMMC driver support for SDIO" + depends on DT_HAS_ST_STM32_SDIO_ENABLED + select USE_STM32_HAL_SDIO + select USE_STM32_LL_SDMMC + select SDHC_SUPPORTS_NATIVE_MODE + imply CACHE_MANAGEMENT if !SDHC_STM32_POLLING_SUPPORT && DCACHE + default y + help + Enable support for SDMMC on STM32 platforms for SDIO devices. + +config SDHC_BUFFER_ALIGNMENT + default 32 + +config SDHC_STM32_POLLING_SUPPORT + bool "STM32 SDHC Polling driver support" + help + Enables support for SDHC Polling mode on STM32 microcontrollers. diff --git a/drivers/sdhc/sdhc_stm32.c b/drivers/sdhc/sdhc_stm32.c new file mode 100644 index 0000000000000..1011066c13756 --- /dev/null +++ b/drivers/sdhc/sdhc_stm32.c @@ -0,0 +1,797 @@ +/* + * Copyright (c) 2025 EXALT Technologies. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#define DT_DRV_COMPAT st_stm32_sdio + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +LOG_MODULE_REGISTER(sdhc_stm32, CONFIG_SDHC_LOG_LEVEL); + +typedef void (*irq_config_func_t)(void); + +BUILD_ASSERT((CONFIG_SDHC_BUFFER_ALIGNMENT % sizeof(uint32_t)) == 0U); + +#define SDIO_OCR_SDIO_S18R BIT(24) /* SDIO OCR bit indicating support for 1.8V switching */ + +struct sdhc_stm32_config { + bool hw_flow_control; /* flag for enabling hardware flow control */ + bool support_1_8_v; /* flag indicating support for 1.8V signaling */ + unsigned int max_freq; /* Max bus frequency in Hz */ + unsigned int min_freq; /* Min bus frequency in Hz */ + uint8_t bus_width; /* Width of the SDIO bus */ + uint16_t clk_div; /* Clock divider value to configure SDIO clock speed */ + uint32_t power_delay_ms; /* power delay prop for the host in milliseconds */ + uint32_t reg_addr; /* Base address of the SDIO peripheral register block */ + SDIO_HandleTypeDef *hsd; /* Pointer to SDIO HAL handle */ + const struct stm32_pclken *pclken; /* Pointer to peripheral clock configuration */ + const struct pinctrl_dev_config *pcfg; /* Pointer to pin control configuration */ + struct gpio_dt_spec sdhi_on_gpio; /* Power pin to control the regulators used by card.*/ + struct gpio_dt_spec cd_gpio; /* Card detect GPIO pin */ + irq_config_func_t irq_config_func; /* IRQ config function */ +}; + +struct sdhc_stm32_data { + struct k_mutex bus_mutex; /* Sync between commands */ + struct sdhc_io host_io; /* Input/Output host configuration */ + uint32_t cmd_index; /* current command opcode */ + struct sdhc_host_props props; /* current host properties */ + struct k_sem device_sync_sem; /* Sync between device communication messages */ + void *sdio_dma_buf; /* DMA buffer for SDIO data transfer */ + uint32_t total_transfer_bytes; /* number of bytes transferred */ +}; + +/* + * Power on the card. + * + * This function toggles a GPIO to control the internal regulator used + * by the card device. It handles GPIO configuration and timing delays. + * + * @param dev Device structure pointer. + * + * @return 0 on success, non-zero code on failure. + */ +static int sdhi_power_on(const struct device *dev) +{ + int ret; + const struct sdhc_stm32_config *config = dev->config; + + if (!device_is_ready(config->sdhi_on_gpio.port)) { + LOG_ERR("Card is not ready"); + return -ENODEV; + } + + ret = gpio_pin_configure_dt(&config->sdhi_on_gpio, GPIO_OUTPUT_HIGH); + if (ret < 0) { + LOG_ERR("Card configuration failed, ret:%d", ret); + return ret; + } + + k_msleep(config->power_delay_ms); + return ret; +} + +/** + * Logs detailed SDIO error types using Zephyr's logging subsystem. + * + * This helper function queries the error status of an SDIO operation + * and reports specific error types using `LOG_ERR()`. + * In addition to logging, it also resets the `ErrorCode` field + * of the `SDIO_HandleTypeDef` to `HAL_SDIO_ERROR_NONE`. + * + * @param hsd Pointer to the SDIO handle. + */ +static void sdhc_stm32_log_err_type(SDIO_HandleTypeDef *hsd) +{ + uint32_t error_code = HAL_SDIO_GetError(hsd); + + if ((error_code & HAL_SDIO_ERROR_TIMEOUT) != 0U) { + LOG_ERR("SDIO Timeout"); + } + + if ((error_code & HAL_SDIO_ERROR_DATA_TIMEOUT) != 0U) { + LOG_ERR("SDIO Data Timeout"); + } + + if ((error_code & HAL_SDIO_ERROR_DATA_CRC_FAIL) != 0U) { + LOG_ERR("SDIO Data CRC"); + } + + if ((error_code & HAL_SDIO_ERROR_TX_UNDERRUN) != 0U) { + LOG_ERR("SDIO FIFO Transmit Underrun"); + } + + if ((error_code & HAL_SDIO_ERROR_RX_OVERRUN) != 0U) { + LOG_ERR("SDIO FIFO Receive Overrun"); + } + + if ((error_code & HAL_SDIO_ERROR_INVALID_CALLBACK) != 0U) { + LOG_ERR("SDIO Invalid Callback"); + } + + if ((error_code & SDMMC_ERROR_ADDR_MISALIGNED) != 0U) { + LOG_ERR("SDIO Misaligned address"); + } + + if ((error_code & SDMMC_ERROR_WRITE_PROT_VIOLATION) != 0U) { + LOG_ERR("Attempt to program a write protected block"); + } + + if ((error_code & SDMMC_ERROR_ILLEGAL_CMD) != 0U) { + LOG_ERR("Command is not legal for the card state"); + } + + hsd->ErrorCode = HAL_SDIO_ERROR_NONE; +} + +/** + * @brief No-operation callback for SDIO card identification. + * @param hsd: Pointer to an SDIO_HandleTypeDef structure that contains + * the configuration information for SDIO module. + * @retval HAL status + */ +static HAL_StatusTypeDef noop_identify_card_callback(SDIO_HandleTypeDef *hsd) +{ + ARG_UNUSED(hsd); + return HAL_OK; +} + +/** + * Initializes the SDIO peripheral with the configuration specified. + * + * This includes deinitializing any previous configuration, and applying + * parameters like clock edge, power saving, clock divider, hardware + * flow control and bus width. + * + * @param dev Pointer to the device structure for the SDIO peripheral. + * + * @return 0 on success, err code on failure. + */ +static int sdhc_stm32_sd_init(const struct device *dev) +{ + struct sdhc_stm32_data *data = dev->data; + const struct sdhc_stm32_config *config = dev->config; + SDIO_HandleTypeDef *hsd = config->hsd; + + data->host_io.bus_width = config->bus_width; + hsd->Instance = (MMC_TypeDef *) config->reg_addr; + + if (HAL_SDIO_DeInit(hsd) != HAL_OK) { + LOG_ERR("Failed to de-initialize the SDIO device"); + return -EIO; + } + + hsd->Init.ClockEdge = SDMMC_CLOCK_EDGE_FALLING; + hsd->Init.ClockPowerSave = SDMMC_CLOCK_POWER_SAVE_DISABLE; + hsd->Init.ClockDiv = config->clk_div; + + if (config->hw_flow_control) { + hsd->Init.HardwareFlowControl = SDMMC_HARDWARE_FLOW_CONTROL_ENABLE; + } else { + hsd->Init.HardwareFlowControl = SDMMC_HARDWARE_FLOW_CONTROL_DISABLE; + } + + if (data->host_io.bus_width == SDHC_BUS_WIDTH4BIT) { + hsd->Init.BusWide = SDMMC_BUS_WIDE_4B; + } else if (data->host_io.bus_width == SDHC_BUS_WIDTH8BIT) { + hsd->Init.BusWide = SDMMC_BUS_WIDE_8B; + } else { + hsd->Init.BusWide = SDMMC_BUS_WIDE_1B; + } + + if (HAL_SDIO_RegisterIdentifyCardCallback(config->hsd, + noop_identify_card_callback) != HAL_OK) { + LOG_ERR("Register identify card callback failed"); + return -EIO; + } + + if (HAL_SDIO_Init(hsd) != HAL_OK) { + return -EIO; + } + return 0; +} + +static int sdhc_stm32_activate(const struct device *dev) +{ + int ret; + const struct sdhc_stm32_config *config = (struct sdhc_stm32_config *)dev->config; + const struct device *const clk = DEVICE_DT_GET(STM32_CLOCK_CONTROL_NODE); + + if (!device_is_ready(clk)) { + return -ENODEV; + } + + ret = pinctrl_apply_state(config->pcfg, PINCTRL_STATE_DEFAULT); + if (ret < 0) { + return ret; + } + + if (DT_INST_NUM_CLOCKS(0) > 1) { + if (clock_control_configure(clk, + (clock_control_subsys_t)(uintptr_t) &config->pclken[1], + NULL) != 0) { + LOG_ERR("Failed to enable SDHC domain clock"); + return -EIO; + } + } + + if (clock_control_on(clk, (clock_control_subsys_t)(uintptr_t)&config->pclken[0]) != 0) { + return -EIO; + } + + return 0; +} + +static uint32_t sdhc_stm32_go_idle_state(const struct device *dev) +{ + const struct sdhc_stm32_config *config = dev->config; + + return SDMMC_CmdGoIdleState(config->hsd->Instance); +} + +static int sdhc_stm32_rw_direct(const struct device *dev, struct sdhc_command *cmd) +{ + HAL_StatusTypeDef res; + const struct sdhc_stm32_config *config = dev->config; + bool direction = cmd->arg >> SDIO_CMD_ARG_RW_SHIFT; + bool raw_flag = cmd->arg >> SDIO_DIRECT_CMD_ARG_RAW_SHIFT; + + uint8_t func = (cmd->arg >> SDIO_CMD_ARG_FUNC_NUM_SHIFT) & 0x7; + uint32_t reg_addr = (cmd->arg >> SDIO_CMD_ARG_REG_ADDR_SHIFT) & SDIO_CMD_ARG_REG_ADDR_MASK; + + HAL_SDIO_DirectCmd_TypeDef arg = { + .Reg_Addr = reg_addr, + .ReadAfterWrite = raw_flag, + .IOFunctionNbr = func + }; + + if (direction == SDIO_IO_WRITE) { + uint8_t data_in = cmd->arg & SDIO_DIRECT_CMD_DATA_MASK; + + res = HAL_SDIO_WriteDirect(config->hsd, &arg, data_in); + } else { + res = HAL_SDIO_ReadDirect(config->hsd, &arg, (uint8_t *)&cmd->response); + } + + return res == HAL_OK ? 0 : -EIO; +} + +static int sdhc_stm32_rw_extended(const struct device *dev, struct sdhc_command *cmd, + struct sdhc_data *data) +{ + HAL_StatusTypeDef res; + struct sdhc_stm32_data *dev_data = dev->data; + const struct sdhc_stm32_config *config = dev->config; + bool direction = cmd->arg >> SDIO_CMD_ARG_RW_SHIFT; + bool increment = cmd->arg & BIT(SDIO_EXTEND_CMD_ARG_OP_CODE_SHIFT); + bool is_block_mode = cmd->arg & BIT(SDIO_EXTEND_CMD_ARG_BLK_SHIFT); + uint8_t func = (cmd->arg >> SDIO_CMD_ARG_FUNC_NUM_SHIFT) & 0x7; + uint32_t reg_addr = (cmd->arg >> SDIO_CMD_ARG_REG_ADDR_SHIFT) & SDIO_CMD_ARG_REG_ADDR_MASK; + + if (data->data == NULL) { + LOG_ERR("Invalid NULL data buffer passed to CMD53"); + return -EINVAL; + } + + HAL_SDIO_ExtendedCmd_TypeDef arg = { + .Reg_Addr = reg_addr, + .IOFunctionNbr = func, + .Block_Mode = is_block_mode ? SDMMC_SDIO_MODE_BLOCK : HAL_SDIO_MODE_BYTE, + .OpCode = increment + }; + + config->hsd->block_size = is_block_mode ? data->block_size : 0; + dev_data->total_transfer_bytes = data->blocks * data->block_size; + + if (!IS_ENABLED(CONFIG_SDHC_STM32_POLLING_SUPPORT)) { + dev_data->sdio_dma_buf = k_aligned_alloc(CONFIG_SDHC_BUFFER_ALIGNMENT, + data->blocks * data->block_size); + if (dev_data->sdio_dma_buf == NULL) { + LOG_ERR("DMA buffer allocation failed"); + return -ENOMEM; + } + } + + if (direction == SDIO_IO_WRITE) { + if (IS_ENABLED(CONFIG_SDHC_STM32_POLLING_SUPPORT)) { + res = HAL_SDIO_WriteExtended(config->hsd, &arg, data->data, + dev_data->total_transfer_bytes, + data->timeout_ms); + } else { + memcpy(dev_data->sdio_dma_buf, data->data, + dev_data->total_transfer_bytes); + sys_cache_data_flush_range(dev_data->sdio_dma_buf, + dev_data->total_transfer_bytes); + res = HAL_SDIO_WriteExtended_DMA(config->hsd, &arg, + dev_data->sdio_dma_buf, + dev_data->total_transfer_bytes); + } + } else { + if (IS_ENABLED(CONFIG_SDHC_STM32_POLLING_SUPPORT)) { + res = HAL_SDIO_ReadExtended(config->hsd, &arg, data->data, + dev_data->total_transfer_bytes, + data->timeout_ms); + } else { + sys_cache_data_flush_range(dev_data->sdio_dma_buf, + dev_data->total_transfer_bytes); + res = HAL_SDIO_ReadExtended_DMA(config->hsd, &arg, dev_data->sdio_dma_buf, + dev_data->total_transfer_bytes); + } + } + + if (!IS_ENABLED(CONFIG_SDHC_STM32_POLLING_SUPPORT)) { + /* Wait for whole transfer to complete */ + if (k_sem_take(&dev_data->device_sync_sem, K_MSEC(CONFIG_SD_CMD_TIMEOUT)) != 0) { + k_free(dev_data->sdio_dma_buf); + return -ETIMEDOUT; + } + + if (direction == SDIO_IO_READ) { + sys_cache_data_invd_range(dev_data->sdio_dma_buf, + dev_data->total_transfer_bytes); + memcpy(data->data, dev_data->sdio_dma_buf, data->block_size * data->blocks); + } + + k_free(dev_data->sdio_dma_buf); + } + + return res == HAL_OK ? 0 : -EIO; +} + +static int sdhc_stm32_switch_to_1_8v(const struct device *dev) +{ + uint32_t res; + struct sdhc_stm32_data *data = dev->data; + const struct sdhc_stm32_config *config = dev->config; + + /* Check if host supports 1.8V signaling */ + if (!data->props.host_caps.vol_180_support) { + LOG_ERR("Host does not support 1.8V signaling"); + return -ENOTSUP; + } + + res = SDMMC_CmdVoltageSwitch(config->hsd->Instance); + if (res != 0) { + LOG_ERR("CMD11 failed: %#x", res); + return -EIO; + } + + LOG_DBG("Successfully switched to 1.8V signaling"); + return 0; +} + +static int sdhc_stm32_request(const struct device *dev, struct sdhc_command *cmd, + struct sdhc_data *data) +{ + int res = 0; + uint32_t sdmmc_res = 0U; + struct sdhc_stm32_data *dev_data = dev->data; + const struct sdhc_stm32_config *config = dev->config; + + __ASSERT_NO_MSG(cmd != NULL); + + if (k_mutex_lock(&dev_data->bus_mutex, K_MSEC(cmd->timeout_ms))) { + return -EBUSY; + } + + if (HAL_SDIO_GetState(config->hsd) != HAL_SDIO_STATE_READY) { + LOG_ERR("SDIO Card is busy"); + k_mutex_unlock(&dev_data->bus_mutex); + return -ETIMEDOUT; + } + + (void)pm_device_runtime_get(dev); + + /* Prevent the clocks to be stopped during the request */ + pm_policy_state_lock_get(PM_STATE_SUSPEND_TO_IDLE, PM_ALL_SUBSTATES); + + dev_data->cmd_index = cmd->opcode; + switch (cmd->opcode) { + case SD_GO_IDLE_STATE: + sdmmc_res = sdhc_stm32_go_idle_state(dev); + if (sdmmc_res != 0U) { + res = -EIO; + } + break; + + case SD_SELECT_CARD: + sdmmc_res = SDMMC_CmdSelDesel(config->hsd->Instance, cmd->arg); + if (sdmmc_res != 0U) { + res = -EIO; + break; + } + /* Clear unused flags to avoid SDIO card identification issues */ + cmd->response[0U] &= + ~(SD_R1_ERASE_SKIP | SD_R1_CSD_OVERWRITE | SD_R1_ERASE_PARAM); + break; + + case SD_SEND_RELATIVE_ADDR: + sdmmc_res = SDMMC_CmdSetRelAdd(config->hsd->Instance, (uint16_t *)&cmd->response); + if (sdmmc_res != 0U) { + res = -EIO; + break; + } + /* + * Restore RCA by reversing the double 16-bit right shift from + * Zephyr subsys and SDMMC_CmdSetRelAdd + */ + cmd->response[0] = cmd->response[0] << 16; + break; + + case SDIO_SEND_OP_COND: + sdmmc_res = SDMMC_CmdSendOperationcondition(config->hsd->Instance, cmd->arg, + (uint32_t *)&cmd->response); + if (sdmmc_res != 0U) { + res = -EIO; + } + break; + + case SDIO_RW_DIRECT: + res = sdhc_stm32_rw_direct(dev, cmd); + break; + + case SDIO_RW_EXTENDED: + __ASSERT_NO_MSG(data != NULL); + res = sdhc_stm32_rw_extended(dev, cmd, data); + break; + + case SD_VOL_SWITCH: + res = sdhc_stm32_switch_to_1_8v(dev); + break; + + default: + LOG_DBG("Unsupported Command, opcode:%d", cmd->opcode); + res = -ENOTSUP; + } + + if (res != 0) { + LOG_DBG("Command Failed, opcode:%d", cmd->opcode); + sdhc_stm32_log_err_type(config->hsd); + } + + pm_policy_state_lock_put(PM_STATE_SUSPEND_TO_IDLE, PM_ALL_SUBSTATES); + (void)pm_device_runtime_put(dev); + k_mutex_unlock(&dev_data->bus_mutex); + + return res; +} + +static int sdhc_stm32_set_io(const struct device *dev, struct sdhc_io *ios) +{ + int res = 0; + struct sdhc_stm32_data *data = dev->data; + const struct sdhc_stm32_config *config = dev->config; + struct sdhc_io *host_io = &data->host_io; + struct sdhc_host_props *props = &data->props; + + (void)pm_device_runtime_get(dev); + /* Prevent the clocks to be stopped during the request */ + pm_policy_state_lock_get(PM_STATE_SUSPEND_TO_IDLE, PM_ALL_SUBSTATES); + k_mutex_lock(&data->bus_mutex, K_FOREVER); + + if ((ios->clock != 0) && (host_io->clock != ios->clock)) { + if ((ios->clock > props->f_max) || (ios->clock < props->f_min)) { + LOG_ERR("Invalid clock frequency, domain (%u, %u)", + props->f_min, props->f_max); + res = -EINVAL; + goto out; + } + if (HAL_SDIO_ConfigFrequency(config->hsd, (uint32_t)ios->clock) != HAL_OK) { + LOG_ERR("Failed to set clock to %d", ios->clock); + res = -EIO; + goto out; + } + host_io->clock = ios->clock; + LOG_DBG("Clock set to %d", ios->clock); + } + + if (ios->power_mode == SDHC_POWER_OFF) { + (void)SDMMC_PowerState_OFF(config->hsd->Instance); + k_msleep(data->props.power_delay); + } else { + (void)SDMMC_PowerState_ON(config->hsd->Instance); + k_msleep(data->props.power_delay); + } + + if ((ios->bus_width != 0) && (host_io->bus_width != ios->bus_width)) { + uint32_t bus_width_reg_value; + + if (ios->bus_width == SDHC_BUS_WIDTH8BIT) { + bus_width_reg_value = SDMMC_BUS_WIDE_8B; + } else if (ios->bus_width == SDHC_BUS_WIDTH4BIT) { + bus_width_reg_value = SDMMC_BUS_WIDE_4B; + } else { + bus_width_reg_value = SDMMC_BUS_WIDE_1B; + } + + MODIFY_REG(config->hsd->Instance->CLKCR, SDMMC_CLKCR_WIDBUS, bus_width_reg_value); + host_io->bus_width = ios->bus_width; + } + +out: + k_mutex_unlock(&data->bus_mutex); + pm_policy_state_lock_put(PM_STATE_SUSPEND_TO_IDLE, PM_ALL_SUBSTATES); + (void)pm_device_runtime_put(dev); + + return res; +} + +static void sdhc_stm32_init_props(const struct device *dev) +{ + const struct sdhc_stm32_config *sdhc_config = (const struct sdhc_stm32_config *)dev->config; + struct sdhc_stm32_data *data = dev->data; + struct sdhc_host_props *props = &data->props; + + memset(props, 0, sizeof(struct sdhc_host_props)); + + props->f_min = sdhc_config->min_freq; + props->f_max = sdhc_config->max_freq; + props->power_delay = sdhc_config->power_delay_ms; + props->host_caps.vol_330_support = true; + props->host_caps.vol_180_support = sdhc_config->support_1_8_v; + props->host_caps.bus_8_bit_support = (sdhc_config->bus_width == SDHC_BUS_WIDTH8BIT); + props->host_caps.bus_4_bit_support = (sdhc_config->bus_width == SDHC_BUS_WIDTH4BIT); +} + +static int sdhc_stm32_get_host_props(const struct device *dev, struct sdhc_host_props *props) +{ + struct sdhc_stm32_data *data = dev->data; + + memcpy(props, &data->props, sizeof(struct sdhc_host_props)); + + return 0; +} + +static int sdhc_stm32_get_card_present(const struct device *dev) +{ + int res = 0; + struct sdhc_stm32_data *dev_data = dev->data; + const struct sdhc_stm32_config *config = dev->config; + + /* If a CD pin is configured, use it for card detection */ + if (config->cd_gpio.port != NULL) { + res = gpio_pin_get_dt(&config->cd_gpio); + return res; + } + + (void)pm_device_runtime_get(dev); + /* Prevent the clocks to be stopped during the request */ + pm_policy_state_lock_get(PM_STATE_SUSPEND_TO_IDLE, PM_ALL_SUBSTATES); + k_mutex_lock(&dev_data->bus_mutex, K_FOREVER); + + /* Card is considered present if the read command did not time out */ + if (SDMMC_CmdSendOperationcondition(config->hsd->Instance, 0, NULL) != 0) { + res = -EIO; + sdhc_stm32_log_err_type(config->hsd); + } + k_mutex_unlock(&dev_data->bus_mutex); + pm_policy_state_lock_put(PM_STATE_SUSPEND_TO_IDLE, PM_ALL_SUBSTATES); + (void)pm_device_runtime_put(dev); + + return res == 0; +} + +static int sdhc_stm32_card_busy(const struct device *dev) +{ + const struct sdhc_stm32_config *config = dev->config; + + return HAL_SDIO_GetState(config->hsd) == HAL_SDIO_STATE_BUSY; +} + +static int sdhc_stm32_reset(const struct device *dev) +{ + HAL_StatusTypeDef res; + struct sdhc_stm32_data *data = dev->data; + const struct sdhc_stm32_config *config = dev->config; + + (void)pm_device_runtime_get(dev); + /* Prevent the clocks to be stopped during the request */ + pm_policy_state_lock_get(PM_STATE_SUSPEND_TO_IDLE, PM_ALL_SUBSTATES); + k_mutex_lock(&data->bus_mutex, K_FOREVER); + + /* Resetting Host controller */ + (void)SDMMC_PowerState_OFF(config->hsd->Instance); + k_msleep(data->props.power_delay); + (void)SDMMC_PowerState_ON(config->hsd->Instance); + k_msleep(data->props.power_delay); + + /* Resetting card */ + res = HAL_SDIO_CardReset(config->hsd); + if (res != HAL_OK) { + LOG_ERR("Card reset failed"); + } + + k_mutex_unlock(&data->bus_mutex); + pm_policy_state_lock_put(PM_STATE_SUSPEND_TO_IDLE, PM_ALL_SUBSTATES); + (void)pm_device_runtime_put(dev); + + return res == HAL_OK ? 0 : -EIO; +} + +static DEVICE_API(sdhc, sdhc_stm32_api) = { + .request = sdhc_stm32_request, + .set_io = sdhc_stm32_set_io, + .get_host_props = sdhc_stm32_get_host_props, + .get_card_present = sdhc_stm32_get_card_present, + .card_busy = sdhc_stm32_card_busy, + .reset = sdhc_stm32_reset, +}; + +void sdhc_stm32_event_isr(const struct device *dev) +{ + uint32_t icr_clear_flag = 0; + struct sdhc_stm32_data *data = dev->data; + const struct sdhc_stm32_config *config = dev->config; + + if (__HAL_SDIO_GET_FLAG(config->hsd, + SDMMC_FLAG_DATAEND | SDMMC_FLAG_DCRCFAIL | SDMMC_FLAG_DTIMEOUT | + SDMMC_FLAG_RXOVERR | SDMMC_FLAG_TXUNDERR)) { + k_sem_give(&data->device_sync_sem); + } + + if ((config->hsd->Instance->STA & SDMMC_STA_DCRCFAIL) != 0U) { + icr_clear_flag |= SDMMC_ICR_DCRCFAILC; + } + if ((config->hsd->Instance->STA & SDMMC_STA_DTIMEOUT) != 0U) { + icr_clear_flag |= SDMMC_ICR_DTIMEOUTC; + } + if ((config->hsd->Instance->STA & SDMMC_STA_TXUNDERR) != 0U) { + icr_clear_flag |= SDMMC_ICR_TXUNDERRC; + } + if ((config->hsd->Instance->STA & SDMMC_STA_RXOVERR) != 0U) { + icr_clear_flag |= SDMMC_ICR_RXOVERRC; + } + if (icr_clear_flag) { + LOG_ERR("SDMMC interrupt err flag raised: 0x%08X", icr_clear_flag); + config->hsd->Instance->ICR = icr_clear_flag; + } + + HAL_SDIO_IRQHandler(config->hsd); +} + +static int sdhc_stm32_init(const struct device *dev) +{ + int ret; + struct sdhc_stm32_data *data = dev->data; + const struct sdhc_stm32_config *config = dev->config; + + if (config->sdhi_on_gpio.port != NULL) { + if (sdhi_power_on(dev) != 0) { + LOG_ERR("Failed to power card on"); + return -ENODEV; + } + } + + if (config->cd_gpio.port != NULL) { + if (!device_is_ready(config->cd_gpio.port)) { + LOG_ERR("Card detect GPIO device not ready"); + return -ENODEV; + } + + ret = gpio_pin_configure_dt(&config->cd_gpio, GPIO_INPUT); + if (ret < 0) { + LOG_ERR("Couldn't configure card-detect pin; (%d)", ret); + return ret; + } + } + + ret = sdhc_stm32_activate(dev); + if (ret != 0) { + LOG_ERR("Clock and GPIO could not be initialized for the SDHC module, err=%d", ret); + return ret; + } + + ret = sdhc_stm32_sd_init(dev); + if (ret != 0) { + LOG_ERR("SDIO Init Failed"); + sdhc_stm32_log_err_type(config->hsd); + return ret; + } + + LOG_INF("SDIO Init Passed Successfully"); + + sdhc_stm32_init_props(dev); + + config->irq_config_func(); + k_sem_init(&data->device_sync_sem, 0, K_SEM_MAX_LIMIT); + k_mutex_init(&data->bus_mutex); + + return ret; +} + +#ifdef CONFIG_PM_DEVICE +static int sdhc_stm32_suspend(const struct device *dev) +{ + int ret; + const struct sdhc_stm32_config *cfg = (struct sdhc_stm32_config *)dev->config; + const struct device *const clk = DEVICE_DT_GET(STM32_CLOCK_CONTROL_NODE); + + /* Disable device clock. */ + ret = clock_control_off(clk, (clock_control_subsys_t)(uintptr_t)&cfg->pclken[0]); + if (ret < 0) { + LOG_ERR("Failed to disable SDHC clock during PM suspend process"); + return ret; + } + + /* Move pins to sleep state */ + ret = pinctrl_apply_state(cfg->pcfg, PINCTRL_STATE_SLEEP); + if (ret == -ENOENT) { + /* Warn but don't block suspend */ + LOG_WRN_ONCE("SDHC pinctrl sleep state not available"); + return 0; + } + + return ret; +} + +static int sdhc_stm32_pm_action(const struct device *dev, enum pm_device_action action) +{ + switch (action) { + case PM_DEVICE_ACTION_RESUME: + return sdhc_stm32_activate(dev); + case PM_DEVICE_ACTION_SUSPEND: + return sdhc_stm32_suspend(dev); + default: + return -ENOTSUP; + } +} +#endif /* CONFIG_PM_DEVICE */ + +#define STM32_SDHC_IRQ_HANDLER(index) \ + static void sdhc_stm32_irq_config_func_##index(void) \ + { \ + IRQ_CONNECT(DT_INST_IRQ_BY_NAME(index, event, irq), \ + DT_INST_IRQ_BY_NAME(index, event, priority), sdhc_stm32_event_isr, \ + DEVICE_DT_INST_GET(index), 0); \ + irq_enable(DT_INST_IRQ_BY_NAME(index, event, irq)); \ + } + +#define SDHC_STM32_INIT(index) \ + \ + STM32_SDHC_IRQ_HANDLER(index) \ + \ + static SDIO_HandleTypeDef hsd_##index; \ + \ + static const struct stm32_pclken pclken_##index[] = STM32_DT_INST_CLOCKS(index); \ + \ + PINCTRL_DT_INST_DEFINE(index); \ + \ + static const struct sdhc_stm32_config sdhc_stm32_cfg_##index = { \ + .hsd = &hsd_##index, \ + .reg_addr = DT_INST_REG_ADDR(index), \ + .irq_config_func = sdhc_stm32_irq_config_func_##index, \ + .pclken = pclken_##index, \ + .pcfg = PINCTRL_DT_INST_DEV_CONFIG_GET(index), \ + .hw_flow_control = DT_INST_PROP(index, hw_flow_control), \ + .clk_div = DT_INST_PROP(index, clk_div), \ + .bus_width = DT_INST_PROP(index, bus_width), \ + .power_delay_ms = DT_INST_PROP(index, power_delay_ms), \ + .support_1_8_v = DT_INST_PROP(index, support_1_8_v), \ + .sdhi_on_gpio = GPIO_DT_SPEC_GET_OR(DT_DRV_INST(index), sdhi_on_gpios, {0}), \ + .cd_gpio = GPIO_DT_SPEC_GET_OR(DT_DRV_INST(index), cd_gpios, {0}), \ + .min_freq = DT_INST_PROP(index, min_bus_freq), \ + .max_freq = DT_INST_PROP(index, max_bus_freq), \ + }; \ + \ + static struct sdhc_stm32_data sdhc_stm32_data_##index; \ + \ + PM_DEVICE_DT_INST_DEFINE(index, sdhc_stm32_pm_action); \ + \ + DEVICE_DT_INST_DEFINE(index, &sdhc_stm32_init, NULL, &sdhc_stm32_data_##index, \ + &sdhc_stm32_cfg_##index, POST_KERNEL, CONFIG_SDHC_INIT_PRIORITY,\ + &sdhc_stm32_api); + +DT_INST_FOREACH_STATUS_OKAY(SDHC_STM32_INIT) From 3735bf44fa92bd462598189cdfe87e8f677d98a8 Mon Sep 17 00:00:00 2001 From: Sara Touqan Date: Sun, 11 May 2025 12:59:03 +0300 Subject: [PATCH 2/4] dts: Add SDHC SDIO configuration for STM32 This commit adds the main DTS configurations required to enable SDHC support on STM32. Signed-off-by: Sara Touqan --- dts/bindings/sdhc/st,stm32-sdio.yaml | 62 ++++++++++++++++++++++++++++ 1 file changed, 62 insertions(+) create mode 100644 dts/bindings/sdhc/st,stm32-sdio.yaml diff --git a/dts/bindings/sdhc/st,stm32-sdio.yaml b/dts/bindings/sdhc/st,stm32-sdio.yaml new file mode 100644 index 0000000000000..02c9fa514b11b --- /dev/null +++ b/dts/bindings/sdhc/st,stm32-sdio.yaml @@ -0,0 +1,62 @@ +# Copyright (c) 2025 EXALT Technologies. +# +# SPDX-License-Identifier: Apache-2.0 + +title: STM32 SDIO Host Controller + +description: Common properties for STM32 SDIO Host Controller peripheral. + +compatible: "st,stm32-sdio" + +bus: sd + +include: [sdhc.yaml, pinctrl-device.yaml, reset-device.yaml] + +properties: + hw-flow-control: + type: boolean + description: Set to enable RTS/CTS flow control at boot time. + + sdhi-on-gpios: + type: phandle-array + description: GPIO used to enable/disable the SDHI. + + cd-gpios: + type: phandle-array + description: Card detect pin. + + clocks: + required: true + + reg: + required: true + + pinctrl-0: + required: true + + pinctrl-names: + required: true + + support-1-8-v: + type: boolean + description: | + When defined, it indicates that the external SDIO circuit supports 1.8V signaling. + + bus-width: + type: int + default: 1 + description: | + Bus width for SDMMC access, defaults to the minimum necessary + number of bus lines. + enum: + - 1 + - 4 + - 8 + + clk-div: + type: int + default: 1 + description: | + Clock division factor for SDMMC. Typically the clock operates at 25MHz so + a division factor of 2 would be 25MHz / 2 = 12.5MHz. + The valid range is 0 to 1023. From 7515cfc83f0d8854b2e2995dccb6e158a820b51f Mon Sep 17 00:00:00 2001 From: Sara Touqan Date: Sun, 22 Jun 2025 09:54:29 +0300 Subject: [PATCH 3/4] boards: Enable SDHC SDIO support This commit enables SDHC support for STM32 on arduino portenta h7, giga r1 and nicla vision boards. Signed-off-by: Sara Touqan --- boards/arduino/giga_r1/arduino_giga_r1.dtsi | 27 +++++++++++++++++++ .../nicla_vision/arduino_nicla_vision.dtsi | 27 +++++++++++++++++++ .../arduino_portenta_h7-common.dtsi | 24 +++++++++++++++++ 3 files changed, 78 insertions(+) diff --git a/boards/arduino/giga_r1/arduino_giga_r1.dtsi b/boards/arduino/giga_r1/arduino_giga_r1.dtsi index d0e8863967e48..0dc6a912f9f59 100644 --- a/boards/arduino/giga_r1/arduino_giga_r1.dtsi +++ b/boards/arduino/giga_r1/arduino_giga_r1.dtsi @@ -8,6 +8,10 @@ #include / { + aliases { + sdhc0 = &sdhc; + }; + leds { compatible = "gpio-leds"; red_led: led_0 { @@ -42,3 +46,26 @@ &mailbox { status = "okay"; }; + +sdhc: &sdmmc1 { + compatible = "st,stm32-sdio"; + interrupts = <49 0>; + interrupt-names = "event"; + pinctrl-0 = <&sdmmc1_d0_pc8 &sdmmc1_d1_pc9 + &sdmmc1_d2_pc10 &sdmmc1_d3_pc11 + &sdmmc1_ck_pc12 &sdmmc1_cmd_pd2>; + pinctrl-names = "default"; + sdhi-on-gpios = <&gpiob 10 GPIO_ACTIVE_HIGH>; + min-bus-freq = ; + max-bus-freq = ; + hw-flow-control; + bus-width = <4>; + status = "okay"; + + wifi: airoc-wifi { + status = "okay"; + compatible = "infineon,airoc-wifi"; + wifi-reg-on-gpios = <&gpiob 10 GPIO_ACTIVE_HIGH>; + wifi-host-wake-gpios = <&gpioi 8 GPIO_ACTIVE_HIGH>; + }; +}; diff --git a/boards/arduino/nicla_vision/arduino_nicla_vision.dtsi b/boards/arduino/nicla_vision/arduino_nicla_vision.dtsi index cec25611b1b96..7c9e908060d66 100644 --- a/boards/arduino/nicla_vision/arduino_nicla_vision.dtsi +++ b/boards/arduino/nicla_vision/arduino_nicla_vision.dtsi @@ -5,6 +5,10 @@ */ / { + aliases { + sdhc0 = &sdhc; + }; + leds { compatible = "gpio-leds"; red_led: led_0 { @@ -31,3 +35,26 @@ &mailbox { status = "okay"; }; + +sdhc: &sdmmc2 { + compatible = "st,stm32-sdio"; + interrupts = <124 0>; + interrupt-names = "event"; + pinctrl-0 = <&sdmmc2_d0_pb14 &sdmmc2_d1_pb15 + &sdmmc2_d2_pg11 &sdmmc2_d3_pb4 + &sdmmc2_ck_pd6 &sdmmc2_cmd_pd7>; + pinctrl-names = "default"; + sdhi-on-gpios = <&gpiog 4 GPIO_ACTIVE_HIGH>; + min-bus-freq = ; + max-bus-freq = ; + hw-flow-control; + bus-width = <4>; + status = "okay"; + + wifi: airoc-wifi { + status = "okay"; + compatible = "infineon,airoc-wifi"; + wifi-reg-on-gpios = <&gpiog 4 GPIO_ACTIVE_HIGH>; + wifi-host-wake-gpios = <&gpiod 15 GPIO_ACTIVE_HIGH>; + }; +}; diff --git a/boards/arduino/portenta_h7/arduino_portenta_h7-common.dtsi b/boards/arduino/portenta_h7/arduino_portenta_h7-common.dtsi index b95a2e6799990..a9931c1787be8 100644 --- a/boards/arduino/portenta_h7/arduino_portenta_h7-common.dtsi +++ b/boards/arduino/portenta_h7/arduino_portenta_h7-common.dtsi @@ -30,6 +30,7 @@ led0 = &red_led; led1 = &green_led; led2 = &blue_led; + sdhc0 = &sdhc; }; }; @@ -239,6 +240,29 @@ zephyr_i2c: &i2c1 { }; }; +sdhc: &sdmmc1 { + compatible = "st,stm32-sdio"; + pinctrl-0 = <&sdmmc1_d0_pc8 &sdmmc1_d1_pc9 + &sdmmc1_d2_pc10 &sdmmc1_d3_pc11 + &sdmmc1_ck_pc12 &sdmmc1_cmd_pd2>; + pinctrl-names = "default"; + sdhi-on-gpios = <&gpioj 1 GPIO_ACTIVE_HIGH>; + interrupts = <49 0>; + interrupt-names = "event"; + min-bus-freq = ; + max-bus-freq = ; + hw-flow-control; + bus-width = <4>; + status = "okay"; + + wifi: airoc-wifi { + status = "okay"; + compatible = "infineon,airoc-wifi"; + wifi-reg-on-gpios = <&gpioj 1 GPIO_ACTIVE_HIGH>; + wifi-host-wake-gpios = <&gpioj 5 GPIO_ACTIVE_HIGH>; + }; +}; + zephyr_udc0: &usbotg_hs { pinctrl-0 = < &usb_otg_hs_ulpi_d0_pa3 &usb_otg_hs_ulpi_ck_pa5 From 3684849e712653dcbcf33d90f5b313cbeceaab93 Mon Sep 17 00:00:00 2001 From: Sara Touqan Date: Mon, 19 May 2025 09:53:44 +0300 Subject: [PATCH 4/4] tests: sdio: Add write test to SDIO subsystem This commit expands the SDIO subsystem test suite by adding support for write test. Also this commit adds needed conf/overlay files for arduino portenta h7, nicla vision and giga r1 for wifi_nm tests Signed-off-by: Sara Touqan --- tests/net/wifi/wifi_nm/testcase.yaml | 4 +++ .../arduino_giga_r1_stm32h747xx_m7.conf | 4 +++ .../arduino_giga_r1_stm32h747xx_m7.overlay | 9 +++++++ .../arduino_nicla_vision_stm32h747xx_m7.conf | 4 +++ ...rduino_nicla_vision_stm32h747xx_m7.overlay | 9 +++++++ .../arduino_portenta_h7_stm32h747xx_m7.conf | 4 +++ ...arduino_portenta_h7_stm32h747xx_m7.overlay | 22 ++++++++++++++++ tests/subsys/sd/sdio/src/main.c | 26 +++++++++++++++++++ 8 files changed, 82 insertions(+) create mode 100644 tests/subsys/sd/sdio/boards/arduino_giga_r1_stm32h747xx_m7.conf create mode 100644 tests/subsys/sd/sdio/boards/arduino_giga_r1_stm32h747xx_m7.overlay create mode 100644 tests/subsys/sd/sdio/boards/arduino_nicla_vision_stm32h747xx_m7.conf create mode 100644 tests/subsys/sd/sdio/boards/arduino_nicla_vision_stm32h747xx_m7.overlay create mode 100644 tests/subsys/sd/sdio/boards/arduino_portenta_h7_stm32h747xx_m7.conf create mode 100644 tests/subsys/sd/sdio/boards/arduino_portenta_h7_stm32h747xx_m7.overlay diff --git a/tests/net/wifi/wifi_nm/testcase.yaml b/tests/net/wifi/wifi_nm/testcase.yaml index b29610ba830d0..d26b0ab6dc5d3 100644 --- a/tests/net/wifi/wifi_nm/testcase.yaml +++ b/tests/net/wifi/wifi_nm/testcase.yaml @@ -12,3 +12,7 @@ tests: platform_exclude: - rd_rw612_bga/rw612/ethernet # Requires binary blobs to build - frdm_rw612 # Requires binary blobs to build + - arduino_giga_r1/stm32h747xx/m7 # Requires binary blobs to build + - arduino_nicla_vision/stm32h747xx/m7 # Requires binary blobs to build + - arduino_portenta_h7/stm32h747xx/m7 # Requires binary blobs to build + - arduino_portenta_h7@4.10.0/stm32h747xx/m7 # Requires binary blobs to build diff --git a/tests/subsys/sd/sdio/boards/arduino_giga_r1_stm32h747xx_m7.conf b/tests/subsys/sd/sdio/boards/arduino_giga_r1_stm32h747xx_m7.conf new file mode 100644 index 0000000000000..33060ffcebc00 --- /dev/null +++ b/tests/subsys/sd/sdio/boards/arduino_giga_r1_stm32h747xx_m7.conf @@ -0,0 +1,4 @@ +# Copyright (c) 2025 EXALT Technologies. +# SPDX-License-Identifier: Apache-2.0 + +CONFIG_HEAP_MEM_POOL_SIZE=24576 diff --git a/tests/subsys/sd/sdio/boards/arduino_giga_r1_stm32h747xx_m7.overlay b/tests/subsys/sd/sdio/boards/arduino_giga_r1_stm32h747xx_m7.overlay new file mode 100644 index 0000000000000..693c0dd25794d --- /dev/null +++ b/tests/subsys/sd/sdio/boards/arduino_giga_r1_stm32h747xx_m7.overlay @@ -0,0 +1,9 @@ +/* + * Copyright (c) 2025 EXALT Technologies. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +&wifi { + status = "disabled"; +}; diff --git a/tests/subsys/sd/sdio/boards/arduino_nicla_vision_stm32h747xx_m7.conf b/tests/subsys/sd/sdio/boards/arduino_nicla_vision_stm32h747xx_m7.conf new file mode 100644 index 0000000000000..33060ffcebc00 --- /dev/null +++ b/tests/subsys/sd/sdio/boards/arduino_nicla_vision_stm32h747xx_m7.conf @@ -0,0 +1,4 @@ +# Copyright (c) 2025 EXALT Technologies. +# SPDX-License-Identifier: Apache-2.0 + +CONFIG_HEAP_MEM_POOL_SIZE=24576 diff --git a/tests/subsys/sd/sdio/boards/arduino_nicla_vision_stm32h747xx_m7.overlay b/tests/subsys/sd/sdio/boards/arduino_nicla_vision_stm32h747xx_m7.overlay new file mode 100644 index 0000000000000..693c0dd25794d --- /dev/null +++ b/tests/subsys/sd/sdio/boards/arduino_nicla_vision_stm32h747xx_m7.overlay @@ -0,0 +1,9 @@ +/* + * Copyright (c) 2025 EXALT Technologies. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +&wifi { + status = "disabled"; +}; diff --git a/tests/subsys/sd/sdio/boards/arduino_portenta_h7_stm32h747xx_m7.conf b/tests/subsys/sd/sdio/boards/arduino_portenta_h7_stm32h747xx_m7.conf new file mode 100644 index 0000000000000..33060ffcebc00 --- /dev/null +++ b/tests/subsys/sd/sdio/boards/arduino_portenta_h7_stm32h747xx_m7.conf @@ -0,0 +1,4 @@ +# Copyright (c) 2025 EXALT Technologies. +# SPDX-License-Identifier: Apache-2.0 + +CONFIG_HEAP_MEM_POOL_SIZE=24576 diff --git a/tests/subsys/sd/sdio/boards/arduino_portenta_h7_stm32h747xx_m7.overlay b/tests/subsys/sd/sdio/boards/arduino_portenta_h7_stm32h747xx_m7.overlay new file mode 100644 index 0000000000000..957e315ef6c71 --- /dev/null +++ b/tests/subsys/sd/sdio/boards/arduino_portenta_h7_stm32h747xx_m7.overlay @@ -0,0 +1,22 @@ +/* + * Copyright (c) 2025 EXALT Technologies. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +&boot_partition{ + reg = <0x00000000 0x00020000>; +}; +&scratch_partition { + reg = <0x00020000 0x00020000>; +}; +&slot0_partition { + reg = <0x00040000 0x001C0000>; +}; +&slot1_partition { + reg = <0x00200000 0x001C0000>; +}; + +&wifi { + status = "disabled"; +}; diff --git a/tests/subsys/sd/sdio/src/main.c b/tests/subsys/sd/sdio/src/main.c index ad311904b4e42..612dc19c21b6f 100644 --- a/tests/subsys/sd/sdio/src/main.c +++ b/tests/subsys/sd/sdio/src/main.c @@ -46,6 +46,32 @@ ZTEST(sd_stack, test_read) zassert_not_equal(reg, 0xFF, "CCCR read returned invalid data"); } +/* + * Verify that a register write works. Given the custom nature of SDIO devices, + * we just write to the card common I/O area. + */ +ZTEST(sd_stack, test_write) +{ + int ret; + uint8_t data = 0x01; + uint8_t reg = 0xFF; + uint8_t new_reg_value = 0xFF; + + /* Read from card common I/O area. */ + ret = sdio_read_byte(&card.func0, SDIO_CCCR_BUS_IF, ®); + zassert_equal(ret, 0, "SD card read failed"); + + /* Write to card common I/O area. */ + ret = sdio_write_byte(&card.func0, SDIO_CCCR_BUS_IF, data); + zassert_equal(ret, 0, "SD card write failed"); + + /* Read after write to verify that data was written */ + ret = sdio_read_byte(&card.func0, SDIO_CCCR_BUS_IF, &new_reg_value); + zassert_equal(ret, 0, "SD card read failed"); + new_reg_value = new_reg_value & SDIO_CCCR_BUS_IF_WIDTH_MASK; + zassert_equal(new_reg_value, data, "read data was not as expected"); +} + /* Simply dump the card configuration. */ ZTEST(sd_stack, test_card_config) {