feat(i2c): Add new API and implementation for I2C driver

This commit is contained in:
Cao Sen Miao 2023-08-03 12:29:44 +08:00
parent db4308888d
commit 4ef94fc0dc
52 changed files with 3351 additions and 605 deletions

View File

@ -91,7 +91,10 @@ endif()
# I2C related source files
if(CONFIG_SOC_I2C_SUPPORTED)
list(APPEND srcs "i2c/i2c.c")
list(APPEND srcs "i2c/i2c.c"
"i2c/i2c_master.c"
"i2c/i2c_common.c"
)
endif()
# I2S related source files
@ -216,7 +219,7 @@ else()
INCLUDE_DIRS ${includes}
PRIV_REQUIRES efuse esp_timer
REQUIRES esp_pm esp_ringbuf freertos soc hal esp_hw_support
LDFRAGMENTS linker.lf gptimer/linker.lf gpio/linker.lf twai/linker.lf)
LDFRAGMENTS linker.lf gptimer/linker.lf gpio/linker.lf twai/linker.lf i2c/linker.lf)
endif()
# If system needs to monitor USJ connection status, then usb_serial_jtag_connection_monitor object file has to be linked

View File

@ -486,4 +486,24 @@ menu "Driver Configurations"
Enabling this option can improve driver performance as well.
endmenu # LEDC Configuration
menu "I2C Configuration"
config I2C_ISR_IRAM_SAFE
bool "I2C ISR IRAM-Safe"
default n
help
Ensure the I2C interrupt is IRAM-Safe by allowing the interrupt handler to be
executable when the cache is disabled (e.g. SPI Flash write).
note: This cannot be used in the I2C legacy driver.
config I2C_ENABLE_DEBUG_LOG
bool "Enable I2C debug log"
default n
help
Wether to enable the debug log message for I2C driver.
Note that this option only controls the I2C driver log, will not affect other drivers.
note: This cannot be used in the I2C legacy driver.
endmenu # I2C Configurations
endmenu # Driver configurations

View File

@ -632,7 +632,7 @@ static esp_err_t i2c_master_clear_bus(i2c_port_t i2c_num)
gpio_set_level(sda_io, 1); // STOP, SDA low -> high while SCL is HIGH
i2c_set_pin(i2c_num, sda_io, scl_io, 1, 1, I2C_MODE_MASTER);
#else
i2c_ll_master_clr_bus(i2c_context[i2c_num].hal.dev);
i2c_ll_master_clr_bus(i2c_context[i2c_num].hal.dev, I2C_CLR_BUS_SCL_NUM);
#endif
return ESP_OK;
}
@ -650,7 +650,7 @@ static esp_err_t i2c_hw_fsm_reset(i2c_port_t i2c_num)
uint8_t filter_cfg;
i2c_hal_get_timing_config(&i2c_context[i2c_num].hal, &timing_config);
i2c_ll_get_filter(i2c_context[i2c_num].hal.dev, &filter_cfg);
i2c_ll_master_get_filter(i2c_context[i2c_num].hal.dev, &filter_cfg);
//to reset the I2C hw module, we need re-enable the hw
i2c_hw_disable(i2c_num);
@ -661,7 +661,7 @@ static esp_err_t i2c_hw_fsm_reset(i2c_port_t i2c_num)
i2c_ll_disable_intr_mask(i2c_context[i2c_num].hal.dev, I2C_LL_INTR_MASK);
i2c_ll_clear_intr_mask(i2c_context[i2c_num].hal.dev, I2C_LL_INTR_MASK);
i2c_hal_set_timing_config(&i2c_context[i2c_num].hal, &timing_config);
i2c_ll_set_filter(i2c_context[i2c_num].hal.dev, filter_cfg);
i2c_ll_master_set_filter(i2c_context[i2c_num].hal.dev, filter_cfg);
#else
i2c_ll_master_fsm_rst(i2c_context[i2c_num].hal.dev);
i2c_master_clear_bus(i2c_num);
@ -767,7 +767,7 @@ esp_err_t i2c_param_config(i2c_port_t i2c_num, const i2c_config_t *i2c_conf)
{
i2c_hal_master_init(&(i2c_context[i2c_num].hal));
//Default, we enable hardware filter
i2c_ll_set_filter(i2c_context[i2c_num].hal.dev, I2C_FILTER_CYC_NUM_DEF);
i2c_ll_master_set_filter(i2c_context[i2c_num].hal.dev, I2C_FILTER_CYC_NUM_DEF);
i2c_hal_set_bus_timing(&(i2c_context[i2c_num].hal), i2c_conf->master.clk_speed, src_clk, s_get_src_clk_freq(src_clk));
}
i2c_ll_update(i2c_context[i2c_num].hal.dev);
@ -802,7 +802,7 @@ esp_err_t i2c_filter_enable(i2c_port_t i2c_num, uint8_t cyc_num)
ESP_RETURN_ON_FALSE(i2c_num < I2C_NUM_MAX, ESP_ERR_INVALID_ARG, I2C_TAG, I2C_NUM_ERROR_STR);
ESP_RETURN_ON_FALSE(p_i2c_obj[i2c_num] != NULL, ESP_FAIL, I2C_TAG, I2C_DRIVER_ERR_STR);
I2C_ENTER_CRITICAL(&(i2c_context[i2c_num].spinlock));
i2c_ll_set_filter(i2c_context[i2c_num].hal.dev, cyc_num);
i2c_ll_master_set_filter(i2c_context[i2c_num].hal.dev, cyc_num);
i2c_ll_update(i2c_context[i2c_num].hal.dev);
I2C_EXIT_CRITICAL(&(i2c_context[i2c_num].spinlock));
return ESP_OK;
@ -812,7 +812,7 @@ esp_err_t i2c_filter_disable(i2c_port_t i2c_num)
{
ESP_RETURN_ON_FALSE(i2c_num < I2C_NUM_MAX, ESP_ERR_INVALID_ARG, I2C_TAG, I2C_NUM_ERROR_STR);
I2C_ENTER_CRITICAL(&(i2c_context[i2c_num].spinlock));
i2c_ll_set_filter(i2c_context[i2c_num].hal.dev, 0);
i2c_ll_master_set_filter(i2c_context[i2c_num].hal.dev, 0);
i2c_ll_update(i2c_context[i2c_num].hal.dev);
I2C_EXIT_CRITICAL(&(i2c_context[i2c_num].spinlock));
return ESP_OK;
@ -825,7 +825,7 @@ esp_err_t i2c_set_start_timing(i2c_port_t i2c_num, int setup_time, int hold_time
ESP_RETURN_ON_FALSE((setup_time <= I2C_SCL_RSTART_SETUP_TIME_V) && (setup_time > 0), ESP_ERR_INVALID_ARG, I2C_TAG, I2C_TIMING_VAL_ERR_STR);
I2C_ENTER_CRITICAL(&(i2c_context[i2c_num].spinlock));
i2c_ll_set_start_timing(i2c_context[i2c_num].hal.dev, setup_time, hold_time);
i2c_ll_master_set_start_timing(i2c_context[i2c_num].hal.dev, setup_time, hold_time);
i2c_ll_update(i2c_context[i2c_num].hal.dev);
I2C_EXIT_CRITICAL(&(i2c_context[i2c_num].spinlock));
return ESP_OK;
@ -847,7 +847,7 @@ esp_err_t i2c_set_stop_timing(i2c_port_t i2c_num, int setup_time, int hold_time)
ESP_RETURN_ON_FALSE((hold_time <= I2C_SCL_STOP_HOLD_TIME_V) && (hold_time > 0), ESP_ERR_INVALID_ARG, I2C_TAG, I2C_TIMING_VAL_ERR_STR);
I2C_ENTER_CRITICAL(&(i2c_context[i2c_num].spinlock));
i2c_ll_set_stop_timing(i2c_context[i2c_num].hal.dev, setup_time, hold_time);
i2c_ll_master_set_stop_timing(i2c_context[i2c_num].hal.dev, setup_time, hold_time);
i2c_ll_update(i2c_context[i2c_num].hal.dev);
I2C_EXIT_CRITICAL(&(i2c_context[i2c_num].spinlock));
return ESP_OK;
@ -1411,8 +1411,8 @@ static void IRAM_ATTR i2c_master_cmd_begin_static(i2c_port_t i2c_num, BaseType_t
}
hw_cmd.byte_num = fifo_fill;
i2c_ll_write_txfifo(i2c_context[i2c_num].hal.dev, write_pr, fifo_fill);
i2c_ll_write_cmd_reg(i2c_context[i2c_num].hal.dev, hw_cmd, p_i2c->cmd_idx);
i2c_ll_write_cmd_reg(i2c_context[i2c_num].hal.dev, hw_end_cmd, p_i2c->cmd_idx + 1);
i2c_ll_master_write_cmd_reg(i2c_context[i2c_num].hal.dev, hw_cmd, p_i2c->cmd_idx);
i2c_ll_master_write_cmd_reg(i2c_context[i2c_num].hal.dev, hw_end_cmd, p_i2c->cmd_idx + 1);
i2c_ll_master_enable_tx_it(i2c_context[i2c_num].hal.dev);
p_i2c->cmd_idx = 0;
if (i2c_cmd_is_single_byte(cmd) || cmd->total_bytes == cmd->bytes_used) {
@ -1428,13 +1428,13 @@ static void IRAM_ATTR i2c_master_cmd_begin_static(i2c_port_t i2c_num, BaseType_t
fifo_fill = MIN(remaining_bytes, SOC_I2C_FIFO_LEN);
p_i2c->rx_cnt = fifo_fill;
hw_cmd.byte_num = fifo_fill;
i2c_ll_write_cmd_reg(i2c_context[i2c_num].hal.dev, hw_cmd, p_i2c->cmd_idx);
i2c_ll_write_cmd_reg(i2c_context[i2c_num].hal.dev, hw_end_cmd, p_i2c->cmd_idx + 1);
i2c_ll_master_write_cmd_reg(i2c_context[i2c_num].hal.dev, hw_cmd, p_i2c->cmd_idx);
i2c_ll_master_write_cmd_reg(i2c_context[i2c_num].hal.dev, hw_end_cmd, p_i2c->cmd_idx + 1);
i2c_ll_master_enable_rx_it(i2c_context[i2c_num].hal.dev);
p_i2c->status = I2C_STATUS_READ;
break;
} else {
i2c_ll_write_cmd_reg(i2c_context[i2c_num].hal.dev, hw_cmd, p_i2c->cmd_idx);
i2c_ll_master_write_cmd_reg(i2c_context[i2c_num].hal.dev, hw_cmd, p_i2c->cmd_idx);
}
p_i2c->cmd_idx++;
p_i2c->cmd_link.head = p_i2c->cmd_link.head->next;
@ -1444,7 +1444,7 @@ static void IRAM_ATTR i2c_master_cmd_begin_static(i2c_port_t i2c_num, BaseType_t
}
}
i2c_ll_update(i2c_context[i2c_num].hal.dev);
i2c_ll_trans_start(i2c_context[i2c_num].hal.dev);
i2c_ll_master_trans_start(i2c_context[i2c_num].hal.dev);
return;
}
@ -1643,3 +1643,19 @@ int i2c_slave_read_buffer(i2c_port_t i2c_num, uint8_t *data, size_t max_size, Ti
return max_size - size_rem;
}
#endif
/**
* @brief This function will be called during start up, to check that this legacy i2c driver is not running along with the new I2C driver
*/
__attribute__((constructor))
static void check_i2c_driver_conflict(void)
{
// This function was declared as weak here. The new I2C driver has the implementation.
// So if the new I2C driver is not linked in, then `i2c_acquire_bus_handle()` should be NULL at runtime.
extern __attribute__((weak)) esp_err_t i2c_acquire_bus_handle(int port_num, void *i2c_new_bus, int mode);
if ((void *)i2c_acquire_bus_handle != NULL) {
ESP_EARLY_LOGE(I2C_TAG, "CONFLICT! driver_ng is not allowed to be used with this old driver");
abort();
}
ESP_EARLY_LOGW(I2C_TAG, "This driver is an old driver, please migrate your application code to adapt `driver/i2c_master.h`");
}

View File

@ -0,0 +1,230 @@
/*
* SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <string.h>
#include <stdio.h>
#include "sdkconfig.h"
#include "esp_types.h"
#if CONFIG_I2C_ENABLE_DEBUG_LOG
// The local log level must be defined before including esp_log.h
// Set the maximum log level for this source file
#define LOG_LOCAL_LEVEL ESP_LOG_DEBUG
#endif
#include "esp_log.h"
#include "esp_check.h"
#include "esp_pm.h"
#include "freertos/FreeRTOS.h"
#include "hal/i2c_hal.h"
#include "hal/gpio_hal.h"
#include "esp_private/periph_ctrl.h"
#include "esp_rom_gpio.h"
#include "i2c_private.h"
#include "driver/gpio.h"
#include "soc/clk_tree_defs.h"
#include "soc/i2c_periph.h"
#include "esp_clk_tree.h"
#include "clk_ctrl_os.h"
static const char *TAG = "i2c.common";
typedef struct i2c_platform_t {
_lock_t mutex; // platform level mutex lock.
i2c_bus_handle_t buses[SOC_I2C_NUM]; // array of I2C bus instances.
uint32_t count[SOC_I2C_NUM]; // reference count used to protect group install/uninstall.
} i2c_platform_t;
static i2c_platform_t s_i2c_platform = {}; // singleton platform
esp_err_t i2c_acquire_bus_handle(i2c_port_num_t port_num, i2c_bus_handle_t *i2c_new_bus, i2c_bus_mode_t mode)
{
#if CONFIG_I2C_ENABLE_DEBUG_LOG
esp_log_level_set(TAG, ESP_LOG_DEBUG);
#endif
bool new_bus = false;
i2c_bus_t *bus = NULL;
esp_err_t ret = ESP_OK;
if (!s_i2c_platform.buses[port_num]) {
new_bus = true;
bus = heap_caps_calloc(1, sizeof(i2c_bus_t), I2C_MEM_ALLOC_CAPS);
if (bus) {
s_i2c_platform.buses[port_num] = bus;
bus->port_num = port_num;
bus->spinlock = (portMUX_TYPE)portMUX_INITIALIZER_UNLOCKED;
bus->bus_mode = mode;
// Enable the I2C module
periph_module_enable(i2c_periph_signal[port_num].module);
periph_module_reset(i2c_periph_signal[port_num].module);
i2c_hal_init(&bus->hal, port_num);
}
} else {
ESP_LOGE(TAG, "I2C bus id(%d) has already been acquired", port_num);
bus = s_i2c_platform.buses[port_num];
ret = ESP_ERR_INVALID_STATE;
}
if (bus) {
s_i2c_platform.count[port_num]++;
}
if (new_bus) {
ESP_LOGD(TAG, "new bus(%d) at %p", port_num, bus);
}
*i2c_new_bus = bus;
return ret;
}
bool i2c_bus_occupied(i2c_port_num_t port_num)
{
bool bus_occupied = false;
_lock_acquire(&s_i2c_platform.mutex);
if (s_i2c_platform.buses[port_num]) {
bus_occupied = true;
}
_lock_release(&s_i2c_platform.mutex);
return bus_occupied;
}
uint8_t i2c_release_bus_handle(i2c_bus_handle_t i2c_bus)
{
int port_num = i2c_bus->port_num;
i2c_clock_source_t clk_src = i2c_bus->clk_src;
bool do_deinitialize = false;
_lock_acquire(&s_i2c_platform.mutex);
if (s_i2c_platform.buses[port_num]) {
s_i2c_platform.count[port_num]--;
if (s_i2c_platform.count[port_num] == 0) {
do_deinitialize = true;
s_i2c_platform.buses[port_num] = NULL;
// Disable I2C module
periph_module_disable(i2c_periph_signal[port_num].module);
free(i2c_bus);
}
}
_lock_release(&s_i2c_platform.mutex);
switch (clk_src) {
#if SOC_I2C_SUPPORT_RTC
case I2C_CLK_SRC_RC_FAST:
periph_rtc_dig_clk8m_disable();
break;
#endif // SOC_I2C_SUPPORT_RTC
default:
break;
}
if (do_deinitialize) {
ESP_LOGD(TAG, "delete bus %d", port_num);
}
return s_i2c_platform.count[port_num];
}
esp_err_t i2c_select_periph_clock(i2c_bus_handle_t handle, i2c_clock_source_t clk_src)
{
esp_err_t ret = ESP_OK;
ESP_RETURN_ON_FALSE(handle, ESP_ERR_INVALID_ARG, TAG, "I2C empty controller handle");
uint32_t periph_src_clk_hz = 0;
bool clock_selection_conflict = 0;
portENTER_CRITICAL(&handle->spinlock);
if (handle->clk_src == 0) {
handle->clk_src = clk_src;
} else {
clock_selection_conflict = (handle->clk_src != clk_src);
}
portEXIT_CRITICAL(&handle->spinlock);
ESP_RETURN_ON_FALSE(!clock_selection_conflict, ESP_ERR_INVALID_STATE, TAG,
"group clock conflict, already is %d but attempt to %d", handle->clk_src, clk_src);
// TODO: [clk_tree] to use a generic clock enable/disable or acquire/release function for all clock source
#if SOC_I2C_SUPPORT_RTC
if (clk_src == I2C_CLK_SRC_RC_FAST) {
// RC_FAST clock is not enabled automatically on start up, we enable it here manually.
// Note there's a ref count in the enable/disable function, we must call them in pair in the driver.
periph_rtc_dig_clk8m_enable();
}
#endif // SOC_I2C_SUPPORT_RTC
ESP_RETURN_ON_ERROR(esp_clk_tree_src_get_freq_hz(clk_src, ESP_CLK_TREE_SRC_FREQ_PRECISION_APPROX, &periph_src_clk_hz), TAG, "i2c get clock frequency error");
handle->clk_src_freq_hz = periph_src_clk_hz;
#if CONFIG_PM_ENABLE
bool need_pm_lock = true;
// to make the I2C work reliable, the source clock must stay alive and unchanged
// driver will create different pm lock for that purpose, according to different clock source
esp_pm_lock_type_t pm_lock_type = ESP_PM_NO_LIGHT_SLEEP;
#if SOC_I2C_SUPPORT_RTC
if (clk_src == I2C_CLK_SRC_RC_FAST) {
// I2C use fifo, which connected to APB, so we cannot use I2C either when in light sleep.
need_pm_lock = ESP_PM_NO_LIGHT_SLEEP;
}
#endif // SOC_I2C_SUPPORT_RTC
#if SOC_I2C_SUPPORT_APB
if (clk_src == I2C_CLK_SRC_APB) {
// APB clock frequency can be changed during DFS
pm_lock_type = ESP_PM_APB_FREQ_MAX;
}
#endif // SOC_I2C_SUPPORT_APB
if (need_pm_lock) {
sprintf(handle->pm_lock_name, "I2C_%d", handle->port_num); // e.g. PORT_0
ret = esp_pm_lock_create(pm_lock_type, 0, handle->pm_lock_name, &handle->pm_lock);
ESP_RETURN_ON_ERROR(ret, TAG, "create pm lock failed");
}
#endif // CONFIG_PM_ENABLE
ESP_LOGD(TAG, "bus clock source frequency: %"PRIu32"hz", periph_src_clk_hz);
return ret;
}
esp_err_t i2c_common_set_pins(i2c_bus_handle_t handle)
{
esp_err_t ret = ESP_OK;
ESP_RETURN_ON_FALSE(handle, ESP_ERR_INVALID_ARG, TAG, "I2C empty controller handle");
int port_id = handle->port_num;
// SDA pin configurations
gpio_config_t sda_conf = {
.intr_type = GPIO_INTR_DISABLE,
.mode = GPIO_MODE_INPUT_OUTPUT_OD,
.pull_down_en = false,
.pull_up_en = handle->pull_up_enable ? GPIO_PULLUP_ENABLE : GPIO_PULLUP_DISABLE,
.pin_bit_mask = 1ULL << handle->sda_num,
};
#if CONFIG_IDF_TARGET_ESP32
// on esp32, must enable internal pull-up
sda_conf.pull_up_en = GPIO_PULLUP_ENABLE;
#endif
ESP_RETURN_ON_ERROR(gpio_config(&sda_conf), TAG, "config GPIO failed");
ESP_RETURN_ON_ERROR(gpio_set_level(handle->sda_num, 1), TAG, "i2c sda pin set level failed");
gpio_hal_iomux_func_sel(GPIO_PIN_MUX_REG[handle->sda_num], PIN_FUNC_GPIO);
esp_rom_gpio_connect_out_signal(handle->sda_num, i2c_periph_signal[port_id].sda_out_sig, 0, 0);
esp_rom_gpio_connect_in_signal(handle->sda_num, i2c_periph_signal[port_id].sda_in_sig, 0);
// SCL pin configurations
gpio_config_t scl_conf = {
.intr_type = GPIO_INTR_DISABLE,
.mode = GPIO_MODE_INPUT_OUTPUT_OD,
.pull_down_en = false,
.pull_up_en = handle->pull_up_enable ? GPIO_PULLUP_ENABLE : GPIO_PULLUP_DISABLE,
.pin_bit_mask = 1ULL << handle->scl_num,
};
#if CONFIG_IDF_TARGET_ESP32
// on esp32, must enable internal pull-up
scl_conf.pull_up_en = GPIO_PULLUP_ENABLE;
#endif
ESP_RETURN_ON_ERROR(gpio_config(&scl_conf), TAG, "config GPIO failed");
ESP_RETURN_ON_ERROR(gpio_set_level(handle->scl_num, 1), TAG, "i2c scl pin set level failed");
gpio_hal_iomux_func_sel(GPIO_PIN_MUX_REG[handle->scl_num], PIN_FUNC_GPIO);
esp_rom_gpio_connect_out_signal(handle->scl_num, i2c_periph_signal[port_id].scl_out_sig, 0, 0);
esp_rom_gpio_connect_in_signal(handle->scl_num, i2c_periph_signal[port_id].scl_in_sig, 0);
return ret;
}

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,209 @@
/*
* SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once
#include <stdint.h>
#include <stdatomic.h>
#include <sys/queue.h>
#include "esp_err.h"
#include "driver/i2c_types.h"
#include "hal/i2c_hal.h"
#include "freertos/FreeRTOS.h"
#include "freertos/semphr.h"
#include "freertos/task.h"
#include "freertos/ringbuf.h"
#include "esp_pm.h"
#ifdef __cplusplus
extern "C" {
#endif
#if CONFIG_I2C_ISR_IRAM_SAFE
#define I2C_MEM_ALLOC_CAPS (MALLOC_CAP_INTERNAL | MALLOC_CAP_8BIT)
#else
#define I2C_MEM_ALLOC_CAPS (MALLOC_CAP_DEFAULT)
#endif
// I2C driver object is per-mode, the interrupt source is shared between modes
#if CONFIG_I2C_ISR_IRAM_SAFE
#define I2C_INTR_ALLOC_FLAG (ESP_INTR_FLAG_SHARED | ESP_INTR_FLAG_IRAM | ESP_INTR_FLAG_LOWMED)
#else
#define I2C_INTR_ALLOC_FLAG (ESP_INTR_FLAG_SHARED | ESP_INTR_FLAG_LOWMED)
#endif
#define I2C_ALLOW_INTR_PRIORITY_MASK ESP_INTR_FLAG_LOWMED
#define I2C_PM_LOCK_NAME_LEN_MAX 16
#define I2C_STATIC_OPERATION_ARRAY_MAX 6
#define ACK_VAL 0
#define NACK_VAL 1
#define I2C_TRANS_READ_COMMAND(ack_value) {.ack_val = (ack_value), .op_code = I2C_LL_CMD_READ}
#define I2C_TRANS_WRITE_COMMAND(ack_check) {.ack_en = (ack_check), .op_code = I2C_LL_CMD_WRITE}
#define I2C_TRANS_STOP_COMMAND {.op_code = I2C_LL_CMD_STOP}
#define I2C_TRANS_START_COMMAND {.op_code = I2C_LL_CMD_RESTART}
typedef struct i2c_bus_t i2c_bus_t;
typedef struct i2c_master_bus_t i2c_master_bus_t;
typedef struct i2c_bus_t *i2c_bus_handle_t;
typedef struct i2c_master_dev_t i2c_master_dev_t;
typedef enum {
I2C_BUS_MODE_MASTER = 0,
I2C_BUS_MODE_SLAVE = 1,
} i2c_bus_mode_t;
typedef enum {
I2C_SLAVE_FIFO = 0,
I2C_SLAVE_NONFIFO = 1,
} i2c_slave_fifo_mode_t;
enum {
I2C_TRANS_QUEUE_READY,
I2C_TRANS_QUEUE_PROGRESS,
I2C_TRANS_QUEUE_COMPLETE,
I2C_TRANS_QUEUE_MAX,
};
typedef struct {
i2c_ll_hw_cmd_t hw_cmd; // I2C command, defined by hardware
uint8_t *data; // Pointer to data
uint16_t bytes_used; // I2C data has been used
size_t total_bytes; // Total bytes to be transferred
} i2c_operation_t;
typedef struct {
uint32_t device_address; // Address of I2C device
i2c_operation_t *ops; // Pointer to I2C operation structure
size_t cmd_count; // Record how many I2C hardware commands in one transaction
} i2c_transaction_t;
struct i2c_bus_t {
i2c_port_num_t port_num; // Port(Bus) ID, index from 0
portMUX_TYPE spinlock; // To protect pre-group register level concurrency access
i2c_hal_context_t hal; // Hal layer for each port(bus)
i2c_clock_source_t clk_src; // Record the port clock source
uint32_t clk_src_freq_hz; // Record the clock source frequency
int sda_num; // SDA pin number
int scl_num; // SCL pin number
bool pull_up_enable; // Disable pull-ups
intr_handle_t intr_handle; // I2C interrupt handle
esp_pm_lock_handle_t pm_lock; // power manange lock
#if CONFIG_PM_ENABLE
char pm_lock_name[I2C_PM_LOCK_NAME_LEN_MAX]; // pm lock name
#endif
i2c_bus_mode_t bus_mode; // I2C bus mode
};
typedef struct i2c_master_device_list {
i2c_master_dev_t *device;
SLIST_ENTRY(i2c_master_device_list) next;
} i2c_master_device_list_t;
struct i2c_master_bus_t {
i2c_bus_t *base; // bus base class
SemaphoreHandle_t bus_lock_mux; // semaphore to lock bus process
int cmd_idx; //record current command index, for master mode
_Atomic i2c_master_status_t status; // record current command status, for master mode
i2c_master_event_t event; // record current i2c bus event
int rx_cnt; // record current read index, for master mode
i2c_transaction_t i2c_trans; // Pointer to I2C transfer structure
i2c_operation_t i2c_ops[I2C_STATIC_OPERATION_ARRAY_MAX]; // I2C operation array
_Atomic uint16_t trans_idx; // Index of I2C transaction command.
SemaphoreHandle_t cmd_semphr; // Semaphore between task and interrupt, using for synchronizing ISR and I2C task.
uint32_t read_buf_pos; // Read buffer position
bool contains_read; // Whether command array includes read operation, true: yes, otherwise, false.
uint32_t read_len_static; // Read static buffer length
uint32_t w_r_size; // The size send/receive last time.
bool trans_over_buffer; // Data length is more than hardware fifo length, needs interrupt.
bool asnyc_trans; // asynchronous transaction, true after callback is installed.
volatile bool trans_done; // transaction command finish
SLIST_HEAD(i2c_master_device_list_head, i2c_master_device_list) device_list; // I2C device (instance) list
// asnyc trans members
bool async_break; // break transaction loop flag.
i2c_addr_bit_len_t addr_10bits_bus; // Slave address is 10 bits.
size_t queue_size; // I2C transaction queue size.
size_t num_trans_inflight; // Indicates the number of transactions that are undergoing but not recycled to ready_queue
size_t num_trans_inqueue; // Indicates the number of transaction in queue transaction.
void* queues_storage; // storage of transaction queues
bool sent_all; // true if the queue transaction is sent
bool in_progress; // true if current transaction is in progress
bool trans_finish; // true if current command has been sent out.
bool queue_trans; // true if current transaction is in queue
bool new_queue; // true if allow a new queue transaction
size_t index; // transaction index
QueueHandle_t trans_queues[I2C_TRANS_QUEUE_MAX]; // transaction queues.
StaticQueue_t trans_queue_structs[I2C_TRANS_QUEUE_MAX]; // memory to store the static structure for trans_queues
i2c_operation_t **i2c_anyc_ops; // pointer to asynchronous operation.
uint8_t **anyc_write_buffer; // pointer to asynchronous write buffer.
i2c_transaction_t i2c_trans_pool[]; // I2C transaction pool.
};
struct i2c_master_dev_t {
i2c_master_bus_t *master_bus; // I2C master bus base class
uint16_t device_address; // I2C device address
uint32_t scl_speed_hz; // SCL clock frequency
i2c_addr_bit_len_t addr_10bits; // Whether I2C device is a 10-bits address device.
i2c_master_callback_t on_trans_done; // I2C master transaction done callback.
void *user_ctx; // Callback user context
};
/**
* @brief Acquire I2C bus handle
*
* @param port_num I2C port number.
* @return
* - ESP_OK: Acquire bus handle successfully.
* - ESP_ERR_INVALID_ARG: Argument error.
* - ESP_ERR_INVALID_STATE: Acquire bus invalid state because bus has already acquired.
*/
esp_err_t i2c_acquire_bus_handle(i2c_port_num_t port_num, i2c_bus_handle_t *i2c_new_bus, i2c_bus_mode_t mode);
/**
* @brief Release I2C bus handle
*
* @param i2c_bus I2C bus handle, returned from `i2c_acquire_bus_handle`
* @return ESP_OK: If release successfully
*/
uint8_t i2c_release_bus_handle(i2c_bus_handle_t i2c_bus);
/**
* @brief Set clock source for I2C peripheral
*
* @param handle I2C bus handle
* @param clk_src Clock source
* @return
* - ESP_OK: Set clock source successfully
* - ESP_ERR_NOT_SUPPORTED: Set clock source failed because the clk_src is not supported
* - ESP_ERR_INVALID_STATE: Set clock source failed because the clk_src is different from other I2C controller
* - ESP_FAIL: Set clock source failed because of other error
*/
esp_err_t i2c_select_periph_clock(i2c_bus_handle_t handle, i2c_clock_source_t clk_src);
/**
* @brief Set I2C SCL/SDA pins
*
* @param handle I2C bus handle
* @return
* - ESP_OK: I2C set SCL/SDA pins successfully.
* - ESP_ERR_INVALID_ARG: Argument error.
* - Otherwise: Set SCL/SDA IOs error.
*/
esp_err_t i2c_common_set_pins(i2c_bus_handle_t handle);
/**
* @brief Check whether I2C bus is occupied
*
* @param port_num I2C port number.
* @return true: occupied, otherwise, false.
*/
bool i2c_bus_occupied(i2c_port_num_t port_num);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,213 @@
/*
* SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once
#include <stdint.h>
#include "esp_err.h"
#include "driver/i2c_types.h"
#include "hal/gpio_types.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief I2C master bus specific configurations
*/
typedef struct {
i2c_port_num_t i2c_port; /*!< I2C port number, `-1` for auto selecting */
gpio_num_t sda_io_num; /*!< GPIO number of I2C SDA signal, pulled-up internally */
gpio_num_t scl_io_num; /*!< GPIO number of I2C SCL signal, pulled-up internally */
i2c_clock_source_t clk_source; /*!< Clock source of I2C master bus, channels in the same group must use the same clock source */
uint8_t glitch_ignore_cnt; /*!< If the glitch period on the line is less than this value, it can be filtered out, typically value is 7 (unit: I2C module clock cycle)*/
int intr_priority; /*!< I2C interrupt priority, if set to 0, driver will select the default priority (1,2,3). */
size_t trans_queue_depth; /*!< Depth of internal transfer queue, increase this value can support more transfers pending in the background, only valid in asynchronous transaction. (Typically max_device_num * per_transaction)*/
struct {
uint32_t enable_internal_pullup:1; /*!< Enable internal pullups */
} flags;
} i2c_master_bus_config_t;
/**
* @brief I2C device configuration
*/
typedef struct {
i2c_addr_bit_len_t dev_addr_length; /*!< Select the address length of the slave device. */
uint16_t device_address; /*!< I2C device raw address. (The 7/10 bit address without read/write bit) */
uint32_t scl_speed_hz; /*!< I2C SCL line frequency. */
} i2c_device_config_t;
/**
* @brief Group of I2C master callbacks, can be used to get status during transaction or doing other small things. But take care potential concurrency issues.
* @note The callbacks are all running under ISR context
* @note When CONFIG_I2C_ISR_IRAM_SAFE is enabled, the callback itself and functions called by it should be placed in IRAM.
* The variables used in the function should be in the SRAM as well.
*/
typedef struct {
i2c_master_callback_t on_trans_done; /*!< I2C master transaction finish callback */
} i2c_master_event_callbacks_t;
/**
* @brief Allocate an I2C master bus
*
* @param[in] bus_config I2C master bus configuration.
* @param[out] ret_bus_handle I2C bus handle
* @return
* - ESP_OK: I2C master bus initialized successfully.
* - ESP_ERR_INVALID_ARG: I2C bus initialization failed because of invalid argument.
* - ESP_ERR_NO_MEM: Create I2C bus failed because of out of memory.
* - ESP_ERR_NOT_FOUND: No more free bus.
*/
esp_err_t i2c_new_master_bus(const i2c_master_bus_config_t *bus_config, i2c_master_bus_handle_t *ret_bus_handle);
/**
* @brief Add I2C master BUS device.
*
* @param[in] bus_handle I2C bus handle.
* @param[in] dev_config device config.
* @param[out] ret_handle device handle.
* @return
* - ESP_OK: Create I2C master device successfully.
* - ESP_ERR_INVALID_ARG: I2C bus initialization failed because of invalid argument.
* - ESP_ERR_NO_MEM: Create I2C bus failed because of out of memory.
*/
esp_err_t i2c_master_bus_add_device(i2c_master_bus_handle_t bus_handle, const i2c_device_config_t *dev_config, i2c_master_dev_handle_t *ret_handle);
/**
* @brief Deinitialize the I2C master bus and delete the handle.
*
* @param[in] bus_handle I2C bus handle.
* @return
* - ESP_OK: Delete I2C bus success, otherwise, failed.
* - Otherwise: Some module delete failed.
*/
esp_err_t i2c_del_master_bus(i2c_master_bus_handle_t bus_handle);
/**
* @brief I2C master bus delete device
*
* @param handle i2c device handle
* @return
* - ESP_OK: If device is successfully deleted.
*/
esp_err_t i2c_master_bus_rm_device(i2c_master_dev_handle_t handle);
/**
* @brief Perform a write transaction on the I2C bus.
* The transaction will be undergoing until it finishes or it reaches
* the timeout provided.
*
* @note If a callback was registered with `i2c_master_register_event_callbacks`, the transaction will be asynchronous, and thus, this function will return directly, without blocking.
* You will get finish information from callback. Besides, data buffer should always be completely prepared when callback is registered, otherwise, the data will get corrupt.
*
* @param[in] i2c_dev I2C master device handle that created by `i2c_master_bus_add_device`.
* @param[in] write_buffer Data bytes to send on the I2C bus.
* @param[in] write_size Size, in bytes, of the write buffer.
* @param[in] xfer_timeout_ms Wait timeout, in ms. Note: -1 means wait forever.
* @return
* - ESP_OK: I2C master transmit success
* - ESP_ERR_INVALID_ARG: I2c master transmit parameter invalid.
* - ESP_ERR_TIMEOUT: Operation timeout(larger than xfer_timeout_ms) because the bus is busy or hardware crash.
*/
esp_err_t i2c_master_transmit(i2c_master_dev_handle_t i2c_dev, const uint8_t *write_buffer, size_t write_size, int xfer_timeout_ms);
/**
* @brief Perform a write-read transaction on the I2C bus.
* The transaction will be undergoing until it finishes or it reaches
* the timeout provided.
*
* @note If a callback was registered with `i2c_master_register_event_callbacks`, the transaction will be asynchronous, and thus, this function will return directly, without blocking.
* You will get finish information from callback. Besides, data buffer should always be completely prepared when callback is registered, otherwise, the data will get corrupt.
*
* @param[in] i2c_dev I2C master device handle that created by `i2c_master_bus_add_device`.
* @param[in] write_buffer Data bytes to send on the I2C bus.
* @param[in] write_size Size, in bytes, of the write buffer.
* @param[out] read_buffer Data bytes received from i2c bus.
* @param[in] read_size Size, in bytes, of the read buffer.
* @param[in] xfer_timeout_ms Wait timeout, in ms. Note: -1 means wait forever.
* @return
* - ESP_OK: I2C master transmit-receive success
* - ESP_ERR_INVALID_ARG: I2c master transmit parameter invalid.
* - ESP_ERR_TIMEOUT: Operation timeout(larger than xfer_timeout_ms) because the bus is busy or hardware crash.
*/
esp_err_t i2c_master_transmit_receive(i2c_master_dev_handle_t i2c_dev, const uint8_t *write_buffer, size_t write_size, uint8_t *read_buffer, size_t read_size, int xfer_timeout_ms);
/**
* @brief Perform a read transaction on the I2C bus.
* The transaction will be undergoing until it finishes or it reaches
* the timeout provided.
*
* @note If a callback was registered with `i2c_master_register_event_callbacks`, the transaction will be asynchronous, and thus, this function will return directly, without blocking.
* You will get finish information from callback. Besides, data buffer should always be completely prepared when callback is registered, otherwise, the data will get corrupt.
*
* @param[in] i2c_dev I2C master device handle that created by `i2c_master_bus_add_device`.
* @param[out] read_buffer Data bytes received from i2c bus.
* @param[in] read_size Size, in bytes, of the read buffer.
* @param[in] xfer_timeout_ms Wait timeout, in ms. Note: -1 means wait forever.
* @return
* - ESP_OK: I2C master receive success
* - ESP_ERR_INVALID_ARG: I2c master receive parameter invalid.
* - ESP_ERR_TIMEOUT: Operation timeout(larger than xfer_timeout_ms) because the bus is busy or hardware crash.
*/
esp_err_t i2c_master_receive(i2c_master_dev_handle_t i2c_dev, uint8_t *read_buffer, size_t read_size, int xfer_timeout_ms);
/**
* @brief Probe I2C address, if address is correct and ACK is received, this function will return ESP_OK.
*
* @param[in] i2c_dev I2C master device handle that created by `i2c_master_bus_add_device`.
* @param[in] xfer_timeout_ms Wait timeout, in ms. Note: -1 means wait forever (Not recommended in this function).
* @return
* - ESP_OK: I2C device probe successfully
* - ESP_ERR_TIMEOUT: Operation timeout(larger than xfer_timeout_ms) because the bus is busy or hardware crash.
*/
// esp_err_t i2c_master_probe(i2c_master_dev_handle_t i2c_dev, int xfer_timeout_ms);
esp_err_t i2c_master_probe(i2c_master_bus_handle_t i2c_master, uint16_t address, int xfer_timeout_ms);
/**
* @brief Register I2C transaction callbacks for a master device
*
* @note User can deregister a previously registered callback by calling this function and setting the callback member in the `cbs` structure to NULL.
* @note When CONFIG_I2C_ISR_IRAM_SAFE is enabled, the callback itself and functions called by it should be placed in IRAM.
* The variables used in the function should be in the SRAM as well. The `user_data` should also reside in SRAM.
* @note If the callback is used for helping asynchronous transaction. On the same bus, only one device can be used for performing asynchronous operation.
*
* @param[in] i2c_dev I2C master device handle that created by `i2c_master_bus_add_device`.
* @param[in] cbs Group of callback functions
* @param[in] user_data User data, which will be passed to callback functions directly
* @return
* - ESP_OK: Set I2C transaction callbacks successfully
* - ESP_ERR_INVALID_ARG: Set I2C transaction callbacks failed because of invalid argument
* - ESP_FAIL: Set I2C transaction callbacks failed because of other error
*/
esp_err_t i2c_master_register_event_callbacks(i2c_master_dev_handle_t i2c_dev, const i2c_master_event_callbacks_t *cbs, void *user_data);
/**
* @brief Reset the I2C master bus.
*
* @param handle I2C bus handle.
* @return
* - ESP_OK: Reset succeed.
* - ESP_ERR_INVALID_ARG: I2C master bus handle is not initialized.
* - Otherwise: Reset failed.
*/
esp_err_t i2c_master_bus_reset(i2c_master_bus_handle_t handle);
/**
* @brief Wait for all pending I2C transactions done
*
* @param[in] i2c_master I2C bus handle
* @param[in] timeout_ms Wait timeout, in ms. Specially, -1 means to wait forever.
* @return
* - ESP_OK: Flush transactions successfully
* - ESP_ERR_INVALID_ARG: Flush transactions failed because of invalid argument
* - ESP_ERR_TIMEOUT: Flush transactions failed because of timeout
* - ESP_FAIL: Flush transactions failed because of other error
*/
esp_err_t i2c_master_wait_all_done(i2c_master_bus_handle_t i2c_master, int timeout_ms);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,74 @@
/*
* SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once
#include <stdint.h>
#include <stdbool.h>
#include "hal/i2c_types.h"
#include "soc/soc_caps.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief I2C port number.
*/
typedef int i2c_port_num_t;
/**
* @brief Enumeration for I2C fsm status.
*/
typedef enum {
I2C_STATUS_READ, /*!< read status for current master command */
I2C_STATUS_WRITE, /*!< write status for current master command */
I2C_STATUS_START, /*!< Start status for current master command */
I2C_STATUS_STOP, /*!< stop status for current master command */
I2C_STATUS_IDLE, /*!< idle status for current master command */
I2C_STATUS_ACK_ERROR, /*!< ack error status for current master command */
I2C_STATUS_DONE, /*!< I2C command done */
I2C_STATUS_TIMEOUT, /*!< I2C bus status error, and operation timeout */
} i2c_master_status_t;
typedef enum {
I2C_EVENT_ALIVE, /*!< i2c bus in alive status.*/
I2C_EVENT_DONE, /*!< i2c bus transaction done */
I2C_EVENT_NACK, /*!< i2c bus nack */
} i2c_master_event_t;
/**
* @brief Type of I2C master bus handle
*/
typedef struct i2c_master_bus_t *i2c_master_bus_handle_t;
/**
* @brief Type of I2C master bus device handle
*/
typedef struct i2c_master_dev_t *i2c_master_dev_handle_t;
/**
* @brief Data type used in I2C event callback
*/
typedef struct {
i2c_master_event_t event; /**< The I2C hardware event that I2C callback is called. */
} i2c_master_event_data_t;
/**
* @brief An callback for I2C transaction.
*
* @param[in] i2c_dev Handle for I2C device.
* @param[out] evt_data I2C capture event data, fed by driver
* @param[in] arg User data, set in `i2c_master_register_event_callbacks()`
*
* @return Whether a high priority task has been waken up by this function
*/
typedef bool (*i2c_master_callback_t)(i2c_master_dev_handle_t i2c_dev, const i2c_master_event_data_t *evt_data, void *arg);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,8 @@
[mapping:i2c_driver]
archive: libdriver.a
entries:
if I2C_ISR_IRAM_SAFE = y:
i2c_master: s_i2c_send_command_async (noflash)
i2c_master: s_i2c_write_command (noflash)
i2c_master: s_i2c_read_command (noflash)
i2c_master: s_i2c_start_end_command (noflash)

View File

@ -0,0 +1,131 @@
/*
* SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Unlicense OR CC0-1.0
*/
#include <stdio.h>
#include <string.h>
#include "sdkconfig.h"
#include "unity.h"
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "esp_err.h"
#include "soc/gpio_periph.h"
#include "soc/clk_tree_defs.h"
#include "soc/soc_caps.h"
#include "hal/gpio_hal.h"
#include "hal/uart_ll.h"
#include "esp_private/periph_ctrl.h"
#include "driver/gpio.h"
#include "driver/i2c_master.h"
#include "esp_rom_gpio.h"
#include "esp_log.h"
#include "test_utils.h"
static const char TAG[] = "test-i2c";
#define TEST_I2C_SCL_PIN 2
#define TEST_I2C_SDA_PIN 4
#define TEST_I2C_SCL_FREQ (100 * 1000)
#define TEST_I2C_PORT 0
#define SLAVE_ADDR 0x58
TEST_CASE("I2C bus install-uninstall test", "[i2c]")
{
i2c_master_bus_config_t i2c_mst_config_1 = {
.clk_source = I2C_CLK_SRC_DEFAULT,
.i2c_port = TEST_I2C_PORT,
.scl_io_num = TEST_I2C_SCL_PIN,
.sda_io_num = TEST_I2C_SDA_PIN,
};
i2c_master_bus_handle_t i2c_mst_handle1;
#if SOC_I2C_NUM > 1
i2c_master_bus_config_t i2c_mst_config_2 = {
.clk_source = I2C_CLK_SRC_DEFAULT,
.i2c_port = 1,
.scl_io_num = TEST_I2C_SCL_PIN,
.sda_io_num = TEST_I2C_SDA_PIN,
};
i2c_master_bus_handle_t i2c_mst_handle2;
#endif
// Install master bus 0
ESP_LOGI(TAG, "Initialize bus0");
TEST_ESP_OK(i2c_new_master_bus(&i2c_mst_config_1, &i2c_mst_handle1));
#if SOC_I2C_NUM > 1
// Install master bus 1
ESP_LOGI(TAG, "Initialize bus1");
TEST_ESP_OK(i2c_new_master_bus(&i2c_mst_config_2, &i2c_mst_handle2));
#endif
// Install master bus 0 again
ESP_LOGI(TAG, "Initialize bus0 again");
TEST_ESP_ERR(ESP_ERR_INVALID_STATE, i2c_new_master_bus(&i2c_mst_config_1, &i2c_mst_handle1));
ESP_LOGI(TAG, "Delete bus0");
TEST_ESP_OK(i2c_del_master_bus(i2c_mst_handle1));
#if SOC_I2C_NUM > 1
ESP_LOGI(TAG, "Delete bus1");
TEST_ESP_OK(i2c_del_master_bus(i2c_mst_handle2));
#endif
}
TEST_CASE("I2C driver memory leaking check", "[i2c]")
{
i2c_master_bus_config_t i2c_mst_config_1 = {
.clk_source = I2C_CLK_SRC_DEFAULT,
.i2c_port = TEST_I2C_PORT,
.scl_io_num = TEST_I2C_SCL_PIN,
.sda_io_num = TEST_I2C_SDA_PIN,
};
i2c_master_bus_handle_t bus_handle;
int size = esp_get_free_heap_size();
for (uint32_t i = 0; i <= 5; i++) {
TEST_ESP_OK(i2c_new_master_bus(&i2c_mst_config_1, &bus_handle));
vTaskDelay(10 / portTICK_PERIOD_MS);
TEST_ESP_OK(i2c_del_master_bus(bus_handle));
}
TEST_ASSERT_INT_WITHIN(300, size, esp_get_free_heap_size());
}
TEST_CASE("I2C device add & remove check", "[i2c]")
{
i2c_master_bus_config_t i2c_mst_config_1 = {
.clk_source = I2C_CLK_SRC_DEFAULT,
.i2c_port = TEST_I2C_PORT,
.scl_io_num = TEST_I2C_SCL_PIN,
.sda_io_num = TEST_I2C_SDA_PIN,
};
i2c_master_bus_handle_t bus_handle;
TEST_ESP_OK(i2c_new_master_bus(&i2c_mst_config_1, &bus_handle));
i2c_device_config_t dev_cfg_1 = {
.scl_speed_hz = 100*1000,
.device_address = 0x10,
};
i2c_master_dev_handle_t dev_1;
i2c_master_bus_add_device(bus_handle, &dev_cfg_1, &dev_1);
i2c_device_config_t dev_cfg_2 = {
.scl_speed_hz = 100*1000,
.device_address = 0x20,
};
i2c_master_dev_handle_t dev_2;
i2c_master_bus_add_device(bus_handle, &dev_cfg_2, &dev_2);
i2c_device_config_t dev_cfg_3 = {
.scl_speed_hz = 100*1000,
.device_address = 0x30,
};
i2c_master_dev_handle_t dev_3;
i2c_master_bus_add_device(bus_handle, &dev_cfg_3, &dev_3);
i2c_master_bus_rm_device(dev_1);
i2c_master_bus_rm_device(dev_2);
i2c_master_bus_rm_device(dev_3);
TEST_ESP_OK(i2c_del_master_bus(bus_handle));
}

View File

@ -0,0 +1,19 @@
# SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD
# SPDX-License-Identifier: CC0-1.0
import pytest
from pytest_embedded import Dut
@pytest.mark.supported_targets
@pytest.mark.generic
@pytest.mark.parametrize(
'config',
[
'release',
'iram_safe',
],
indirect=True,
)
def test_i2c(dut: Dut) -> None:
dut.run_all_single_board_cases()

View File

@ -0,0 +1,6 @@
CONFIG_PM_ENABLE=y
CONFIG_COMPILER_DUMP_RTL_FILES=y
CONFIG_FREERTOS_USE_TICKLESS_IDLE=y
CONFIG_COMPILER_OPTIMIZATION_NONE=y
CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_SILENT=y
CONFIG_I2C_ISR_IRAM_SAFE=y

View File

@ -0,0 +1,22 @@
# This is the project CMakeLists.txt file for the test subproject
cmake_minimum_required(VERSION 3.16)
set(EXTRA_COMPONENT_DIRS
"$ENV{IDF_PATH}/tools/unit-test-app/components"
)
include($ENV{IDF_PATH}/tools/cmake/project.cmake)
project(legacy_i2c_test)
if(CONFIG_COMPILER_DUMP_RTL_FILES)
add_custom_target(check_test_app_sections ALL
COMMAND ${PYTHON} $ENV{IDF_PATH}/tools/ci/check_callgraph.py
--rtl-dirs ${CMAKE_BINARY_DIR}/esp-idf/driver/,${CMAKE_BINARY_DIR}/esp-idf/hal/
--elf-file ${CMAKE_BINARY_DIR}/legacy_i2c_test.elf
find-refs
--from-sections=.iram0.text
--to-sections=.flash.text,.flash.rodata
--exit-code
DEPENDS ${elf}
)
endif()

View File

@ -0,0 +1,2 @@
| Supported Targets | ESP32 | ESP32-C2 | ESP32-C3 | ESP32-C6 | ESP32-H2 | ESP32-S2 | ESP32-S3 |
| ----------------- | ----- | -------- | -------- | -------- | -------- | -------- | -------- |

View File

@ -0,0 +1,6 @@
set(srcs "test_app_main.c"
"test_i2c.c"
)
idf_component_register(SRCS ${srcs}
WHOLE_ARCHIVE)

View File

@ -0,0 +1,42 @@
/*
* SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include "unity.h"
#include "unity_test_runner.h"
#include "unity_test_utils_memory.h"
#include "esp_heap_caps.h"
// Some resources are lazy allocated in I2C driver, so we reserved this threshold when checking memory leak
// A better way to check a potential memory leak is running a same case by twice, for the second time, the memory usage delta should be zero
#define LEAKS (400)
void setUp(void)
{
unity_utils_record_free_mem();
}
void tearDown(void)
{
unity_utils_evaluate_leaks_direct(LEAKS);
}
void app_main(void)
{
// ___ ____ ____ _____ _
// |_ _|___ \ / ___| |_ _|__ ___| |_
// | | __) | | | |/ _ \/ __| __|
// | | / __/| |___ | | __/\__ \ |_
// |___|_____|\____| |_|\___||___/\__|
printf(" ___ ____ ____ _____ _ \n");
printf("|_ _|___ \\ / ___| |_ _|__ ___| |_ \n");
printf(" | | __) | | | |/ _ \\/ __| __|\n");
printf(" | | / __/| |___ | | __/\\__ \\ |_ \n");
printf("|___|_____|\\____| |_|\\___||___/\\__|\n");
unity_run_menu();
}

View File

@ -15,7 +15,7 @@ from pytest_embedded import Dut
],
indirect=True,
)
def test_i2c(dut: Dut) -> None:
def test_i2c_legacy(dut: Dut) -> None:
dut.run_all_single_board_cases()
@ -33,7 +33,7 @@ def test_i2c(dut: Dut) -> None:
],
indirect=True
)
def test_i2c_multi_dev(case_tester) -> None: # type: ignore
def test_i2c_multi_dev_legacy(case_tester) -> None: # type: ignore
for case in case_tester.test_menu:
if case.attributes.get('test_env', 'generic_multi_device') == 'generic_multi_device':
case_tester.run_multi_dev_case(case=case, reset=True)

View File

@ -0,0 +1,2 @@
CONFIG_FREERTOS_HZ=1000
CONFIG_ESP_TASK_WDT=n

View File

@ -0,0 +1,5 @@
CONFIG_PM_ENABLE=y
CONFIG_FREERTOS_USE_TICKLESS_IDLE=y
CONFIG_COMPILER_OPTIMIZATION_SIZE=y
CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_SIZE=y
CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_SILENT=y

View File

@ -0,0 +1,2 @@
CONFIG_FREERTOS_HZ=1000
CONFIG_ESP_TASK_WDT=n

View File

@ -25,13 +25,13 @@ extern "C" {
*/
typedef union {
struct {
uint32_t byte_num: 8,
ack_en: 1,
ack_exp: 1,
ack_val: 1,
op_code: 3,
reserved14: 17,
done: 1;
uint32_t byte_num: 8, /*!< Specifies the length of data (in bytes) to be read or written */
ack_en: 1, /*!< Used to enable the I2C controller during a write operation to check whether ACK */
ack_exp: 1, /*!< Used to configure the level of the ACK bit expected by the I2C controller during a write operation */
ack_val: 1, /*!< Used to configure the level of the ACK bit sent by the I2C controller during a read operation */
op_code: 3, /*!< Indicates the command */
reserved14: 17, /*!< Reserved bits */
done: 1; /*!< Indicates that a command has been executed */
};
uint32_t val;
} i2c_ll_hw_cmd_t;
@ -44,26 +44,25 @@ typedef union {
#define I2C_LL_CMD_END 4 /*!<I2C end command */
typedef enum {
I2C_INTR_NACK = (1 << 10),
I2C_INTR_TIMEOUT = (1 << 8),
I2C_INTR_MST_COMPLETE = (1 << 7),
I2C_INTR_ARBITRATION = (1 << 5),
I2C_INTR_END_DETECT = (1 << 3),
I2C_INTR_ST_TO = (1 << 13),
} i2c_ll_master_intr_t;
typedef enum {
I2C_INTR_TXFIFO_WM = (1 << 1),
I2C_INTR_RXFIFO_WM = (1 << 0),
I2C_INTR_SLV_COMPLETE = (1 << 7),
I2C_INTR_START = (1 << 15),
} i2c_ll_slave_intr_t;
I2C_LL_INTR_TXFIFO_WM = (1 << 1),
I2C_LL_INTR_RXFIFO_WM = (1 << 0),
I2C_LL_INTR_NACK = (1 << 10),
I2C_LL_INTR_TIMEOUT = (1 << 8),
I2C_LL_INTR_MST_COMPLETE = (1 << 7),
I2C_LL_INTR_ARBITRATION = (1 << 5),
I2C_LL_INTR_END_DETECT = (1 << 3),
I2C_LL_INTR_ST_TO = (1 << 13),
I2C_LL_INTR_START = (1 << 15),
I2C_LL_INTR_STRETCH = (1 << 16),
I2C_LL_INTR_UNMATCH = (1 << 18),
} i2c_ll_intr_t;
// Get the I2C hardware instance
#define I2C_LL_GET_HW(i2c_num) (((i2c_num) == 0) ? &I2C0 : &I2C1)
#define I2C_LL_MASTER_EVENT_INTR (I2C_ACK_ERR_INT_ENA_M|I2C_TIME_OUT_INT_ENA_M|I2C_TRANS_COMPLETE_INT_ENA_M|I2C_ARBITRATION_LOST_INT_ENA_M|I2C_END_DETECT_INT_ENA_M)
#define I2C_LL_SLAVE_EVENT_INTR (I2C_RXFIFO_FULL_INT_ENA_M|I2C_TRANS_COMPLETE_INT_ENA_M|I2C_TXFIFO_EMPTY_INT_ENA_M)
#define I2C_LL_SLAVE_EVENT_INTR (I2C_TRANS_COMPLETE_INT_ENA_M|I2C_TXFIFO_EMPTY_INT_ENA_M)
#define I2C_LL_SLAVE_RX_EVENT_INTR (I2C_TRANS_COMPLETE_INT_ENA_M|I2C_RXFIFO_FULL_INT_ENA_M)
#define I2C_LL_SLAVE_TX_EVENT_INTR (I2C_TXFIFO_EMPTY_INT_ENA_M)
/**
* @brief Calculate I2C bus frequency
@ -74,7 +73,7 @@ typedef enum {
*
* @return None
*/
static inline void i2c_ll_cal_bus_clk(uint32_t source_clk, uint32_t bus_freq, i2c_hal_clk_config_t *clk_cal)
static inline void i2c_ll_master_cal_bus_clk(uint32_t source_clk, uint32_t bus_freq, i2c_hal_clk_config_t *clk_cal)
{
uint32_t half_cycle = source_clk / bus_freq / 2;
clk_cal->scl_low = half_cycle;
@ -94,7 +93,7 @@ static inline void i2c_ll_cal_bus_clk(uint32_t source_clk, uint32_t bus_freq, i2
*
* @return None
*/
static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bus_cfg)
static inline void i2c_ll_master_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bus_cfg)
{
/* SCL period. According to the TRM, we should always subtract 1 to SCL low period */
assert(bus_cfg->scl_low > 0);
@ -130,6 +129,18 @@ static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bu
hw->timeout.tout = bus_cfg->tout;
}
/**
* @brief Set fractional divider
*
* @param hw Beginning address of the peripheral registers
* @param div_a The denominator of the frequency divider factor of the i2c function clock
* @param div_b The numerator of the frequency divider factor of the i2c function clock.
*/
static inline void i2c_ll_master_set_fractional_divider(i2c_dev_t *hw, uint8_t div_a, uint8_t div_b)
{
// Not supported on ESP32
}
/**
* @brief Reset I2C txFIFO
*
@ -137,6 +148,7 @@ static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bu
*
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_txfifo_rst(i2c_dev_t *hw)
{
hw->fifo_conf.tx_fifo_rst = 1;
@ -150,27 +162,13 @@ static inline void i2c_ll_txfifo_rst(i2c_dev_t *hw)
*
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_rxfifo_rst(i2c_dev_t *hw)
{
hw->fifo_conf.rx_fifo_rst = 1;
hw->fifo_conf.rx_fifo_rst = 0;
}
/**
* @brief Configure I2C SCL timing
*
* @param hw Beginning address of the peripheral registers
* @param hight_period The I2C SCL hight period (in APB cycle)
* @param low_period The I2C SCL low period (in APB cycle)
*
* @return None.
*/
static inline void i2c_ll_set_scl_timing(i2c_dev_t *hw, int hight_period, int low_period)
{
hw->scl_low_period.period = low_period;
hw->scl_high_period.period = hight_period;
}
/**
* @brief Clear I2C interrupt status
*
@ -193,6 +191,7 @@ static inline void i2c_ll_clear_intr_mask(i2c_dev_t *hw, uint32_t mask)
*
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_enable_intr_mask(i2c_dev_t *hw, uint32_t mask)
{
hw->int_ena.val |= mask;
@ -233,7 +232,7 @@ static inline void i2c_ll_get_intr_mask(i2c_dev_t *hw, uint32_t *intr_status)
*
* @return None
*/
static inline void i2c_ll_set_fifo_mode(i2c_dev_t *hw, bool fifo_mode_en)
static inline void i2c_ll_slave_set_fifo_mode(i2c_dev_t *hw, bool fifo_mode_en)
{
hw->fifo_conf.nonfifo_en = fifo_mode_en ? 0 : 1;
}
@ -251,6 +250,19 @@ static inline void i2c_ll_set_tout(i2c_dev_t *hw, int tout)
hw->timeout.tout = tout;
}
/**
* @brief Configure I2C slave broadcasting mode.
*
* @param hw Beginning address of the peripheral registers
* @param broadcast_en Set true to enable broadcast, else, set it false
*
* @return None
*/
static inline void i2c_ll_slave_broadcast_enable(i2c_dev_t *hw, bool broadcast_en)
{
// Not supported on esp32
}
/**
* @brief Configure I2C slave address
*
@ -262,8 +274,14 @@ static inline void i2c_ll_set_tout(i2c_dev_t *hw, int tout)
*/
static inline void i2c_ll_set_slave_addr(i2c_dev_t *hw, uint16_t slave_addr, bool addr_10bit_en)
{
hw->slave_addr.addr = slave_addr;
hw->slave_addr.en_10bit = addr_10bit_en;
if (addr_10bit_en) {
uint8_t addr_14_7 = (slave_addr & 0xff) << 7;
uint8_t addr_6_0 = ((slave_addr & 0x300) >> 8) || 0x78;
hw->slave_addr.addr = addr_14_7 || addr_6_0;
} else {
hw->slave_addr.addr = slave_addr;
}
}
/**
@ -276,7 +294,7 @@ static inline void i2c_ll_set_slave_addr(i2c_dev_t *hw, uint16_t slave_addr, boo
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_write_cmd_reg(i2c_dev_t *hw, i2c_ll_hw_cmd_t cmd, int cmd_idx)
static inline void i2c_ll_master_write_cmd_reg(i2c_dev_t *hw, i2c_ll_hw_cmd_t cmd, int cmd_idx)
{
hw->command[cmd_idx].val = cmd.val;
}
@ -290,7 +308,7 @@ static inline void i2c_ll_write_cmd_reg(i2c_dev_t *hw, i2c_ll_hw_cmd_t cmd, int
*
* @return None
*/
static inline void i2c_ll_set_start_timing(i2c_dev_t *hw, int start_setup, int start_hold)
static inline void i2c_ll_master_set_start_timing(i2c_dev_t *hw, int start_setup, int start_hold)
{
hw->scl_rstart_setup.time = start_setup;
hw->scl_start_hold.time = start_hold;
@ -305,7 +323,7 @@ static inline void i2c_ll_set_start_timing(i2c_dev_t *hw, int start_setup, int s
*
* @return None
*/
static inline void i2c_ll_set_stop_timing(i2c_dev_t *hw, int stop_setup, int stop_hold)
static inline void i2c_ll_master_set_stop_timing(i2c_dev_t *hw, int stop_setup, int stop_hold)
{
hw->scl_stop_setup.time = stop_setup;
hw->scl_stop_hold.time = stop_hold;
@ -367,21 +385,6 @@ static inline void i2c_ll_set_data_mode(i2c_dev_t *hw, i2c_trans_mode_t tx_mode,
hw->ctr.rx_lsb_first = rx_mode;
}
/**
* @brief Get the I2C data mode
*
* @param hw Beginning address of the peripheral registers
* @param tx_mode Pointer to accept the received bytes mode
* @param rx_mode Pointer to accept the sended bytes mode
*
* @return None
*/
static inline void i2c_ll_get_data_mode(i2c_dev_t *hw, i2c_trans_mode_t *tx_mode, i2c_trans_mode_t *rx_mode)
{
*tx_mode = hw->ctr.tx_lsb_first;
*rx_mode = hw->ctr.rx_lsb_first;
}
/**
* @brief Get I2C sda timing configuration
*
@ -405,6 +408,7 @@ static inline void i2c_ll_get_sda_timing(i2c_dev_t *hw, int *sda_sample, int *sd
*
* @return True if I2C state machine is busy, else false will be returned
*/
__attribute__((always_inline))
static inline bool i2c_ll_is_bus_busy(i2c_dev_t *hw)
{
return hw->status_reg.bus_busy;
@ -456,7 +460,7 @@ static inline void i2c_ll_get_tout(i2c_dev_t *hw, int *timeout)
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_trans_start(i2c_dev_t *hw)
static inline void i2c_ll_master_trans_start(i2c_dev_t *hw)
{
hw->ctr.trans_start = 1;
}
@ -491,21 +495,6 @@ static inline void i2c_ll_get_stop_timing(i2c_dev_t *hw, int *setup_time, int *h
*hold_time = hw->scl_stop_hold.time;
}
/**
* @brief Get I2C SCL timing configuration
*
* @param hw Beginning address of the peripheral registers
* @param high_period Pointer to accept the SCL high period
* @param low_period Pointer to accept the SCL low period
*
* @return None
*/
static inline void i2c_ll_get_scl_timing(i2c_dev_t *hw, int *high_period, int *low_period)
{
*high_period = hw->scl_high_period.period;
*low_period = hw->scl_low_period.period;
}
/**
* @brief Write the I2C hardware txFIFO
*
@ -550,7 +539,7 @@ static inline void i2c_ll_read_rxfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
*
* @return None
*/
static inline void i2c_ll_set_filter(i2c_dev_t *hw, uint8_t filter_num)
static inline void i2c_ll_master_set_filter(i2c_dev_t *hw, uint8_t filter_num)
{
if(filter_num > 0) {
hw->scl_filter_cfg.thres = filter_num;
@ -570,7 +559,7 @@ static inline void i2c_ll_set_filter(i2c_dev_t *hw, uint8_t filter_num)
*
* @return The hardware filter configuration
*/
static inline void i2c_ll_get_filter(i2c_dev_t *hw, uint8_t *filter_conf)
static inline void i2c_ll_master_get_filter(i2c_dev_t *hw, uint8_t *filter_conf)
{
*filter_conf = hw->sda_filter_cfg.thres;
}
@ -597,7 +586,7 @@ static inline void i2c_ll_master_fsm_rst(i2c_dev_t *hw)
*
* @return None
*/
static inline void i2c_ll_master_clr_bus(i2c_dev_t *hw)
static inline void i2c_ll_master_clr_bus(i2c_dev_t *hw, uint32_t slave_pulses)
{
;//ESP32 do not support
}
@ -693,6 +682,28 @@ static inline volatile void *i2c_ll_get_interrupt_status_reg(i2c_dev_t *dev)
return &dev->int_status;
}
/**
* @brief Enable I2C slave clock stretch.
*
* @param dev Beginning address of the peripheral registers.
* @param enable true: Enable, false: Disable.
*/
static inline void i2c_ll_slave_enable_scl_stretch(i2c_dev_t *dev, bool enable)
{
// Not supported on esp32
}
/**
* @brief Clear I2C clock stretch status
*
* @param dev Beginning address of the peripheral registers
*/
__attribute__((always_inline))
static inline void i2c_ll_slave_clear_stretch(i2c_dev_t *dev)
{
// Not supported on esp32
}
//////////////////////////////////////////Deprecated Functions//////////////////////////////////////////////////////////
/////////////////////////////The following functions are only used by the legacy driver/////////////////////////////////
/////////////////////////////They might be removed in the next major release (ESP-IDF 6.0)//////////////////////////////
@ -922,6 +933,50 @@ static inline uint32_t i2c_ll_get_hw_version(i2c_dev_t *hw)
return hw->date;
}
/**
* @brief Configure I2C SCL timing
*
* @param hw Beginning address of the peripheral registers
* @param hight_period The I2C SCL hight period (in APB cycle)
* @param low_period The I2C SCL low period (in APB cycle)
*
* @return None.
*/
static inline void i2c_ll_set_scl_timing(i2c_dev_t *hw, int hight_period, int low_period)
{
hw->scl_low_period.period = low_period;
hw->scl_high_period.period = hight_period;
}
/**
* @brief Get the I2C data mode
*
* @param hw Beginning address of the peripheral registers
* @param tx_mode Pointer to accept the received bytes mode
* @param rx_mode Pointer to accept the sended bytes mode
*
* @return None
*/
static inline void i2c_ll_get_data_mode(i2c_dev_t *hw, i2c_trans_mode_t *tx_mode, i2c_trans_mode_t *rx_mode)
{
*tx_mode = hw->ctr.tx_lsb_first;
*rx_mode = hw->ctr.rx_lsb_first;
}
/**
* @brief Get I2C SCL timing configuration
*
* @param hw Beginning address of the peripheral registers
* @param high_period Pointer to accept the SCL high period
* @param low_period Pointer to accept the SCL low period
*
* @return None
*/
static inline void i2c_ll_get_scl_timing(i2c_dev_t *hw, int *high_period, int *low_period)
{
*high_period = hw->scl_high_period.period;
*low_period = hw->scl_low_period.period;
}
#ifdef __cplusplus
}

View File

@ -28,13 +28,13 @@ extern "C" {
*/
typedef union {
struct {
uint32_t byte_num: 8,
ack_en: 1,
ack_exp: 1,
ack_val: 1,
op_code: 3,
reserved14: 17,
done: 1;
uint32_t byte_num: 8, /*!< Specifies the length of data (in bytes) to be read or written */
ack_en: 1, /*!< Used to enable the I2C controller during a write operation to check whether ACK */
ack_exp: 1, /*!< Used to configure the level of the ACK bit expected by the I2C controller during a write operation */
ack_val: 1, /*!< Used to configure the level of the ACK bit sent by the I2C controller during a read operation */
op_code: 3, /*!< Indicates the command */
reserved14: 17, /*!< Reserved bits */
done: 1; /*!< Indicates that a command has been executed */
};
uint32_t val;
} i2c_ll_hw_cmd_t;
@ -47,25 +47,24 @@ typedef union {
#define I2C_LL_CMD_END 4 /*!<I2C end command */
typedef enum {
I2C_INTR_NACK = (1 << 10),
I2C_INTR_TIMEOUT = (1 << 8),
I2C_INTR_MST_COMPLETE = (1 << 7),
I2C_INTR_ARBITRATION = (1 << 5),
I2C_INTR_END_DETECT = (1 << 3),
I2C_INTR_ST_TO = (1 << 13),
} i2c_ll_master_intr_t;
typedef enum {
I2C_INTR_TXFIFO_WM = (1 << 1),
I2C_INTR_RXFIFO_WM = (1 << 0),
I2C_INTR_SLV_COMPLETE = (1 << 7),
I2C_INTR_START = (1 << 15),
} i2c_ll_slave_intr_t;
I2C_LL_INTR_TXFIFO_WM = (1 << 1),
I2C_LL_INTR_RXFIFO_WM = (1 << 0),
I2C_LL_INTR_NACK = (1 << 10),
I2C_LL_INTR_TIMEOUT = (1 << 8),
I2C_LL_INTR_MST_COMPLETE = (1 << 7),
I2C_LL_INTR_ARBITRATION = (1 << 5),
I2C_LL_INTR_END_DETECT = (1 << 3),
I2C_LL_INTR_ST_TO = (1 << 13),
I2C_LL_INTR_START = (1 << 15),
I2C_LL_INTR_STRETCH = (1 << 16),
I2C_LL_INTR_UNMATCH = (1 << 18),
} i2c_ll_intr_t;
// Get the I2C hardware instance
#define I2C_LL_GET_HW(i2c_num) (&I2C0)
#define I2C_LL_MASTER_EVENT_INTR (I2C_NACK_INT_ENA_M|I2C_TIME_OUT_INT_ENA_M|I2C_TRANS_COMPLETE_INT_ENA_M|I2C_ARBITRATION_LOST_INT_ENA_M|I2C_END_DETECT_INT_ENA_M)
#define I2C_LL_SLAVE_EVENT_INTR (I2C_RXFIFO_WM_INT_ENA_M|I2C_TRANS_COMPLETE_INT_ENA_M|I2C_TXFIFO_WM_INT_ENA_M)
#define I2C_LL_SLAVE_EVENT_INTR 0
#define I2C_LL_RESET_SLV_SCL_PULSE_NUM_DEFAULT (9)
/**
* @brief Calculate I2C bus frequency
@ -79,7 +78,7 @@ typedef enum {
*
* @return None
*/
static inline void i2c_ll_cal_bus_clk(uint32_t source_clk, uint32_t bus_freq, i2c_hal_clk_config_t *clk_cal)
static inline void i2c_ll_master_cal_bus_clk(uint32_t source_clk, uint32_t bus_freq, i2c_hal_clk_config_t *clk_cal)
{
uint32_t clkm_div = source_clk / (bus_freq * 1024) +1;
uint32_t sclk_freq = source_clk / clkm_div;
@ -126,7 +125,7 @@ static inline void i2c_ll_update(i2c_dev_t *hw)
*
* @return None
*/
static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bus_cfg)
static inline void i2c_ll_master_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bus_cfg)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->clk_conf, sclk_div_num, bus_cfg->clkm_div - 1);
/* According to the Technical Reference Manual, the following timings must be subtracted by 1.
@ -150,6 +149,20 @@ static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bu
hw->to.time_out_en = 1;
}
/**
* @brief Set fractional divider
*
* @param hw Beginning address of the peripheral registers
* @param div_a The denominator of the frequency divider factor of the i2c function clock
* @param div_b The numerator of the frequency divider factor of the i2c function clock.
*/
static inline void i2c_ll_master_set_fractional_divider(i2c_dev_t *hw, uint8_t div_a, uint8_t div_b)
{
/* Set div_a and div_b to 0, as it's not necessary to use them */
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->clk_conf, sclk_div_a, div_a);
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->clk_conf, sclk_div_b, div_b);
}
/**
* @brief Reset I2C txFIFO
*
@ -157,6 +170,7 @@ static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bu
*
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_txfifo_rst(i2c_dev_t *hw)
{
hw->fifo_conf.tx_fifo_rst = 1;
@ -170,28 +184,13 @@ static inline void i2c_ll_txfifo_rst(i2c_dev_t *hw)
*
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_rxfifo_rst(i2c_dev_t *hw)
{
hw->fifo_conf.rx_fifo_rst = 1;
hw->fifo_conf.rx_fifo_rst = 0;
}
/**
* @brief Configure I2C SCL timing
*
* @param hw Beginning address of the peripheral registers
* @param hight_period The I2C SCL hight period (in core clock cycle, hight_period > 2)
* @param low_period The I2C SCL low period (in core clock cycle, low_period > 1)
*
* @return None.
*/
static inline void i2c_ll_set_scl_timing(i2c_dev_t *hw, int hight_period, int low_period)
{
hw->scl_low_period.scl_low_period = low_period - 1;
hw->scl_high_period.scl_high_period = hight_period - 10;
hw->scl_high_period.scl_wait_high_period = hight_period - hw->scl_high_period.scl_high_period;
}
/**
* @brief Clear I2C interrupt status
*
@ -214,6 +213,7 @@ static inline void i2c_ll_clear_intr_mask(i2c_dev_t *hw, uint32_t mask)
*
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_enable_intr_mask(i2c_dev_t *hw, uint32_t mask)
{
hw->int_ena.val |= mask;
@ -254,7 +254,7 @@ static inline void i2c_ll_get_intr_mask(i2c_dev_t *hw, uint32_t *intr_status)
*
* @return None
*/
static inline void i2c_ll_set_fifo_mode(i2c_dev_t *hw, bool fifo_mode_en)
static inline void i2c_ll_slave_set_fifo_mode(i2c_dev_t *hw, bool fifo_mode_en)
{
hw->fifo_conf.nonfifo_en = fifo_mode_en ? 0 : 1;
}
@ -282,7 +282,7 @@ static inline void i2c_ll_set_tout(i2c_dev_t *hw, int tout)
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_write_cmd_reg(i2c_dev_t *hw, i2c_ll_hw_cmd_t cmd, int cmd_idx)
static inline void i2c_ll_master_write_cmd_reg(i2c_dev_t *hw, i2c_ll_hw_cmd_t cmd, int cmd_idx)
{
hw->command[cmd_idx].val = cmd.val;
}
@ -296,7 +296,7 @@ static inline void i2c_ll_write_cmd_reg(i2c_dev_t *hw, i2c_ll_hw_cmd_t cmd, int
*
* @return None
*/
static inline void i2c_ll_set_start_timing(i2c_dev_t *hw, int start_setup, int start_hold)
static inline void i2c_ll_master_set_start_timing(i2c_dev_t *hw, int start_setup, int start_hold)
{
hw->scl_rstart_setup.scl_rstart_setup_time = start_setup;
hw->scl_start_hold.scl_start_hold_time = start_hold - 1;
@ -311,7 +311,7 @@ static inline void i2c_ll_set_start_timing(i2c_dev_t *hw, int start_setup, int s
*
* @return None
*/
static inline void i2c_ll_set_stop_timing(i2c_dev_t *hw, int stop_setup, int stop_hold)
static inline void i2c_ll_master_set_stop_timing(i2c_dev_t *hw, int stop_setup, int stop_hold)
{
hw->scl_stop_setup.scl_stop_setup_time = stop_setup;
hw->scl_stop_hold.scl_stop_hold_time = stop_hold;
@ -373,21 +373,6 @@ static inline void i2c_ll_set_data_mode(i2c_dev_t *hw, i2c_trans_mode_t tx_mode,
hw->ctr.rx_lsb_first = rx_mode;
}
/**
* @brief Get the I2C data mode
*
* @param hw Beginning address of the peripheral registers
* @param tx_mode Pointer to accept the received bytes mode
* @param rx_mode Pointer to accept the sended bytes mode
*
* @return None
*/
static inline void i2c_ll_get_data_mode(i2c_dev_t *hw, i2c_trans_mode_t *tx_mode, i2c_trans_mode_t *rx_mode)
{
*tx_mode = hw->ctr.tx_lsb_first;
*rx_mode = hw->ctr.rx_lsb_first;
}
/**
* @brief Get I2C sda timing configuration
*
@ -422,6 +407,7 @@ static inline uint32_t i2c_ll_get_hw_version(i2c_dev_t *hw)
*
* @return True if I2C state machine is busy, else false will be returned
*/
__attribute__((always_inline))
static inline bool i2c_ll_is_bus_busy(i2c_dev_t *hw)
{
return hw->sr.bus_busy;
@ -485,7 +471,7 @@ static inline void i2c_ll_get_tout(i2c_dev_t *hw, int *timeout)
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_trans_start(i2c_dev_t *hw)
static inline void i2c_ll_master_trans_start(i2c_dev_t *hw)
{
hw->ctr.trans_start = 1;
}
@ -520,21 +506,6 @@ static inline void i2c_ll_get_stop_timing(i2c_dev_t *hw, int *setup_time, int *h
*hold_time = hw->scl_stop_hold.scl_stop_hold_time;
}
/**
* @brief Get I2C SCL timing configuration
*
* @param hw Beginning address of the peripheral registers
* @param high_period Pointer to accept the SCL high period
* @param low_period Pointer to accept the SCL low period
*
* @return None
*/
static inline void i2c_ll_get_scl_timing(i2c_dev_t *hw, int *high_period, int *low_period)
{
*high_period = hw->scl_high_period.scl_high_period + hw->scl_high_period.scl_wait_high_period;
*low_period = hw->scl_low_period.scl_low_period + 1;
}
/**
* @brief Write the I2C hardware txFIFO
*
@ -578,7 +549,7 @@ static inline void i2c_ll_read_rxfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
*
* @return None
*/
static inline void i2c_ll_set_filter(i2c_dev_t *hw, uint8_t filter_num)
static inline void i2c_ll_master_set_filter(i2c_dev_t *hw, uint8_t filter_num)
{
if (filter_num > 0) {
hw->filter_cfg.scl_filter_thres = filter_num;
@ -598,7 +569,7 @@ static inline void i2c_ll_set_filter(i2c_dev_t *hw, uint8_t filter_num)
*
* @return The hardware filter configuration
*/
static inline void i2c_ll_get_filter(i2c_dev_t *hw, uint8_t *filter_conf)
static inline void i2c_ll_master_get_filter(i2c_dev_t *hw, uint8_t *filter_conf)
{
*filter_conf = hw->filter_cfg.scl_filter_thres;
}
@ -623,12 +594,13 @@ static inline void i2c_ll_master_fsm_rst(i2c_dev_t *hw)
* Note: The master cannot detect if deadlock happens, but when the scl_st_to interrupt is generated, a deadlock may occur.
*
* @param hw Beginning address of the peripheral registers
* @param slave_pulses When I2C master is IDLE, the number of pulses will be sent out.
*
* @return None
*/
static inline void i2c_ll_master_clr_bus(i2c_dev_t *hw)
static inline void i2c_ll_master_clr_bus(i2c_dev_t *hw, uint32_t slave_pulses)
{
hw->scl_sp_conf.scl_rst_slv_num = 9;
hw->scl_sp_conf.scl_rst_slv_num = slave_pulses;
hw->scl_sp_conf.scl_rst_slv_en = 1;
hw->ctr.conf_upgate = 1;
// hardward will clear scl_rst_slv_en after sending SCL pulses,
@ -829,6 +801,52 @@ static inline void i2c_ll_master_disable_rx_it(i2c_dev_t *hw)
hw->int_ena.val &= (~I2C_LL_MASTER_RX_INT);
}
/**
* @brief Configure I2C SCL timing
*
* @param hw Beginning address of the peripheral registers
* @param hight_period The I2C SCL hight period (in core clock cycle, hight_period > 2)
* @param low_period The I2C SCL low period (in core clock cycle, low_period > 1)
*
* @return None.
*/
static inline void i2c_ll_set_scl_timing(i2c_dev_t *hw, int hight_period, int low_period)
{
hw->scl_low_period.scl_low_period = low_period - 1;
hw->scl_high_period.scl_high_period = hight_period - 10;
hw->scl_high_period.scl_wait_high_period = hight_period - hw->scl_high_period.scl_high_period;
}
/**
* @brief Get the I2C data mode
*
* @param hw Beginning address of the peripheral registers
* @param tx_mode Pointer to accept the received bytes mode
* @param rx_mode Pointer to accept the sended bytes mode
*
* @return None
*/
static inline void i2c_ll_get_data_mode(i2c_dev_t *hw, i2c_trans_mode_t *tx_mode, i2c_trans_mode_t *rx_mode)
{
*tx_mode = hw->ctr.tx_lsb_first;
*rx_mode = hw->ctr.rx_lsb_first;
}
/**
* @brief Get I2C SCL timing configuration
*
* @param hw Beginning address of the peripheral registers
* @param high_period Pointer to accept the SCL high period
* @param low_period Pointer to accept the SCL low period
*
* @return None
*/
static inline void i2c_ll_get_scl_timing(i2c_dev_t *hw, int *high_period, int *low_period)
{
*high_period = hw->scl_high_period.scl_high_period + hw->scl_high_period.scl_wait_high_period;
*low_period = hw->scl_low_period.scl_low_period + 1;
}
#ifdef __cplusplus
}
#endif

View File

@ -29,13 +29,13 @@ extern "C" {
*/
typedef union {
struct {
uint32_t byte_num: 8,
ack_en: 1,
ack_exp: 1,
ack_val: 1,
op_code: 3,
reserved14: 17,
done: 1;
uint32_t byte_num: 8, /*!< Specifies the length of data (in bytes) to be read or written */
ack_en: 1, /*!< Used to enable the I2C controller during a write operation to check whether ACK */
ack_exp: 1, /*!< Used to configure the level of the ACK bit expected by the I2C controller during a write operation */
ack_val: 1, /*!< Used to configure the level of the ACK bit sent by the I2C controller during a read operation */
op_code: 3, /*!< Indicates the command */
reserved14: 17, /*!< Reserved bits */
done: 1; /*!< Indicates that a command has been executed */
};
uint32_t val;
} i2c_ll_hw_cmd_t;
@ -48,25 +48,32 @@ typedef union {
#define I2C_LL_CMD_END 4 /*!<I2C end command */
typedef enum {
I2C_INTR_NACK = (1 << 10),
I2C_INTR_TIMEOUT = (1 << 8),
I2C_INTR_MST_COMPLETE = (1 << 7),
I2C_INTR_ARBITRATION = (1 << 5),
I2C_INTR_END_DETECT = (1 << 3),
I2C_INTR_ST_TO = (1 << 13),
} i2c_ll_master_intr_t;
I2C_LL_INTR_TXFIFO_WM = (1 << 1),
I2C_LL_INTR_RXFIFO_WM = (1 << 0),
I2C_LL_INTR_NACK = (1 << 10),
I2C_LL_INTR_TIMEOUT = (1 << 8),
I2C_LL_INTR_MST_COMPLETE = (1 << 7),
I2C_LL_INTR_ARBITRATION = (1 << 5),
I2C_LL_INTR_END_DETECT = (1 << 3),
I2C_LL_INTR_ST_TO = (1 << 13),
I2C_LL_INTR_START = (1 << 15),
I2C_LL_INTR_STRETCH = (1 << 16),
I2C_LL_INTR_UNMATCH = (1 << 18),
} i2c_ll_intr_t;
typedef enum {
I2C_INTR_TXFIFO_WM = (1 << 1),
I2C_INTR_RXFIFO_WM = (1 << 0),
I2C_INTR_SLV_COMPLETE = (1 << 7),
I2C_INTR_START = (1 << 15),
} i2c_ll_slave_intr_t;
I2C_LL_STRETCH_REASON_MASTER_START = 0,
I2C_LL_STRETCH_REASON_TX_EMPTY = 1,
I2C_LL_STRETCH_REASON_RX_FULL = 2,
} i2c_ll_stretch_cause_t;
// Get the I2C hardware instance
#define I2C_LL_GET_HW(i2c_num) (&I2C0)
#define I2C_LL_MASTER_EVENT_INTR (I2C_NACK_INT_ENA_M|I2C_TIME_OUT_INT_ENA_M|I2C_TRANS_COMPLETE_INT_ENA_M|I2C_ARBITRATION_LOST_INT_ENA_M|I2C_END_DETECT_INT_ENA_M)
#define I2C_LL_SLAVE_EVENT_INTR (I2C_RXFIFO_WM_INT_ENA_M|I2C_TRANS_COMPLETE_INT_ENA_M|I2C_TXFIFO_WM_INT_ENA_M)
#define I2C_LL_SLAVE_EVENT_INTR (I2C_TRANS_COMPLETE_INT_ENA_M|I2C_TXFIFO_WM_INT_ENA_M|I2C_RXFIFO_WM_INT_ENA_M | I2C_SLAVE_STRETCH_INT_ENA_M)
#define I2C_LL_SLAVE_RX_EVENT_INTR (I2C_TRANS_COMPLETE_INT_ENA_M | I2C_RXFIFO_WM_INT_ENA_M | I2C_SLAVE_STRETCH_INT_ENA_M)
#define I2C_LL_SLAVE_TX_EVENT_INTR (I2C_TXFIFO_WM_INT_ENA_M)
#define I2C_LL_RESET_SLV_SCL_PULSE_NUM_DEFAULT (9)
/**
* @brief Calculate I2C bus frequency
@ -80,7 +87,7 @@ typedef enum {
*
* @return None
*/
static inline void i2c_ll_cal_bus_clk(uint32_t source_clk, uint32_t bus_freq, i2c_hal_clk_config_t *clk_cal)
static inline void i2c_ll_master_cal_bus_clk(uint32_t source_clk, uint32_t bus_freq, i2c_hal_clk_config_t *clk_cal)
{
uint32_t clkm_div = source_clk / (bus_freq * 1024) +1;
uint32_t sclk_freq = source_clk / clkm_div;
@ -127,7 +134,7 @@ static inline void i2c_ll_update(i2c_dev_t *hw)
*
* @return None
*/
static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bus_cfg)
static inline void i2c_ll_master_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bus_cfg)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->clk_conf, sclk_div_num, bus_cfg->clkm_div - 1);
/* According to the Technical Reference Manual, the following timings must be subtracted by 1.
@ -151,6 +158,20 @@ static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bu
hw->timeout.time_out_en = 1;
}
/**
* @brief Set fractional divider
*
* @param hw Beginning address of the peripheral registers
* @param div_a The denominator of the frequency divider factor of the i2c function clock
* @param div_b The numerator of the frequency divider factor of the i2c function clock.
*/
static inline void i2c_ll_master_set_fractional_divider(i2c_dev_t *hw, uint8_t div_a, uint8_t div_b)
{
/* Set div_a and div_b to 0, as it's not necessary to use them */
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->clk_conf, sclk_div_a, div_a);
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->clk_conf, sclk_div_b, div_b);
}
/**
* @brief Reset I2C txFIFO
*
@ -158,6 +179,7 @@ static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bu
*
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_txfifo_rst(i2c_dev_t *hw)
{
hw->fifo_conf.tx_fifo_rst = 1;
@ -171,28 +193,13 @@ static inline void i2c_ll_txfifo_rst(i2c_dev_t *hw)
*
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_rxfifo_rst(i2c_dev_t *hw)
{
hw->fifo_conf.rx_fifo_rst = 1;
hw->fifo_conf.rx_fifo_rst = 0;
}
/**
* @brief Configure I2C SCL timing
*
* @param hw Beginning address of the peripheral registers
* @param hight_period The I2C SCL hight period (in core clock cycle, hight_period > 2)
* @param low_period The I2C SCL low period (in core clock cycle, low_period > 1)
*
* @return None.
*/
static inline void i2c_ll_set_scl_timing(i2c_dev_t *hw, int hight_period, int low_period)
{
hw->scl_low_period.period = low_period - 1;
hw->scl_high_period.period = hight_period - 10;
hw->scl_high_period.scl_wait_high_period = hight_period - hw->scl_high_period.period;
}
/**
* @brief Clear I2C interrupt status
*
@ -215,6 +222,7 @@ static inline void i2c_ll_clear_intr_mask(i2c_dev_t *hw, uint32_t mask)
*
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_enable_intr_mask(i2c_dev_t *hw, uint32_t mask)
{
hw->int_ena.val |= mask;
@ -255,7 +263,7 @@ static inline void i2c_ll_get_intr_mask(i2c_dev_t *hw, uint32_t *intr_status)
*
* @return None
*/
static inline void i2c_ll_set_fifo_mode(i2c_dev_t *hw, bool fifo_mode_en)
static inline void i2c_ll_slave_set_fifo_mode(i2c_dev_t *hw, bool fifo_mode_en)
{
hw->fifo_conf.nonfifo_en = fifo_mode_en ? 0 : 1;
}
@ -273,6 +281,19 @@ static inline void i2c_ll_set_tout(i2c_dev_t *hw, int tout)
hw->timeout.time_out_value = tout;
}
/**
* @brief Configure I2C slave broadcasting mode.
*
* @param hw Beginning address of the peripheral registers
* @param broadcast_en Set true to enable broadcast, else, set it false
*
* @return None
*/
static inline void i2c_ll_slave_broadcast_enable(i2c_dev_t *hw, bool broadcast_en)
{
hw->ctr.addr_broadcasting_en = broadcast_en;
}
/**
* @brief Configure I2C slave address
*
@ -284,8 +305,15 @@ static inline void i2c_ll_set_tout(i2c_dev_t *hw, int tout)
*/
static inline void i2c_ll_set_slave_addr(i2c_dev_t *hw, uint16_t slave_addr, bool addr_10bit_en)
{
hw->slave_addr.addr = slave_addr;
hw->slave_addr.en_10bit = addr_10bit_en;
if (addr_10bit_en) {
uint16_t addr_14_7 = (slave_addr & 0xff) << 7;
uint8_t addr_6_0 = ((slave_addr & 0x300) >> 8) | 0x78;
hw->slave_addr.addr = addr_14_7 | addr_6_0;
hw->ctr.addr_10bit_rw_check_en = addr_10bit_en;
} else {
hw->slave_addr.addr = slave_addr;
}
}
/**
@ -298,7 +326,7 @@ static inline void i2c_ll_set_slave_addr(i2c_dev_t *hw, uint16_t slave_addr, boo
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_write_cmd_reg(i2c_dev_t *hw, i2c_ll_hw_cmd_t cmd, int cmd_idx)
static inline void i2c_ll_master_write_cmd_reg(i2c_dev_t *hw, i2c_ll_hw_cmd_t cmd, int cmd_idx)
{
hw->command[cmd_idx].val = cmd.val;
}
@ -312,7 +340,7 @@ static inline void i2c_ll_write_cmd_reg(i2c_dev_t *hw, i2c_ll_hw_cmd_t cmd, int
*
* @return None
*/
static inline void i2c_ll_set_start_timing(i2c_dev_t *hw, int start_setup, int start_hold)
static inline void i2c_ll_master_set_start_timing(i2c_dev_t *hw, int start_setup, int start_hold)
{
hw->scl_rstart_setup.time = start_setup;
hw->scl_start_hold.time = start_hold - 1;
@ -327,7 +355,7 @@ static inline void i2c_ll_set_start_timing(i2c_dev_t *hw, int start_setup, int s
*
* @return None
*/
static inline void i2c_ll_set_stop_timing(i2c_dev_t *hw, int stop_setup, int stop_hold)
static inline void i2c_ll_master_set_stop_timing(i2c_dev_t *hw, int stop_setup, int stop_hold)
{
hw->scl_stop_setup.time = stop_setup;
hw->scl_stop_hold.time = stop_hold;
@ -389,21 +417,6 @@ static inline void i2c_ll_set_data_mode(i2c_dev_t *hw, i2c_trans_mode_t tx_mode,
hw->ctr.rx_lsb_first = rx_mode;
}
/**
* @brief Get the I2C data mode
*
* @param hw Beginning address of the peripheral registers
* @param tx_mode Pointer to accept the received bytes mode
* @param rx_mode Pointer to accept the sended bytes mode
*
* @return None
*/
static inline void i2c_ll_get_data_mode(i2c_dev_t *hw, i2c_trans_mode_t *tx_mode, i2c_trans_mode_t *rx_mode)
{
*tx_mode = hw->ctr.tx_lsb_first;
*rx_mode = hw->ctr.rx_lsb_first;
}
/**
* @brief Get I2C sda timing configuration
*
@ -438,6 +451,7 @@ static inline uint32_t i2c_ll_get_hw_version(i2c_dev_t *hw)
*
* @return True if I2C state machine is busy, else false will be returned
*/
__attribute__((always_inline))
static inline bool i2c_ll_is_bus_busy(i2c_dev_t *hw)
{
return hw->sr.bus_busy;
@ -501,7 +515,7 @@ static inline void i2c_ll_get_tout(i2c_dev_t *hw, int *timeout)
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_trans_start(i2c_dev_t *hw)
static inline void i2c_ll_master_trans_start(i2c_dev_t *hw)
{
hw->ctr.trans_start = 1;
}
@ -536,21 +550,6 @@ static inline void i2c_ll_get_stop_timing(i2c_dev_t *hw, int *setup_time, int *h
*hold_time = hw->scl_stop_hold.time;
}
/**
* @brief Get I2C SCL timing configuration
*
* @param hw Beginning address of the peripheral registers
* @param high_period Pointer to accept the SCL high period
* @param low_period Pointer to accept the SCL low period
*
* @return None
*/
static inline void i2c_ll_get_scl_timing(i2c_dev_t *hw, int *high_period, int *low_period)
{
*high_period = hw->scl_high_period.period + hw->scl_high_period.scl_wait_high_period;
*low_period = hw->scl_low_period.period + 1;
}
/**
* @brief Write the I2C hardware txFIFO
*
@ -585,6 +584,56 @@ static inline void i2c_ll_read_rxfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
}
}
/**
* @brief Write the I2C hardware txFIFO
*
* @param hw Beginning address of the peripheral registers
* @param ram_offset Offset value of I2C RAM.
* @param ptr Pointer to data buffer
* @param len Amount of data needs to be writen
*
* @return None.
*/
static inline void i2c_ll_write_by_nonfifo(i2c_dev_t *hw, uint8_t ram_offset, const uint8_t *ptr, uint8_t len)
{
uint32_t *fifo_addr = (uint32_t *)&hw->txfifo_start_addr;
for (int i = 0; i < len; i++) {
fifo_addr[i + ram_offset] = ptr[i];
}
}
/**
* @brief Read the I2C hardware ram
*
* @param hw Beginning address of the peripheral registers
* @param ram_offset Offset value of I2C RAM.
* @param ptr Pointer to data buffer
* @param len Amount of data needs read
*
* @return None
*/
static inline void i2c_ll_read_by_nonfifo(i2c_dev_t *hw, uint8_t ram_offset, uint8_t *ptr, uint8_t len)
{
uint32_t *fifo_addr = (uint32_t *)&hw->rxfifo_start_addr;
for (int i = 0; i < len; i++) {
ptr[i] = fifo_addr[i + ram_offset];
}
}
/**
* @brief Get access to I2C RAM address directly
*
* @param hw Beginning address of the peripheral registers
* @param addr_wr_en Enable I2C ram address read and write
*
* @return None
*/
static inline void i2c_ll_enable_mem_access_nonfifo(i2c_dev_t *hw, bool addr_wr_en)
{
hw->fifo_conf.fifo_addr_cfg_en = addr_wr_en;
}
/**
* @brief Configure I2C hardware filter
*
@ -594,7 +643,7 @@ static inline void i2c_ll_read_rxfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
*
* @return None
*/
static inline void i2c_ll_set_filter(i2c_dev_t *hw, uint8_t filter_num)
static inline void i2c_ll_master_set_filter(i2c_dev_t *hw, uint8_t filter_num)
{
if (filter_num > 0) {
hw->filter_cfg.scl_thres = filter_num;
@ -614,7 +663,7 @@ static inline void i2c_ll_set_filter(i2c_dev_t *hw, uint8_t filter_num)
*
* @return The hardware filter configuration
*/
static inline void i2c_ll_get_filter(i2c_dev_t *hw, uint8_t *filter_conf)
static inline void i2c_ll_master_get_filter(i2c_dev_t *hw, uint8_t *filter_conf)
{
*filter_conf = hw->filter_cfg.scl_thres;
}
@ -641,12 +690,13 @@ static inline void i2c_ll_master_fsm_rst(i2c_dev_t *hw)
* Note: The master cannot detect if deadlock happens, but when the scl_st_to interrupt is generated, a deadlock may occur.
*
* @param hw Beginning address of the peripheral registers
* @param slave_pulses When I2C master is IDLE, the number of pulses will be sent out.
*
* @return None
*/
static inline void i2c_ll_master_clr_bus(i2c_dev_t *hw)
static inline void i2c_ll_master_clr_bus(i2c_dev_t *hw, uint32_t slave_pulses)
{
hw->scl_sp_conf.scl_rst_slv_num = 9;
hw->scl_sp_conf.scl_rst_slv_num = slave_pulses;
hw->scl_sp_conf.scl_rst_slv_en = 1;
hw->ctr.conf_upgate = 1;
// hardward will clear scl_rst_slv_en after sending SCL pulses,
@ -734,6 +784,28 @@ static inline volatile void *i2c_ll_get_interrupt_status_reg(i2c_dev_t *dev)
return &dev->int_status;
}
/**
* @brief Enable I2C slave clock stretch.
*
* @param dev Beginning address of the peripheral registers.
* @param enable true: Enable, false: Disable.
*/
static inline void i2c_ll_slave_enable_scl_stretch(i2c_dev_t *dev, bool enable)
{
dev->scl_stretch_conf.slave_scl_stretch_en = enable;
}
/**
* @brief Clear I2C clock stretch status
*
* @param dev Beginning address of the peripheral registers
*/
__attribute__((always_inline))
static inline void i2c_ll_slave_clear_stretch(i2c_dev_t *dev)
{
dev->scl_stretch_conf.slave_scl_stretch_clr = 1;
}
//////////////////////////////////////////Deprecated Functions//////////////////////////////////////////////////////////
/////////////////////////////The following functions are only used by the legacy driver/////////////////////////////////
/////////////////////////////They might be removed in the next major release (ESP-IDF 6.0)//////////////////////////////
@ -952,6 +1024,52 @@ static inline void i2c_ll_slave_disable_rx_it(i2c_dev_t *hw)
}
/**
* @brief Configure I2C SCL timing
*
* @param hw Beginning address of the peripheral registers
* @param hight_period The I2C SCL hight period (in core clock cycle, hight_period > 2)
* @param low_period The I2C SCL low period (in core clock cycle, low_period > 1)
*
* @return None.
*/
static inline void i2c_ll_set_scl_timing(i2c_dev_t *hw, int hight_period, int low_period)
{
hw->scl_low_period.period = low_period - 1;
hw->scl_high_period.period = hight_period - 10;
hw->scl_high_period.scl_wait_high_period = hight_period - hw->scl_high_period.period;
}
/**
* @brief Get the I2C data mode
*
* @param hw Beginning address of the peripheral registers
* @param tx_mode Pointer to accept the received bytes mode
* @param rx_mode Pointer to accept the sended bytes mode
*
* @return None
*/
static inline void i2c_ll_get_data_mode(i2c_dev_t *hw, i2c_trans_mode_t *tx_mode, i2c_trans_mode_t *rx_mode)
{
*tx_mode = hw->ctr.tx_lsb_first;
*rx_mode = hw->ctr.rx_lsb_first;
}
/**
* @brief Get I2C SCL timing configuration
*
* @param hw Beginning address of the peripheral registers
* @param high_period Pointer to accept the SCL high period
* @param low_period Pointer to accept the SCL low period
*
* @return None
*/
static inline void i2c_ll_get_scl_timing(i2c_dev_t *hw, int *high_period, int *low_period)
{
*high_period = hw->scl_high_period.period + hw->scl_high_period.scl_wait_high_period;
*low_period = hw->scl_low_period.period + 1;
}
#ifdef __cplusplus
}
#endif

View File

@ -17,6 +17,7 @@
#include "soc/pcr_struct.h"
#include "hal/i2c_types.h"
#include "soc/clk_tree_defs.h"
#include "soc/lp_clkrst_struct.h"
#ifdef __cplusplus
extern "C" {
@ -27,13 +28,13 @@ extern "C" {
*/
typedef union {
struct {
uint32_t byte_num: 8,
ack_en: 1,
ack_exp: 1,
ack_val: 1,
op_code: 3,
reserved14: 17,
done: 1;
uint32_t byte_num: 8, /*!< Specifies the length of data (in bytes) to be read or written */
ack_en: 1, /*!< Used to enable the I2C controller during a write operation to check whether ACK */
ack_exp: 1, /*!< Used to configure the level of the ACK bit expected by the I2C controller during a write operation */
ack_val: 1, /*!< Used to configure the level of the ACK bit sent by the I2C controller during a read operation */
op_code: 3, /*!< Indicates the command */
reserved14: 17, /*!< Reserved bits */
done: 1; /*!< Indicates that a command has been executed */
};
uint32_t val;
} i2c_ll_hw_cmd_t;
@ -46,25 +47,32 @@ typedef union {
#define I2C_LL_CMD_END 4 /*!<I2C end command */
typedef enum {
I2C_INTR_NACK = (1 << 10),
I2C_INTR_TIMEOUT = (1 << 8),
I2C_INTR_MST_COMPLETE = (1 << 7),
I2C_INTR_ARBITRATION = (1 << 5),
I2C_INTR_END_DETECT = (1 << 3),
I2C_INTR_ST_TO = (1 << 13),
} i2c_ll_master_intr_t;
I2C_LL_INTR_TXFIFO_WM = (1 << 1),
I2C_LL_INTR_RXFIFO_WM = (1 << 0),
I2C_LL_INTR_NACK = (1 << 10),
I2C_LL_INTR_TIMEOUT = (1 << 8),
I2C_LL_INTR_MST_COMPLETE = (1 << 7),
I2C_LL_INTR_ARBITRATION = (1 << 5),
I2C_LL_INTR_END_DETECT = (1 << 3),
I2C_LL_INTR_ST_TO = (1 << 13),
I2C_LL_INTR_START = (1 << 15),
I2C_LL_INTR_STRETCH = (1 << 16),
I2C_LL_INTR_UNMATCH = (1 << 18),
} i2c_ll_intr_t;
typedef enum {
I2C_INTR_TXFIFO_WM = (1 << 1),
I2C_INTR_RXFIFO_WM = (1 << 0),
I2C_INTR_SLV_COMPLETE = (1 << 7),
I2C_INTR_START = (1 << 15),
} i2c_ll_slave_intr_t;
I2C_LL_STRETCH_REASON_MASTER_START = 0,
I2C_LL_STRETCH_REASON_TX_EMPTY = 1,
I2C_LL_STRETCH_REASON_RX_FULL = 2,
} i2c_ll_stretch_cause_t;
// Get the I2C hardware instance
#define I2C_LL_GET_HW(i2c_num) (((i2c_num) == I2C_NUM_0) ? (&I2C0) : (&LP_I2C))
#define I2C_LL_MASTER_EVENT_INTR (I2C_NACK_INT_ENA_M|I2C_TIME_OUT_INT_ENA_M|I2C_TRANS_COMPLETE_INT_ENA_M|I2C_ARBITRATION_LOST_INT_ENA_M|I2C_END_DETECT_INT_ENA_M)
#define I2C_LL_SLAVE_EVENT_INTR (I2C_RXFIFO_WM_INT_ENA_M|I2C_TRANS_COMPLETE_INT_ENA_M|I2C_TXFIFO_WM_INT_ENA_M)
#define I2C_LL_SLAVE_EVENT_INTR (I2C_TRANS_COMPLETE_INT_ENA_M|I2C_TXFIFO_WM_INT_ENA_M|I2C_RXFIFO_WM_INT_ENA_M | I2C_SLAVE_STRETCH_INT_ENA_M | I2C_SLAVE_ADDR_UNMATCH_INT_ENA_M)
#define I2C_LL_SLAVE_RX_EVENT_INTR (I2C_TRANS_COMPLETE_INT_ENA_M | I2C_RXFIFO_WM_INT_ENA_M | I2C_SLAVE_STRETCH_INT_ENA_M | I2C_SLAVE_ADDR_UNMATCH_INT_ENA_M)
#define I2C_LL_SLAVE_TX_EVENT_INTR (I2C_TXFIFO_WM_INT_ENA_M | I2C_SLAVE_ADDR_UNMATCH_INT_ENA_M)
#define I2C_LL_RESET_SLV_SCL_PULSE_NUM_DEFAULT (9)
/**
* @brief Calculate I2C bus frequency
@ -78,7 +86,7 @@ typedef enum {
*
* @return None
*/
static inline void i2c_ll_cal_bus_clk(uint32_t source_clk, uint32_t bus_freq, i2c_hal_clk_config_t *clk_cal)
static inline void i2c_ll_master_cal_bus_clk(uint32_t source_clk, uint32_t bus_freq, i2c_hal_clk_config_t *clk_cal)
{
uint32_t clkm_div = source_clk / (bus_freq * 1024) +1;
uint32_t sclk_freq = source_clk / clkm_div;
@ -125,7 +133,7 @@ static inline void i2c_ll_update(i2c_dev_t *hw)
*
* @return None
*/
static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bus_cfg)
static inline void i2c_ll_master_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bus_cfg)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(PCR.i2c_sclk_conf, i2c_sclk_div_num, bus_cfg->clkm_div - 1);
@ -153,6 +161,20 @@ static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bu
hw->to.time_out_en = 1;
}
/**
* @brief Set fractional divider
*
* @param hw Beginning address of the peripheral registers
* @param div_a The denominator of the frequency divider factor of the i2c function clock
* @param div_b The numerator of the frequency divider factor of the i2c function clock.
*/
static inline void i2c_ll_master_set_fractional_divider(i2c_dev_t *hw, uint8_t div_a, uint8_t div_b)
{
/* Set div_a and div_b to 0, as it's not necessary to use them */
HAL_FORCE_MODIFY_U32_REG_FIELD(PCR.i2c_sclk_conf, i2c_sclk_div_a, div_a);
HAL_FORCE_MODIFY_U32_REG_FIELD(PCR.i2c_sclk_conf, i2c_sclk_div_b, div_b);
}
/**
* @brief Reset I2C txFIFO
*
@ -160,6 +182,7 @@ static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bu
*
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_txfifo_rst(i2c_dev_t *hw)
{
hw->fifo_conf.tx_fifo_rst = 1;
@ -173,28 +196,13 @@ static inline void i2c_ll_txfifo_rst(i2c_dev_t *hw)
*
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_rxfifo_rst(i2c_dev_t *hw)
{
hw->fifo_conf.rx_fifo_rst = 1;
hw->fifo_conf.rx_fifo_rst = 0;
}
/**
* @brief Configure I2C SCL timing
*
* @param hw Beginning address of the peripheral registers
* @param hight_period The I2C SCL hight period (in core clock cycle, hight_period > 2)
* @param low_period The I2C SCL low period (in core clock cycle, low_period > 1)
*
* @return None.
*/
static inline void i2c_ll_set_scl_timing(i2c_dev_t *hw, int hight_period, int low_period)
{
hw->scl_low_period.scl_low_period = low_period - 1;
hw->scl_high_period.scl_high_period = hight_period - 10;
hw->scl_high_period.scl_wait_high_period = hight_period - hw->scl_high_period.scl_high_period;
}
/**
* @brief Clear I2C interrupt status
*
@ -217,6 +225,7 @@ static inline void i2c_ll_clear_intr_mask(i2c_dev_t *hw, uint32_t mask)
*
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_enable_intr_mask(i2c_dev_t *hw, uint32_t mask)
{
hw->int_ena.val |= mask;
@ -257,7 +266,7 @@ static inline void i2c_ll_get_intr_mask(i2c_dev_t *hw, uint32_t *intr_status)
*
* @return None
*/
static inline void i2c_ll_set_fifo_mode(i2c_dev_t *hw, bool fifo_mode_en)
static inline void i2c_ll_slave_set_fifo_mode(i2c_dev_t *hw, bool fifo_mode_en)
{
hw->fifo_conf.nonfifo_en = fifo_mode_en ? 0 : 1;
}
@ -275,6 +284,19 @@ static inline void i2c_ll_set_tout(i2c_dev_t *hw, int tout)
hw->to.time_out_value = tout;
}
/**
* @brief Configure I2C slave broadcasting mode.
*
* @param hw Beginning address of the peripheral registers
* @param broadcast_en Set true to enable broadcast, else, set it false
*
* @return None
*/
static inline void i2c_ll_slave_broadcast_enable(i2c_dev_t *hw, bool broadcast_en)
{
hw->ctr.addr_broadcasting_en = broadcast_en;
}
/**
* @brief Configure I2C slave address
*
@ -286,8 +308,15 @@ static inline void i2c_ll_set_tout(i2c_dev_t *hw, int tout)
*/
static inline void i2c_ll_set_slave_addr(i2c_dev_t *hw, uint16_t slave_addr, bool addr_10bit_en)
{
hw->slave_addr.slave_addr = slave_addr;
hw->slave_addr.addr_10bit_en = addr_10bit_en;
if (addr_10bit_en) {
uint8_t addr_14_7 = (slave_addr & 0xff) << 7;
uint8_t addr_6_0 = ((slave_addr & 0x300) >> 8) | 0x78;
hw->slave_addr.slave_addr = addr_14_7 | addr_6_0;
hw->ctr.addr_10bit_rw_check_en = addr_10bit_en;
} else {
hw->slave_addr.slave_addr = slave_addr;
}
}
/**
@ -300,7 +329,7 @@ static inline void i2c_ll_set_slave_addr(i2c_dev_t *hw, uint16_t slave_addr, boo
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_write_cmd_reg(i2c_dev_t *hw, i2c_ll_hw_cmd_t cmd, int cmd_idx)
static inline void i2c_ll_master_write_cmd_reg(i2c_dev_t *hw, i2c_ll_hw_cmd_t cmd, int cmd_idx)
{
hw->command[cmd_idx].val = cmd.val;
}
@ -314,7 +343,7 @@ static inline void i2c_ll_write_cmd_reg(i2c_dev_t *hw, i2c_ll_hw_cmd_t cmd, int
*
* @return None
*/
static inline void i2c_ll_set_start_timing(i2c_dev_t *hw, int start_setup, int start_hold)
static inline void i2c_ll_master_set_start_timing(i2c_dev_t *hw, int start_setup, int start_hold)
{
hw->scl_rstart_setup.scl_rstart_setup_time = start_setup;
hw->scl_start_hold.scl_start_hold_time = start_hold - 1;
@ -329,7 +358,7 @@ static inline void i2c_ll_set_start_timing(i2c_dev_t *hw, int start_setup, int s
*
* @return None
*/
static inline void i2c_ll_set_stop_timing(i2c_dev_t *hw, int stop_setup, int stop_hold)
static inline void i2c_ll_master_set_stop_timing(i2c_dev_t *hw, int stop_setup, int stop_hold)
{
hw->scl_stop_setup.scl_stop_setup_time = stop_setup;
hw->scl_stop_hold.scl_stop_hold_time = stop_hold;
@ -391,21 +420,6 @@ static inline void i2c_ll_set_data_mode(i2c_dev_t *hw, i2c_trans_mode_t tx_mode,
hw->ctr.rx_lsb_first = rx_mode;
}
/**
* @brief Get the I2C data mode
*
* @param hw Beginning address of the peripheral registers
* @param tx_mode Pointer to accept the received bytes mode
* @param rx_mode Pointer to accept the sended bytes mode
*
* @return None
*/
static inline void i2c_ll_get_data_mode(i2c_dev_t *hw, i2c_trans_mode_t *tx_mode, i2c_trans_mode_t *rx_mode)
{
*tx_mode = hw->ctr.tx_lsb_first;
*rx_mode = hw->ctr.rx_lsb_first;
}
/**
* @brief Get I2C sda timing configuration
*
@ -440,6 +454,7 @@ static inline uint32_t i2c_ll_get_hw_version(i2c_dev_t *hw)
*
* @return True if I2C state machine is busy, else false will be returned
*/
__attribute__((always_inline))
static inline bool i2c_ll_is_bus_busy(i2c_dev_t *hw)
{
return hw->sr.bus_busy;
@ -503,7 +518,7 @@ static inline void i2c_ll_get_tout(i2c_dev_t *hw, int *timeout)
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_trans_start(i2c_dev_t *hw)
static inline void i2c_ll_master_trans_start(i2c_dev_t *hw)
{
hw->ctr.trans_start = 1;
}
@ -538,21 +553,6 @@ static inline void i2c_ll_get_stop_timing(i2c_dev_t *hw, int *setup_time, int *h
*hold_time = hw->scl_stop_hold.scl_stop_hold_time;
}
/**
* @brief Get I2C SCL timing configuration
*
* @param hw Beginning address of the peripheral registers
* @param high_period Pointer to accept the SCL high period
* @param low_period Pointer to accept the SCL low period
*
* @return None
*/
static inline void i2c_ll_get_scl_timing(i2c_dev_t *hw, int *high_period, int *low_period)
{
*high_period = hw->scl_high_period.scl_high_period + hw->scl_high_period.scl_wait_high_period;
*low_period = hw->scl_low_period.scl_low_period + 1;
}
/**
* @brief Write the I2C hardware txFIFO
*
@ -587,6 +587,56 @@ static inline void i2c_ll_read_rxfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
}
}
/**
* @brief Write the I2C hardware txFIFO
*
* @param hw Beginning address of the peripheral registers
* @param ram_offset Offset value of I2C RAM.
* @param ptr Pointer to data buffer
* @param len Amount of data needs to be writen
*
* @return None.
*/
static inline void i2c_ll_write_by_nonfifo(i2c_dev_t *hw, uint8_t ram_offset, const uint8_t *ptr, uint8_t len)
{
uint32_t *fifo_addr = (uint32_t *)&hw->txfifo_start_addr;
for (int i = 0; i < len; i++) {
fifo_addr[i + ram_offset] = ptr[i];
}
}
/**
* @brief Read the I2C hardware ram
*
* @param hw Beginning address of the peripheral registers
* @param ram_offset Offset value of I2C RAM.
* @param ptr Pointer to data buffer
* @param len Amount of data needs read
*
* @return None
*/
static inline void i2c_ll_read_by_nonfifo(i2c_dev_t *hw, uint8_t ram_offset, uint8_t *ptr, uint8_t len)
{
uint32_t *fifo_addr = (uint32_t *)&hw->rxfifo_start_addr;
for (int i = 0; i < len; i++) {
ptr[i] = fifo_addr[i + ram_offset];
}
}
/**
* @brief Get access to I2C RAM address directly
*
* @param hw Beginning address of the peripheral registers
* @param addr_wr_en Enable I2C ram address read and write
*
* @return None
*/
static inline void i2c_ll_enable_mem_access_nonfifo(i2c_dev_t *hw, bool addr_wr_en)
{
hw->fifo_conf.fifo_addr_cfg_en = addr_wr_en;
}
/**
* @brief Configure I2C hardware filter
*
@ -596,7 +646,7 @@ static inline void i2c_ll_read_rxfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
*
* @return None
*/
static inline void i2c_ll_set_filter(i2c_dev_t *hw, uint8_t filter_num)
static inline void i2c_ll_master_set_filter(i2c_dev_t *hw, uint8_t filter_num)
{
if (filter_num > 0) {
hw->filter_cfg.scl_filter_thres = filter_num;
@ -616,7 +666,7 @@ static inline void i2c_ll_set_filter(i2c_dev_t *hw, uint8_t filter_num)
*
* @return The hardware filter configuration
*/
static inline void i2c_ll_get_filter(i2c_dev_t *hw, uint8_t *filter_conf)
static inline void i2c_ll_master_get_filter(i2c_dev_t *hw, uint8_t *filter_conf)
{
*filter_conf = hw->filter_cfg.scl_filter_thres;
}
@ -641,12 +691,13 @@ static inline void i2c_ll_master_fsm_rst(i2c_dev_t *hw)
* Note: The master cannot detect if deadlock happens, but when the scl_st_to interrupt is generated, a deadlock may occur.
*
* @param hw Beginning address of the peripheral registers
* @param slave_pulses When I2C master is IDLE, the number of pulses will be sent out.
*
* @return None
*/
static inline void i2c_ll_master_clr_bus(i2c_dev_t *hw)
static inline void i2c_ll_master_clr_bus(i2c_dev_t *hw, uint32_t slave_pulses)
{
hw->scl_sp_conf.scl_rst_slv_num = 9;
hw->scl_sp_conf.scl_rst_slv_num = slave_pulses;
hw->scl_sp_conf.scl_rst_slv_en = 1;
hw->ctr.conf_upgate = 1;
// hardward will clear scl_rst_slv_en after sending SCL pulses,
@ -758,6 +809,28 @@ static inline volatile void *i2c_ll_get_interrupt_status_reg(i2c_dev_t *dev)
}
/**
* @brief Enable I2C slave clock stretch.
*
* @param dev Beginning address of the peripheral registers.
* @param enable true: Enable, false: Disable.
*/
static inline void i2c_ll_slave_enable_scl_stretch(i2c_dev_t *dev, bool enable)
{
dev->scl_stretch_conf.slave_scl_stretch_en = enable;
}
/**
* @brief Clear I2C clock stretch status
*
* @param dev Beginning address of the peripheral registers
*/
__attribute__((always_inline))
static inline void i2c_ll_slave_clear_stretch(i2c_dev_t *dev)
{
dev->scl_stretch_conf.slave_scl_stretch_clr = 1;
}
//////////////////////////////////////////Deprecated Functions//////////////////////////////////////////////////////////
/////////////////////////////The following functions are only used by the legacy driver/////////////////////////////////
/////////////////////////////They might be removed in the next major release (ESP-IDF 6.0)//////////////////////////////
@ -975,6 +1048,52 @@ static inline void i2c_ll_slave_disable_rx_it(i2c_dev_t *hw)
hw->int_ena.val &= (~I2C_LL_SLAVE_RX_INT);
}
/**
* @brief Configure I2C SCL timing
*
* @param hw Beginning address of the peripheral registers
* @param hight_period The I2C SCL hight period (in core clock cycle, hight_period > 2)
* @param low_period The I2C SCL low period (in core clock cycle, low_period > 1)
*
* @return None.
*/
static inline void i2c_ll_set_scl_timing(i2c_dev_t *hw, int hight_period, int low_period)
{
hw->scl_low_period.scl_low_period = low_period - 1;
hw->scl_high_period.scl_high_period = hight_period - 10;
hw->scl_high_period.scl_wait_high_period = hight_period - hw->scl_high_period.scl_high_period;
}
/**
* @brief Get the I2C data mode
*
* @param hw Beginning address of the peripheral registers
* @param tx_mode Pointer to accept the received bytes mode
* @param rx_mode Pointer to accept the sended bytes mode
*
* @return None
*/
static inline void i2c_ll_get_data_mode(i2c_dev_t *hw, i2c_trans_mode_t *tx_mode, i2c_trans_mode_t *rx_mode)
{
*tx_mode = hw->ctr.tx_lsb_first;
*rx_mode = hw->ctr.rx_lsb_first;
}
/**
* @brief Get I2C SCL timing configuration
*
* @param hw Beginning address of the peripheral registers
* @param high_period Pointer to accept the SCL high period
* @param low_period Pointer to accept the SCL low period
*
* @return None
*/
static inline void i2c_ll_get_scl_timing(i2c_dev_t *hw, int *high_period, int *low_period)
{
*high_period = hw->scl_high_period.scl_high_period + hw->scl_high_period.scl_wait_high_period;
*low_period = hw->scl_low_period.scl_low_period + 1;
}
#ifdef __cplusplus
}
#endif

View File

@ -27,13 +27,13 @@ extern "C" {
*/
typedef union {
struct {
uint32_t byte_num: 8,
ack_en: 1,
ack_exp: 1,
ack_val: 1,
op_code: 3,
reserved14: 17,
done: 1;
uint32_t byte_num: 8, /*!< Specifies the length of data (in bytes) to be read or written */
ack_en: 1, /*!< Used to enable the I2C controller during a write operation to check whether ACK */
ack_exp: 1, /*!< Used to configure the level of the ACK bit expected by the I2C controller during a write operation */
ack_val: 1, /*!< Used to configure the level of the ACK bit sent by the I2C controller during a read operation */
op_code: 3, /*!< Indicates the command */
reserved14: 17, /*!< Reserved bits */
done: 1; /*!< Indicates that a command has been executed */
};
uint32_t val;
} i2c_ll_hw_cmd_t;
@ -46,26 +46,33 @@ typedef union {
#define I2C_LL_CMD_END 4 /*!<I2C end command */
typedef enum {
I2C_INTR_NACK = (1 << 10),
I2C_INTR_TIMEOUT = (1 << 8),
I2C_INTR_MST_COMPLETE = (1 << 7),
I2C_INTR_ARBITRATION = (1 << 5),
I2C_INTR_END_DETECT = (1 << 3),
I2C_INTR_ST_TO = (1 << 13),
} i2c_ll_master_intr_t;
I2C_LL_INTR_TXFIFO_WM = (1 << 1),
I2C_LL_INTR_RXFIFO_WM = (1 << 0),
I2C_LL_INTR_NACK = (1 << 10),
I2C_LL_INTR_TIMEOUT = (1 << 8),
I2C_LL_INTR_MST_COMPLETE = (1 << 7),
I2C_LL_INTR_ARBITRATION = (1 << 5),
I2C_LL_INTR_END_DETECT = (1 << 3),
I2C_LL_INTR_ST_TO = (1 << 13),
I2C_LL_INTR_START = (1 << 15),
I2C_LL_INTR_STRETCH = (1 << 16),
I2C_LL_INTR_UNMATCH = (1 << 18),
} i2c_ll_intr_t;
typedef enum {
I2C_INTR_TXFIFO_WM = (1 << 1),
I2C_INTR_RXFIFO_WM = (1 << 0),
I2C_INTR_SLV_COMPLETE = (1 << 7),
I2C_INTR_START = (1 << 15),
} i2c_ll_slave_intr_t;
I2C_LL_STRETCH_REASON_MASTER_START = 0,
I2C_LL_STRETCH_REASON_TX_EMPTY = 1,
I2C_LL_STRETCH_REASON_RX_FULL = 2,
} i2c_ll_stretch_cause_t;
// Get the I2C hardware instance
#define I2C_LL_GET_HW(i2c_num) (i2c_num == 0 ? (&I2C0) : (&I2C1))
#define I2C_LL_GET_NUM(hw) (hw == &I2C0 ? 0 : 1)
#define I2C_LL_MASTER_EVENT_INTR (I2C_NACK_INT_ENA_M|I2C_TIME_OUT_INT_ENA_M|I2C_TRANS_COMPLETE_INT_ENA_M|I2C_ARBITRATION_LOST_INT_ENA_M|I2C_END_DETECT_INT_ENA_M)
#define I2C_LL_SLAVE_EVENT_INTR (I2C_RXFIFO_WM_INT_ENA_M|I2C_TRANS_COMPLETE_INT_ENA_M|I2C_TXFIFO_WM_INT_ENA_M)
#define I2C_LL_SLAVE_EVENT_INTR (I2C_TRANS_COMPLETE_INT_ENA_M|I2C_TXFIFO_WM_INT_ENA_M|I2C_RXFIFO_WM_INT_ENA_M | I2C_SLAVE_STRETCH_INT_ENA_M | I2C_SLAVE_ADDR_UNMATCH_INT_ENA_M)
#define I2C_LL_SLAVE_RX_EVENT_INTR (I2C_TRANS_COMPLETE_INT_ENA_M | I2C_RXFIFO_WM_INT_ENA_M | I2C_SLAVE_STRETCH_INT_ENA_M | I2C_SLAVE_ADDR_UNMATCH_INT_ENA_M)
#define I2C_LL_SLAVE_TX_EVENT_INTR (I2C_TXFIFO_WM_INT_ENA_M | I2C_SLAVE_ADDR_UNMATCH_INT_ENA_M)
#define I2C_LL_RESET_SLV_SCL_PULSE_NUM_DEFAULT (9)
/**
* @brief Calculate I2C bus frequency
@ -79,7 +86,7 @@ typedef enum {
*
* @return None
*/
static inline void i2c_ll_cal_bus_clk(uint32_t source_clk, uint32_t bus_freq, i2c_hal_clk_config_t *clk_cal)
static inline void i2c_ll_master_cal_bus_clk(uint32_t source_clk, uint32_t bus_freq, i2c_hal_clk_config_t *clk_cal)
{
uint32_t clkm_div = source_clk / (bus_freq * 1024) +1;
uint32_t sclk_freq = source_clk / clkm_div;
@ -126,13 +133,10 @@ static inline void i2c_ll_update(i2c_dev_t *hw)
*
* @return None
*/
static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bus_cfg)
static inline void i2c_ll_master_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bus_cfg)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(PCR.i2c[I2C_LL_GET_NUM(hw)].i2c_sclk_conf, i2c_sclk_div_num, bus_cfg->clkm_div - 1);
/* Set div_a and div_b to 0, as it's not necessary to use them */
HAL_FORCE_MODIFY_U32_REG_FIELD(PCR.i2c[I2C_LL_GET_NUM(hw)].i2c_sclk_conf, i2c_sclk_div_a, 0);
HAL_FORCE_MODIFY_U32_REG_FIELD(PCR.i2c[I2C_LL_GET_NUM(hw)].i2c_sclk_conf, i2c_sclk_div_b, 0);
/* According to the Technical Reference Manual, the following timings must be subtracted by 1.
* However, according to the practical measurement and some hardware behaviour, if wait_high_period and scl_high minus one.
* The SCL frequency would be a little higher than expected. Therefore, the solution
@ -154,6 +158,20 @@ static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bu
hw->to.time_out_en = 1;
}
/**
* @brief Set fractional divider
*
* @param hw Beginning address of the peripheral registers
* @param div_a The denominator of the frequency divider factor of the i2c function clock
* @param div_b The numerator of the frequency divider factor of the i2c function clock.
*/
static inline void i2c_ll_master_set_fractional_divider(i2c_dev_t *hw, uint8_t div_a, uint8_t div_b)
{
/* Set div_a and div_b to 0, as it's not necessary to use them */
HAL_FORCE_MODIFY_U32_REG_FIELD(PCR.i2c[I2C_LL_GET_NUM(hw)].i2c_sclk_conf, i2c_sclk_div_a, div_a);
HAL_FORCE_MODIFY_U32_REG_FIELD(PCR.i2c[I2C_LL_GET_NUM(hw)].i2c_sclk_conf, i2c_sclk_div_b, div_b);
}
/**
* @brief Reset I2C txFIFO
*
@ -161,6 +179,7 @@ static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bu
*
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_txfifo_rst(i2c_dev_t *hw)
{
hw->fifo_conf.tx_fifo_rst = 1;
@ -174,28 +193,13 @@ static inline void i2c_ll_txfifo_rst(i2c_dev_t *hw)
*
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_rxfifo_rst(i2c_dev_t *hw)
{
hw->fifo_conf.rx_fifo_rst = 1;
hw->fifo_conf.rx_fifo_rst = 0;
}
/**
* @brief Configure I2C SCL timing
*
* @param hw Beginning address of the peripheral registers
* @param hight_period The I2C SCL hight period (in core clock cycle, hight_period > 2)
* @param low_period The I2C SCL low period (in core clock cycle, low_period > 1)
*
* @return None.
*/
static inline void i2c_ll_set_scl_timing(i2c_dev_t *hw, int hight_period, int low_period)
{
hw->scl_low_period.scl_low_period = low_period - 1;
hw->scl_high_period.scl_high_period = hight_period - 10;
hw->scl_high_period.scl_wait_high_period = hight_period - hw->scl_high_period.scl_high_period;
}
/**
* @brief Clear I2C interrupt status
*
@ -218,6 +222,7 @@ static inline void i2c_ll_clear_intr_mask(i2c_dev_t *hw, uint32_t mask)
*
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_enable_intr_mask(i2c_dev_t *hw, uint32_t mask)
{
hw->int_ena.val |= mask;
@ -258,7 +263,7 @@ static inline void i2c_ll_get_intr_mask(i2c_dev_t *hw, uint32_t *intr_status)
*
* @return None
*/
static inline void i2c_ll_set_fifo_mode(i2c_dev_t *hw, bool fifo_mode_en)
static inline void i2c_ll_slave_set_fifo_mode(i2c_dev_t *hw, bool fifo_mode_en)
{
hw->fifo_conf.nonfifo_en = fifo_mode_en ? 0 : 1;
}
@ -276,6 +281,19 @@ static inline void i2c_ll_set_tout(i2c_dev_t *hw, int tout)
hw->to.time_out_value = tout;
}
/**
* @brief Configure I2C slave broadcasting mode.
*
* @param hw Beginning address of the peripheral registers
* @param broadcast_en Set true to enable broadcast, else, set it false
*
* @return None
*/
static inline void i2c_ll_slave_broadcast_enable(i2c_dev_t *hw, bool broadcast_en)
{
hw->ctr.addr_broadcasting_en = broadcast_en;
}
/**
* @brief Configure I2C slave address
*
@ -287,8 +305,15 @@ static inline void i2c_ll_set_tout(i2c_dev_t *hw, int tout)
*/
static inline void i2c_ll_set_slave_addr(i2c_dev_t *hw, uint16_t slave_addr, bool addr_10bit_en)
{
hw->slave_addr.slave_addr = slave_addr;
hw->slave_addr.addr_10bit_en = addr_10bit_en;
if (addr_10bit_en) {
uint8_t addr_14_7 = (slave_addr & 0xff) << 7;
uint8_t addr_6_0 = ((slave_addr & 0x300) >> 8) | 0x78;
hw->slave_addr.slave_addr = addr_14_7 | addr_6_0;
hw->ctr.addr_10bit_rw_check_en = addr_10bit_en;
} else {
hw->slave_addr.slave_addr = slave_addr;
}
}
/**
@ -301,7 +326,7 @@ static inline void i2c_ll_set_slave_addr(i2c_dev_t *hw, uint16_t slave_addr, boo
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_write_cmd_reg(i2c_dev_t *hw, i2c_ll_hw_cmd_t cmd, int cmd_idx)
static inline void i2c_ll_master_write_cmd_reg(i2c_dev_t *hw, i2c_ll_hw_cmd_t cmd, int cmd_idx)
{
hw->command[cmd_idx].val = cmd.val;
}
@ -315,7 +340,7 @@ static inline void i2c_ll_write_cmd_reg(i2c_dev_t *hw, i2c_ll_hw_cmd_t cmd, int
*
* @return None
*/
static inline void i2c_ll_set_start_timing(i2c_dev_t *hw, int start_setup, int start_hold)
static inline void i2c_ll_master_set_start_timing(i2c_dev_t *hw, int start_setup, int start_hold)
{
hw->scl_rstart_setup.scl_rstart_setup_time = start_setup;
hw->scl_start_hold.scl_start_hold_time = start_hold - 1;
@ -330,7 +355,7 @@ static inline void i2c_ll_set_start_timing(i2c_dev_t *hw, int start_setup, int s
*
* @return None
*/
static inline void i2c_ll_set_stop_timing(i2c_dev_t *hw, int stop_setup, int stop_hold)
static inline void i2c_ll_master_set_stop_timing(i2c_dev_t *hw, int stop_setup, int stop_hold)
{
hw->scl_stop_setup.scl_stop_setup_time = stop_setup;
hw->scl_stop_hold.scl_stop_hold_time = stop_hold;
@ -392,21 +417,6 @@ static inline void i2c_ll_set_data_mode(i2c_dev_t *hw, i2c_trans_mode_t tx_mode,
hw->ctr.rx_lsb_first = rx_mode;
}
/**
* @brief Get the I2C data mode
*
* @param hw Beginning address of the peripheral registers
* @param tx_mode Pointer to accept the received bytes mode
* @param rx_mode Pointer to accept the sended bytes mode
*
* @return None
*/
static inline void i2c_ll_get_data_mode(i2c_dev_t *hw, i2c_trans_mode_t *tx_mode, i2c_trans_mode_t *rx_mode)
{
*tx_mode = hw->ctr.tx_lsb_first;
*rx_mode = hw->ctr.rx_lsb_first;
}
/**
* @brief Get I2C sda timing configuration
*
@ -441,6 +451,7 @@ static inline uint32_t i2c_ll_get_hw_version(i2c_dev_t *hw)
*
* @return True if I2C state machine is busy, else false will be returned
*/
__attribute__((always_inline))
static inline bool i2c_ll_is_bus_busy(i2c_dev_t *hw)
{
return hw->sr.bus_busy;
@ -504,7 +515,7 @@ static inline void i2c_ll_get_tout(i2c_dev_t *hw, int *timeout)
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_trans_start(i2c_dev_t *hw)
static inline void i2c_ll_master_trans_start(i2c_dev_t *hw)
{
hw->ctr.trans_start = 1;
}
@ -539,21 +550,6 @@ static inline void i2c_ll_get_stop_timing(i2c_dev_t *hw, int *setup_time, int *h
*hold_time = hw->scl_stop_hold.scl_stop_hold_time;
}
/**
* @brief Get I2C SCL timing configuration
*
* @param hw Beginning address of the peripheral registers
* @param high_period Pointer to accept the SCL high period
* @param low_period Pointer to accept the SCL low period
*
* @return None
*/
static inline void i2c_ll_get_scl_timing(i2c_dev_t *hw, int *high_period, int *low_period)
{
*high_period = hw->scl_high_period.scl_high_period + hw->scl_high_period.scl_wait_high_period;
*low_period = hw->scl_low_period.scl_low_period + 1;
}
/**
* @brief Write the I2C hardware txFIFO
*
@ -588,6 +584,56 @@ static inline void i2c_ll_read_rxfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
}
}
/**
* @brief Write the I2C hardware txFIFO
*
* @param hw Beginning address of the peripheral registers
* @param ram_offset Offset value of I2C RAM.
* @param ptr Pointer to data buffer
* @param len Amount of data needs to be writen
*
* @return None.
*/
static inline void i2c_ll_write_by_nonfifo(i2c_dev_t *hw, uint8_t ram_offset, const uint8_t *ptr, uint8_t len)
{
uint32_t *fifo_addr = (uint32_t *)&hw->txfifo_start_addr;
for (int i = 0; i < len; i++) {
fifo_addr[i + ram_offset] = ptr[i];
}
}
/**
* @brief Read the I2C hardware ram
*
* @param hw Beginning address of the peripheral registers
* @param ram_offset Offset value of I2C RAM.
* @param ptr Pointer to data buffer
* @param len Amount of data needs read
*
* @return None
*/
static inline void i2c_ll_read_by_nonfifo(i2c_dev_t *hw, uint8_t ram_offset, uint8_t *ptr, uint8_t len)
{
uint32_t *fifo_addr = (uint32_t *)&hw->rxfifo_start_addr;
for (int i = 0; i < len; i++) {
ptr[i] = fifo_addr[i + ram_offset];
}
}
/**
* @brief Get access to I2C RAM address directly
*
* @param hw Beginning address of the peripheral registers
* @param addr_wr_en Enable I2C ram address read and write
*
* @return None
*/
static inline void i2c_ll_enable_mem_access_nonfifo(i2c_dev_t *hw, bool addr_wr_en)
{
hw->fifo_conf.fifo_addr_cfg_en = addr_wr_en;
}
/**
* @brief Configure I2C hardware filter
*
@ -597,7 +643,7 @@ static inline void i2c_ll_read_rxfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
*
* @return None
*/
static inline void i2c_ll_set_filter(i2c_dev_t *hw, uint8_t filter_num)
static inline void i2c_ll_master_set_filter(i2c_dev_t *hw, uint8_t filter_num)
{
if (filter_num > 0) {
hw->filter_cfg.scl_filter_thres = filter_num;
@ -617,7 +663,7 @@ static inline void i2c_ll_set_filter(i2c_dev_t *hw, uint8_t filter_num)
*
* @return The hardware filter configuration
*/
static inline void i2c_ll_get_filter(i2c_dev_t *hw, uint8_t *filter_conf)
static inline void i2c_ll_master_get_filter(i2c_dev_t *hw, uint8_t *filter_conf)
{
*filter_conf = hw->filter_cfg.scl_filter_thres;
}
@ -642,12 +688,13 @@ static inline void i2c_ll_master_fsm_rst(i2c_dev_t *hw)
* Note: The master cannot detect if deadlock happens, but when the scl_st_to interrupt is generated, a deadlock may occur.
*
* @param hw Beginning address of the peripheral registers
* @param slave_pulses When I2C master is IDLE, the number of pulses will be sent out.
*
* @return None
*/
static inline void i2c_ll_master_clr_bus(i2c_dev_t *hw)
static inline void i2c_ll_master_clr_bus(i2c_dev_t *hw, uint32_t slave_pulses)
{
hw->scl_sp_conf.scl_rst_slv_num = 9;
hw->scl_sp_conf.scl_rst_slv_num = slave_pulses;
hw->scl_sp_conf.scl_rst_slv_en = 1;
hw->ctr.conf_upgate = 1;
// hardward will clear scl_rst_slv_en after sending SCL pulses,
@ -735,6 +782,28 @@ static inline volatile void *i2c_ll_get_interrupt_status_reg(i2c_dev_t *dev)
return &dev->int_status;
}
/**
* @brief Enable I2C slave clock stretch.
*
* @param dev Beginning address of the peripheral registers.
* @param enable true: Enable, false: Disable.
*/
static inline void i2c_ll_slave_enable_scl_stretch(i2c_dev_t *dev, bool enable)
{
dev->scl_stretch_conf.slave_scl_stretch_en = enable;
}
/**
* @brief Clear I2C clock stretch status
*
* @param dev Beginning address of the peripheral registers
*/
__attribute__((always_inline))
static inline void i2c_ll_slave_clear_stretch(i2c_dev_t *dev)
{
dev->scl_stretch_conf.slave_scl_stretch_clr = 1;
}
//////////////////////////////////////////Deprecated Functions//////////////////////////////////////////////////////////
/////////////////////////////The following functions are only used by the legacy driver/////////////////////////////////
/////////////////////////////They might be removed in the next major release (ESP-IDF 6.0)//////////////////////////////
@ -952,6 +1021,52 @@ static inline void i2c_ll_slave_disable_rx_it(i2c_dev_t *hw)
hw->int_ena.val &= (~I2C_LL_SLAVE_RX_INT);
}
/**
* @brief Configure I2C SCL timing
*
* @param hw Beginning address of the peripheral registers
* @param hight_period The I2C SCL hight period (in core clock cycle, hight_period > 2)
* @param low_period The I2C SCL low period (in core clock cycle, low_period > 1)
*
* @return None.
*/
static inline void i2c_ll_set_scl_timing(i2c_dev_t *hw, int hight_period, int low_period)
{
hw->scl_low_period.scl_low_period = low_period - 1;
hw->scl_high_period.scl_high_period = hight_period - 10;
hw->scl_high_period.scl_wait_high_period = hight_period - hw->scl_high_period.scl_high_period;
}
/**
* @brief Get the I2C data mode
*
* @param hw Beginning address of the peripheral registers
* @param tx_mode Pointer to accept the received bytes mode
* @param rx_mode Pointer to accept the sended bytes mode
*
* @return None
*/
static inline void i2c_ll_get_data_mode(i2c_dev_t *hw, i2c_trans_mode_t *tx_mode, i2c_trans_mode_t *rx_mode)
{
*tx_mode = hw->ctr.tx_lsb_first;
*rx_mode = hw->ctr.rx_lsb_first;
}
/**
* @brief Get I2C SCL timing configuration
*
* @param hw Beginning address of the peripheral registers
* @param high_period Pointer to accept the SCL high period
* @param low_period Pointer to accept the SCL low period
*
* @return None
*/
static inline void i2c_ll_get_scl_timing(i2c_dev_t *hw, int *high_period, int *low_period)
{
*high_period = hw->scl_high_period.scl_high_period + hw->scl_high_period.scl_wait_high_period;
*low_period = hw->scl_low_period.scl_low_period + 1;
}
#ifdef __cplusplus
}
#endif

View File

@ -25,13 +25,13 @@ extern "C" {
*/
typedef union {
struct {
uint32_t byte_num: 8,
ack_en: 1,
ack_exp: 1,
ack_val: 1,
op_code: 3,
reserved14: 17,
done: 1;
uint32_t byte_num: 8, /*!< Specifies the length of data (in bytes) to be read or written */
ack_en: 1, /*!< Used to enable the I2C controller during a write operation to check whether ACK */
ack_exp: 1, /*!< Used to configure the level of the ACK bit expected by the I2C controller during a write operation */
ack_val: 1, /*!< Used to configure the level of the ACK bit sent by the I2C controller during a read operation */
op_code: 3, /*!< Indicates the command */
reserved14: 17, /*!< Reserved bits */
done: 1; /*!< Indicates that a command has been executed */
};
uint32_t val;
} i2c_ll_hw_cmd_t;
@ -44,26 +44,26 @@ typedef union {
#define I2C_LL_CMD_END 4 /*!<I2C end command */
typedef enum {
I2C_INTR_NACK = (1 << 10),
I2C_INTR_TIMEOUT = (1 << 8),
I2C_INTR_MST_COMPLETE = (1 << 7),
I2C_INTR_ARBITRATION = (1 << 5),
I2C_INTR_END_DETECT = (1 << 3),
I2C_INTR_ST_TO = (1 << 13),
} i2c_ll_master_intr_t;
typedef enum {
I2C_INTR_TXFIFO_WM = (1 << 1),
I2C_INTR_RXFIFO_WM = (1 << 0),
I2C_INTR_SLV_COMPLETE = (1 << 7),
I2C_INTR_START = (1 << 15),
} i2c_ll_slave_intr_t;
I2C_LL_INTR_TXFIFO_WM = (1 << 1),
I2C_LL_INTR_RXFIFO_WM = (1 << 0),
I2C_LL_INTR_NACK = (1 << 10),
I2C_LL_INTR_TIMEOUT = (1 << 8),
I2C_LL_INTR_MST_COMPLETE = (1 << 7),
I2C_LL_INTR_ARBITRATION = (1 << 5),
I2C_LL_INTR_END_DETECT = (1 << 3),
I2C_LL_INTR_ST_TO = (1 << 13),
I2C_LL_INTR_START = (1 << 15),
I2C_LL_INTR_STRETCH = (1 << 16),
I2C_LL_INTR_UNMATCH = (1 << 18),
} i2c_ll_intr_t;
// Get the I2C hardware instance
#define I2C_LL_GET_HW(i2c_num) (((i2c_num) == 0) ? &I2C0 : &I2C1)
#define I2C_LL_MASTER_EVENT_INTR (I2C_NACK_INT_ENA_M|I2C_TIME_OUT_INT_ENA_M|I2C_TRANS_COMPLETE_INT_ENA_M|I2C_ARBITRATION_LOST_INT_ENA_M|I2C_END_DETECT_INT_ENA_M)
#define I2C_LL_SLAVE_EVENT_INTR (I2C_RXFIFO_WM_INT_ENA_M|I2C_TRANS_COMPLETE_INT_ENA_M|I2C_TXFIFO_WM_INT_ENA_M)
#define I2C_LL_SLAVE_EVENT_INTR (I2C_TRANS_COMPLETE_INT_ENA_M|I2C_TXFIFO_WM_INT_ENA_M|I2C_SLAVE_STRETCH_INT_ENA_M)
#define I2C_LL_SLAVE_RX_EVENT_INTR (I2C_TRANS_COMPLETE_INT_ENA_M | I2C_SLAVE_STRETCH_INT_ENA_M)
#define I2C_LL_SLAVE_TX_EVENT_INTR (I2C_TXFIFO_WM_INT_ENA_M)
#define I2C_LL_RESET_SLV_SCL_PULSE_NUM_DEFAULT (9)
/**
* @brief Calculate I2C bus frequency
@ -74,7 +74,7 @@ typedef enum {
*
* @return None
*/
static inline void i2c_ll_cal_bus_clk(uint32_t source_clk, uint32_t bus_freq, i2c_hal_clk_config_t *clk_cal)
static inline void i2c_ll_master_cal_bus_clk(uint32_t source_clk, uint32_t bus_freq, i2c_hal_clk_config_t *clk_cal)
{
uint32_t half_cycle = source_clk / bus_freq / 2;
//SCL
@ -99,7 +99,7 @@ static inline void i2c_ll_cal_bus_clk(uint32_t source_clk, uint32_t bus_freq, i2
*
* @return None
*/
static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bus_cfg)
static inline void i2c_ll_master_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bus_cfg)
{
//scl period
hw->scl_low_period.period = bus_cfg->scl_low - 1;
@ -117,6 +117,18 @@ static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bu
hw->timeout.tout = bus_cfg->tout;
}
/**
* @brief Set fractional divider
*
* @param hw Beginning address of the peripheral registers
* @param div_a The denominator of the frequency divider factor of the i2c function clock
* @param div_b The numerator of the frequency divider factor of the i2c function clock.
*/
static inline void i2c_ll_master_set_fractional_divider(i2c_dev_t *hw, uint8_t div_a, uint8_t div_b)
{
// Not supported on ESP32S2
}
/**
* @brief Reset I2C txFIFO
*
@ -124,6 +136,7 @@ static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bu
*
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_txfifo_rst(i2c_dev_t *hw)
{
hw->fifo_conf.tx_fifo_rst = 1;
@ -137,28 +150,13 @@ static inline void i2c_ll_txfifo_rst(i2c_dev_t *hw)
*
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_rxfifo_rst(i2c_dev_t *hw)
{
hw->fifo_conf.rx_fifo_rst = 1;
hw->fifo_conf.rx_fifo_rst = 0;
}
/**
* @brief Configure I2C SCL timing
*
* @param hw Beginning address of the peripheral registers
* @param hight_period The I2C SCL hight period (in APB cycle, hight_period > 2)
* @param low_period The I2C SCL low period (in APB cycle, low_period > 1)
*
* @return None.
*/
static inline void i2c_ll_set_scl_timing(i2c_dev_t *hw, int hight_period, int low_period)
{
hw->scl_low_period.period = low_period-1;
hw->scl_high_period.period = hight_period/2+2;
hw->scl_high_period.scl_wait_high_period = hight_period - hw->scl_high_period.period;
}
/**
* @brief Clear I2C interrupt status
*
@ -181,6 +179,7 @@ static inline void i2c_ll_clear_intr_mask(i2c_dev_t *hw, uint32_t mask)
*
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_enable_intr_mask(i2c_dev_t *hw, uint32_t mask)
{
hw->int_ena.val |= mask;
@ -221,7 +220,7 @@ static inline void i2c_ll_get_intr_mask(i2c_dev_t *hw, uint32_t *intr_status)
*
* @return None
*/
static inline void i2c_ll_set_fifo_mode(i2c_dev_t *hw, bool fifo_mode_en)
static inline void i2c_ll_slave_set_fifo_mode(i2c_dev_t *hw, bool fifo_mode_en)
{
hw->fifo_conf.nonfifo_en = fifo_mode_en ? 0 : 1;
}
@ -240,6 +239,19 @@ static inline void i2c_ll_set_tout(i2c_dev_t *hw, int tout)
hw->timeout.time_out_en = tout > 0;
}
/**
* @brief Configure I2C slave broadcasting mode.
*
* @param hw Beginning address of the peripheral registers
* @param broadcast_en Set true to enable broadcast, else, set it false
*
* @return None
*/
static inline void i2c_ll_slave_broadcast_enable(i2c_dev_t *hw, bool broadcast_en)
{
// Not supported on esp32s2
}
/**
* @brief Configure I2C slave address
*
@ -251,8 +263,14 @@ static inline void i2c_ll_set_tout(i2c_dev_t *hw, int tout)
*/
static inline void i2c_ll_set_slave_addr(i2c_dev_t *hw, uint16_t slave_addr, bool addr_10bit_en)
{
hw->slave_addr.addr = slave_addr;
hw->slave_addr.en_10bit = addr_10bit_en;
if (addr_10bit_en) {
uint8_t addr_14_7 = (slave_addr & 0xff) << 7;
uint8_t addr_6_0 = ((slave_addr & 0x300) >> 8) || 0x78;
hw->slave_addr.addr = addr_14_7 || addr_6_0;
} else {
hw->slave_addr.addr = slave_addr;
}
}
/**
@ -265,7 +283,7 @@ static inline void i2c_ll_set_slave_addr(i2c_dev_t *hw, uint16_t slave_addr, boo
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_write_cmd_reg(i2c_dev_t *hw, i2c_ll_hw_cmd_t cmd, int cmd_idx)
static inline void i2c_ll_master_write_cmd_reg(i2c_dev_t *hw, i2c_ll_hw_cmd_t cmd, int cmd_idx)
{
hw->command[cmd_idx].val = cmd.val;
}
@ -279,7 +297,7 @@ static inline void i2c_ll_write_cmd_reg(i2c_dev_t *hw, i2c_ll_hw_cmd_t cmd, int
*
* @return None
*/
static inline void i2c_ll_set_start_timing(i2c_dev_t *hw, int start_setup, int start_hold)
static inline void i2c_ll_master_set_start_timing(i2c_dev_t *hw, int start_setup, int start_hold)
{
hw->scl_rstart_setup.time = start_setup;
hw->scl_start_hold.time = start_hold-1;
@ -294,7 +312,7 @@ static inline void i2c_ll_set_start_timing(i2c_dev_t *hw, int start_setup, int s
*
* @return None
*/
static inline void i2c_ll_set_stop_timing(i2c_dev_t *hw, int stop_setup, int stop_hold)
static inline void i2c_ll_master_set_stop_timing(i2c_dev_t *hw, int stop_setup, int stop_hold)
{
hw->scl_stop_setup.time = stop_setup;
hw->scl_stop_hold.time = stop_hold;
@ -356,21 +374,6 @@ static inline void i2c_ll_set_data_mode(i2c_dev_t *hw, i2c_trans_mode_t tx_mode,
hw->ctr.rx_lsb_first = rx_mode;
}
/**
* @brief Get the I2C data mode
*
* @param hw Beginning address of the peripheral registers
* @param tx_mode Pointer to accept the received bytes mode
* @param rx_mode Pointer to accept the sended bytes mode
*
* @return None
*/
static inline void i2c_ll_get_data_mode(i2c_dev_t *hw, i2c_trans_mode_t *tx_mode, i2c_trans_mode_t *rx_mode)
{
*tx_mode = hw->ctr.tx_lsb_first;
*rx_mode = hw->ctr.rx_lsb_first;
}
/**
* @brief Get I2C sda timing configuration
*
@ -405,6 +408,7 @@ static inline uint32_t i2c_ll_get_hw_version(i2c_dev_t *hw)
*
* @return True if I2C state machine is busy, else false will be returned
*/
__attribute__((always_inline))
static inline bool i2c_ll_is_bus_busy(i2c_dev_t *hw)
{
return hw->status_reg.bus_busy;
@ -468,7 +472,7 @@ static inline void i2c_ll_get_tout(i2c_dev_t *hw, int *timeout)
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_trans_start(i2c_dev_t *hw)
static inline void i2c_ll_master_trans_start(i2c_dev_t *hw)
{
hw->ctr.trans_start = 1;
}
@ -503,21 +507,6 @@ static inline void i2c_ll_get_stop_timing(i2c_dev_t *hw, int *setup_time, int *h
*hold_time = hw->scl_stop_hold.time;
}
/**
* @brief Get I2C SCL timing configuration
*
* @param hw Beginning address of the peripheral registers
* @param high_period Pointer to accept the SCL high period
* @param low_period Pointer to accept the SCL low period
*
* @return None
*/
static inline void i2c_ll_get_scl_timing(i2c_dev_t *hw, int *high_period, int *low_period)
{
*high_period = hw->scl_high_period.period + hw->scl_high_period.scl_wait_high_period;
*low_period = hw->scl_low_period.period + 1;
}
/**
* @brief Write the I2C hardware txFIFO
*
@ -563,7 +552,7 @@ static inline void i2c_ll_read_rxfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
*
* @return None
*/
static inline void i2c_ll_set_filter(i2c_dev_t *hw, uint8_t filter_num)
static inline void i2c_ll_master_set_filter(i2c_dev_t *hw, uint8_t filter_num)
{
if(filter_num > 0) {
hw->scl_filter_cfg.thres = filter_num;
@ -583,7 +572,7 @@ static inline void i2c_ll_set_filter(i2c_dev_t *hw, uint8_t filter_num)
*
* @return The hardware filter configuration
*/
static inline void i2c_ll_get_filter(i2c_dev_t *hw, uint8_t *filter_conf)
static inline void i2c_ll_master_get_filter(i2c_dev_t *hw, uint8_t *filter_conf)
{
*filter_conf = hw->sda_filter_cfg.thres;
}
@ -607,12 +596,13 @@ static inline void i2c_ll_master_fsm_rst(i2c_dev_t *hw)
* Note: The master cannot detect if deadlock happens, but when the scl_st_to interrupt is generated, a deadlock may occur.
*
* @param hw Beginning address of the peripheral registers
* @param slave_pulses When I2C master is IDLE, the number of pulses will be sent out.
*
* @return None
*/
static inline void i2c_ll_master_clr_bus(i2c_dev_t *hw)
static inline void i2c_ll_master_clr_bus(i2c_dev_t *hw, uint32_t slave_pulses)
{
hw->scl_sp_conf.scl_rst_slv_num = 9;
hw->scl_sp_conf.scl_rst_slv_num = slave_pulses;
hw->scl_sp_conf.scl_rst_slv_en = 0;
hw->scl_sp_conf.scl_rst_slv_en = 1;
}
@ -727,6 +717,28 @@ static inline volatile void *i2c_ll_get_interrupt_status_reg(i2c_dev_t *dev)
return &dev->int_status;
}
/**
* @brief Enable I2C slave clock stretch.
*
* @param dev Beginning address of the peripheral registers.
* @param enable true: Enable, false: Disable.
*/
static inline void i2c_ll_slave_enable_scl_stretch(i2c_dev_t *dev, bool enable)
{
dev->scl_stretch_conf.slave_scl_stretch_en = enable;
}
/**
* @brief Clear I2C clock stretch status
*
* @param dev Beginning address of the peripheral registers
*/
__attribute__((always_inline))
static inline void i2c_ll_slave_clear_stretch(i2c_dev_t *dev)
{
dev->scl_stretch_conf.slave_scl_stretch_clr = 1;
}
//////////////////////////////////////////Deprecated Functions//////////////////////////////////////////////////////////
/////////////////////////////The following functions are only used by the legacy driver/////////////////////////////////
/////////////////////////////They might be removed in the next major release (ESP-IDF 6.0)//////////////////////////////
@ -945,6 +957,52 @@ static inline void i2c_ll_slave_disable_rx_it(i2c_dev_t *hw)
hw->int_ena.val &= (~I2C_LL_SLAVE_RX_INT);
}
/**
* @brief Configure I2C SCL timing
*
* @param hw Beginning address of the peripheral registers
* @param hight_period The I2C SCL hight period (in APB cycle, hight_period > 2)
* @param low_period The I2C SCL low period (in APB cycle, low_period > 1)
*
* @return None.
*/
static inline void i2c_ll_set_scl_timing(i2c_dev_t *hw, int hight_period, int low_period)
{
hw->scl_low_period.period = low_period-1;
hw->scl_high_period.period = hight_period/2+2;
hw->scl_high_period.scl_wait_high_period = hight_period - hw->scl_high_period.period;
}
/**
* @brief Get the I2C data mode
*
* @param hw Beginning address of the peripheral registers
* @param tx_mode Pointer to accept the received bytes mode
* @param rx_mode Pointer to accept the sended bytes mode
*
* @return None
*/
static inline void i2c_ll_get_data_mode(i2c_dev_t *hw, i2c_trans_mode_t *tx_mode, i2c_trans_mode_t *rx_mode)
{
*tx_mode = hw->ctr.tx_lsb_first;
*rx_mode = hw->ctr.rx_lsb_first;
}
/**
* @brief Get I2C SCL timing configuration
*
* @param hw Beginning address of the peripheral registers
* @param high_period Pointer to accept the SCL high period
* @param low_period Pointer to accept the SCL low period
*
* @return None
*/
static inline void i2c_ll_get_scl_timing(i2c_dev_t *hw, int *high_period, int *low_period)
{
*high_period = hw->scl_high_period.period + hw->scl_high_period.scl_wait_high_period;
*low_period = hw->scl_low_period.period + 1;
}
#ifdef __cplusplus
}
#endif

View File

@ -28,13 +28,13 @@ extern "C" {
*/
typedef union {
struct {
uint32_t byte_num: 8,
ack_en: 1,
ack_exp: 1,
ack_val: 1,
op_code: 3,
reserved14: 17,
done: 1;
uint32_t byte_num: 8, /*!< Specifies the length of data (in bytes) to be read or written */
ack_en: 1, /*!< Used to enable the I2C controller during a write operation to check whether ACK */
ack_exp: 1, /*!< Used to configure the level of the ACK bit expected by the I2C controller during a write operation */
ack_val: 1, /*!< Used to configure the level of the ACK bit sent by the I2C controller during a read operation */
op_code: 3, /*!< Indicates the command */
reserved14: 17, /*!< Reserved bits */
done: 1; /*!< Indicates that a command has been executed */
};
uint32_t val;
} i2c_ll_hw_cmd_t;
@ -47,25 +47,26 @@ typedef union {
#define I2C_LL_CMD_END 4 /*!<I2C end command */
typedef enum {
I2C_INTR_NACK = (1 << 10),
I2C_INTR_TIMEOUT = (1 << 8),
I2C_INTR_MST_COMPLETE = (1 << 7),
I2C_INTR_ARBITRATION = (1 << 5),
I2C_INTR_END_DETECT = (1 << 3),
I2C_INTR_ST_TO = (1 << 13),
} i2c_ll_master_intr_t;
typedef enum {
I2C_INTR_TXFIFO_WM = (1 << 1),
I2C_INTR_RXFIFO_WM = (1 << 0),
I2C_INTR_SLV_COMPLETE = (1 << 7),
I2C_INTR_START = (1 << 15),
} i2c_ll_slave_intr_t;
I2C_LL_INTR_TXFIFO_WM = (1 << 1),
I2C_LL_INTR_RXFIFO_WM = (1 << 0),
I2C_LL_INTR_NACK = (1 << 10),
I2C_LL_INTR_TIMEOUT = (1 << 8),
I2C_LL_INTR_MST_COMPLETE = (1 << 7),
I2C_LL_INTR_ARBITRATION = (1 << 5),
I2C_LL_INTR_END_DETECT = (1 << 3),
I2C_LL_INTR_ST_TO = (1 << 13),
I2C_LL_INTR_START = (1 << 15),
I2C_LL_INTR_STRETCH = (1 << 16),
I2C_LL_INTR_UNMATCH = (1 << 18),
} i2c_ll_intr_t;
// Get the I2C hardware instance
#define I2C_LL_GET_HW(i2c_num) (((i2c_num) == 0) ? &I2C0 : &I2C1)
#define I2C_LL_MASTER_EVENT_INTR (I2C_NACK_INT_ENA_M|I2C_TIME_OUT_INT_ENA_M|I2C_TRANS_COMPLETE_INT_ENA_M|I2C_ARBITRATION_LOST_INT_ENA_M|I2C_END_DETECT_INT_ENA_M)
#define I2C_LL_SLAVE_EVENT_INTR (I2C_RXFIFO_WM_INT_ENA_M|I2C_TRANS_COMPLETE_INT_ENA_M|I2C_TXFIFO_WM_INT_ENA_M)
#define I2C_LL_SLAVE_EVENT_INTR (I2C_TRANS_COMPLETE_INT_ENA_M|I2C_TXFIFO_WM_INT_ENA_M|I2C_RXFIFO_WM_INT_ENA_M | I2C_SLAVE_STRETCH_INT_ENA_M)
#define I2C_LL_SLAVE_RX_EVENT_INTR (I2C_TRANS_COMPLETE_INT_ENA_M | I2C_RXFIFO_WM_INT_ENA_M | I2C_SLAVE_STRETCH_INT_ENA_M)
#define I2C_LL_SLAVE_TX_EVENT_INTR (I2C_TXFIFO_WM_INT_ENA_M)
#define I2C_LL_RESET_SLV_SCL_PULSE_NUM_DEFAULT (9)
/**
* @brief Calculate I2C bus frequency
@ -79,7 +80,7 @@ typedef enum {
*
* @return None
*/
static inline void i2c_ll_cal_bus_clk(uint32_t source_clk, uint32_t bus_freq, i2c_hal_clk_config_t *clk_cal)
static inline void i2c_ll_master_cal_bus_clk(uint32_t source_clk, uint32_t bus_freq, i2c_hal_clk_config_t *clk_cal)
{
uint32_t clkm_div = source_clk / (bus_freq * 1024) +1;
uint32_t sclk_freq = source_clk / clkm_div;
@ -126,7 +127,7 @@ static inline void i2c_ll_update(i2c_dev_t *hw)
*
* @return None
*/
static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bus_cfg)
static inline void i2c_ll_master_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bus_cfg)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->clk_conf, sclk_div_num, bus_cfg->clkm_div - 1);
/* According to the Technical Reference Manual, the following timings must be subtracted by 1.
@ -150,6 +151,20 @@ static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bu
hw->to.time_out_en = 1;
}
/**
* @brief Set fractional divider
*
* @param hw Beginning address of the peripheral registers
* @param div_a The denominator of the frequency divider factor of the i2c function clock
* @param div_b The numerator of the frequency divider factor of the i2c function clock.
*/
static inline void i2c_ll_master_set_fractional_divider(i2c_dev_t *hw, uint8_t div_a, uint8_t div_b)
{
/* Set div_a and div_b to 0, as it's not necessary to use them */
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->clk_conf, sclk_div_a, div_a);
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->clk_conf, sclk_div_b, div_b);
}
/**
* @brief Reset I2C txFIFO
*
@ -157,6 +172,7 @@ static inline void i2c_ll_set_bus_timing(i2c_dev_t *hw, i2c_hal_clk_config_t *bu
*
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_txfifo_rst(i2c_dev_t *hw)
{
hw->fifo_conf.tx_fifo_rst = 1;
@ -170,29 +186,13 @@ static inline void i2c_ll_txfifo_rst(i2c_dev_t *hw)
*
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_rxfifo_rst(i2c_dev_t *hw)
{
hw->fifo_conf.rx_fifo_rst = 1;
hw->fifo_conf.rx_fifo_rst = 0;
}
/**
* @brief Configure I2C SCL timing
*
* @param hw Beginning address of the peripheral registers
* @param high_period The I2C SCL hight period (in core clock cycle, hight_period > 2)
* @param low_period The I2C SCL low period (in core clock cycle, low_period > 1)
*
* @return None.
*/
static inline void i2c_ll_set_scl_timing(i2c_dev_t *hw, int high_period, int low_period)
{
int high_period_output = high_period - 10; // The rising edge by open-drain output + internal pullup (about 50K) is slow
hw->scl_low_period.scl_low_period = low_period - 1;
hw->scl_high_period.scl_high_period = high_period_output;
hw->scl_high_period.scl_wait_high_period = high_period - high_period_output;
}
/**
* @brief Clear I2C interrupt status
*
@ -215,6 +215,7 @@ static inline void i2c_ll_clear_intr_mask(i2c_dev_t *hw, uint32_t mask)
*
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_enable_intr_mask(i2c_dev_t *hw, uint32_t mask)
{
hw->int_ena.val |= mask;
@ -255,7 +256,7 @@ static inline void i2c_ll_get_intr_mask(i2c_dev_t *hw, uint32_t *intr_status)
*
* @return None
*/
static inline void i2c_ll_set_fifo_mode(i2c_dev_t *hw, bool fifo_mode_en)
static inline void i2c_ll_slave_set_fifo_mode(i2c_dev_t *hw, bool fifo_mode_en)
{
hw->fifo_conf.nonfifo_en = fifo_mode_en ? 0 : 1;
}
@ -273,6 +274,19 @@ static inline void i2c_ll_set_tout(i2c_dev_t *hw, int tout)
hw->to.time_out_value = tout;
}
/**
* @brief Configure I2C slave broadcasting mode.
*
* @param hw Beginning address of the peripheral registers
* @param broadcast_en Set true to enable broadcast, else, set it false
*
* @return None
*/
static inline void i2c_ll_slave_broadcast_enable(i2c_dev_t *hw, bool broadcast_en)
{
hw->ctr.addr_broadcasting_en = broadcast_en;
}
/**
* @brief Configure I2C slave address
*
@ -284,8 +298,15 @@ static inline void i2c_ll_set_tout(i2c_dev_t *hw, int tout)
*/
static inline void i2c_ll_set_slave_addr(i2c_dev_t *hw, uint16_t slave_addr, bool addr_10bit_en)
{
hw->slave_addr.slave_addr = slave_addr;
hw->slave_addr.addr_10bit_en = addr_10bit_en;
if (addr_10bit_en) {
uint8_t addr_14_7 = (slave_addr & 0xff) << 7;
uint8_t addr_6_0 = ((slave_addr & 0x300) >> 8) | 0x78;
hw->slave_addr.slave_addr = addr_14_7 | addr_6_0;
hw->ctr.addr_10bit_rw_check_en = addr_10bit_en;
} else {
hw->slave_addr.slave_addr = slave_addr;
}
}
/**
@ -298,7 +319,7 @@ static inline void i2c_ll_set_slave_addr(i2c_dev_t *hw, uint16_t slave_addr, boo
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_write_cmd_reg(i2c_dev_t *hw, i2c_ll_hw_cmd_t cmd, int cmd_idx)
static inline void i2c_ll_master_write_cmd_reg(i2c_dev_t *hw, i2c_ll_hw_cmd_t cmd, int cmd_idx)
{
hw->comd[cmd_idx].val = cmd.val;
}
@ -312,7 +333,7 @@ static inline void i2c_ll_write_cmd_reg(i2c_dev_t *hw, i2c_ll_hw_cmd_t cmd, int
*
* @return None
*/
static inline void i2c_ll_set_start_timing(i2c_dev_t *hw, int start_setup, int start_hold)
static inline void i2c_ll_master_set_start_timing(i2c_dev_t *hw, int start_setup, int start_hold)
{
hw->scl_rstart_setup.scl_rstart_setup_time = start_setup;
hw->scl_start_hold.scl_start_hold_time = start_hold - 1;
@ -327,7 +348,7 @@ static inline void i2c_ll_set_start_timing(i2c_dev_t *hw, int start_setup, int s
*
* @return None
*/
static inline void i2c_ll_set_stop_timing(i2c_dev_t *hw, int stop_setup, int stop_hold)
static inline void i2c_ll_master_set_stop_timing(i2c_dev_t *hw, int stop_setup, int stop_hold)
{
hw->scl_stop_setup.scl_stop_setup_time = stop_setup;
hw->scl_stop_hold.scl_stop_hold_time = stop_hold;
@ -389,21 +410,6 @@ static inline void i2c_ll_set_data_mode(i2c_dev_t *hw, i2c_trans_mode_t tx_mode,
hw->ctr.rx_lsb_first = rx_mode;
}
/**
* @brief Get the I2C data mode
*
* @param hw Beginning address of the peripheral registers
* @param tx_mode Pointer to accept the received bytes mode
* @param rx_mode Pointer to accept the sended bytes mode
*
* @return None
*/
static inline void i2c_ll_get_data_mode(i2c_dev_t *hw, i2c_trans_mode_t *tx_mode, i2c_trans_mode_t *rx_mode)
{
*tx_mode = hw->ctr.tx_lsb_first;
*rx_mode = hw->ctr.rx_lsb_first;
}
/**
* @brief Get I2C sda timing configuration
*
@ -438,6 +444,7 @@ static inline uint32_t i2c_ll_get_hw_version(i2c_dev_t *hw)
*
* @return True if I2C state machine is busy, else false will be returned
*/
__attribute__((always_inline))
static inline bool i2c_ll_is_bus_busy(i2c_dev_t *hw)
{
return hw->sr.bus_busy;
@ -501,7 +508,7 @@ static inline void i2c_ll_get_tout(i2c_dev_t *hw, int *timeout)
* @return None
*/
__attribute__((always_inline))
static inline void i2c_ll_trans_start(i2c_dev_t *hw)
static inline void i2c_ll_master_trans_start(i2c_dev_t *hw)
{
hw->ctr.trans_start = 1;
}
@ -536,21 +543,6 @@ static inline void i2c_ll_get_stop_timing(i2c_dev_t *hw, int *setup_time, int *h
*hold_time = hw->scl_stop_hold.scl_stop_hold_time;
}
/**
* @brief Get I2C SCL timing configuration
*
* @param hw Beginning address of the peripheral registers
* @param high_period Pointer to accept the SCL high period
* @param low_period Pointer to accept the SCL low period
*
* @return None
*/
static inline void i2c_ll_get_scl_timing(i2c_dev_t *hw, int *high_period, int *low_period)
{
*high_period = hw->scl_high_period.scl_high_period + hw->scl_high_period.scl_wait_high_period;
*low_period = hw->scl_low_period.scl_low_period + 1;
}
/**
* @brief Write the I2C hardware txFIFO
*
@ -585,6 +577,56 @@ static inline void i2c_ll_read_rxfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
}
}
/**
* @brief Write the I2C hardware txFIFO
*
* @param hw Beginning address of the peripheral registers
* @param ram_offset Offset value of I2C RAM.
* @param ptr Pointer to data buffer
* @param len Amount of data needs to be writen
*
* @return None.
*/
static inline void i2c_ll_write_by_nonfifo(i2c_dev_t *hw, uint8_t ram_offset, const uint8_t *ptr, uint8_t len)
{
uint32_t *fifo_addr = (uint32_t *)&hw->txfifo_start_addr;
for (int i = 0; i < len; i++) {
fifo_addr[i + ram_offset] = ptr[i];
}
}
/**
* @brief Read the I2C hardware ram
*
* @param hw Beginning address of the peripheral registers
* @param ram_offset Offset value of I2C RAM.
* @param ptr Pointer to data buffer
* @param len Amount of data needs read
*
* @return None
*/
static inline void i2c_ll_read_by_nonfifo(i2c_dev_t *hw, uint8_t ram_offset, uint8_t *ptr, uint8_t len)
{
uint32_t *fifo_addr = (uint32_t *)&hw->rxfifo_start_addr;
for (int i = 0; i < len; i++) {
ptr[i] = fifo_addr[i + ram_offset];
}
}
/**
* @brief Get access to I2C RAM address directly
*
* @param hw Beginning address of the peripheral registers
* @param addr_wr_en Enable I2C ram address read and write
*
* @return None
*/
static inline void i2c_ll_enable_mem_access_nonfifo(i2c_dev_t *hw, bool addr_wr_en)
{
hw->fifo_conf.fifo_addr_cfg_en = addr_wr_en;
}
/**
* @brief Configure I2C hardware filter
*
@ -594,7 +636,7 @@ static inline void i2c_ll_read_rxfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
*
* @return None
*/
static inline void i2c_ll_set_filter(i2c_dev_t *hw, uint8_t filter_num)
static inline void i2c_ll_master_set_filter(i2c_dev_t *hw, uint8_t filter_num)
{
if (filter_num > 0) {
hw->filter_cfg.scl_filter_thres = filter_num;
@ -614,7 +656,7 @@ static inline void i2c_ll_set_filter(i2c_dev_t *hw, uint8_t filter_num)
*
* @return The hardware filter configuration
*/
static inline void i2c_ll_get_filter(i2c_dev_t *hw, uint8_t *filter_conf)
static inline void i2c_ll_master_get_filter(i2c_dev_t *hw, uint8_t *filter_conf)
{
*filter_conf = hw->filter_cfg.scl_filter_thres;
}
@ -638,12 +680,13 @@ static inline void i2c_ll_master_fsm_rst(i2c_dev_t *hw)
* Note: The master cannot detect if deadlock happens, but when the scl_st_to interrupt is generated, a deadlock may occur.
*
* @param hw Beginning address of the peripheral registers
* @param slave_pulses When I2C master is IDLE, the number of pulses will be sent out.
*
* @return None
*/
static inline void i2c_ll_master_clr_bus(i2c_dev_t *hw)
static inline void i2c_ll_master_clr_bus(i2c_dev_t *hw, uint32_t slave_pulses)
{
hw->scl_sp_conf.scl_rst_slv_num = 9;
hw->scl_sp_conf.scl_rst_slv_num = slave_pulses;
hw->scl_sp_conf.scl_rst_slv_en = 1;
hw->ctr.conf_upgate = 1;
}
@ -726,6 +769,28 @@ static inline volatile void *i2c_ll_get_interrupt_status_reg(i2c_dev_t *dev)
return &dev->int_status;
}
/**
* @brief Enable I2C slave clock stretch.
*
* @param dev Beginning address of the peripheral registers.
* @param enable true: Enable, false: Disable.
*/
static inline void i2c_ll_slave_enable_scl_stretch(i2c_dev_t *dev, bool enable)
{
dev->scl_stretch_conf.slave_scl_stretch_en = enable;
}
/**
* @brief Clear I2C clock stretch status
*
* @param dev Beginning address of the peripheral registers
*/
__attribute__((always_inline))
static inline void i2c_ll_slave_clear_stretch(i2c_dev_t *dev)
{
dev->scl_stretch_conf.slave_scl_stretch_clr = 1;
}
//////////////////////////////////////////Deprecated Functions//////////////////////////////////////////////////////////
/////////////////////////////The following functions are only used by the legacy driver/////////////////////////////////
/////////////////////////////They might be removed in the next major release (ESP-IDF 6.0)//////////////////////////////
@ -943,6 +1008,53 @@ static inline void i2c_ll_slave_disable_rx_it(i2c_dev_t *hw)
hw->int_ena.val &= (~I2C_LL_SLAVE_RX_INT);
}
/**
* @brief Configure I2C SCL timing
*
* @param hw Beginning address of the peripheral registers
* @param high_period The I2C SCL hight period (in core clock cycle, hight_period > 2)
* @param low_period The I2C SCL low period (in core clock cycle, low_period > 1)
*
* @return None.
*/
static inline void i2c_ll_set_scl_timing(i2c_dev_t *hw, int high_period, int low_period)
{
int high_period_output = high_period - 10; // The rising edge by open-drain output + internal pullup (about 50K) is slow
hw->scl_low_period.scl_low_period = low_period - 1;
hw->scl_high_period.scl_high_period = high_period_output;
hw->scl_high_period.scl_wait_high_period = high_period - high_period_output;
}
/**
* @brief Get the I2C data mode
*
* @param hw Beginning address of the peripheral registers
* @param tx_mode Pointer to accept the received bytes mode
* @param rx_mode Pointer to accept the sended bytes mode
*
* @return None
*/
static inline void i2c_ll_get_data_mode(i2c_dev_t *hw, i2c_trans_mode_t *tx_mode, i2c_trans_mode_t *rx_mode)
{
*tx_mode = hw->ctr.tx_lsb_first;
*rx_mode = hw->ctr.rx_lsb_first;
}
/**
* @brief Get I2C SCL timing configuration
*
* @param hw Beginning address of the peripheral registers
* @param high_period Pointer to accept the SCL high period
* @param low_period Pointer to accept the SCL low period
*
* @return None
*/
static inline void i2c_ll_get_scl_timing(i2c_dev_t *hw, int *high_period, int *low_period)
{
*high_period = hw->scl_high_period.scl_high_period + hw->scl_high_period.scl_wait_high_period;
*low_period = hw->scl_low_period.scl_low_period + 1;
}
#ifdef __cplusplus
}
#endif

View File

@ -14,8 +14,6 @@
void i2c_hal_slave_init(i2c_hal_context_t *hal)
{
i2c_ll_slave_init(hal->dev);
//Use fifo mode
i2c_ll_set_fifo_mode(hal->dev, true);
//MSB
i2c_ll_set_data_mode(hal->dev, I2C_DATA_MODE_MSB_FIRST, I2C_DATA_MODE_MSB_FIRST);
//Reset fifo
@ -28,8 +26,8 @@ void i2c_hal_set_bus_timing(i2c_hal_context_t *hal, int scl_freq, i2c_clock_sour
{
i2c_ll_set_source_clk(hal->dev, src_clk);
i2c_hal_clk_config_t clk_cal = {0};
i2c_ll_cal_bus_clk(source_freq, scl_freq, &clk_cal);
i2c_ll_set_bus_timing(hal->dev, &clk_cal);
i2c_ll_master_cal_bus_clk(source_freq, scl_freq, &clk_cal);
i2c_ll_master_set_bus_timing(hal->dev, &clk_cal);
}
void i2c_hal_master_fsm_rst(i2c_hal_context_t *hal)
@ -40,8 +38,6 @@ void i2c_hal_master_fsm_rst(i2c_hal_context_t *hal)
void i2c_hal_master_init(i2c_hal_context_t *hal)
{
i2c_ll_master_init(hal->dev);
//Use fifo mode
i2c_ll_set_fifo_mode(hal->dev, true);
//MSB
i2c_ll_set_data_mode(hal->dev, I2C_DATA_MODE_MSB_FIRST, I2C_DATA_MODE_MSB_FIRST);
//Reset fifo
@ -63,12 +59,6 @@ void i2c_hal_deinit(i2c_hal_context_t *hal)
hal->dev = NULL;
}
void i2c_hal_master_trans_start(i2c_hal_context_t *hal)
{
i2c_ll_update(hal->dev);
i2c_ll_trans_start(hal->dev);
}
void i2c_hal_get_timing_config(i2c_hal_context_t *hal, i2c_hal_timing_config_t *timing_config)
{
i2c_ll_get_scl_clk_timing(hal->dev, &timing_config->high_period, &timing_config->low_period, &timing_config->wait_high_period);
@ -81,8 +71,8 @@ void i2c_hal_get_timing_config(i2c_hal_context_t *hal, i2c_hal_timing_config_t *
void i2c_hal_set_timing_config(i2c_hal_context_t *hal, i2c_hal_timing_config_t *timing_config)
{
i2c_ll_set_scl_clk_timing(hal->dev, timing_config->high_period, timing_config->low_period, timing_config->wait_high_period);
i2c_ll_set_start_timing(hal->dev, timing_config->rstart_setup, timing_config->start_hold);
i2c_ll_set_stop_timing(hal->dev, timing_config->stop_setup, timing_config->stop_hold);
i2c_ll_master_set_start_timing(hal->dev, timing_config->rstart_setup, timing_config->start_hold);
i2c_ll_master_set_stop_timing(hal->dev, timing_config->stop_setup, timing_config->stop_hold);
i2c_ll_set_sda_timing(hal->dev, timing_config->sda_sample, timing_config->sda_hold);
i2c_ll_set_tout(hal->dev, timing_config->timeout);
}

View File

@ -6,6 +6,11 @@
#include "hal/i2c_hal.h"
void i2c_hal_master_trans_start(i2c_hal_context_t *hal)
{
i2c_ll_update(hal->dev);
i2c_ll_master_trans_start(hal->dev);
}
//////////////////////////////////////////Deprecated Functions//////////////////////////////////////////////////////////
/////////////////////////////The following functions are only used by the legacy driver/////////////////////////////////

View File

@ -33,6 +33,22 @@ typedef struct {
i2c_dev_t *dev;
} i2c_hal_context_t;
/**
* @brief Timing configuration structure. Used for I2C reset internally.
*/
typedef struct {
int high_period; /*!< high_period time */
int low_period; /*!< low_period time */
int wait_high_period; /*!< wait_high_period time */
int rstart_setup; /*!< restart setup */
int start_hold; /*!< start hold time */
int stop_setup; /*!< stop setup */
int stop_hold; /*!< stop hold time */
int sda_sample; /*!< high_period time */
int sda_hold; /*!< sda hold time */
int timeout; /*!< timeout value */
} i2c_hal_timing_config_t;
#if SOC_I2C_SUPPORT_SLAVE
/**

View File

@ -29,6 +29,16 @@ typedef enum {
I2C_NUM_MAX, /*!< I2C port max */
} i2c_port_t;
/**
* @brief Enumeration for I2C device address bit length
*/
typedef enum {
I2C_ADDR_BIT_LEN_7 = 0, /*!< i2c address bit length 7 */
#if SOC_I2C_SUPPORT_10BIT_ADDR
I2C_ADDR_BIT_LEN_10 = 1, /*!< i2c address bit length 10 */
#endif
} i2c_addr_bit_len_t;
/**
* @brief Data structure for calculating I2C bus timing.
*/
@ -63,6 +73,7 @@ typedef enum {
I2C_DATA_MODE_MAX
} i2c_trans_mode_t;
__attribute__((deprecated("please use 'i2c_addr_bit_len_t' instead")))
typedef enum {
I2C_ADDR_BIT_7 = 0, /*!< I2C 7bit address for slave mode */
I2C_ADDR_BIT_10, /*!< I2C 10bit address for slave mode */
@ -76,22 +87,6 @@ typedef enum {
I2C_MASTER_ACK_MAX,
} i2c_ack_type_t;
/**
* @brief Timing configuration structure. Used for I2C reset internally.
*/
typedef struct {
int high_period; /*!< high_period time */
int low_period; /*!< low_period time */
int wait_high_period; /*!< wait_high_period time */
int rstart_setup; /*!< restart setup */
int start_hold; /*!< start hold time */
int stop_setup; /*!< stop setup */
int stop_hold; /*!< stop hold time */
int sda_sample; /*!< high_period time */
int sda_hold; /*!< sda hold time */
int timeout; /*!< timeout value */
} i2c_hal_timing_config_t;
#if SOC_I2C_SUPPORTED
/**
* @brief I2C group clock source

View File

@ -315,6 +315,10 @@ config SOC_I2C_SUPPORT_APB
bool
default y
config SOC_I2C_STOP_INDEPENDENT
bool
default y
config SOC_I2S_NUM
int
default 2

View File

@ -184,6 +184,9 @@
#define SOC_I2C_SUPPORT_APB (1)
// On ESP32, the stop bit should be independent, we can't put trans data and stop command together
#define SOC_I2C_STOP_INDEPENDENT (1)
/*-------------------------- I2S CAPS ----------------------------------------*/
// ESP32 has 2 I2S
#define SOC_I2S_NUM (2U)

View File

@ -299,6 +299,10 @@ config SOC_I2C_SUPPORT_RTC
bool
default y
config SOC_I2C_SUPPORT_10BIT_ADDR
bool
default y
config SOC_LEDC_SUPPORT_PLL_DIV_CLOCK
bool
default y

View File

@ -147,6 +147,7 @@
#define SOC_I2C_SUPPORT_XTAL (1)
#define SOC_I2C_SUPPORT_RTC (1)
#define SOC_I2C_SUPPORT_10BIT_ADDR (1)
/*-------------------------- LEDC CAPS ---------------------------------------*/
#define SOC_LEDC_SUPPORT_PLL_DIV_CLOCK (1)

View File

@ -395,6 +395,10 @@ config SOC_I2C_SUPPORT_RTC
bool
default y
config SOC_I2C_SUPPORT_10BIT_ADDR
bool
default y
config SOC_I2S_NUM
int
default 1

View File

@ -186,6 +186,7 @@
#define SOC_I2C_SUPPORT_XTAL (1)
#define SOC_I2C_SUPPORT_RTC (1)
#define SOC_I2C_SUPPORT_10BIT_ADDR (1)
/*-------------------------- I2S CAPS ----------------------------------------*/
#define SOC_I2S_NUM (1U)

View File

@ -511,6 +511,10 @@ config SOC_I2C_SUPPORT_RTC
bool
default y
config SOC_I2C_SUPPORT_10BIT_ADDR
bool
default y
config SOC_LP_I2C_NUM
int
default 1

View File

@ -228,6 +228,7 @@
#define SOC_I2C_SUPPORT_XTAL (1)
#define SOC_I2C_SUPPORT_RTC (1)
#define SOC_I2C_SUPPORT_10BIT_ADDR (1)
/*-------------------------- LP_I2C CAPS -------------------------------------*/
// ESP32-C6 has 1 LP_I2C

View File

@ -499,6 +499,10 @@ config SOC_I2C_SUPPORT_RTC
bool
default y
config SOC_I2C_SUPPORT_10BIT_ADDR
bool
default y
config SOC_I2S_NUM
int
default 1

View File

@ -230,6 +230,7 @@
#define SOC_I2C_SUPPORT_XTAL (1)
#define SOC_I2C_SUPPORT_RTC (1)
#define SOC_I2C_SUPPORT_10BIT_ADDR (1)
/*-------------------------- I2S CAPS ----------------------------------------*/
#define SOC_I2S_NUM (1U)

View File

@ -455,6 +455,10 @@ config SOC_I2C_SUPPORT_RTC
bool
default y
config SOC_I2C_SUPPORT_10BIT_ADDR
bool
default y
config SOC_I2S_NUM
int
default 2

View File

@ -190,6 +190,8 @@
#define SOC_I2C_SUPPORT_XTAL (1)
#define SOC_I2C_SUPPORT_RTC (1)
#define SOC_I2C_SUPPORT_10BIT_ADDR (1)
/*-------------------------- I2S CAPS ----------------------------------------*/
#define SOC_I2S_NUM (2U)
#define SOC_I2S_HW_VERSION_2 (1)