Skip to content

Commit

Permalink
espressif: clean up unused code
Browse files Browse the repository at this point in the history
Remove all entries that as not being used.
This also update hal to re-enable warning flags
as such as -Wno-unused-variable.

Signed-off-by: Sylvio Alves <[email protected]>
  • Loading branch information
sylvioalves committed Jul 1, 2024
1 parent 2c34da9 commit c3615b3
Show file tree
Hide file tree
Showing 18 changed files with 20 additions and 56 deletions.
6 changes: 2 additions & 4 deletions drivers/adc/adc_esp32.c
Original file line number Diff line number Diff line change
Expand Up @@ -130,8 +130,6 @@ static void atten_to_gain(adc_atten_t atten, uint32_t *val_mv)

static bool adc_calibration_init(const struct device *dev)
{
struct adc_esp32_data *data = dev->data;

switch (esp_adc_cal_check_efuse(ADC_CALI_SCHEME)) {
case ESP_ERR_NOT_SUPPORTED:
LOG_WRN("Skip software calibration - Not supported!");
Expand Down Expand Up @@ -555,7 +553,6 @@ static int adc_esp32_channel_setup(const struct device *dev, const struct adc_ch
{
const struct adc_esp32_conf *conf = (const struct adc_esp32_conf *)dev->config;
struct adc_esp32_data *data = (struct adc_esp32_data *) dev->data;
int err;

if (cfg->channel_id >= conf->channel_count) {
LOG_ERR("Unsupported channel id '%d'", cfg->channel_id);
Expand Down Expand Up @@ -623,7 +620,8 @@ static int adc_esp32_channel_setup(const struct device *dev, const struct adc_ch
.pin = io_num,
};

err = gpio_pin_configure_dt(&gpio, GPIO_DISCONNECTED);
int err = gpio_pin_configure_dt(&gpio, GPIO_DISCONNECTED);

if (err) {
LOG_ERR("Error disconnecting io (%d)", io_num);
return err;
Expand Down
6 changes: 1 addition & 5 deletions drivers/clock_control/clock_control_esp32.c
Original file line number Diff line number Diff line change
Expand Up @@ -513,7 +513,6 @@ static int esp32_cpu_clock_configure(const struct esp32_cpu_clock_config *cpu_cf
rtc_cpu_freq_config_t old_config;
rtc_cpu_freq_config_t new_config;
rtc_clk_config_t rtc_clk_cfg = RTC_CLK_CONFIG_DEFAULT();
uint32_t uart_clock_src_hz;
bool ret;

rtc_clk_cfg.xtal_freq = cpu_cfg->xtal_freq;
Expand Down Expand Up @@ -585,10 +584,9 @@ static int esp32_cpu_clock_configure(const struct esp32_cpu_clock_config *cpu_cf
old_config.freq_mhz);

#if !defined(CONFIG_SOC_SERIES_ESP32C6)
uint32_t uart_clock_src_hz = esp_clk_apb_freq();
#if ESP_ROM_UART_CLK_IS_XTAL
uart_clock_src_hz = (uint32_t)rtc_clk_xtal_freq_get() * MHZ(1);
#else
uart_clock_src_hz = esp_clk_apb_freq();
#endif

#if !defined(ESP_CONSOLE_UART_NONE)
Expand All @@ -602,8 +600,6 @@ static int esp32_cpu_clock_configure(const struct esp32_cpu_clock_config *cpu_cf
static int clock_control_esp32_configure(const struct device *dev, clock_control_subsys_t sys,
void *data)
{

const struct esp32_clock_config *cfg = dev->config;
struct esp32_clock_config *new_cfg = data;
int ret = 0;

Expand Down
10 changes: 0 additions & 10 deletions drivers/dma/dma_esp32_gdma.c
Original file line number Diff line number Diff line change
Expand Up @@ -142,16 +142,12 @@ static int dma_esp32_disable_interrupt(const struct device *dev,
static int dma_esp32_enable_interrupt(const struct device *dev,
struct dma_esp32_channel *dma_channel)
{
struct dma_esp32_config *config = (struct dma_esp32_config *)dev->config;

return esp_intr_enable(dma_channel->intr_handle);
}

static int dma_esp32_disable_interrupt(const struct device *dev,
struct dma_esp32_channel *dma_channel)
{
struct dma_esp32_config *config = (struct dma_esp32_config *)dev->config;

return esp_intr_disable(dma_channel->intr_handle);
}

Expand All @@ -177,7 +173,6 @@ static int dma_esp32_config_rx(const struct device *dev, struct dma_esp32_channe
{
struct dma_esp32_config *config = (struct dma_esp32_config *)dev->config;
struct dma_esp32_data *data = (struct dma_esp32_data *const)(dev)->data;
struct dma_block_config *block = config_dma->head_block;

dma_channel->dir = DMA_RX;

Expand Down Expand Up @@ -232,10 +227,6 @@ static int dma_esp32_config_tx_descriptor(struct dma_esp32_channel *dma_channel,
static int dma_esp32_config_tx(const struct device *dev, struct dma_esp32_channel *dma_channel,
struct dma_config *config_dma)
{
struct dma_esp32_config *config = (struct dma_esp32_config *)dev->config;
struct dma_esp32_data *data = (struct dma_esp32_data *const)(dev)->data;
struct dma_block_config *block = config_dma->head_block;

dma_channel->dir = DMA_TX;

gdma_ll_tx_reset_channel(data->hal.dev, dma_channel->channel_id);
Expand Down Expand Up @@ -493,7 +484,6 @@ static int dma_esp32_configure_irq(const struct device *dev)
static int dma_esp32_configure_irq(const struct device *dev)
{
struct dma_esp32_config *config = (struct dma_esp32_config *)dev->config;
struct dma_esp32_data *data = (struct dma_esp32_data *)dev->data;
struct dma_esp32_channel *dma_channel;

for (uint8_t i = 0; i < config->irq_size; i++) {
Expand Down
2 changes: 0 additions & 2 deletions drivers/gpio/gpio_esp32.c
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,6 @@ static int gpio_esp32_config(const struct device *dev,
gpio_flags_t flags)
{
const struct gpio_esp32_config *const cfg = dev->config;
struct gpio_esp32_data *data = dev->data;
uint32_t io_pin = (uint32_t) pin + ((cfg->gpio_port == 1 && pin < 32) ? 32 : 0);
uint32_t key;
int ret = 0;
Expand Down Expand Up @@ -464,7 +463,6 @@ static void gpio_esp32_isr(void *param);

static int gpio_esp32_init(const struct device *dev)
{
struct gpio_esp32_data *data = dev->data;
static bool isr_connected;

if (!isr_connected) {
Expand Down
4 changes: 0 additions & 4 deletions drivers/i2c/i2c_esp32.c
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,6 @@ static i2c_clock_source_t i2c_get_clk_src(uint32_t clk_freq)
static int i2c_esp32_config_pin(const struct device *dev)
{
const struct i2c_esp32_config *config = dev->config;
struct i2c_esp32_data *data = (struct i2c_esp32_data *const)(dev)->data;
int ret = 0;

if (config->index >= SOC_I2C_NUM) {
Expand Down Expand Up @@ -311,7 +310,6 @@ static void i2c_esp32_configure_data_mode(const struct device *dev)

static int i2c_esp32_configure(const struct device *dev, uint32_t dev_config)
{
const struct i2c_esp32_config *config = dev->config;
struct i2c_esp32_data *data = (struct i2c_esp32_data *const)(dev)->data;
uint32_t bitrate;

Expand Down Expand Up @@ -506,7 +504,6 @@ static int IRAM_ATTR i2c_esp32_read_msg(const struct device *dev,
struct i2c_msg *msg, uint16_t addr)
{
int ret = 0;
struct i2c_esp32_data *data = (struct i2c_esp32_data *const)(dev)->data;

/* Set the R/W bit to R */
addr |= BIT(0);
Expand Down Expand Up @@ -582,7 +579,6 @@ static int IRAM_ATTR i2c_esp32_master_write(const struct device *dev, struct i2c
static int IRAM_ATTR i2c_esp32_write_msg(const struct device *dev,
struct i2c_msg *msg, uint16_t addr)
{
struct i2c_esp32_data *data = (struct i2c_esp32_data *const)(dev)->data;
int ret = 0;

if (msg->flags & I2C_MSG_RESTART) {
Expand Down
5 changes: 0 additions & 5 deletions drivers/pwm/pwm_led_esp32.c
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,6 @@ static struct pwm_ledc_esp32_channel_config *get_channel_config(const struct dev

static void pwm_led_esp32_low_speed_update(const struct device *dev, int speed_mode, int channel)
{
uint32_t reg_addr;
struct pwm_ledc_esp32_data *data = (struct pwm_ledc_esp32_data *const)(dev)->data;

if (speed_mode == LEDC_LOW_SPEED_MODE) {
Expand Down Expand Up @@ -250,7 +249,6 @@ static int pwm_led_esp32_timer_set(const struct device *dev,
static int pwm_led_esp32_get_cycles_per_sec(const struct device *dev,
uint32_t channel_idx, uint64_t *cycles)
{
struct pwm_ledc_esp32_config *config = (struct pwm_ledc_esp32_config *) dev->config;
struct pwm_ledc_esp32_channel_config *channel = get_channel_config(dev, channel_idx);

if (!channel) {
Expand All @@ -273,7 +271,6 @@ static int pwm_led_esp32_set_cycles(const struct device *dev, uint32_t channel_i
{
int ret;
uint64_t clk_freq;
struct pwm_ledc_esp32_config *config = (struct pwm_ledc_esp32_config *) dev->config;
struct pwm_ledc_esp32_data *data = (struct pwm_ledc_esp32_data *const)(dev)->data;
struct pwm_ledc_esp32_channel_config *channel = get_channel_config(dev, channel_idx);

Expand Down Expand Up @@ -333,9 +330,7 @@ static int pwm_led_esp32_set_cycles(const struct device *dev, uint32_t channel_i

int pwm_led_esp32_init(const struct device *dev)
{
int ret;
const struct pwm_ledc_esp32_config *config = dev->config;
struct pwm_ledc_esp32_data *data = (struct pwm_ledc_esp32_data *const)(dev)->data;

if (!device_is_ready(config->clock_dev)) {
LOG_ERR("clock control device not ready");
Expand Down
2 changes: 0 additions & 2 deletions drivers/pwm/pwm_mc_esp32.c
Original file line number Diff line number Diff line change
Expand Up @@ -413,7 +413,6 @@ int mcpwm_esp32_init(const struct device *dev)
int ret;
struct mcpwm_esp32_config *config = (struct mcpwm_esp32_config *)dev->config;
struct mcpwm_esp32_data *data = (struct mcpwm_esp32_data *const)(dev)->data;
struct mcpwm_esp32_channel_config *channel;

if (!device_is_ready(config->clock_dev)) {
LOG_ERR("clock control device not ready");
Expand Down Expand Up @@ -448,7 +447,6 @@ static void IRAM_ATTR mcpwm_esp32_isr(const struct device *dev)
struct mcpwm_esp32_channel_config *channel;
struct mcpwm_esp32_capture_config *capture;
uint32_t mcpwm_intr_status;
struct capture_data cap_data;

mcpwm_intr_status = mcpwm_ll_intr_get_capture_status(data->hal.dev);

Expand Down
1 change: 0 additions & 1 deletion drivers/sensor/espressif/esp32_temp/esp32_temp.c
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,6 @@ static int esp32_temp_channel_get(const struct device *dev, enum sensor_channel
struct sensor_value *val)
{
struct esp32_temp_data *data = dev->data;
const struct esp32_temp_config *cfg = dev->config;

if (chan != SENSOR_CHAN_DIE_TEMP) {
return -ENOTSUP;
Expand Down
1 change: 0 additions & 1 deletion drivers/sensor/espressif/pcnt_esp32/pcnt_esp32.c
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,6 @@ static int pcnt_esp32_channel_get(const struct device *dev, enum sensor_channel

static int pcnt_esp32_configure_pinctrl(const struct device *dev)
{
int ret;
struct pcnt_esp32_config *config = (struct pcnt_esp32_config *)dev->config;

return pinctrl_apply_state(config->pincfg, PINCTRL_STATE_DEFAULT);
Expand Down
5 changes: 2 additions & 3 deletions drivers/serial/serial_esp32_usb.c
Original file line number Diff line number Diff line change
Expand Up @@ -60,8 +60,6 @@ static void serial_esp32_usb_isr(void *arg);

static int serial_esp32_usb_poll_in(const struct device *dev, unsigned char *p_char)
{
struct serial_esp32_usb_data *data = dev->data;

if (!usb_serial_jtag_ll_rxfifo_data_available()) {
return -1;
}
Expand Down Expand Up @@ -99,7 +97,6 @@ static int serial_esp32_usb_err_check(const struct device *dev)
static int serial_esp32_usb_init(const struct device *dev)
{
const struct serial_esp32_usb_config *config = dev->config;
struct serial_esp32_usb_data *data = dev->data;

if (!device_is_ready(config->clock_dev)) {
return -ENODEV;
Expand All @@ -108,6 +105,8 @@ static int serial_esp32_usb_init(const struct device *dev)
int ret = clock_control_on(config->clock_dev, config->clock_subsys);

#ifdef CONFIG_UART_INTERRUPT_DRIVEN
struct serial_esp32_usb_data *data = dev->data;

data->irq_line = esp_intr_alloc(config->irq_source, 0, (ISR_HANDLER)serial_esp32_usb_isr,
(void *)dev, NULL);
#endif
Expand Down
9 changes: 2 additions & 7 deletions drivers/serial/uart_esp32.c
Original file line number Diff line number Diff line change
Expand Up @@ -497,7 +497,6 @@ static void uart_esp32_isr(void *arg)
const struct device *dev = (const struct device *)arg;
struct uart_esp32_data *data = dev->data;
uint32_t uart_intr_status = uart_hal_get_intsts_mask(&data->hal);
const struct uart_esp32_config *config = dev->config;

if (uart_intr_status == 0) {
return;
Expand Down Expand Up @@ -529,7 +528,6 @@ static void IRAM_ATTR uart_esp32_dma_rx_done(const struct device *dma_dev, void
const struct uart_esp32_config *config = uart_dev->config;
struct uart_esp32_data *data = uart_dev->data;
struct uart_event evt = {0};
struct dma_status dma_status = {0};
unsigned int key = irq_lock();

/* If the receive buffer is not complete we reload the DMA at current buffer position and
Expand Down Expand Up @@ -596,7 +594,6 @@ static void IRAM_ATTR uart_esp32_dma_tx_done(const struct device *dma_dev, void
uint32_t channel, int status)
{
const struct device *uart_dev = user_data;
const struct uart_esp32_config *config = uart_dev->config;
struct uart_esp32_data *data = uart_dev->data;
struct uart_event evt = {0};
unsigned int key = irq_lock();
Expand Down Expand Up @@ -661,9 +658,7 @@ static void uart_esp32_async_rx_timeout(struct k_work *work)
struct uart_esp32_async_data *async =
CONTAINER_OF(dwork, struct uart_esp32_async_data, rx_timeout_work);
struct uart_esp32_data *data = CONTAINER_OF(async, struct uart_esp32_data, async);
const struct uart_esp32_config *config = data->uart_dev->config;
struct uart_event evt = {0};
int err = 0;
unsigned int key = irq_lock();

evt.type = UART_RX_RDY;
Expand Down Expand Up @@ -837,7 +832,6 @@ static int uart_esp32_async_rx_enable(const struct device *dev, uint8_t *buf, si

static int uart_esp32_async_rx_buf_rsp(const struct device *dev, uint8_t *buf, size_t len)
{
const struct uart_esp32_config *config = dev->config;
struct uart_esp32_data *data = dev->data;

data->async.rx_next_buf = buf;
Expand Down Expand Up @@ -918,7 +912,6 @@ static int uart_esp32_async_rx_disable(const struct device *dev)

static int uart_esp32_init(const struct device *dev)
{
const struct uart_esp32_config *config = dev->config;
struct uart_esp32_data *data = dev->data;
int ret = uart_esp32_configure(dev, &data->uart_config);

Expand All @@ -928,6 +921,8 @@ static int uart_esp32_init(const struct device *dev)
}

#if CONFIG_UART_INTERRUPT_DRIVEN || CONFIG_UART_ASYNC_API
const struct uart_esp32_config *config = dev->config;

ret = esp_intr_alloc(config->irq_source,
config->irq_priority,
(ISR_HANDLER)uart_esp32_isr,
Expand Down
7 changes: 6 additions & 1 deletion drivers/spi/spi_esp32_spim.c
Original file line number Diff line number Diff line change
Expand Up @@ -296,7 +296,6 @@ static int IRAM_ATTR spi_esp32_configure(const struct device *dev,
struct spi_context *ctx = &data->ctx;
spi_hal_context_t *hal = &data->hal;
spi_hal_dev_config_t *hal_dev = &data->dev_config;
spi_dev_t *hw = hal->hw;
int freq;

if (spi_context_configured(ctx, spi_cfg)) {
Expand All @@ -322,6 +321,10 @@ static int IRAM_ATTR spi_esp32_configure(const struct device *dev,

hal_dev->cs_pin_id = ctx->config->slave;
int ret = pinctrl_apply_state(cfg->pcfg, PINCTRL_STATE_DEFAULT);

Check failure on line 324 in drivers/spi/spi_esp32_spim.c

View workflow job for this annotation

GitHub Actions / Run compliance checks on patch series (PR)

TRAILING_WHITESPACE

drivers/spi/spi_esp32_spim.c:324 trailing whitespace
if (ret) {
return ret;
}

/* input parameters to calculate timing configuration */
spi_hal_timing_param_t timing_param = {
Expand Down Expand Up @@ -367,6 +370,8 @@ static int IRAM_ATTR spi_esp32_configure(const struct device *dev,

/* Workaround to handle default state of MISO and MOSI lines */
#ifndef CONFIG_SOC_SERIES_ESP32
spi_dev_t *hw = hal->hw;

if (cfg->line_idle_low) {
hw->ctrl.d_pol = 0;
hw->ctrl.q_pol = 0;
Expand Down
1 change: 0 additions & 1 deletion drivers/watchdog/wdt_esp32.c
Original file line number Diff line number Diff line change
Expand Up @@ -206,7 +206,6 @@ static const struct wdt_driver_api wdt_api = {
static void wdt_esp32_isr(void *arg)
{
const struct device *dev = (const struct device *)arg;
const struct wdt_esp32_config *config = dev->config;
struct wdt_esp32_data *data = dev->data;

if (data->callback) {
Expand Down
3 changes: 0 additions & 3 deletions drivers/wifi/esp32/src/esp_wifi_drv.c
Original file line number Diff line number Diff line change
Expand Up @@ -67,8 +67,6 @@ static struct net_mgmt_event_callback esp32_dhcp_cb;
static void wifi_event_handler(struct net_mgmt_event_callback *cb, uint32_t mgmt_event,
struct net_if *iface)
{
const struct wifi_status *status = (const struct wifi_status *)cb->info;

switch (mgmt_event) {
case NET_EVENT_IPV4_DHCP_BOUND:
wifi_mgmt_raise_connect_result_event(esp32_wifi_iface, 0);
Expand Down Expand Up @@ -346,7 +344,6 @@ void esp_wifi_event_handler(const char *event_base, int32_t event_id, void *even

static int esp32_wifi_disconnect(const struct device *dev)
{
struct esp32_wifi_runtime *data = dev->data;
int ret = esp_wifi_disconnect();

if (ret != ESP_OK) {
Expand Down
8 changes: 6 additions & 2 deletions soc/espressif/common/loader.c
Original file line number Diff line number Diff line change
Expand Up @@ -50,14 +50,17 @@ extern esp_image_header_t bootloader_image_hdr;
extern uint32_t _image_irom_start, _image_irom_size, _image_irom_vaddr;
extern uint32_t _image_drom_start, _image_drom_size, _image_drom_vaddr;

#ifndef CONFIG_MCUBOOT
static uint32_t _app_irom_start = (FIXED_PARTITION_OFFSET(slot0_partition) +
(uint32_t)&_image_irom_start);
static uint32_t _app_irom_size = (uint32_t)&_image_irom_size;
static uint32_t _app_irom_vaddr = ((uint32_t)&_image_irom_vaddr);

static uint32_t _app_drom_start = (FIXED_PARTITION_OFFSET(slot0_partition) +
(uint32_t)&_image_drom_start);
static uint32_t _app_drom_size = (uint32_t)&_image_drom_size;
#endif

static uint32_t _app_irom_vaddr = ((uint32_t)&_image_irom_vaddr);
static uint32_t _app_drom_vaddr = ((uint32_t)&_image_drom_vaddr);

#ifndef CONFIG_BOOTLOADER_MCUBOOT
Expand All @@ -76,7 +79,6 @@ void map_rom_segments(uint32_t app_drom_start, uint32_t app_drom_vaddr,

uint32_t app_drom_start_aligned = app_drom_start & MMU_FLASH_MASK;
uint32_t app_drom_vaddr_aligned = app_drom_vaddr & MMU_FLASH_MASK;
uint32_t actual_mapped_len = 0;

#ifndef CONFIG_BOOTLOADER_MCUBOOT
esp_image_segment_header_t WORD_ALIGNED_ATTR segment_hdr;
Expand Down Expand Up @@ -174,6 +176,8 @@ void map_rom_segments(uint32_t app_drom_start, uint32_t app_drom_vaddr,
abort();
}
#else
uint32_t actual_mapped_len = 0;

mmu_hal_map_region(0, MMU_TARGET_FLASH0,
app_drom_vaddr_aligned, app_drom_start_aligned,
app_drom_size, &actual_mapped_len);
Expand Down
2 changes: 0 additions & 2 deletions soc/espressif/esp32/esp32-mp.c
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,6 @@ volatile struct cpustart_rec *start_rec;
static void *appcpu_top;
static bool cpus_active[CONFIG_MP_MAX_NUM_CPUS];
#endif
static struct k_spinlock loglock;


/* Note that the logging done here is ACTUALLY REQUIRED FOR RELIABLE
* OPERATION! At least one particular board will experience spurious
Expand Down
Loading

0 comments on commit c3615b3

Please sign in to comment.