Skip to content

Commit

Permalink
drivers: Update SOC_ESP32 -> SOC_SERIES_ESP32
Browse files Browse the repository at this point in the history
Signed-off-by: Marek Matej <marek.matej@espressif.com>
  • Loading branch information
Marek Matej committed May 30, 2023
1 parent 1ecbdb6 commit 3c5a22f
Show file tree
Hide file tree
Showing 13 changed files with 67 additions and 67 deletions.
14 changes: 7 additions & 7 deletions drivers/adc/adc_esp32.c
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#include <zephyr/logging/log.h>
LOG_MODULE_REGISTER(adc_esp32, CONFIG_ADC_LOG_LEVEL);

#if CONFIG_SOC_ESP32
#if CONFIG_SOC_SERIES_ESP32
#define ADC_CALI_SCHEME ESP_ADC_CAL_VAL_EFUSE_VREF
#define ADC_RESOLUTION_MIN SOC_ADC_DIGI_MIN_BITWIDTH
#define ADC_RESOLUTION_MAX SOC_ADC_DIGI_MAX_BITWIDTH
Expand All @@ -31,12 +31,12 @@ LOG_MODULE_REGISTER(adc_esp32, CONFIG_ADC_LOG_LEVEL);
*/
#define ADC_CLIP_MVOLT_11DB 2550

#elif CONFIG_SOC_ESP32S2
#elif CONFIG_SOC_SERIES_ESP32S2
#define ADC_CALI_SCHEME ESP_ADC_CAL_VAL_EFUSE_TP
#define ADC_RESOLUTION_MIN SOC_ADC_DIGI_MAX_BITWIDTH
#define ADC_RESOLUTION_MAX SOC_ADC_MAX_BITWIDTH

#elif CONFIG_SOC_ESP32C3
#elif CONFIG_SOC_SERIES_ESP32C3
#define ADC_CALI_SCHEME ESP_ADC_CAL_VAL_EFUSE_TP
#define ADC_RESOLUTION_MIN SOC_ADC_DIGI_MAX_BITWIDTH
#define ADC_RESOLUTION_MAX SOC_ADC_DIGI_MAX_BITWIDTH
Expand Down Expand Up @@ -165,14 +165,14 @@ static int adc_esp32_read(const struct device *dev, const struct adc_sequence *s

data->resolution[channel_id] = seq->resolution;

#if CONFIG_SOC_ESP32C3
#if CONFIG_SOC_SERIES_ESP32C3
/* NOTE: nothing to set on ESP32C3 SoC */
if (conf->unit == ADC_UNIT_1) {
adc1_config_width(ADC_WIDTH_BIT_DEFAULT);
}
#else
adc_set_data_width(conf->unit, WIDTH_MASK(data->resolution[channel_id]));
#endif /* CONFIG_SOC_ESP32C3 */
#endif /* CONFIG_SOC_SERIES_ESP32C3 */

/* Read raw value */
if (conf->unit == ADC_UNIT_1) {
Expand All @@ -191,13 +191,13 @@ static int adc_esp32_read(const struct device *dev, const struct adc_sequence *s
/* Get corrected voltage output */
cal = cal_mv = esp_adc_cal_raw_to_voltage(reading, &data->chars[channel_id]);

#if CONFIG_SOC_ESP32
#if CONFIG_SOC_SERIES_ESP32
if (data->attenuation[channel_id] == ADC_ATTEN_DB_11) {
if (cal > ADC_CLIP_MVOLT_11DB) {
cal = ADC_CLIP_MVOLT_11DB;
}
}
#endif /* CONFIG_SOC_ESP32 */
#endif /* CONFIG_SOC_SERIES_ESP32 */

/* Fit according to selected attenuation */
atten_to_gain(data->attenuation[channel_id], &cal);
Expand Down
2 changes: 1 addition & 1 deletion drivers/bluetooth/hci/hci_esp32.c
Original file line number Diff line number Diff line change
Expand Up @@ -280,7 +280,7 @@ static int bt_esp32_ble_init(void)
int ret;
esp_bt_controller_config_t bt_cfg = BT_CONTROLLER_INIT_CONFIG_DEFAULT();

#if defined(CONFIG_BT_BREDR) && defined(CONFIG_SOC_ESP32)
#if defined(CONFIG_BT_BREDR) && defined(CONFIG_SOC_SERIES_ESP32)
esp_bt_mode_t mode = ESP_BT_MODE_BTDM;
#else
esp_bt_mode_t mode = ESP_BT_MODE_BLE;
Expand Down
30 changes: 15 additions & 15 deletions drivers/can/can_esp32_twai.c
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ LOG_MODULE_REGISTER(can_esp32_twai, CONFIG_CAN_LOG_LEVEL);
* The names with TWAI_ prefixes from Espressif reference manuals are used for these incompatible
* registers.
*/
#ifndef CONFIG_SOC_ESP32
#ifndef CONFIG_SOC_SERIES_ESP32

/* TWAI_BUS_TIMING_0_REG is incompatible with CAN_SJA1000_BTR0 */
#define TWAI_BUS_TIMING_0_REG (6U)
Expand Down Expand Up @@ -63,18 +63,18 @@ LOG_MODULE_REGISTER(can_esp32_twai, CONFIG_CAN_LOG_LEVEL);
#define TWAI_CD_MASK GENMASK(2, 0)
#define TWAI_CLOCK_OFF BIT(3)

#endif /* !CONFIG_SOC_ESP32 */
#endif /* !CONFIG_SOC_SERIES_ESP32 */

struct can_esp32_twai_config {
mm_reg_t base;
const struct pinctrl_dev_config *pcfg;
const struct device *clock_dev;
const clock_control_subsys_t clock_subsys;
int irq_source;
#ifndef CONFIG_SOC_ESP32
#ifndef CONFIG_SOC_SERIES_ESP32
/* 32-bit variant of output clock divider register required for non-ESP32 MCUs */
uint32_t cdr32;
#endif /* !CONFIG_SOC_ESP32 */
#endif /* !CONFIG_SOC_SERIES_ESP32 */
};

static uint8_t can_esp32_twai_read_reg(const struct device *dev, uint8_t reg)
Expand All @@ -95,7 +95,7 @@ static void can_esp32_twai_write_reg(const struct device *dev, uint8_t reg, uint
sys_write32(val & 0xFF, addr);
}

#ifndef CONFIG_SOC_ESP32
#ifndef CONFIG_SOC_SERIES_ESP32

/*
* Required for newer ESP32-series MCUs which violate the original SJA1000 8-bit register size.
Expand Down Expand Up @@ -157,7 +157,7 @@ static int can_esp32_twai_set_timing(const struct device *dev, const struct can_
return 0;
}

#endif /* !CONFIG_SOC_ESP32 */
#endif /* !CONFIG_SOC_SERIES_ESP32 */

static int can_esp32_twai_get_core_clock(const struct device *dev, uint32_t *rate)
{
Expand Down Expand Up @@ -205,7 +205,7 @@ static int can_esp32_twai_init(const struct device *dev)
return err;
}

#ifndef CONFIG_SOC_ESP32
#ifndef CONFIG_SOC_SERIES_ESP32
/*
* TWAI_CLOCK_DIVIDER_REG is incompatible with CAN_SJA1000_CDR for non-ESP32 MCUs
* - TWAI_CD has length of 8 bits instead of 3 bits
Expand All @@ -215,7 +215,7 @@ static int can_esp32_twai_init(const struct device *dev)
* Overwrite with 32-bit register variant configured via devicetree.
*/
can_esp32_twai_write_reg32(dev, TWAI_CLOCK_DIVIDER_REG, twai_config->cdr32);
#endif /* !CONFIG_SOC_ESP32 */
#endif /* !CONFIG_SOC_SERIES_ESP32 */

esp_intr_alloc(twai_config->irq_source, 0, can_esp32_twai_isr, (void *)dev, NULL);

Expand All @@ -227,11 +227,11 @@ const struct can_driver_api can_esp32_twai_driver_api = {
.start = can_sja1000_start,
.stop = can_sja1000_stop,
.set_mode = can_sja1000_set_mode,
#ifdef CONFIG_SOC_ESP32
#ifdef CONFIG_SOC_SERIES_ESP32
.set_timing = can_sja1000_set_timing,
#else
.set_timing = can_esp32_twai_set_timing,
#endif /* CONFIG_SOC_ESP32 */
#endif /* CONFIG_SOC_SERIES_ESP32 */
.send = can_sja1000_send,
.add_rx_filter = can_sja1000_add_rx_filter,
.remove_rx_filter = can_sja1000_remove_rx_filter,
Expand All @@ -244,7 +244,7 @@ const struct can_driver_api can_esp32_twai_driver_api = {
.recover = can_sja1000_recover,
#endif /* !CONFIG_CAN_AUTO_BUS_OFF_RECOVERY */
.timing_min = CAN_SJA1000_TIMING_MIN_INITIALIZER,
#ifdef CONFIG_SOC_ESP32
#ifdef CONFIG_SOC_SERIES_ESP32
.timing_max = CAN_SJA1000_TIMING_MAX_INITIALIZER,
#else
/* larger prescaler allowed for newer ESP32-series MCUs */
Expand All @@ -255,16 +255,16 @@ const struct can_driver_api can_esp32_twai_driver_api = {
.phase_seg2 = 0x8,
.prescaler = 0x2000,
}
#endif /* CONFIG_SOC_ESP32 */
#endif /* CONFIG_SOC_SERIES_ESP32 */
};

#ifdef CONFIG_SOC_ESP32
#ifdef CONFIG_SOC_SERIES_ESP32
#define TWAI_CLKOUT_DIVIDER_MAX (14)
#define TWAI_CDR32_INIT(inst)
#else
#define TWAI_CLKOUT_DIVIDER_MAX (490)
#define TWAI_CDR32_INIT(inst) .cdr32 = CAN_ESP32_TWAI_DT_CDR_INST_GET(inst)
#endif /* CONFIG_SOC_ESP32 */
#endif /* CONFIG_SOC_SERIES_ESP32 */

#define CAN_ESP32_TWAI_ASSERT_CLKOUT_DIVIDER(inst) \
BUILD_ASSERT(COND_CODE_0(DT_INST_NODE_HAS_PROP(inst, clkout_divider), (1), \
Expand Down Expand Up @@ -295,7 +295,7 @@ const struct can_driver_api can_esp32_twai_driver_api = {
CAN_SJA1000_DT_CONFIG_INST_GET(inst, &can_esp32_twai_config_##inst, \
can_esp32_twai_read_reg, can_esp32_twai_write_reg, \
CAN_SJA1000_OCR_OCMODE_BIPHASE, \
COND_CODE_0(IS_ENABLED(CONFIG_SOC_ESP32), (0), \
COND_CODE_0(IS_ENABLED(CONFIG_SOC_SERIES_ESP32), (0), \
(CAN_ESP32_TWAI_DT_CDR_INST_GET(inst)))); \
\
static struct can_sja1000_data can_sja1000_data_##inst = \
Expand Down
34 changes: 17 additions & 17 deletions drivers/clock_control/clock_control_esp32.c
Original file line number Diff line number Diff line change
Expand Up @@ -9,32 +9,32 @@

#define CPU_RESET_REASON RTC_SW_CPU_RESET

#if defined(CONFIG_SOC_ESP32) || defined(CONFIG_SOC_ESP32_NET)
#if defined(CONFIG_SOC_SERIES_ESP32) || defined(CONFIG_SOC_SERIES_ESP32_NET)
#define DT_CPU_COMPAT cdns_tensilica_xtensa_lx6
#undef CPU_RESET_REASON
#define CPU_RESET_REASON SW_CPU_RESET
#include <zephyr/dt-bindings/clock/esp32_clock.h>
#include "esp32/rom/rtc.h"
#include "soc/dport_reg.h"
#elif defined(CONFIG_SOC_ESP32S2)
#elif defined(CONFIG_SOC_SERIES_ESP32S2)
#define DT_CPU_COMPAT cdns_tensilica_xtensa_lx7
#include <zephyr/dt-bindings/clock/esp32s2_clock.h>
#include "esp32s2/rom/rtc.h"
#include "soc/dport_reg.h"
#elif defined(CONFIG_SOC_ESP32S3)
#elif defined(CONFIG_SOC_SERIES_ESP32S3)
#define DT_CPU_COMPAT cdns_tensilica_xtensa_lx7
#include <zephyr/dt-bindings/clock/esp32s3_clock.h>
#include "esp32s3/rom/rtc.h"
#include "soc/dport_reg.h"
#include "esp32s3/clk.h"
#elif CONFIG_IDF_TARGET_ESP32C3
#elif CONFIG_SOC_SERIES_ESP32C3
#define DT_CPU_COMPAT espressif_riscv
#include <zephyr/dt-bindings/clock/esp32c3_clock.h>
#include "esp32c3/rom/rtc.h"
#include <soc/soc_caps.h>
#include <soc/soc.h>
#include <soc/rtc.h>
#endif
#endif /* CONFIG_SOC_SERIES_ESP32xx */

#include "esp_rom_sys.h"
#include <soc/rtc.h>
Expand All @@ -55,14 +55,14 @@ struct esp32_clock_config {
};

static uint8_t const xtal_freq[] = {
#if defined(CONFIG_SOC_ESP32) || defined(CONFIG_SOC_ESP32_NET) || defined(CONFIG_SOC_ESP32S3)
#if defined(CONFIG_SOC_SERIES_ESP32) || defined(CONFIG_SOC_SERIES_ESP32_NET) || defined(CONFIG_SOC_SERIES_ESP32S3)
[ESP32_CLK_XTAL_24M] = 24,
[ESP32_CLK_XTAL_26M] = 26,
[ESP32_CLK_XTAL_40M] = 40,
[ESP32_CLK_XTAL_AUTO] = 0
#elif defined(CONFIG_SOC_ESP32S2)
#elif defined(CONFIG_SOC_SERIES_ESP32S2)
[ESP32_CLK_XTAL_40M] = 40,
#elif defined(CONFIG_SOC_ESP32C3)
#elif defined(CONFIG_SOC_SERIES_ESP32C3)
[ESP32_CLK_XTAL_32M] = 32,
[ESP32_CLK_XTAL_40M] = 40,
#endif
Expand Down Expand Up @@ -124,7 +124,7 @@ static int clock_control_esp32_get_rate(const struct device *dev,
return 0;
}

#if defined(CONFIG_SOC_ESP32) || defined(CONFIG_SOC_ESP32_NET)
#if defined(CONFIG_SOC_SERIES_ESP32) || defined(CONFIG_SOC_SERIES_ESP32_NET)
static void esp32_clock_perip_init(void)
{
uint32_t common_perip_clk;
Expand Down Expand Up @@ -217,9 +217,9 @@ static void esp32_clock_perip_init(void)
/* Enable RNG clock. */
periph_module_enable(PERIPH_RNG_MODULE);
}
#endif
#endif /* CONFIG_SOC_SERIES_ESP32 */

#if defined(CONFIG_SOC_ESP32S2)
#if defined(CONFIG_SOC_SERIES_ESP32S2)
static void esp32_clock_perip_init(void)
{
uint32_t common_perip_clk;
Expand Down Expand Up @@ -321,9 +321,9 @@ static void esp32_clock_perip_init(void)
/* Enable RNG clock. */
periph_module_enable(PERIPH_RNG_MODULE);
}
#endif
#endif /* CONFIG_SOC_SERIES_ESP32S2 */

#if defined(CONFIG_SOC_ESP32S3)
#if defined(CONFIG_SOC_SERIES_ESP32S3)
static void esp32_clock_perip_init(void)
{
uint32_t common_perip_clk, hwcrypto_perip_clk, wifi_bt_sdio_clk = 0;
Expand Down Expand Up @@ -421,9 +421,9 @@ static void esp32_clock_perip_init(void)
esp_rom_uart_tx_wait_idle(0);
esp_rom_uart_set_clock_baudrate(0, UART_CLK_FREQ_ROM, 115200);
}
#endif
#endif /* CONFIG_SOC_SERIES_ESP32S3 */

#if defined(CONFIG_SOC_ESP32C3)
#if defined(CONFIG_SOC_SERIES_ESP32C3)
static void esp32_clock_perip_init(void)
{
uint32_t common_perip_clk;
Expand Down Expand Up @@ -510,7 +510,7 @@ static void esp32_clock_perip_init(void)
/* Enable RNG clock. */
periph_module_enable(PERIPH_RNG_MODULE);
}
#endif
#endif /* CONFIG_SOC_SERIES_ESP32C3 */

static int clock_control_esp32_init(const struct device *dev)
{
Expand Down Expand Up @@ -596,7 +596,7 @@ DEVICE_DT_DEFINE(DT_NODELABEL(rtc),
CONFIG_CLOCK_CONTROL_INIT_PRIORITY,
&clock_control_esp32_api);

#ifndef CONFIG_SOC_ESP32C3
#ifndef CONFIG_SOC_SERIES_ESP32C3
BUILD_ASSERT((CONFIG_SYS_CLOCK_HW_CYCLES_PER_SEC) ==
DT_PROP(DT_INST(0, DT_CPU_COMPAT), clock_frequency),
"SYS_CLOCK_HW_CYCLES_PER_SEC Value must be equal to CPU_Freq");
Expand Down
6 changes: 3 additions & 3 deletions drivers/counter/counter_esp32_rtc.c
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include <zephyr/spinlock.h>
#include <zephyr/kernel.h>

#if defined(CONFIG_SOC_ESP32C3)
#if defined(CONFIG_SOC_SERIES_ESP32C3)
#include <zephyr/drivers/interrupt_controller/intc_esp32c3.h>
#else
#include <zephyr/drivers/interrupt_controller/intc_esp32.h>
Expand All @@ -27,7 +27,7 @@
#include <zephyr/logging/log.h>
LOG_MODULE_REGISTER(esp32_counter_rtc, CONFIG_COUNTER_LOG_LEVEL);

#if defined(CONFIG_SOC_ESP32C3)
#if defined(CONFIG_SOC_SERIES_ESP32C3)
#define ESP32_COUNTER_RTC_ISR_HANDLER isr_handler_t
#else
#define ESP32_COUNTER_RTC_ISR_HANDLER intr_handler_t
Expand Down Expand Up @@ -88,7 +88,7 @@ static int counter_esp32_get_value(const struct device *dev, uint32_t *ticks)
ARG_UNUSED(dev);

SET_PERI_REG_MASK(RTC_CNTL_TIME_UPDATE_REG, RTC_CNTL_TIME_UPDATE);
#if defined(CONFIG_SOC_ESP32)
#if defined(CONFIG_SOC_SERIES_ESP32)
while (GET_PERI_REG_MASK(RTC_CNTL_TIME_UPDATE_REG, RTC_CNTL_TIME_VALID) == 0) {
/* might take 1 RTC slowclk period, don't flood RTC bus */
k_sleep(K_USEC(1));
Expand Down
8 changes: 4 additions & 4 deletions drivers/flash/flash_esp32.c
Original file line number Diff line number Diff line change
Expand Up @@ -30,20 +30,20 @@
#include <zephyr/drivers/flash.h>
#include <soc.h>

#if defined(CONFIG_SOC_ESP32)
#if defined(CONFIG_SOC_SERIES_ESP32)
#include "soc/dport_reg.h"
#include "esp32/rom/cache.h"
#include "esp32/rom/spi_flash.h"
#include "esp32/spiram.h"
#elif defined(CONFIG_SOC_ESP32S2)
#elif defined(CONFIG_SOC_SERIES_ESP32S2)
#include "soc/spi_mem_reg.h"
#include "esp32s2/rom/cache.h"
#include "esp32s2/rom/spi_flash.h"
#elif defined(CONFIG_SOC_ESP32S3)
#elif defined(CONFIG_SOC_SERIES_ESP32S3)
#include "soc/spi_mem_reg.h"
#include "esp32s3/rom/cache.h"
#include "esp32s3/rom/spi_flash.h"
#elif defined(CONFIG_SOC_ESP32C3)
#elif defined(CONFIG_SOC_SERIES_ESP32C3)
#include "soc/spi_periph.h"
#include "soc/spi_mem_reg.h"
#include "soc/dport_access.h"
Expand Down
2 changes: 1 addition & 1 deletion drivers/hwinfo/hwinfo_esp32.c
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@

ssize_t z_impl_hwinfo_get_device_id(uint8_t *buffer, size_t length)
{
#if !defined(CONFIG_SOC_ESP32) && !defined(CONFIG_SOC_ESP32_NET)
#if !defined(CONFIG_SOC_SERIES_ESP32) && !defined(CONFIG_SOC_SERIES_ESP32_NET)
uint32_t rdata1 = sys_read32(EFUSE_RD_MAC_SPI_SYS_0_REG);
uint32_t rdata2 = sys_read32(EFUSE_RD_MAC_SPI_SYS_1_REG);
#else
Expand Down
2 changes: 1 addition & 1 deletion drivers/i2c/i2c_esp32.c
Original file line number Diff line number Diff line change
Expand Up @@ -255,7 +255,7 @@ static void IRAM_ATTR i2c_esp32_configure_timeout(const struct device *dev)
* at least for ESP32-C3 (tested with communication to bq76952 chip). So we set the
* timeout to maximum supported value instead.
*/
#if defined(CONFIG_SOC_ESP32C3) || defined(CONFIG_SOC_ESP32)
#if defined(CONFIG_SOC_SERIES_ESP32C3) || defined(CONFIG_SOC_SERIES_ESP32)
i2c_hal_set_tout(&data->hal, I2C_LL_MAX_TIMEOUT);
#else
i2c_hal_set_tout_en(&data->hal, 0);
Expand Down
2 changes: 1 addition & 1 deletion drivers/interrupt_controller/Kconfig.esp32
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

config INTC_ESP32
bool "Interrupt allocator for Xtensa-based Espressif SoCs"
default y if SOC_ESP32 || SOC_ESP32S2 || SOC_ESP32_NET || SOC_ESP32S3
default y if SOC_FAMILY_ESP32
help
Enable custom interrupt allocator for Espressif SoCs based on Xtensa
architecture.
Expand Down
2 changes: 1 addition & 1 deletion drivers/sensor/esp32_temp/esp32_temp.c
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
#include <zephyr/logging/log.h>
LOG_MODULE_REGISTER(esp32_temp, CONFIG_SENSOR_LOG_LEVEL);

#if CONFIG_SOC_ESP32
#if CONFIG_SOC_SERIES_ESP32
#error "Temperature sensor not supported on ESP32"
#endif /* CONFIG_IDF_TARGET_ESP32 */

Expand Down
Loading

0 comments on commit 3c5a22f

Please sign in to comment.