espressif: clean up unused code
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 <sylvio.alves@espressif.com>
This commit is contained in:
parent
d207edb1cf
commit
8233b70ece
|
@ -145,8 +145,6 @@ static void adc_hw_calibration(adc_unit_t unit)
|
|||
|
||||
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!");
|
||||
|
@ -570,7 +568,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);
|
||||
|
@ -638,7 +635,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;
|
||||
|
|
|
@ -616,7 +616,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;
|
||||
|
@ -687,14 +686,13 @@ static int esp32_cpu_clock_configure(const struct esp32_cpu_clock_config *cpu_cf
|
|||
esp_cpu_set_cycle_count((uint64_t)esp_cpu_get_cycle_count() * rtc_clk_cfg.cpu_freq_mhz /
|
||||
old_config.freq_mhz);
|
||||
|
||||
#if !defined(ESP_CONSOLE_UART_NONE)
|
||||
#if !defined(CONFIG_SOC_SERIES_ESP32C2) && !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)
|
||||
esp_rom_uart_set_clock_baudrate(ESP_CONSOLE_UART_NUM, uart_clock_src_hz,
|
||||
ESP_CONSOLE_UART_BAUDRATE);
|
||||
#endif
|
||||
|
@ -705,8 +703,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;
|
||||
|
||||
|
|
|
@ -192,7 +192,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;
|
||||
|
||||
|
@ -277,9 +276,7 @@ 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;
|
||||
|
||||
|
@ -315,7 +312,6 @@ static int dma_esp32_config(const struct device *dev, uint32_t 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_esp32_channel *dma_channel = &config->dma_channel[channel];
|
||||
int ret = 0;
|
||||
|
||||
|
|
|
@ -146,10 +146,11 @@ flash_esp32_get_parameters(const struct device *dev)
|
|||
|
||||
static int flash_esp32_init(const struct device *dev)
|
||||
{
|
||||
struct flash_esp32_dev_data *const dev_data = dev->data;
|
||||
uint32_t ret = 0;
|
||||
|
||||
#ifdef CONFIG_MULTITHREADING
|
||||
struct flash_esp32_dev_data *const dev_data = dev->data;
|
||||
|
||||
k_sem_init(&dev_data->sem, 1, 1);
|
||||
#endif /* CONFIG_MULTITHREADING */
|
||||
ret = esp_flash_init_default_chip();
|
||||
|
|
|
@ -108,7 +108,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;
|
||||
|
@ -474,7 +473,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) {
|
||||
|
|
|
@ -149,7 +149,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) {
|
||||
|
@ -313,7 +312,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;
|
||||
|
||||
|
@ -508,7 +506,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);
|
||||
|
@ -584,7 +581,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) {
|
||||
|
|
|
@ -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) {
|
||||
|
@ -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) {
|
||||
|
@ -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);
|
||||
|
||||
|
@ -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");
|
||||
|
|
|
@ -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");
|
||||
|
@ -452,7 +451,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);
|
||||
|
||||
|
|
|
@ -64,7 +64,7 @@ static const struct linear_range dcdc1_ranges[] = {
|
|||
LINEAR_RANGE_INIT(700000U, 25000U, 0x00U, 0x7FU),
|
||||
};
|
||||
|
||||
static const struct regulator_axp192_desc dcdc1_desc = {
|
||||
__maybe_unused static const struct regulator_axp192_desc dcdc1_desc = {
|
||||
.enable_reg = AXP192_REG_DCDC123_LDO23_CONTROL,
|
||||
.enable_mask = 0x01U,
|
||||
.enable_val = 0x01U,
|
||||
|
@ -83,7 +83,7 @@ static const struct linear_range dcdc2_ranges[] = {
|
|||
LINEAR_RANGE_INIT(700000U, 25000U, 0x00U, 0x3FU),
|
||||
};
|
||||
|
||||
static const struct regulator_axp192_desc dcdc2_desc = {
|
||||
__maybe_unused static const struct regulator_axp192_desc dcdc2_desc = {
|
||||
.enable_reg = AXP192_REG_EXTEN_DCDC2_CONTROL,
|
||||
.enable_mask = 0x01U,
|
||||
.enable_val = 0x01U,
|
||||
|
@ -102,7 +102,7 @@ static const struct linear_range dcdc3_ranges[] = {
|
|||
LINEAR_RANGE_INIT(700000U, 25000U, 0x00U, 0x7FU),
|
||||
};
|
||||
|
||||
static const struct regulator_axp192_desc dcdc3_desc = {
|
||||
__maybe_unused static const struct regulator_axp192_desc dcdc3_desc = {
|
||||
.enable_reg = AXP192_REG_DCDC123_LDO23_CONTROL,
|
||||
.enable_mask = 0x02U,
|
||||
.enable_val = 0x02U,
|
||||
|
@ -121,7 +121,7 @@ static const struct linear_range ldoio0_ranges[] = {
|
|||
LINEAR_RANGE_INIT(1800000u, 100000u, 0x00u, 0x0Fu),
|
||||
};
|
||||
|
||||
static const struct regulator_axp192_desc ldoio0_desc = {
|
||||
__maybe_unused static const struct regulator_axp192_desc ldoio0_desc = {
|
||||
.enable_reg = AXP192_REG_GPIO0_CONTROL,
|
||||
.enable_mask = 0x07u,
|
||||
.enable_val = 0x03u,
|
||||
|
@ -139,7 +139,7 @@ static const struct linear_range ldo2_ranges[] = {
|
|||
LINEAR_RANGE_INIT(1800000U, 100000U, 0x00U, 0x0FU),
|
||||
};
|
||||
|
||||
static const struct regulator_axp192_desc ldo2_desc = {
|
||||
__maybe_unused static const struct regulator_axp192_desc ldo2_desc = {
|
||||
.enable_reg = AXP192_REG_DCDC123_LDO23_CONTROL,
|
||||
.enable_mask = 0x04U,
|
||||
.enable_val = 0x04U,
|
||||
|
@ -157,7 +157,7 @@ static const struct linear_range ldo3_ranges[] = {
|
|||
LINEAR_RANGE_INIT(1800000U, 100000U, 0x00U, 0x0FU),
|
||||
};
|
||||
|
||||
static const struct regulator_axp192_desc ldo3_desc = {
|
||||
__maybe_unused static const struct regulator_axp192_desc ldo3_desc = {
|
||||
.enable_reg = AXP192_REG_DCDC123_LDO23_CONTROL,
|
||||
.enable_mask = 0x08U,
|
||||
.enable_val = 0x08U,
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -123,7 +123,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);
|
||||
|
|
|
@ -61,8 +61,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;
|
||||
}
|
||||
|
@ -100,7 +98,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;
|
||||
|
|
|
@ -506,7 +506,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;
|
||||
|
@ -538,7 +537,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
|
||||
|
@ -605,7 +603,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();
|
||||
|
@ -670,9 +667,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;
|
||||
|
@ -846,7 +841,6 @@ unlock:
|
|||
|
||||
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;
|
||||
|
@ -927,7 +921,6 @@ unlock:
|
|||
|
||||
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);
|
||||
|
||||
|
@ -937,6 +930,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,
|
||||
ESP_PRIO_TO_FLAGS(config->irq_priority) |
|
||||
ESP_INT_FLAGS_CHECK(config->irq_flags),
|
||||
|
|
|
@ -305,7 +305,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)) {
|
||||
|
@ -332,6 +331,11 @@ 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);
|
||||
|
||||
if (ret) {
|
||||
LOG_ERR("Failed to configure SPI pins");
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* input parameters to calculate timing configuration */
|
||||
spi_hal_timing_param_t timing_param = {
|
||||
.half_duplex = hal_dev->half_duplex,
|
||||
|
@ -376,6 +380,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;
|
||||
|
|
|
@ -216,7 +216,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) {
|
||||
|
|
|
@ -74,8 +74,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(iface, 0);
|
||||
|
@ -437,7 +435,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) {
|
||||
|
|
|
@ -47,14 +47,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
|
||||
|
@ -73,7 +76,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;
|
||||
|
@ -171,6 +173,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);
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -43,8 +43,6 @@ extern void z_prep_c(void);
|
|||
void __app_cpu_start(void)
|
||||
{
|
||||
extern uint32_t _init_start;
|
||||
extern uint32_t _bss_start;
|
||||
extern uint32_t _bss_end;
|
||||
|
||||
/* Move the exception vector table to IRAM. */
|
||||
__asm__ __volatile__ (
|
||||
|
|
|
@ -13,8 +13,6 @@
|
|||
#include <esp_cpu.h>
|
||||
#include <zephyr/drivers/interrupt_controller/intc_esp32.h>
|
||||
|
||||
static struct k_spinlock loglock;
|
||||
|
||||
void smp_log(const char *msg)
|
||||
{
|
||||
while (*msg) {
|
||||
|
|
|
@ -47,8 +47,6 @@ static void core_intr_matrix_clear(void)
|
|||
void IRAM_ATTR __app_cpu_start(void)
|
||||
{
|
||||
extern uint32_t _init_start;
|
||||
extern uint32_t _bss_start;
|
||||
extern uint32_t _bss_end;
|
||||
|
||||
/* Move the exception vector table to IRAM. */
|
||||
__asm__ __volatile__("wsr %0, vecbase" : : "r"(&_init_start));
|
||||
|
|
Loading…
Reference in New Issue