Merge branch 'master' of ssh://gitlab.espressif.cn:27227/idf/esp-idf

This commit is contained in:
Yulong 2017-04-25 07:58:24 -04:00
commit 09f69fe9ea
167 changed files with 11024 additions and 731 deletions

View file

@ -65,7 +65,7 @@ build_template_app:
IDF_PATH: "$CI_PROJECT_DIR"
GIT_STRATEGY: clone
BATCH_BUILD: "1"
V: "0"
build_ssc:
<<: *build_template
@ -79,7 +79,6 @@ build_ssc:
- cd SSC
- git checkout ${CI_BUILD_REF_NAME} || echo "Using SSC default branch..."
- make defconfig
- chmod +x gen_misc_ng.sh
- ./gen_misc_ng.sh
build_at:
@ -151,6 +150,18 @@ test_nvs_on_host:
- cd components/nvs_flash/test_nvs_host
- make test
test_wl_on_host:
stage: test
image: $CI_DOCKER_REGISTRY/esp32-ci-env
tags:
- wl_host_test
artifacts:
paths:
- components/wear_levelling/test_wl_host/coverage_report.zip
script:
- cd components/wear_levelling/test_wl_host
- make test
test_build_system:
stage: test
image: $CI_DOCKER_REGISTRY/esp32-ci-env

View file

@ -19,6 +19,7 @@
#include "esp_log.h"
#include "rom/cache.h"
#include "rom/efuse.h"
#include "rom/ets_sys.h"
#include "rom/spi_flash.h"
#include "rom/crc.h"
@ -73,6 +74,7 @@ static void set_cache_and_start_app(uint32_t drom_addr,
uint32_t entry_addr);
static void update_flash_config(const esp_image_header_t* pfhdr);
static void uart_console_configure(void);
static void wdt_reset_check(void);
void IRAM_ATTR call_start_cpu0()
{
@ -238,12 +240,14 @@ void bootloader_main()
/* Set CPU to 80MHz. Keep other clocks unmodified. */
uart_tx_wait_idle(0);
rtc_clk_config_t clk_cfg = RTC_CLK_CONFIG_DEFAULT();
clk_cfg.xtal_freq = CONFIG_ESP32_XTAL_FREQ;
clk_cfg.cpu_freq = RTC_CPU_FREQ_80M;
clk_cfg.slow_freq = rtc_clk_slow_freq_get();
clk_cfg.fast_freq = rtc_clk_fast_freq_get();
rtc_clk_init(clk_cfg);
uart_console_configure();
wdt_reset_check();
ESP_LOGI(TAG, "ESP-IDF %s 2nd stage bootloader", IDF_VER);
#if defined(CONFIG_SECURE_BOOT_ENABLED) || defined(CONFIG_FLASH_ENCRYPTION_ENABLED)
esp_err_t err;
@ -260,6 +264,15 @@ void bootloader_main()
/* disable watch dog here */
REG_CLR_BIT( RTC_CNTL_WDTCONFIG0_REG, RTC_CNTL_WDT_FLASHBOOT_MOD_EN );
REG_CLR_BIT( TIMG_WDTCONFIG0_REG(0), TIMG_WDT_FLASHBOOT_MOD_EN );
#ifndef CONFIG_SPI_FLASH_ROM_DRIVER_PATCH
const uint32_t spiconfig = ets_efuse_get_spiconfig();
if(spiconfig != EFUSE_SPICONFIG_SPI_DEFAULTS && spiconfig != EFUSE_SPICONFIG_HSPI_DEFAULTS) {
ESP_LOGE(TAG, "SPI flash pins are overridden. \"Enable SPI flash ROM driver patched functions\" must be enabled in menuconfig");
return;
}
#endif
esp_rom_spiflash_unlock();
ESP_LOGI(TAG, "Enabling RNG early entropy source...");
@ -728,3 +741,81 @@ static void uart_console_configure(void)
#endif // CONFIG_CONSOLE_UART_NONE
}
static void wdt_reset_info_enable(void)
{
REG_SET_BIT(DPORT_PRO_CPU_RECORD_CTRL_REG, DPORT_PRO_CPU_PDEBUG_ENABLE | DPORT_PRO_CPU_RECORD_ENABLE);
REG_CLR_BIT(DPORT_PRO_CPU_RECORD_CTRL_REG, DPORT_PRO_CPU_RECORD_ENABLE);
REG_SET_BIT(DPORT_APP_CPU_RECORD_CTRL_REG, DPORT_APP_CPU_PDEBUG_ENABLE | DPORT_APP_CPU_RECORD_ENABLE);
REG_CLR_BIT(DPORT_APP_CPU_RECORD_CTRL_REG, DPORT_APP_CPU_RECORD_ENABLE);
}
static void wdt_reset_info_dump(int cpu)
{
uint32_t inst = 0, pid = 0, stat = 0, data = 0, pc = 0,
lsstat = 0, lsaddr = 0, lsdata = 0, dstat = 0;
char *cpu_name = cpu ? "APP" : "PRO";
if (cpu == 0) {
stat = REG_READ(DPORT_PRO_CPU_RECORD_STATUS_REG);
pid = REG_READ(DPORT_PRO_CPU_RECORD_PID_REG);
inst = REG_READ(DPORT_PRO_CPU_RECORD_PDEBUGINST_REG);
dstat = REG_READ(DPORT_PRO_CPU_RECORD_PDEBUGSTATUS_REG);
data = REG_READ(DPORT_PRO_CPU_RECORD_PDEBUGDATA_REG);
pc = REG_READ(DPORT_PRO_CPU_RECORD_PDEBUGPC_REG);
lsstat = REG_READ(DPORT_PRO_CPU_RECORD_PDEBUGLS0STAT_REG);
lsaddr = REG_READ(DPORT_PRO_CPU_RECORD_PDEBUGLS0ADDR_REG);
lsdata = REG_READ(DPORT_PRO_CPU_RECORD_PDEBUGLS0DATA_REG);
} else {
stat = REG_READ(DPORT_APP_CPU_RECORD_STATUS_REG);
pid = REG_READ(DPORT_APP_CPU_RECORD_PID_REG);
inst = REG_READ(DPORT_APP_CPU_RECORD_PDEBUGINST_REG);
dstat = REG_READ(DPORT_APP_CPU_RECORD_PDEBUGSTATUS_REG);
data = REG_READ(DPORT_APP_CPU_RECORD_PDEBUGDATA_REG);
pc = REG_READ(DPORT_APP_CPU_RECORD_PDEBUGPC_REG);
lsstat = REG_READ(DPORT_APP_CPU_RECORD_PDEBUGLS0STAT_REG);
lsaddr = REG_READ(DPORT_APP_CPU_RECORD_PDEBUGLS0ADDR_REG);
lsdata = REG_READ(DPORT_APP_CPU_RECORD_PDEBUGLS0DATA_REG);
}
if (DPORT_RECORD_PDEBUGINST_SZ(inst) == 0 &&
DPORT_RECORD_PDEBUGSTATUS_BBCAUSE(dstat) == DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_WAITI) {
ESP_LOGW(TAG, "WDT reset info: %s CPU PC=0x%x (waiti mode)", cpu_name, pc);
} else {
ESP_LOGW(TAG, "WDT reset info: %s CPU PC=0x%x", cpu_name, pc);
}
ESP_LOGD(TAG, "WDT reset info: %s CPU STATUS 0x%08x", cpu_name, stat);
ESP_LOGD(TAG, "WDT reset info: %s CPU PID 0x%08x", cpu_name, pid);
ESP_LOGD(TAG, "WDT reset info: %s CPU PDEBUGINST 0x%08x", cpu_name, inst);
ESP_LOGD(TAG, "WDT reset info: %s CPU PDEBUGSTATUS 0x%08x", cpu_name, dstat);
ESP_LOGD(TAG, "WDT reset info: %s CPU PDEBUGDATA 0x%08x", cpu_name, data);
ESP_LOGD(TAG, "WDT reset info: %s CPU PDEBUGPC 0x%08x", cpu_name, pc);
ESP_LOGD(TAG, "WDT reset info: %s CPU PDEBUGLS0STAT 0x%08x", cpu_name, lsstat);
ESP_LOGD(TAG, "WDT reset info: %s CPU PDEBUGLS0ADDR 0x%08x", cpu_name, lsaddr);
ESP_LOGD(TAG, "WDT reset info: %s CPU PDEBUGLS0DATA 0x%08x", cpu_name, lsdata);
}
static void wdt_reset_check(void)
{
int wdt_rst = 0;
RESET_REASON rst_reas[2];
rst_reas[0] = rtc_get_reset_reason(0);
rst_reas[1] = rtc_get_reset_reason(1);
if (rst_reas[0] == RTCWDT_SYS_RESET || rst_reas[0] == TG0WDT_SYS_RESET || rst_reas[0] == TG1WDT_SYS_RESET ||
rst_reas[0] == TGWDT_CPU_RESET || rst_reas[0] == RTCWDT_CPU_RESET) {
ESP_LOGW(TAG, "PRO CPU has been reset by WDT.");
wdt_rst = 1;
}
if (rst_reas[1] == RTCWDT_SYS_RESET || rst_reas[1] == TG0WDT_SYS_RESET || rst_reas[1] == TG1WDT_SYS_RESET ||
rst_reas[1] == TGWDT_CPU_RESET || rst_reas[1] == RTCWDT_CPU_RESET) {
ESP_LOGW(TAG, "APP CPU has been reset by WDT.");
wdt_rst = 1;
}
if (wdt_rst) {
// if reset by WDT dump info from trace port
wdt_reset_info_dump(0);
wdt_reset_info_dump(1);
}
wdt_reset_info_enable();
}

View file

@ -16,7 +16,9 @@
#include "flash_qio_mode.h"
#include "esp_log.h"
#include "rom/spi_flash.h"
#include "rom/efuse.h"
#include "soc/spi_struct.h"
#include "soc/efuse_reg.h"
#include "sdkconfig.h"
/* SPI flash controller */
@ -33,6 +35,9 @@
#define CMD_RDSR 0x05
#define CMD_RDSR2 0x35 /* Not all SPI flash uses this command */
#define ESP32_D2WD_WP_GPIO 7 /* ESP32-D2WD has this GPIO wired to WP pin of flash */
static const char *TAG = "qio_mode";
typedef unsigned (*read_status_fn_t)();
@ -77,7 +82,7 @@ static void write_status_16b_wrsr(unsigned new_status);
const static qio_info_t chip_data[] = {
/* Manufacturer, mfg_id, flash_id, id mask, Read Status, Write Status, QIE Bit */
{ "MXIC", 0xC2, 0x2000, 0xFF00, read_status_8b_rdsr, write_status_8b_wrsr, 6 },
{ "ISSI", 0x9D, 0x4000, 0xFF00, read_status_8b_rdsr, write_status_8b_wrsr, 6 },
{ "ISSI", 0x9D, 0x4000, 0xCF00, read_status_8b_rdsr, write_status_8b_wrsr, 6 }, /* IDs 0x40xx, 0x70xx */
{ "WinBond", 0xEF, 0x4000, 0xFF00, read_status_16b_rdsr_rdsr2, write_status_16b_wrsr, 9 },
/* Final entry is default entry, if no other IDs have matched.
@ -102,6 +107,9 @@ static void enable_qio_mode(read_status_fn_t read_status_fn,
*/
static uint32_t execute_flash_command(uint8_t command, uint32_t mosi_data, uint8_t mosi_len, uint8_t miso_len);
/* dummy_len_plus values defined in ROM for SPI flash configuration */
extern uint8_t g_rom_spiflash_dummy_len_plus[];
void bootloader_enable_qio_mode(void)
{
uint32_t raw_flash_id;
@ -149,6 +157,20 @@ static void enable_qio_mode(read_status_fn_t read_status_fn,
uint8_t status_qio_bit)
{
uint32_t status;
const uint32_t spiconfig = ets_efuse_get_spiconfig();
if (spiconfig != EFUSE_SPICONFIG_SPI_DEFAULTS && spiconfig != EFUSE_SPICONFIG_HSPI_DEFAULTS) {
// spiconfig specifies a custom efuse pin configuration. This config defines all pins -except- WP.
//
// For now, in this situation we only support Quad I/O mode for ESP32-D2WD where WP pin is known.
uint32_t chip_ver = REG_GET_FIELD(EFUSE_BLK0_RDATA3_REG, EFUSE_RD_CHIP_VER_RESERVE);
uint32_t pkg_ver = chip_ver & 0x7;
const uint32_t PKG_VER_ESP32_D2WD = 2; // TODO: use chip detection API once available
if (pkg_ver != PKG_VER_ESP32_D2WD) {
ESP_LOGE(TAG, "Quad I/O is only supported for standard pin numbers or ESP32-D2WD. Falling back to Dual I/O.");
return;
}
}
esp_rom_spiflash_wait_idle(&g_rom_flashchip);
@ -180,7 +202,10 @@ static void enable_qio_mode(read_status_fn_t read_status_fn,
#else
mode = ESP_ROM_SPIFLASH_QIO_MODE;
#endif
esp_rom_spiflash_master_config_readmode(mode);
esp_rom_spiflash_config_readmode(mode);
esp_rom_spiflash_select_qio_pins(ESP32_D2WD_WP_GPIO, spiconfig);
}
static unsigned read_status_8b_rdsr()
@ -222,6 +247,17 @@ static uint32_t execute_flash_command(uint8_t command, uint32_t mosi_data, uint8
SPIFLASH.mosi_dlen.usr_mosi_dbitlen = mosi_len ? (mosi_len - 1) : 0;
SPIFLASH.data_buf[0] = mosi_data;
if (g_rom_spiflash_dummy_len_plus[1]) {
/* When flash pins are mapped via GPIO matrix, need a dummy cycle before reading via MISO */
if (miso_len > 0) {
SPIFLASH.user.usr_dummy = 1;
SPIFLASH.user1.usr_dummy_cyclelen = g_rom_spiflash_dummy_len_plus[1] - 1;
} else {
SPIFLASH.user.usr_dummy = 0;
SPIFLASH.user1.usr_dummy_cyclelen = 0;
}
}
SPIFLASH.cmd.usr = 1;
while(SPIFLASH.cmd.usr != 0)
{ }

View file

@ -0,0 +1,27 @@
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "btc_task.h"
#include "btc_alarm.h"
void btc_alarm_handler(btc_msg_t *msg)
{
btc_alarm_args_t *arg = (btc_alarm_args_t *)msg->arg;
LOG_DEBUG("%s act %d\n", __FUNCTION__, msg->act);
if (arg->cb) {
arg->cb(arg->cb_data);
}
}

View file

@ -26,6 +26,7 @@
#include "btc_gap_ble.h"
#include "btc_blufi_prf.h"
#include "btc_dm.h"
#include "btc_alarm.h"
#include "bta_gatt_api.h"
#if CONFIG_CLASSIC_BT_ENABLED
#include "btc_gap_bt.h"
@ -48,6 +49,7 @@ static btc_func_t profile_tab[BTC_PID_NUM] = {
[BTC_PID_SPPLIKE] = {NULL, NULL},
[BTC_PID_BLUFI] = {btc_blufi_call_handler, btc_blufi_cb_handler },
[BTC_PID_DM_SEC] = {NULL, btc_dm_sec_cb_handler },
[BTC_PID_ALARM] = {btc_alarm_handler, NULL },
#if CONFIG_CLASSIC_BT_ENABLED
[BTC_PID_GAP_BT] = {btc_gap_bt_call_handler, NULL },
[BTC_PID_PRF_QUE] = {btc_profile_queue_handler, NULL },

View file

@ -0,0 +1,30 @@
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef __BTC_ALARM_H__
#define __BTC_ALARM_H__
#include <stdint.h>
#include "alarm.h"
/* btc_alarm_args_t */
typedef struct {
osi_alarm_callback_t cb;
void *cb_data;
} btc_alarm_args_t;
void btc_alarm_handler(btc_msg_t *msg);
#endif /* __BTC_ALARM_H__ */

View file

@ -44,6 +44,7 @@ typedef enum {
BTC_PID_SPPLIKE,
BTC_PID_BLUFI,
BTC_PID_DM_SEC,
BTC_PID_ALARM,
#if CONFIG_CLASSIC_BT_ENABLED
BTC_PID_GAP_BT,
BTC_PID_PRF_QUE,

View file

@ -345,7 +345,7 @@ static void btc_blufi_send_notify(uint8_t *pkt, int pkt_len)
static void btc_blufi_recv_handler(uint8_t *data, int len)
{
struct blufi_hdr *hdr = (struct blufi_hdr *)data;
uint16_t checksum;
uint16_t checksum, checksum_pkt;
int ret;
if (hdr->seq != blufi_env.recv_seq) {
@ -369,8 +369,9 @@ static void btc_blufi_recv_handler(uint8_t *data, int len)
if (BLUFI_FC_IS_CHECK(hdr->fc)
&& (blufi_env.cbs && blufi_env.cbs->checksum_func)) {
checksum = blufi_env.cbs->checksum_func(hdr->seq, &hdr->seq, hdr->data_len + 2);
if (memcmp(&checksum, &hdr->data[hdr->data_len], 2) != 0) {
LOG_ERROR("%s checksum error %04x, pkt %04x\n", __func__, checksum, *(uint16_t *)&hdr->data[hdr->data_len]);
checksum_pkt = hdr->data[hdr->data_len] | (((uint16_t) hdr->data[hdr->data_len + 1]) << 8);
if (checksum != checksum_pkt) {
LOG_ERROR("%s checksum error %04x, pkt %04x\n", __func__, checksum, checksum_pkt);
return;
}
}
@ -381,7 +382,7 @@ static void btc_blufi_recv_handler(uint8_t *data, int len)
if (BLUFI_FC_IS_FRAG(hdr->fc)) {
if (blufi_env.offset == 0) {
blufi_env.total_len = *(uint16_t *)(hdr->data);
blufi_env.total_len = hdr->data[0] | (((uint16_t) hdr->data[1]) << 8);
blufi_env.aggr_buf = GKI_getbuf(blufi_env.total_len);
if (blufi_env.aggr_buf == NULL) {
LOG_ERROR("%s no mem, len %d\n", __func__, blufi_env.total_len);
@ -420,7 +421,8 @@ void btc_blufi_send_encap(uint8_t type, uint8_t *data, int total_data_len)
}
hdr->fc = 0x0;
hdr->data_len = blufi_env.frag_size + 2;
*(uint16_t *)hdr->data = remain_len;
hdr->data[0] = remain_len & 0xff;
hdr->data[1] = (remain_len >> 8) & 0xff;
memcpy(hdr->data + 2, &data[total_data_len - remain_len], blufi_env.frag_size); //copy first, easy for check sum
hdr->fc |= BLUFI_FC_FRAG;
} else {

View file

@ -27,6 +27,8 @@
#include "freertos/FreeRTOSConfig.h"
#include "freertos/xtensa_api.h"
#include "rom/ets_sys.h"
#include "btc_task.h"
#include "btc_alarm.h"
#define RTC_TIMER_TICKS_TO_MS(ticks) (((ticks/625)<<1) + (ticks-(ticks/625)*625)/312)
@ -122,17 +124,21 @@ static struct alarm_t *alarm_cbs_lookfor_available(void)
static void alarm_cb_handler(TimerHandle_t xTimer)
{
struct alarm_t *alarm;
if (!xTimer) {
LOG_ERROR("TimerName: NULL\n");
return;
}
alarm = pvTimerGetTimerID(xTimer);
LOG_DEBUG("TimerID %p, Name %s\n", alarm, pcTimerGetTimerName(xTimer));
if (alarm->cb) {
alarm->cb(alarm->cb_data);
}
btc_msg_t msg;
btc_alarm_args_t arg;
msg.sig = BTC_SIG_API_CALL;
msg.pid = BTC_PID_ALARM;
arg.cb = alarm->cb;
arg.cb_data = alarm->cb_data;
btc_transfer_context(&msg, &arg, sizeof(btc_alarm_args_t), NULL);
}
osi_alarm_t *osi_alarm_new(char *alarm_name, osi_alarm_callback_t callback, void *data, period_ms_t timer_expire)

View file

@ -223,8 +223,11 @@ static void btu_hci_msg_process(BT_HDR *p_msg)
/* Determine the input message type. */
switch (p_msg->event & BT_EVT_MASK) {
case BTU_POST_TO_TASK_NO_GOOD_HORRIBLE_HACK: // TODO(zachoverflow): remove this
((post_to_task_hack_t *)(&p_msg->data[0]))->callback(p_msg);
{
post_to_task_hack_t *ph = (post_to_task_hack_t *) &p_msg->data[0];
ph->callback(p_msg);
break;
}
case BT_EVT_TO_BTU_HCI_ACL:
/* All Acl Data goes to L2CAP */
l2c_rcv_acl_data (p_msg);

View file

@ -270,7 +270,7 @@ esp_err_t gpio_set_direction(gpio_num_t gpio_num, gpio_mode_t mode)
return ret;
}
esp_err_t gpio_config(gpio_config_t *pGPIOConfig)
esp_err_t gpio_config(const gpio_config_t *pGPIOConfig)
{
uint64_t gpio_pin_mask = (pGPIOConfig->pin_bit_mask);
uint32_t io_reg = 0;

View file

@ -429,7 +429,7 @@ esp_err_t i2c_get_data_mode(i2c_port_t i2c_num, i2c_trans_mode_t *tx_trans_mode,
return ESP_OK;
}
esp_err_t i2c_param_config(i2c_port_t i2c_num, i2c_config_t* i2c_conf)
esp_err_t i2c_param_config(i2c_port_t i2c_num, const i2c_config_t* i2c_conf)
{
I2C_CHECK(i2c_num < I2C_NUM_MAX, I2C_NUM_ERROR_STR, ESP_ERR_INVALID_ARG);
I2C_CHECK(i2c_conf != NULL, I2C_ADDR_ERROR_STR, ESP_ERR_INVALID_ARG);

View file

@ -221,7 +221,7 @@ typedef intr_handle_t gpio_isr_handle_t;
* - ESP_ERR_INVALID_ARG Parameter error
*
*/
esp_err_t gpio_config(gpio_config_t *pGPIOConfig);
esp_err_t gpio_config(const gpio_config_t *pGPIOConfig);
/**

View file

@ -135,7 +135,7 @@ esp_err_t i2c_driver_delete(i2c_port_t i2c_num);
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_param_config(i2c_port_t i2c_num, i2c_config_t* i2c_conf);
esp_err_t i2c_param_config(i2c_port_t i2c_num, const i2c_config_t* i2c_conf);
/**
* @brief reset I2C tx hardware fifo

View file

@ -115,7 +115,7 @@ typedef intr_handle_t ledc_isr_handle_t;
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t ledc_channel_config(ledc_channel_config_t* ledc_conf);
esp_err_t ledc_channel_config(const ledc_channel_config_t* ledc_conf);
/**
* @brief LEDC timer configuration
@ -128,7 +128,7 @@ esp_err_t ledc_channel_config(ledc_channel_config_t* ledc_conf);
* - ESP_ERR_INVALID_ARG Parameter error
* - ESP_FAIL Can not find a proper pre-divider number base on the given frequency and the current bit_num.
*/
esp_err_t ledc_timer_config(ledc_timer_config_t* timer_conf);
esp_err_t ledc_timer_config(const ledc_timer_config_t* timer_conf);
/**
* @brief LEDC update channel parameters

View file

@ -88,7 +88,7 @@ typedef intr_handle_t pcnt_isr_handle_t;
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t pcnt_unit_config(pcnt_config_t *pcnt_config);
esp_err_t pcnt_unit_config(const pcnt_config_t *pcnt_config);
/**
* @brief Get pulse counter value

View file

@ -57,7 +57,7 @@ typedef struct {
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t sigmadelta_config(sigmadelta_config_t *config);
esp_err_t sigmadelta_config(const sigmadelta_config_t *config);
/**
* @brief Set Sigma-delta channel duty.

View file

@ -131,7 +131,7 @@ typedef struct spi_device_t* spi_device_handle_t; ///< Handle for a device on a
* - ESP_ERR_NO_MEM if out of memory
* - ESP_OK on success
*/
esp_err_t spi_bus_initialize(spi_host_device_t host, spi_bus_config_t *bus_config, int dma_chan);
esp_err_t spi_bus_initialize(spi_host_device_t host, const spi_bus_config_t *bus_config, int dma_chan);
/**
* @brief Free a SPI bus
@ -235,4 +235,4 @@ esp_err_t spi_device_transmit(spi_device_handle_t handle, spi_transaction_t *tra
}
#endif
#endif
#endif

View file

@ -287,7 +287,7 @@ esp_err_t timer_isr_register(timer_group_t group_num, timer_idx_t timer_num, voi
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t timer_init(timer_group_t group_num, timer_idx_t timer_num, timer_config_t* config);
esp_err_t timer_init(timer_group_t group_num, timer_idx_t timer_num, const timer_config_t* config);
/** @brief Get timer configure value.
*

View file

@ -180,7 +180,7 @@ esp_err_t ledc_isr_register(void (*fn)(void*), void * arg, int intr_alloc_flags,
return ret;
}
esp_err_t ledc_timer_config(ledc_timer_config_t* timer_conf)
esp_err_t ledc_timer_config(const ledc_timer_config_t* timer_conf)
{
int freq_hz = timer_conf->freq_hz;
int bit_num = timer_conf->bit_num;
@ -245,7 +245,7 @@ esp_err_t ledc_set_pin(int gpio_num, ledc_mode_t speed_mode, ledc_channel_t ledc
return ESP_OK;
}
esp_err_t ledc_channel_config(ledc_channel_config_t* ledc_conf)
esp_err_t ledc_channel_config(const ledc_channel_config_t* ledc_conf)
{
uint32_t speed_mode = ledc_conf->speed_mode;
uint32_t gpio_num = ledc_conf->gpio_num;
@ -541,6 +541,7 @@ esp_err_t ledc_set_fade_with_step(ledc_mode_t speed_mode, ledc_channel_t channel
int duty_cur = LEDC.channel_group[speed_mode].channel[channel].duty_rd.duty_read >> LEDC_DUTY_DECIMAL_BIT_NUM;
int duty_delta = target_duty > duty_cur ? target_duty - duty_cur : duty_cur - target_duty;
if (duty_delta == 0) {
portEXIT_CRITICAL(&ledc_spinlock);
return ESP_OK;
}
s_ledc_fade_rec[speed_mode][channel]->speed_mode = speed_mode;

View file

@ -39,7 +39,7 @@ static portMUX_TYPE pcnt_spinlock = portMUX_INITIALIZER_UNLOCKED;
#define PCNT_ENTER_CRITICAL_ISR(mux) portENTER_CRITICAL_ISR(mux)
#define PCNT_EXIT_CRITICAL_ISR(mux) portEXIT_CRITICAL_ISR(mux)
esp_err_t pcnt_unit_config(pcnt_config_t *pcnt_config)
esp_err_t pcnt_unit_config(const pcnt_config_t *pcnt_config)
{
uint8_t unit = pcnt_config->unit;
uint8_t channel = pcnt_config->channel;

View file

@ -202,6 +202,17 @@ esp_err_t sdmmc_host_set_card_clk(int slot, uint32_t freq_khz)
SDMMC.clkena.cclk_enable |= BIT(slot);
SDMMC.clkena.cclk_low_power |= BIT(slot);
sdmmc_host_clock_update_command(slot);
// set data timeout
const uint32_t data_timeout_ms = 100;
uint32_t data_timeout_cycles = data_timeout_ms * freq_khz;
const uint32_t data_timeout_cycles_max = 0xffffff;
if (data_timeout_cycles > data_timeout_cycles_max) {
data_timeout_cycles = data_timeout_cycles_max;
}
SDMMC.tmout.data = data_timeout_cycles;
// always set response timeout to highest value, it's small enough anyway
SDMMC.tmout.response = 255;
return ESP_OK;
}
@ -419,9 +430,6 @@ void sdmmc_host_dma_stop()
void sdmmc_host_dma_prepare(sdmmc_desc_t* desc, size_t block_size, size_t data_size)
{
// TODO: set timeout depending on data size
SDMMC.tmout.val = 0xffffffff;
// Set size of data and DMA descriptor pointer
SDMMC.bytcnt = data_size;
SDMMC.blksiz = block_size;

View file

@ -32,6 +32,13 @@
*/
#define SDMMC_DMA_DESC_CNT 4
/* Max delay value is mostly useful for cases when CD pin is not used, and
* the card is removed. In this case, SDMMC peripheral may not always return
* CMD_DONE / DATA_DONE interrupts after signaling the error. This delay works
* as a safety net in such cases.
*/
#define SDMMC_MAX_EVT_WAIT_DELAY_MS 1000
static const char* TAG = "sdmmc_req";
typedef enum {
@ -188,9 +195,12 @@ static esp_err_t handle_idle_state_events()
static esp_err_t handle_event(sdmmc_command_t* cmd, sdmmc_req_state_t* state)
{
sdmmc_event_t evt;
esp_err_t err = sdmmc_host_wait_for_event(portMAX_DELAY, &evt);
esp_err_t err = sdmmc_host_wait_for_event(SDMMC_MAX_EVT_WAIT_DELAY_MS / portTICK_PERIOD_MS, &evt);
if (err != ESP_OK) {
ESP_LOGE(TAG, "sdmmc_host_wait_for_event returned %d", err);
ESP_LOGE(TAG, "sdmmc_host_wait_for_event returned 0x%x", err);
if (err == ESP_ERR_TIMEOUT) {
sdmmc_host_dma_stop();
}
return err;
}
ESP_LOGV(TAG, "sdmmc_handle_event: evt %08x %08x", evt.sdmmc_status, evt.dma_status);
@ -268,7 +278,7 @@ static void process_command_response(uint32_t status, sdmmc_command_t* cmd)
if (cmd->data) {
sdmmc_host_dma_stop();
}
ESP_LOGD(TAG, "%s: error %d", __func__, cmd->error);
ESP_LOGD(TAG, "%s: error 0x%x (status=%08x)", __func__, cmd->error, status);
}
}
@ -291,7 +301,7 @@ static void process_data_status(uint32_t status, sdmmc_command_t* cmd)
if (cmd->data) {
sdmmc_host_dma_stop();
}
ESP_LOGD(TAG, "%s: error %d", __func__, cmd->error);
ESP_LOGD(TAG, "%s: error 0x%x (status=%08x)", __func__, cmd->error, status);
}
}
@ -323,9 +333,14 @@ static esp_err_t process_events(sdmmc_event_t evt, sdmmc_command_t* cmd, sdmmc_r
case SDMMC_SENDING_CMD:
if (mask_check_and_clear(&evt.sdmmc_status, SDMMC_CMD_ERR_MASK)) {
process_command_response(orig_evt.sdmmc_status, cmd);
break;
if (cmd->error != ESP_ERR_TIMEOUT) {
// Unless this is a timeout error, we need to wait for the
// CMD_DONE interrupt
break;
}
}
if (!mask_check_and_clear(&evt.sdmmc_status, SDMMC_INTMASK_CMD_DONE)) {
if (!mask_check_and_clear(&evt.sdmmc_status, SDMMC_INTMASK_CMD_DONE) &&
cmd->error != ESP_ERR_TIMEOUT) {
break;
}
process_command_response(orig_evt.sdmmc_status, cmd);
@ -352,6 +367,11 @@ static esp_err_t process_events(sdmmc_event_t evt, sdmmc_command_t* cmd, sdmmc_r
next_state = SDMMC_BUSY;
}
}
if (orig_evt.sdmmc_status & (SDMMC_INTMASK_SBE | SDMMC_INTMASK_DATA_OVER)) {
// On start bit error, DATA_DONE interrupt will not be generated
next_state = SDMMC_IDLE;
break;
}
break;
case SDMMC_BUSY:

View file

@ -25,7 +25,7 @@ static const char* SIGMADELTA_TAG = "SIGMADELTA";
return (ret_val); \
}
esp_err_t sigmadelta_config(sigmadelta_config_t *config)
esp_err_t sigmadelta_config(const sigmadelta_config_t *config)
{
SIGMADELTA_CHECK(config->channel < SIGMADELTA_CHANNEL_MAX, SIGMADELTA_CHANNEL_ERR_STR, ESP_ERR_INVALID_ARG);
SIGMADELTA_CHECK(GPIO_IS_VALID_OUTPUT_GPIO(config->sigmadelta_gpio), SIGMADELTA_IO_ERR_STR, ESP_ERR_INVALID_ARG);

View file

@ -191,7 +191,7 @@ static const spi_signal_conn_t io_signal[3]={
static void spi_intr(void *arg);
esp_err_t spi_bus_initialize(spi_host_device_t host, spi_bus_config_t *bus_config, int dma_chan)
esp_err_t spi_bus_initialize(spi_host_device_t host, const spi_bus_config_t *bus_config, int dma_chan)
{
bool native=true;
/* ToDo: remove this when we have flash operations cooperating with this */
@ -698,8 +698,8 @@ esp_err_t spi_device_queue_trans(spi_device_handle_t handle, spi_transaction_t *
{
BaseType_t r;
SPI_CHECK(handle!=NULL, "invalid dev handle", ESP_ERR_INVALID_ARG);
SPI_CHECK((trans_desc->flags & SPI_TRANS_USE_RXDATA)==0 ||trans_desc->length <= 32, "rxdata transfer > 32bytes", ESP_ERR_INVALID_ARG);
SPI_CHECK((trans_desc->flags & SPI_TRANS_USE_TXDATA)==0 ||trans_desc->length <= 32, "txdata transfer > 32bytes", ESP_ERR_INVALID_ARG);
SPI_CHECK((trans_desc->flags & SPI_TRANS_USE_RXDATA)==0 ||trans_desc->rxlength <= 32, "rxdata transfer > 32 bits", ESP_ERR_INVALID_ARG);
SPI_CHECK((trans_desc->flags & SPI_TRANS_USE_TXDATA)==0 ||trans_desc->length <= 32, "txdata transfer > 32 bits", ESP_ERR_INVALID_ARG);
SPI_CHECK(!((trans_desc->flags & (SPI_TRANS_MODE_DIO|SPI_TRANS_MODE_QIO)) && (handle->cfg.flags & SPI_DEVICE_3WIRE)), "incompatible iface params", ESP_ERR_INVALID_ARG);
SPI_CHECK(!((trans_desc->flags & (SPI_TRANS_MODE_DIO|SPI_TRANS_MODE_QIO)) && (!(handle->cfg.flags & SPI_DEVICE_HALFDUPLEX))), "incompatible iface params", ESP_ERR_INVALID_ARG);
r=xQueueSend(handle->trans_queue, (void*)&trans_desc, ticks_to_wait);

View file

@ -204,7 +204,7 @@ esp_err_t timer_isr_register(timer_group_t group_num, timer_idx_t timer_num,
return esp_intr_alloc_intrstatus(intr_source, intr_alloc_flags, status_reg, mask, fn, arg, handle);
}
esp_err_t timer_init(timer_group_t group_num, timer_idx_t timer_num, timer_config_t *config)
esp_err_t timer_init(timer_group_t group_num, timer_idx_t timer_num, const timer_config_t *config)
{
TIMER_CHECK(group_num < TIMER_GROUP_MAX, TIMER_GROUP_NUM_ERROR, ESP_ERR_INVALID_ARG);
TIMER_CHECK(timer_num < TIMER_MAX, TIMER_NUM_ERROR, ESP_ERR_INVALID_ARG);

View file

@ -28,24 +28,33 @@ config MEMMAP_SMP
to save some memory. (ToDo: Make this automatically depend on unicore support)
config MEMMAP_TRACEMEM
bool "Use TRAX tracing feature"
default "n"
help
The ESP32 contains a feature which allows you to trace the execution path the processor
has taken through the program. This is stored in a chunk of 32K (16K for single-processor)
of memory that can't be used for general purposes anymore. Disable this if you do not know
what this is.
bool
default "n"
config MEMMAP_TRACEMEM_TWOBANKS
bool "Reserve memory for tracing both pro as well as app cpu execution"
bool
default "n"
depends on MEMMAP_TRACEMEM && MEMMAP_SMP
config ESP32_TRAX
bool "Use TRAX tracing feature"
default "n"
select MEMMAP_TRACEMEM
help
The ESP32 contains a feature which allows you to trace the execution path the processor
has taken through the program. This is stored in a chunk of 32K (16K for single-processor)
of memory that can't be used for general purposes anymore. Disable this if you do not know
what this is.
config ESP32_TRAX_TWOBANKS
bool "Reserve memory for tracing both pro as well as app cpu execution"
default "n"
depends on ESP32_TRAX && MEMMAP_SMP
select MEMMAP_TRACEMEM_TWOBANKS
help
The ESP32 contains a feature which allows you to trace the execution path the processor
has taken through the program. This is stored in a chunk of 32K (16K for single-processor)
of memory that can't be used for general purposes anymore. Disable this if you do not know
what this is.
# Memory to reverse for trace, used in linker script
config TRACEMEM_RESERVE_DRAM
@ -95,6 +104,45 @@ config ESP32_CORE_DUMP_LOG_LEVEL
help
Config core dump module logging level (0-5).
choice ESP32_APPTRACE_DESTINATION
prompt "AppTrace: destination"
default ESP32_APPTRACE_DEST_NONE
help
Select destination for application trace: trace memory, uart or none (to disable).
config ESP32_APPTRACE_DEST_TRAX
bool "Trace memory"
select ESP32_APPTRACE_ENABLE
config ESP32_APPTRACE_DEST_UART
bool "UART"
select ESP32_APPTRACE_ENABLE
config ESP32_APPTRACE_DEST_NONE
bool "None"
endchoice
config ESP32_APPTRACE_ENABLE
bool
depends on !ESP32_TRAX
select MEMMAP_TRACEMEM
select MEMMAP_TRACEMEM_TWOBANKS
default F
help
Enables/disable application tracing module.
config ESP32_APPTRACE_ONPANIC_HOST_FLUSH_TMO
int "AppTrace: Timeout for flushing last trace data to host on panic"
depends on ESP32_APPTRACE_ENABLE
default 4294967295
help
Timeout for flushing last trace data to host in case of panic. In us.
config ESP32_APPTRACE_ONPANIC_HOST_FLUSH_TRAX_THRESH
int "AppTrace: Threshold for flushing last trace data to host on panic"
depends on ESP32_APPTRACE_DEST_TRAX
default 50
help
Threshold for flushing last trace data to host on panic. In percents of TRAX memory block length.
# Not implemented and/or needs new silicon rev to work
config MEMMAP_SPISRAM
bool "Use external SPI SRAM chip as main memory"
@ -105,16 +153,37 @@ config MEMMAP_SPISRAM
main memory map. Enable this if you have this hardware and want to use it in the same
way as on-chip RAM.
choice BASE_MAC_ADDRESS_STORAGE
prompt "Storage of the base MAC address"
default BASE_MAC_STORED_DEFAULT_EFUSE
help
Select storage of the base MAC address which is used for all network interfaces when networking is initialized.
If "Default place in EFUSE" is selected, esp32 will use the base MAC address which is written into default
place in EFUSE when the chip is manufactured.
If "Customer-defined place in EFUSE" is selected, ESP32 will use customer-defined base MAC address which
is written into EFUSE Block 3 words 0, 1.
If "Other customer-defined place" is selected, esp32 will use customer-defined base MAC address from other
place(flash, EEPROM, etc). User code must call esp_base_mac_addr_set_external to set the base MAC address
before network features are initialised.
config BASE_MAC_STORED_DEFAULT_EFUSE
bool "Default place in EFUSE"
config BASE_MAC_STORED_CUSTOMER_DEFINED_EFUSE
bool "Customer-defined place in EFUSE"
config BASE_MAC_STORED_OTHER_CUSTOMER_DEFINED_PLACE
bool "Other customer-defined place"
endchoice
choice NUMBER_OF_MAC_ADDRESS_GENERATED_FROM_EFUSE
bool "Number of MAC address generated from the hardware MAC address in efuse"
default FOUR_MAC_ADDRESS_FROM_EFUSE
help
Config the number of MAC address which is generated from the hardware MAC address in efuse.
Config the number of MAC address which is generated from the base MAC address in efuse.
If the number is two, the MAC addresses of WiFi station and bluetooth are generated from
the hardware MAC address in efuse. The MAC addresses of WiFi softap and ethernet are derived
the base MAC address in efuse. The MAC addresses of WiFi softap and ethernet are derived
from that of WiFi station and bluetooth respectively.
If the number is four, the MAC addresses of WiFi station, WiFi softap, bluetooth and ethernet
are all generated from the hardware MAC address in efuse.
are all generated from the base MAC address in efuse.
config TWO_MAC_ADDRESS_FROM_EFUSE
bool "Two"
@ -139,7 +208,6 @@ config SYSTEM_EVENT_TASK_STACK_SIZE
help
Config system event task stack size in different application.
config MAIN_TASK_STACK_SIZE
int "Main task stack size"
default 4096
@ -492,6 +560,34 @@ config ESP32_DEEP_SLEEP_WAKEUP_DELAY
If you are seeing "flash read err, 1000" message printed to the
console after deep sleep reset, try increasing this value.
choice ESP32_XTAL_FREQ_SEL
prompt "Main XTAL frequency"
default ESP32_XTAL_FREQ_AUTO
help
ESP32 currently supports the following XTAL frequencies:
- 26 MHz
- 40 MHz
Startup code can automatically estimate XTAL frequency. This feature
uses the internal 8MHz oscillator as a reference. Because the internal
oscillator frequency is temperature dependent, it is not recommended
to use automatic XTAL frequency detection in applications which need
to work at high ambient temperatures and use high-temperature
qualified chips and modules.
config ESP32_XTAL_FREQ_40
bool "40 MHz"
config ESP32_XTAL_FREQ_26
bool "26 MHz"
config ESP32_XTAL_FREQ_AUTO
bool "Autodetect"
endchoice
# Keep these values in sync with rtc_xtal_freq_t enum in soc/rtc.h
config ESP32_XTAL_FREQ
int
default 0 if ESP32_XTAL_FREQ_AUTO
default 40 if ESP32_XTAL_FREQ_40
default 26 if ESP32_XTAL_FREQ_26
endmenu
menuconfig WIFI_ENABLED
@ -525,8 +621,8 @@ config ESP32_WIFI_STATIC_RX_BUFFER_NUM
config ESP32_WIFI_DYNAMIC_RX_BUFFER_NUM
int "Max number of WiFi dynamic RX buffers"
depends on WIFI_ENABLED
range 0 64
default 0
range 0 128
default 64
help
Set the number of WiFi dynamic rx buffers, 0 means no limitation for dynamic rx buffer
allocation. The size of dynamic rx buffers is not fixed.

View file

@ -0,0 +1,994 @@
// Copyright 2017 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
//
// Hot It Works
// ************
// 1. Components Overview
// ======================
// Xtensa has useful feature: TRAX debug module. It allows recording program execution flow during run-time without disturbing CPU commands flow.
// Exectution flow data are written to configurable Trace RAM block. Besides accessing Trace RAM itself TRAX module also allows to read/write
// trace memory via its registers by means of JTAG, APB or ERI transactions.
// ESP32 has two Xtensa cores with separate TRAX modules on them and provides two special memory regions to be used as trace memory.
// ESP32 allows muxing access to trace memory blocks in such a way that while one block is accessed by CPUs another can be accessed via JTAG by host
// via reading/writing TRAX registers. Block muxing is configurable at run-time and allows switching trace memory blocks between
// accessors in round-robin fashion so they can read/write separate memory blocks without disturbing each other.
// This moduile implements application tracing feature based on above mechanisms. This feature allows to transfer arbitrary user data to
// host via JTAG with minimal impact on system performance. This module is implied to be used in the following tracing scheme.
// ------>------ ----- (host components) -----
// | | | |
// --------------- ----------------------- ----------------------- ---------------- ------ --------- -----------------
// |apptrace user|-->|target tracing module|<--->|TRAX_MEM0 | TRAX_MEM1|---->|TRAX_DATA_REGS|<-->|JTAG|<--->|OpenOCD|-->|trace data file|
// --------------- ----------------------- ----------------------- ---------------- ------ --------- -----------------
// | | | |
// | ------<------ ---------------- |
// |<------------------------------------------->|TRAX_CTRL_REGS|<---->|
// ----------------
// In general tracing happens in the following way. User aplication requests tracing module to send some data by calling esp_apptrace_buffer_get(),
// moduile allocates necessary buffer in current input trace block. Then user fills received buffer with data and calls esp_apptrace_buffer_put().
// When current input trace block is filled with app data it is exposed to host and the second block becomes input one and buffer filling restarts.
// While target application fills one memory block host reads another block via JTAG.
// To control buffer switching and for other communication purposes this implementation uses some TRAX registers. It is safe since HW TRAX tracing
// can not be used along with application tracing feature so these registers are freely readable/writeable via JTAG from host and via ERI from ESP32 cores.
// So this implementation's target CPU overhead is produced only by calls to allocate/manage buffers and data copying.
// On host special OpenOCD command must be used to read trace data.
// 2.1.1.1 TRAX Registers layout
// =============================
// This module uses two TRAX HW registers to communicate with host SW (OpenOCD).
// - Control register uses TRAX_DELAYCNT as storage. Only lower 24 bits of TRAX_DELAYCNT are writable. Control register has the following bitfields:
// | 31..XXXXXX..24 | 23 .(host_connect). 23| 22..(block_id)..15 | 14..(block_len)..0 |
// 14..0 bits - actual length of user data in trace memory block. Target updates it every time it fills memory block and exposes it to host.
// Host writes zero to this field when it finishes reading exposed block;
// 22..15 bits - trace memory block transfer ID. Block counter. It can overflow. Updated by target, host should not modify it. Actually can be 1-2 bits;
// 23 bit - 'host connected' flag. If zero then host is not connected and tracing module works in post-mortem mode, otherwise in streaming mode;
// - Status register uses TRAX_TRIGGERPC as storage. If this register is not zero then currentlly CPU is changing TRAX registers and
// this register holds address of the instruction which application will execute when it finishes with those registers modifications.
// See 'Targets Connection' setion for details.
// 3. Modes of operation
// =====================
// This module supports two modes of operation:
// - Post-mortem mode. This is the default mode. In this mode application tracing module does not check whether host has read all the data from block
// exposed to it and switches block in any case. The mode does not need host interaction for operation and so can be useful when only the latest
// trace data are necessary, e.g. for analyzing crashes. On panic the latest data from current input block are exposed to host and host can read them.
// There is menuconfig option CONFIG_ESP32_APPTRACE_ONPANIC_HOST_FLUSH_TRAX_THRESH which control the threshold for flushing data on panic.
// - Streaming mode. Tracing module enters this mode when host connects to targets and sets respective bit in control register. In this mode tracing
// module waits for specified time until host read all the data from exposed block.
// On panic tracing module waits (timeout is configured via menuconfig via ESP32_APPTRACE_ONPANIC_HOST_FLUSH_TMO) for the host to read all data
// from the previously exposed block.
// 4. Communication Protocol
// =========================
// 4.1 Trace Memory Blocks
// ^^^^^^^^^^^^^^^^^^^^^^^^^
// Communication is controlled via special register. Host periodically polls control register on each core to find out if there are any data avalable.
// When current input trace memory block is filled tracing module exposes block to host and updates block_len and block_id fields in control register.
// Host reads new register value and according to it starts reading data from exposed block. Meanwhile target starts filling another trace block.
// When host finishes reading the block it clears block_len field in control register indicating to target that it is ready to accept the next block.
// 4.2 User Data Chunks Level
// --------------------------
// Since trace memory block is shared between user data chunks and data copying is performed on behalf of the API user (in its normal context) in
// multithreading environment it can happen that task/ISR which copies data is preempted by another high prio task/ISR. So it is possible situation
// that task/ISR will fail to complete filling its data chunk before the whole trace block is exposed to the host. To handle such conditions tracing
// module prepends all user data chunks with 4 bytes header which contains allocated buffer size and actual data length within it. OpenOCD command
// which reads application traces will report error when it will read incompleted user data block.
// 4.3 Targets Connection/Disconnection
// ------------------------------------
// When host is going to start tracing in streaming mode it needs to put both ESP32 cores into initial state when 'host connected' bit is set
// on both cores. To accomplish this host halts both cores and sets this bit in TRAX registers. But target code can be halted in state when it has read control
// register but has not updated its value. To handle such situations target code indicates to the host that it is updating control register by writing
// non-zero value to status register. Actually it writes address of the instruction which it will execute when it finishes with
// the registers update. When target is halted during control register update host sets breakpoint at the address from status register and resumes CPU.
// After target code finishes with register update it is halted on breakpoint, host detects it and safely sets 'host connected' bit. When both cores
// are set up they are resumed. Tracing starts without further intrusion into CPUs work.
// When host is going to stop tracing in streaming mode it needs to disconnect targets. Disconnection process is done using the same algorithm
// as for connecting, but 'host connected' bits are cleared on ESP32 cores.
// 5. Module Access Synchronization
// ================================
// Access to internal module's data is synchronized with custom mutex. Mutex is a wrapper for portMUX_TYPE and uses almost the same sync mechanism as in
// vPortCPUAcquireMutex/vPortCPUReleaseMutex. The mechanism uses S32C1I Xtensa instruction to implement exclusive access to module's data from tasks and
// ISRs running on both cores. Also custom mutex allows specifying timeout for locking operation. Locking routine checks underlaying mutex in cycle until
// it gets its ownership or timeout expires. The differences of application tracing module's mutex implementation from vPortCPUAcquireMutex/vPortCPUReleaseMutex are:
// - Support for timeouts.
// - Local IRQs for CPU which owns the mutex are disabled till the call to unlocking routine. This is made to avoid possible task's prio inversion.
// When low prio task takes mutex and enables local IRQs gets preempted by high prio task which in its turn can try to acquire mutex using infinite timeout.
// So no local task switch occurs when mutex is locked. But this does not apply to tasks on another CPU.
// WARNING: Priority inversion can happen when low prio task works on one CPU and medium and high prio tasks work on another.
// There are some differences how mutex behaves when it is used from task and ISR context when timeout is non-zero:
// - In task context when mutex can not be locked portYIELD() is called before check for timeout condition to alow othet tasks work on the same CPU.
// - In ISR context when mutex can not be locked nothing is done before expired time check.
// WARNING: Care must be taken when selecting timeout values for trace calls from ISRs. Tracing module does not care about watchdogs when waiting on internal locks
// and when waiting for host to complete previous block reading, so if wating timeout value exceedes watchdog's one it can lead to system reboot.
// 6. Timeouts
// ------------
// Timeout mechanism is based on xthal_get_ccount() routine and supports timeout values in micorseconds.
// There are two situations when task/ISR can be delayed by tracing API call. Timeout mechanism takes into account both conditions:
// - Trace data are locked by another task/ISR. When wating on trace data lock.
// - Current TRAX memory input block is full when working in streaming mode (host is connected). When waiting for host to complete previous block reading.
// When wating for any of above conditions xthal_get_ccount() is called periodically to calculate time elapsed from trace API routine entry. When elapsed
// time exceeds specified timeout value operation is canceled and ESP_ERR_TIMEOUT code is returned.
// ALSO SEE example usage of application tracing module in 'components/log/README.rst'
#include <string.h>
#include "soc/soc.h"
#include "soc/dport_reg.h"
#include "eri.h"
#include "trax.h"
#include "freertos/FreeRTOS.h"
#include "freertos/portmacro.h"
#include "freertos/semphr.h"
#include "freertos/task.h"
#include "soc/timer_group_struct.h"
#include "soc/timer_group_reg.h"
#include "esp_app_trace.h"
#if CONFIG_ESP32_APPTRACE_ENABLE
#define ESP_APPTRACE_DEBUG_STATS_ENABLE 0
#define ESP_APPTRACE_BUF_HISTORY_DEPTH (16*100)
#define ESP_APPTRACE_MAX_VPRINTF_ARGS 256
#define ESP_APPTRACE_PRINT_LOCK_NONE 0
#define ESP_APPTRACE_PRINT_LOCK_SEM 1
#define ESP_APPTRACE_PRINT_LOCK_MUX 2
#define ESP_APPTRACE_PRINT_LOCK ESP_APPTRACE_PRINT_LOCK_NONE//ESP_APPTRACE_PRINT_LOCK_SEM
#define ESP_APPTRACE_USE_LOCK_SEM 0 // 1 - semaphore (now may be broken), 0 - portMUX_TYPE
#define LOG_LOCAL_LEVEL ESP_LOG_VERBOSE
#include "esp_log.h"
const static char *TAG = "esp_apptrace";
#if ESP_APPTRACE_PRINT_LOCK != ESP_APPTRACE_PRINT_LOCK_NONE
#define ESP_APPTRACE_LOG( format, ... ) \
do { \
esp_apptrace_log_lock(); \
ets_printf(format, ##__VA_ARGS__); \
esp_apptrace_log_unlock(); \
} while(0)
#else
#define ESP_APPTRACE_LOG( format, ... ) \
do { \
ets_printf(format, ##__VA_ARGS__); \
} while(0)
#endif
#define ESP_APPTRACE_LOG_LEV( _L_, level, format, ... ) \
do { \
if (LOG_LOCAL_LEVEL >= level) { \
ESP_APPTRACE_LOG(LOG_FORMAT(_L_, format), esp_log_early_timestamp(), TAG, ##__VA_ARGS__); \
} \
} while(0)
#define ESP_APPTRACE_LOGE( format, ... ) ESP_APPTRACE_LOG_LEV(E, ESP_LOG_ERROR, format, ##__VA_ARGS__)
#define ESP_APPTRACE_LOGW( format, ... ) ESP_APPTRACE_LOG_LEV(W, ESP_LOG_WARN, format, ##__VA_ARGS__)
#define ESP_APPTRACE_LOGI( format, ... ) ESP_APPTRACE_LOG_LEV(I, ESP_LOG_INFO, format, ##__VA_ARGS__)
#define ESP_APPTRACE_LOGD( format, ... ) ESP_APPTRACE_LOG_LEV(D, ESP_LOG_DEBUG, format, ##__VA_ARGS__)
#define ESP_APPTRACE_LOGV( format, ... ) ESP_APPTRACE_LOG_LEV(V, ESP_LOG_VERBOSE, format, ##__VA_ARGS__)
#define ESP_APPTRACE_LOGO( format, ... ) ESP_APPTRACE_LOG_LEV(E, ESP_LOG_NONE, format, ##__VA_ARGS__)
#define ESP_APPTRACE_CPUTICKS2US(_t_) ((_t_)/(XT_CLOCK_FREQ/1000000))
// TODO: move these (and same definitions in trax.c to dport_reg.h)
#define TRACEMEM_MUX_PROBLK0_APPBLK1 0
#define TRACEMEM_MUX_BLK0_ONLY 1
#define TRACEMEM_MUX_BLK1_ONLY 2
#define TRACEMEM_MUX_PROBLK1_APPBLK0 3
// TRAX is disabled, so we use its registers for our own purposes
// | 31..XXXXXX..24 | 23 .(host_connect). 23| 22..(block_id)..15 | 14..(block_len)..0 |
#define ESP_APPTRACE_TRAX_CTRL_REG ERI_TRAX_DELAYCNT
#define ESP_APPTRACE_TRAX_STAT_REG ERI_TRAX_TRIGGERPC
#define ESP_APPTRACE_TRAX_BLOCK_LEN_MSK 0x7FFFUL
#define ESP_APPTRACE_TRAX_BLOCK_LEN(_l_) ((_l_) & ESP_APPTRACE_TRAX_BLOCK_LEN_MSK)
#define ESP_APPTRACE_TRAX_BLOCK_LEN_GET(_v_) ((_v_) & ESP_APPTRACE_TRAX_BLOCK_LEN_MSK)
#define ESP_APPTRACE_TRAX_BLOCK_ID_MSK 0xFFUL
#define ESP_APPTRACE_TRAX_BLOCK_ID(_id_) (((_id_) & ESP_APPTRACE_TRAX_BLOCK_ID_MSK) << 15)
#define ESP_APPTRACE_TRAX_BLOCK_ID_GET(_v_) (((_v_) >> 15) & ESP_APPTRACE_TRAX_BLOCK_ID_MSK)
#define ESP_APPTRACE_TRAX_HOST_CONNECT (1 << 23)
static volatile uint8_t *s_trax_blocks[] = {
(volatile uint8_t *) 0x3FFFC000,
(volatile uint8_t *) 0x3FFF8000
};
#define ESP_APPTRACE_TRAX_BLOCKS_NUM (sizeof(s_trax_blocks)/sizeof(s_trax_blocks[0]))
//#define ESP_APPTRACE_TRAX_BUFFER_SIZE (ESP_APPTRACE_TRAX_BLOCK_SIZE/4)
#define ESP_APPTRACE_TRAX_INBLOCK_START 0//(ESP_APPTRACE_TRAX_BLOCK_ID_MSK - 4)
#define ESP_APPTRACE_TRAX_INBLOCK_MARKER_PTR_GET() (&s_trace_buf.trax.state.markers[s_trace_buf.trax.state.in_block % 2])
#define ESP_APPTRACE_TRAX_INBLOCK_GET() (&s_trace_buf.trax.blocks[s_trace_buf.trax.state.in_block % 2])
#if ESP_APPTRACE_DEBUG_STATS_ENABLE == 1
/** keeps info about apptrace API (write/get buffer) caller and internal module's data related to that call
* NOTE: used for module debug purposes, currently this functionality is partially broken,
* but can be useful in future
*/
typedef struct {
uint32_t hnd; // task/ISR handle
uint32_t ts; // timestamp
uint32_t stamp; // test (user) trace buffer stamp
uint32_t in_block; // TRAX input block ID
uint32_t eri_len[2]; // contents of ERI control register upon entry to / exit from API routine
uint32_t wr_err; // number of trace write errors
} esp_trace_buffer_wr_hitem_t;
/** apptrace API calls history. History is organized as ring buffer*/
typedef struct {
uint32_t hist_rd; // the first history entry index
uint32_t hist_wr; // the last history entry index
esp_trace_buffer_wr_hitem_t hist[ESP_APPTRACE_BUF_HISTORY_DEPTH]; // history data
} esp_trace_buffer_wr_stats_t;
/** trace module stats */
typedef struct {
esp_trace_buffer_wr_stats_t wr;
} esp_trace_buffer_stats_t;
#endif
/** Trace data header. Every user data chunk is prepended with this header.
* User allocates block with esp_apptrace_buffer_get and then fills it with data,
* in multithreading environment it can happen that tasks gets buffer and then gets interrupted,
* so it is possible that user data are incomplete when TRAX memory block is exposed to the host.
* In this case host SW will see that wr_sz < block_sz and will report error.
*/
typedef struct {
uint16_t block_sz; // size of allocated block for user data
uint16_t wr_sz; // size of actually written data
} esp_tracedata_hdr_t;
/** TRAX HW transport state */
typedef struct {
uint32_t in_block; // input block ID
uint32_t markers[ESP_APPTRACE_TRAX_BLOCKS_NUM]; // block filling level markers
#if ESP_APPTRACE_DEBUG_STATS_ENABLE == 1
esp_trace_buffer_stats_t stats; // stats
#endif
} esp_apptrace_trax_state_t;
/** memory block parameters */
typedef struct {
uint8_t *start; // start address
uint32_t sz; // size
} esp_apptrace_mem_block_t;
/** TRAX HW transport data */
typedef struct {
volatile esp_apptrace_trax_state_t state; // state
esp_apptrace_mem_block_t blocks[ESP_APPTRACE_TRAX_BLOCKS_NUM]; // memory blocks
} esp_apptrace_trax_data_t;
/** tracing module synchronization lock */
typedef struct {
volatile unsigned int irq_stat; // local (on 1 CPU) IRQ state
portMUX_TYPE portmux; // mux for synchronization
} esp_apptrace_lock_t;
#define ESP_APPTRACE_MUX_GET(_m_) (&(_m_)->portmux)
/** tracing module internal data */
typedef struct {
#if ESP_APPTRACE_USE_LOCK_SEM == 1
SemaphoreHandle_t lock;
#else
esp_apptrace_lock_t lock; // sync lock
#endif
uint8_t inited; // module initialization state flag
esp_apptrace_trax_data_t trax; // TRAX HW transport data
} esp_apptrace_buffer_t;
/** waiting timeout data */
typedef struct {
uint32_t start; // waiting start (in ticks)
uint32_t tmo; // timeout (in us)
} esp_apptrace_tmo_t;
static esp_apptrace_buffer_t s_trace_buf;
#if ESP_APPTRACE_PRINT_LOCK == ESP_APPTRACE_PRINT_LOCK_SEM
static SemaphoreHandle_t s_log_lock;
#elif ESP_APPTRACE_PRINT_LOCK == ESP_APPTRACE_PRINT_LOCK_MUX
static esp_apptrace_lock_t s_log_lock;
#endif
static inline void esp_apptrace_tmo_init(esp_apptrace_tmo_t *tmo, uint32_t user_tmo)
{
tmo->start = xthal_get_ccount();
tmo->tmo = user_tmo;
}
static esp_err_t esp_apptrace_tmo_check(esp_apptrace_tmo_t *tmo)
{
unsigned cur, elapsed;
if (tmo->tmo != ESP_APPTRACE_TMO_INFINITE) {
cur = xthal_get_ccount();
if (tmo->start <= cur) {
elapsed = cur - tmo->start;
} else {
elapsed = 0xFFFFFFFF - tmo->start + cur;
}
if (ESP_APPTRACE_CPUTICKS2US(elapsed) >= tmo->tmo) {
return ESP_ERR_TIMEOUT;
}
}
return ESP_OK;
}
#if ESP_APPTRACE_PRINT_LOCK == ESP_APPTRACE_PRINT_LOCK_MUX || ESP_APPTRACE_USE_LOCK_SEM == 0
static inline void esp_apptrace_mux_init(esp_apptrace_lock_t *mux)
{
ESP_APPTRACE_MUX_GET(mux)->mux = portMUX_FREE_VAL;
mux->irq_stat = 0;
}
static esp_err_t esp_apptrace_lock_take(esp_apptrace_lock_t *mux, uint32_t tmo)
{
uint32_t res = ~portMUX_FREE_VAL;
esp_apptrace_tmo_t sleeping_tmo;
esp_apptrace_tmo_init(&sleeping_tmo, tmo);
while (1) {
res = (xPortGetCoreID() << portMUX_VAL_SHIFT) | portMUX_MAGIC_VAL;
// first disable IRQs on this CPU, this will prevent current task from been
// preempted by higher prio tasks, otherwise deadlock can happen:
// when lower prio task took mux and then preempted by higher prio one which also tries to
// get mux with INFINITE timeout
unsigned int irq_stat = portENTER_CRITICAL_NESTED();
// Now try to lock mux
uxPortCompareSet(&ESP_APPTRACE_MUX_GET(mux)->mux, portMUX_FREE_VAL, &res);
if (res == portMUX_FREE_VAL) {
// do not enable IRQs, we will held them disabled until mux is unlocked
// we do not need to flush cache region for mux->irq_stat because it is used
// to hold and restore IRQ state only for CPU which took mux, other CPUs will not use this value
mux->irq_stat = irq_stat;
break;
}
// if mux is locked by other task/ISR enable IRQs and let other guys work
portEXIT_CRITICAL_NESTED(irq_stat);
if (!xPortInIsrContext()) {
portYIELD();
}
int err = esp_apptrace_tmo_check(&sleeping_tmo);
if (err != ESP_OK) {
return err;
}
}
return ESP_OK;
}
esp_err_t esp_apptrace_mux_give(esp_apptrace_lock_t *mux)
{
esp_err_t ret = ESP_OK;
uint32_t res = 0;
unsigned int irq_stat;
res = portMUX_FREE_VAL;
// first of all save a copy of IRQ status for this locker because uxPortCompareSet will unlock mux and tasks/ISRs
// from other core can overwrite mux->irq_stat
irq_stat = mux->irq_stat;
uxPortCompareSet(&ESP_APPTRACE_MUX_GET(mux)->mux, (xPortGetCoreID() << portMUX_VAL_SHIFT) | portMUX_MAGIC_VAL, &res);
// enable local interrupts
portEXIT_CRITICAL_NESTED(irq_stat);
if ( ((res & portMUX_VAL_MASK) >> portMUX_VAL_SHIFT) == xPortGetCoreID() ) {
// nothing to do
} else if ( res == portMUX_FREE_VAL ) {
ret = ESP_FAIL; // should never get here
} else {
ret = ESP_FAIL; // should never get here
}
return ret;
}
#endif
static inline esp_err_t esp_apptrace_log_init()
{
#if ESP_APPTRACE_PRINT_LOCK == ESP_APPTRACE_PRINT_LOCK_SEM
s_log_lock = xSemaphoreCreateBinary();
if (!s_log_lock) {
ets_printf("%s: Failed to create print lock sem!", TAG);
return ESP_FAIL;
}
xSemaphoreGive(s_log_lock);
#elif ESP_APPTRACE_PRINT_LOCK == ESP_APPTRACE_PRINT_LOCK_MUX
esp_apptrace_mux_init(&s_log_lock);
#endif
return ESP_OK;
}
static inline void esp_apptrace_log_cleanup()
{
#if ESP_APPTRACE_PRINT_LOCK == ESP_APPTRACE_PRINT_LOCK_SEM
vSemaphoreDelete(s_log_lock);
#endif
}
static inline int esp_apptrace_log_lock()
{
#if ESP_APPTRACE_PRINT_LOCK == ESP_APPTRACE_PRINT_LOCK_SEM
BaseType_t ret;
if (xPortInIsrContext()) {
ret = xSemaphoreTakeFromISR(s_print_lock, NULL);
} else {
ret = xSemaphoreTake(s_print_lock, portMAX_DELAY);
}
return ret;
#elif ESP_APPTRACE_PRINT_LOCK == ESP_APPTRACE_PRINT_LOCK_MUX
int ret = esp_apptrace_lock_take(&s_log_lock, ESP_APPTRACE_TMO_INFINITE);
return ret;
#endif
return 0;
}
static inline void esp_apptrace_log_unlock()
{
#if ESP_APPTRACE_PRINT_LOCK == ESP_APPTRACE_PRINT_LOCK_SEM
if (xPortInIsrContext()) {
xSemaphoreGiveFromISR(s_log_lock, NULL);
} else {
xSemaphoreGive(s_log_lock);
}
#elif ESP_APPTRACE_PRINT_LOCK == ESP_APPTRACE_PRINT_LOCK_MUX
esp_apptrace_mux_give(&s_log_lock);
#endif
}
esp_err_t esp_apptrace_lock_init()
{
#if ESP_APPTRACE_USE_LOCK_SEM == 1
s_trace_buf.lock = xSemaphoreCreateBinary();
if (!s_trace_buf.lock) {
ESP_APPTRACE_LOGE("Failed to create lock!");
return ESP_FAIL;
}
xSemaphoreGive(s_trace_buf.lock);
#else
esp_apptrace_mux_init(&s_trace_buf.lock);
#endif
return ESP_OK;
}
esp_err_t esp_apptrace_lock_cleanup()
{
#if ESP_APPTRACE_USE_LOCK_SEM == 1
vSemaphoreDelete(s_trace_buf.lock);
#endif
return ESP_OK;
}
esp_err_t esp_apptrace_lock(uint32_t *tmo)
{
unsigned cur, elapsed, start = xthal_get_ccount();
#if ESP_APPTRACE_USE_LOCK_SEM == 1
BaseType_t ret;
if (xPortInIsrContext()) {
ret = xSemaphoreTakeFromISR(s_trace_buf.lock, NULL);
} else {
ret = xSemaphoreTake(s_trace_buf.lock, portTICK_PERIOD_MS * (*tmo) / 1000);
}
if (ret != pdTRUE) {
return ESP_FAIL;
}
#else
esp_err_t ret = esp_apptrace_lock_take(&s_trace_buf.lock, *tmo);
if (ret != ESP_OK) {
return ESP_FAIL;
}
#endif
// decrease tmo by actual waiting time
cur = xthal_get_ccount();
if (start <= cur) {
elapsed = cur - start;
} else {
elapsed = ULONG_MAX - start + cur;
}
if (ESP_APPTRACE_CPUTICKS2US(elapsed) > *tmo) {
*tmo = 0;
} else {
*tmo -= ESP_APPTRACE_CPUTICKS2US(elapsed);
}
return ESP_OK;
}
esp_err_t esp_apptrace_unlock()
{
esp_err_t ret = ESP_OK;
#if ESP_APPTRACE_USE_LOCK_SEM == 1
if (xPortInIsrContext()) {
xSemaphoreGiveFromISR(s_trace_buf.lock, NULL);
} else {
xSemaphoreGive(s_trace_buf.lock);
}
#else
ret = esp_apptrace_mux_give(&s_trace_buf.lock);
#endif
return ret;
}
#if CONFIG_ESP32_APPTRACE_DEST_TRAX
static void esp_apptrace_trax_init()
{
// Stop trace, if any (on the current CPU)
eri_write(ERI_TRAX_TRAXCTRL, TRAXCTRL_TRSTP);
eri_write(ERI_TRAX_TRAXCTRL, TRAXCTRL_TMEN);
eri_write(ESP_APPTRACE_TRAX_CTRL_REG, ESP_APPTRACE_TRAX_BLOCK_ID(ESP_APPTRACE_TRAX_INBLOCK_START));
eri_write(ESP_APPTRACE_TRAX_STAT_REG, 0);
ESP_APPTRACE_LOGI("Initialized TRAX on CPU%d", xPortGetCoreID());
}
// assumed to be protected by caller from multi-core/thread access
static esp_err_t esp_apptrace_trax_block_switch()
{
int prev_block_num = s_trace_buf.trax.state.in_block % 2;
int new_block_num = prev_block_num ? (0) : (1);
int res = ESP_OK;
extern uint32_t __esp_apptrace_trax_eri_updated;
// indicate to host that we are about to update.
// this is used only to place CPU into streaming mode at tracing startup
// before starting streaming host can halt us after we read ESP_APPTRACE_TRAX_CTRL_REG and before we updated it
// HACK: in this case host will set breakpoint just after ESP_APPTRACE_TRAX_CTRL_REG update,
// here we set address to set bp at
// enter ERI update critical section
eri_write(ESP_APPTRACE_TRAX_STAT_REG, (uint32_t)&__esp_apptrace_trax_eri_updated);
uint32_t ctrl_reg = eri_read(ESP_APPTRACE_TRAX_CTRL_REG);
#if ESP_APPTRACE_DEBUG_STATS_ENABLE == 1
if (s_trace_buf.state.stats.wr.hist_wr < ESP_APPTRACE_BUF_HISTORY_DEPTH) {
esp_trace_buffer_wr_hitem_t *hi = (esp_trace_buffer_wr_hitem_t *)&s_trace_buf.state.stats.wr.hist[s_trace_buf.state.stats.wr.hist_wr - 1];
hi->eri_len[1] = ctrl_reg;
}
#endif
uint32_t host_connected = ESP_APPTRACE_TRAX_HOST_CONNECT & ctrl_reg;
if (host_connected) {
uint32_t acked_block = ESP_APPTRACE_TRAX_BLOCK_ID_GET(ctrl_reg);
uint32_t host_to_read = ESP_APPTRACE_TRAX_BLOCK_LEN_GET(ctrl_reg);
if (host_to_read != 0 || acked_block != (s_trace_buf.trax.state.in_block & ESP_APPTRACE_TRAX_BLOCK_ID_MSK)) {
// ESP_APPTRACE_LOGE("HC[%d]: Can not switch %x %d %x %x/%lx", xPortGetCoreID(), ctrl_reg, host_to_read, acked_block,
// s_trace_buf.trax.state.in_block & ESP_APPTRACE_TRAX_BLOCK_ID_MSK, s_trace_buf.trax.state.in_block);
res = ESP_ERR_NO_MEM;
goto _on_func_exit;
}
}
s_trace_buf.trax.state.markers[new_block_num] = 0;
// switch to new block
s_trace_buf.trax.state.in_block++;
WRITE_PERI_REG(DPORT_TRACEMEM_MUX_MODE_REG, new_block_num ? TRACEMEM_MUX_BLK0_ONLY : TRACEMEM_MUX_BLK1_ONLY);
eri_write(ESP_APPTRACE_TRAX_CTRL_REG, ESP_APPTRACE_TRAX_BLOCK_ID(s_trace_buf.trax.state.in_block) |
host_connected | ESP_APPTRACE_TRAX_BLOCK_LEN(s_trace_buf.trax.state.markers[prev_block_num]));
_on_func_exit:
// exit ERI update critical section
eri_write(ESP_APPTRACE_TRAX_STAT_REG, 0x0);
asm volatile (
" .global __esp_apptrace_trax_eri_updated\n"
"__esp_apptrace_trax_eri_updated:\n"); // host will set bp here to resolve collision at streaming start
return res;
}
static esp_err_t esp_apptrace_trax_block_switch_waitus(uint32_t tmo)
{
int res;
esp_apptrace_tmo_t sleeping_tmo;
esp_apptrace_tmo_init(&sleeping_tmo, tmo);
while ((res = esp_apptrace_trax_block_switch()) != ESP_OK) {
res = esp_apptrace_tmo_check(&sleeping_tmo);
if (res != ESP_OK) {
break;
}
}
return res;
}
static uint8_t *esp_apptrace_trax_get_buffer(size_t size, uint32_t *tmo)
{
uint8_t *buf_ptr = NULL;
volatile uint32_t *cur_block_marker;
esp_apptrace_mem_block_t *cur_block;
int res = esp_apptrace_lock(tmo);
if (res != ESP_OK) {
return NULL;
}
#if ESP_APPTRACE_DEBUG_STATS_ENABLE == 1
esp_trace_buffer_wr_hitem_t *hi = NULL;
if (s_trace_buf.state.stats.wr.hist_wr < ESP_APPTRACE_BUF_HISTORY_DEPTH) {
hi = (esp_trace_buffer_wr_hitem_t *)&s_trace_buf.state.stats.wr.hist[s_trace_buf.state.stats.wr.hist_wr++];
hi->hnd = *(uint32_t *)(buf + 0);
hi->ts = *(uint32_t *)(buf + sizeof(uint32_t));
hi->stamp = *(buf + 2 * sizeof(uint32_t));
hi->in_block = s_trace_buf.state.in_block;
hi->wr_err = 0;
hi->eri_len[0] = eri_read(ESP_APPTRACE_TRAX_CTRL_REG);
if (s_trace_buf.state.stats.wr.hist_wr == ESP_APPTRACE_BUF_HISTORY_DEPTH) {
s_trace_buf.state.stats.wr.hist_wr = 0;
}
if (s_trace_buf.state.stats.wr.hist_wr == s_trace_buf.state.stats.wr.hist_rd) {
s_trace_buf.state.stats.wr.hist_rd++;
if (s_trace_buf.state.stats.wr.hist_rd == ESP_APPTRACE_BUF_HISTORY_DEPTH) {
s_trace_buf.state.stats.wr.hist_rd = 0;
}
}
}
#endif
cur_block_marker = ESP_APPTRACE_TRAX_INBLOCK_MARKER_PTR_GET();
cur_block = ESP_APPTRACE_TRAX_INBLOCK_GET();
if (*cur_block_marker + size + sizeof(esp_tracedata_hdr_t) >= cur_block->sz) {
// flush data, we can not unlock apptrace until we have buffer for all user data
// otherwise other tasks/ISRs can get control and write their data between chunks of this data
res = esp_apptrace_trax_block_switch_waitus(/*size + sizeof(esp_tracedata_hdr_t),*/*tmo);
if (res != ESP_OK) {
if (esp_apptrace_unlock() != ESP_OK) {
ESP_APPTRACE_LOGE("Failed to unlock apptrace data!");
// there is a bug, should never get here
}
return NULL;
}
// we switched to new block, update TRAX block pointers
cur_block_marker = ESP_APPTRACE_TRAX_INBLOCK_MARKER_PTR_GET();
cur_block = ESP_APPTRACE_TRAX_INBLOCK_GET();
}
buf_ptr = cur_block->start + *cur_block_marker;
((esp_tracedata_hdr_t *)buf_ptr)->block_sz = size;
((esp_tracedata_hdr_t *)buf_ptr)->wr_sz = 0;
*cur_block_marker += size + sizeof(esp_tracedata_hdr_t);
// now we can safely unlock apptrace to allow other tasks/ISRs to get other buffers and write their data
if (esp_apptrace_unlock() != ESP_OK) {
ESP_APPTRACE_LOGE("Failed to unlock apptrace data!");
// there is a bug, should never get here
}
return buf_ptr + sizeof(esp_tracedata_hdr_t);
}
static esp_err_t esp_apptrace_trax_put_buffer(uint8_t *ptr, uint32_t *tmo)
{
int res = ESP_OK;
esp_tracedata_hdr_t *hdr = (esp_tracedata_hdr_t *)(ptr - sizeof(esp_tracedata_hdr_t));
// update written size
hdr->wr_sz = hdr->block_sz;
// TODO: mark block as busy in order not to re-use it for other tracing calls until it is completely written
// TODO: avoid potential situation when all memory is consumed by low prio tasks which can not complete writing due to
// higher prio tasks and the latter can not allocate buffers at all
// this is abnormal situation can be detected on host which will receive only uncompleted buffers
// workaround: use own memcpy which will kick-off dead tracing calls
return res;
}
static esp_err_t esp_apptrace_trax_flush(uint32_t min_sz, uint32_t tmo)
{
volatile uint32_t *in_block_marker;
int res = ESP_OK;
in_block_marker = ESP_APPTRACE_TRAX_INBLOCK_MARKER_PTR_GET();
if (*in_block_marker > min_sz) {
ESP_APPTRACE_LOGD("Wait until block switch for %u us", tmo);
res = esp_apptrace_trax_block_switch_waitus(/*0 query any size,*/tmo);
if (res != ESP_OK) {
ESP_APPTRACE_LOGE("Failed to switch to another block");
return res;
}
ESP_APPTRACE_LOGD("Flushed last block %u bytes", *in_block_marker);
*in_block_marker = 0;
}
return res;
}
static esp_err_t esp_apptrace_trax_dest_init()
{
for (int i = 0; i < ESP_APPTRACE_TRAX_BLOCKS_NUM; i++) {
s_trace_buf.trax.blocks[i].start = (uint8_t *)s_trax_blocks[i];
s_trace_buf.trax.blocks[i].sz = ESP_APPTRACE_TRAX_BLOCK_SIZE;
s_trace_buf.trax.state.markers[i] = 0;
}
s_trace_buf.trax.state.in_block = ESP_APPTRACE_TRAX_INBLOCK_START;
WRITE_PERI_REG(DPORT_PRO_TRACEMEM_ENA_REG, DPORT_PRO_TRACEMEM_ENA_M);
#if CONFIG_FREERTOS_UNICORE == 0
WRITE_PERI_REG(DPORT_APP_TRACEMEM_ENA_REG, DPORT_APP_TRACEMEM_ENA_M);
#endif
// Expose block 1 to host, block 0 is current trace input buffer
WRITE_PERI_REG(DPORT_TRACEMEM_MUX_MODE_REG, TRACEMEM_MUX_BLK1_ONLY);
return ESP_OK;
}
#endif
esp_err_t esp_apptrace_init()
{
int res;
if (!s_trace_buf.inited) {
res = esp_apptrace_log_init();
if (res != ESP_OK) {
ets_printf("%s: Failed to init log lock (%d)!", TAG, res);
return res;
}
//memset(&s_trace_buf, 0, sizeof(s_trace_buf));
res = esp_apptrace_lock_init(&s_trace_buf.lock);
if (res != ESP_OK) {
ESP_APPTRACE_LOGE("Failed to init log lock (%d)!", res);
esp_apptrace_log_cleanup();
return res;
}
#if CONFIG_ESP32_APPTRACE_DEST_TRAX
res = esp_apptrace_trax_dest_init();
if (res != ESP_OK) {
ESP_APPTRACE_LOGE("Failed to init TRAX dest data (%d)!", res);
esp_apptrace_lock_cleanup();
esp_apptrace_log_cleanup();
return res;
}
#endif
}
#if CONFIG_ESP32_APPTRACE_DEST_TRAX
// init TRAX on this CPU
esp_apptrace_trax_init();
#endif
s_trace_buf.inited |= 1 << xPortGetCoreID(); // global and this CPU-specific data are inited
return ESP_OK;
}
esp_err_t esp_apptrace_write(esp_apptrace_dest_t dest, void *data, size_t size, uint32_t user_tmo)
{
uint8_t *ptr = NULL;
uint32_t tmo = user_tmo;
//TODO: use ptr to HW transport iface struct
uint8_t *(*apptrace_get_buffer)(size_t, uint32_t *);
esp_err_t (*apptrace_put_buffer)(uint8_t *, uint32_t *);
if (dest == ESP_APPTRACE_DEST_TRAX) {
#if CONFIG_ESP32_APPTRACE_DEST_TRAX
apptrace_get_buffer = esp_apptrace_trax_get_buffer;
apptrace_put_buffer = esp_apptrace_trax_put_buffer;
#else
ESP_APPTRACE_LOGE("Application tracing via TRAX is disabled in menuconfig!");
return ESP_ERR_NOT_SUPPORTED;
#endif
} else {
ESP_APPTRACE_LOGE("Trace destinations other then TRAX are not supported yet!");
return ESP_ERR_NOT_SUPPORTED;
}
ptr = apptrace_get_buffer(size, &tmo);
if (ptr == NULL) {
//ESP_APPTRACE_LOGE("Failed to get buffer!");
return ESP_ERR_NO_MEM;
}
// actually can be suspended here by higher prio tasks/ISRs
//TODO: use own memcpy with dead trace calls kick-off algo, and tmo expiration check
memcpy(ptr, data, size);
// now indicate that this buffer is ready to be sent off to host
return apptrace_put_buffer(ptr, &tmo);
}
int esp_apptrace_vprintf_to(esp_apptrace_dest_t dest, uint32_t user_tmo, const char *fmt, va_list ap)
{
uint16_t nargs = 0;
uint8_t *pout, *p = (uint8_t *)fmt;
uint32_t tmo = user_tmo;
//TODO: use ptr to HW transport iface struct
uint8_t *(*apptrace_get_buffer)(size_t, uint32_t *);
esp_err_t (*apptrace_put_buffer)(uint8_t *, uint32_t *);
if (dest == ESP_APPTRACE_DEST_TRAX) {
#if CONFIG_ESP32_APPTRACE_DEST_TRAX
apptrace_get_buffer = esp_apptrace_trax_get_buffer;
apptrace_put_buffer = esp_apptrace_trax_put_buffer;
#else
ESP_APPTRACE_LOGE("Application tracing via TRAX is disabled in menuconfig!");
return ESP_ERR_NOT_SUPPORTED;
#endif
} else {
ESP_APPTRACE_LOGE("Trace destinations other then TRAX are not supported yet!");
return ESP_ERR_NOT_SUPPORTED;
}
// ESP_APPTRACE_LOGI("fmt %x", fmt);
while ((p = (uint8_t *)strchr((char *)p, '%')) && nargs < ESP_APPTRACE_MAX_VPRINTF_ARGS) {
p++;
if (*p != '%' && *p != 0) {
nargs++;
}
}
// ESP_APPTRACE_LOGI("nargs = %d", nargs);
if (p) {
ESP_APPTRACE_LOGE("Failed to store all printf args!");
}
pout = apptrace_get_buffer(1 + sizeof(char *) + nargs * sizeof(uint32_t), &tmo);
if (pout == NULL) {
ESP_APPTRACE_LOGE("Failed to get buffer!");
return -1;
}
p = pout;
*pout = nargs;
pout++;
*(const char **)pout = fmt;
pout += sizeof(char *);
while (nargs-- > 0) {
uint32_t arg = va_arg(ap, uint32_t);
*(uint32_t *)pout = arg;
pout += sizeof(uint32_t);
// ESP_APPTRACE_LOGI("arg %x", arg);
}
int ret = apptrace_put_buffer(p, &tmo);
if (ret != ESP_OK) {
ESP_APPTRACE_LOGE("Failed to put printf buf (%d)!", ret);
return -1;
}
return (pout - p);
}
int esp_apptrace_vprintf(const char *fmt, va_list ap)
{
return esp_apptrace_vprintf_to(ESP_APPTRACE_DEST_TRAX, /*ESP_APPTRACE_TMO_INFINITE*/0, fmt, ap);
}
uint8_t *esp_apptrace_buffer_get(esp_apptrace_dest_t dest, size_t size, uint32_t user_tmo)
{
uint32_t tmo = user_tmo;
//TODO: use ptr to HW transport iface struct
uint8_t *(*apptrace_get_buffer)(size_t, uint32_t *);
if (dest == ESP_APPTRACE_DEST_TRAX) {
#if CONFIG_ESP32_APPTRACE_DEST_TRAX
apptrace_get_buffer = esp_apptrace_trax_get_buffer;
#else
ESP_APPTRACE_LOGE("Application tracing via TRAX is disabled in menuconfig!");
return NULL;
#endif
} else {
ESP_APPTRACE_LOGE("Trace destinations other then TRAX are not supported yet!");
return NULL;
}
return apptrace_get_buffer(size, &tmo);
}
esp_err_t esp_apptrace_buffer_put(esp_apptrace_dest_t dest, uint8_t *ptr, uint32_t user_tmo)
{
uint32_t tmo = user_tmo;
//TODO: use ptr to HW transport iface struct
esp_err_t (*apptrace_put_buffer)(uint8_t *, uint32_t *);
if (dest == ESP_APPTRACE_DEST_TRAX) {
#if CONFIG_ESP32_APPTRACE_DEST_TRAX
apptrace_put_buffer = esp_apptrace_trax_put_buffer;
#else
ESP_APPTRACE_LOGE("Application tracing via TRAX is disabled in menuconfig!");
return ESP_ERR_NOT_SUPPORTED;
#endif
} else {
ESP_APPTRACE_LOGE("Trace destinations other then TRAX are not supported yet!");
return ESP_ERR_NOT_SUPPORTED;
}
return apptrace_put_buffer(ptr, &tmo);
}
esp_err_t esp_apptrace_flush_nolock(esp_apptrace_dest_t dest, uint32_t min_sz, uint32_t tmo)
{
//TODO: use ptr to HW transport iface struct
esp_err_t (*apptrace_flush)(uint32_t, uint32_t);
if (dest == ESP_APPTRACE_DEST_TRAX) {
#if CONFIG_ESP32_APPTRACE_DEST_TRAX
apptrace_flush = esp_apptrace_trax_flush;
#else
ESP_APPTRACE_LOGE("Application tracing via TRAX is disabled in menuconfig!");
return ESP_ERR_NOT_SUPPORTED;
#endif
} else {
ESP_APPTRACE_LOGE("Trace destinations other then TRAX are not supported yet!");
return ESP_ERR_NOT_SUPPORTED;
}
return apptrace_flush(min_sz, tmo);
}
esp_err_t esp_apptrace_flush(esp_apptrace_dest_t dest, uint32_t tmo)
{
int res;
res = esp_apptrace_lock(&tmo);
if (res != ESP_OK) {
ESP_APPTRACE_LOGE("Failed to lock apptrace data (%d)!", res);
return res;
}
res = esp_apptrace_flush_nolock(dest, 0, tmo);
if (res != ESP_OK) {
ESP_APPTRACE_LOGE("Failed to fluch apptrace data (%d)!", res);
}
if (esp_apptrace_unlock() != ESP_OK) {
ESP_APPTRACE_LOGE("Failed to unlock apptrace data (%d)!", res);
}
return res;
}
#if ESP_APPTRACE_DEBUG_STATS_ENABLE == 1
void esp_apptrace_print_stats()
{
uint32_t i;
uint32_t tmo = ESP_APPTRACE_TMO_INFINITE;
esp_apptrace_lock(&tmo);
for (i = s_trace_buf.state.stats.wr.hist_rd; (i < s_trace_buf.state.stats.wr.hist_wr) && (i < ESP_APPTRACE_BUF_HISTORY_DEPTH); i++) {
esp_trace_buffer_wr_hitem_t *hi = (esp_trace_buffer_wr_hitem_t *)&s_trace_buf.state.stats.wr.hist[i];
ESP_APPTRACE_LOGO("hist[%u] = {%x, %x}", i, hi->hnd, hi->ts);
}
if (i == ESP_APPTRACE_BUF_HISTORY_DEPTH) {
for (i = 0; i < s_trace_buf.state.stats.wr.hist_wr; i++) {
esp_trace_buffer_wr_hitem_t *hi = (esp_trace_buffer_wr_hitem_t *)&s_trace_buf.state.stats.wr.hist[i];
ESP_APPTRACE_LOGO("hist[%u] = {%x, %x}", i, hi->hnd, hi->ts);
}
}
esp_apptrace_unlock();
}
#endif
#endif

View file

@ -59,6 +59,7 @@
#include "esp_coexist.h"
#include "esp_panic.h"
#include "esp_core_dump.h"
#include "esp_app_trace.h"
#include "trax.h"
#define STRINGIFY(s) STRINGIFY2(s)
@ -108,20 +109,21 @@ void IRAM_ATTR call_start_cpu0()
::"r"(&_init_start));
rst_reas[0] = rtc_get_reset_reason(0);
#if !CONFIG_FREERTOS_UNICORE
rst_reas[1] = rtc_get_reset_reason(1);
#endif
// from panic handler we can be reset by RWDT or TG0WDT
if (rst_reas[0] == RTCWDT_SYS_RESET || rst_reas[0] == TG0WDT_SYS_RESET
#if !CONFIG_FREERTOS_UNICORE
|| rst_reas[1] == RTCWDT_SYS_RESET || rst_reas[1] == TG0WDT_SYS_RESET
#endif
) {
// stop wdt in case of any
ESP_EARLY_LOGI(TAG, "Stop panic WDT");
) {
esp_panic_wdt_stop();
}
//Clear BSS. Please do not attempt to do any complex stuff (like early logging) before this.
memset(&_bss_start, 0, (&_bss_end - &_bss_start) * sizeof(_bss_start));
/* Unless waking from deep sleep (implying RTC memory is intact), clear RTC bss */
@ -129,7 +131,6 @@ void IRAM_ATTR call_start_cpu0()
memset(&_rtc_bss_start, 0, (&_rtc_bss_end - &_rtc_bss_start) * sizeof(_rtc_bss_start));
}
ESP_EARLY_LOGI(TAG, "Pro cpu up.");
#if !CONFIG_FREERTOS_UNICORE
@ -193,8 +194,8 @@ void start_cpu0_default(void)
{
esp_setup_syscall_table();
//Enable trace memory and immediately start trace.
#if CONFIG_MEMMAP_TRACEMEM
#if CONFIG_MEMMAP_TRACEMEM_TWOBANKS
#if CONFIG_ESP32_TRAX
#if CONFIG_ESP32_TRAX_TWOBANKS
trax_enable(TRAX_ENA_PRO_APP);
#else
trax_enable(TRAX_ENA_PRO);
@ -221,6 +222,12 @@ void start_cpu0_default(void)
_GLOBAL_REENT->_stdin = (FILE*) &__sf_fake_stdin;
_GLOBAL_REENT->_stdout = (FILE*) &__sf_fake_stdout;
_GLOBAL_REENT->_stderr = (FILE*) &__sf_fake_stderr;
#endif
#if CONFIG_ESP32_APPTRACE_ENABLE
esp_err_t err = esp_apptrace_init();
if (err != ESP_OK) {
ESP_EARLY_LOGE(TAG, "Failed to init apptrace module on CPU0 (%d)!", err);
}
#endif
do_global_ctors();
#if CONFIG_INT_WDT
@ -250,8 +257,14 @@ void start_cpu0_default(void)
#if !CONFIG_FREERTOS_UNICORE
void start_cpu1_default(void)
{
#if CONFIG_MEMMAP_TRACEMEM_TWOBANKS
#if CONFIG_ESP32_TRAX_TWOBANKS
trax_start_trace(TRAX_DOWNCOUNT_WORDS);
#endif
#if CONFIG_ESP32_APPTRACE_ENABLE
esp_err_t err = esp_apptrace_init();
if (err != ESP_OK) {
ESP_EARLY_LOGE(TAG, "Failed to init apptrace module on CPU1 (%d)!", err);
}
#endif
// Wait for FreeRTOS initialization to finish on PRO CPU
while (port_xSchedulerRunning[0] == 0) {

View file

@ -0,0 +1,123 @@
// Copyright 2017 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef ESP_APP_TRACE_H_
#define ESP_APP_TRACE_H_
#include <stdarg.h>
#include "esp_err.h"
// infinite waiting timeout
#define ESP_APPTRACE_TMO_INFINITE ((uint32_t)-1)
// Trace memory block size
#define ESP_APPTRACE_TRAX_BLOCK_SIZE 0x4000UL
/**
* Application trace data destinations bits.
*/
typedef enum {
ESP_APPTRACE_DEST_TRAX = 0x1,
ESP_APPTRACE_DEST_UART0 = 0x2,
//ESP_APPTRACE_DEST_UART1 = 0x4,
} esp_apptrace_dest_t;
/**
* @brief Initializes application tracing module.
*
* @note Should be called before any esp_apptrace_xxx call.
*
* @return ESP_OK on success, otherwise \see esp_err_t
*/
esp_err_t esp_apptrace_init();
/**
* @brief Allocates buffer for trace data.
* After data in buffer are ready to be sent off esp_apptrace_buffer_put must be called to indicate it.
*
* @param dest Indicates HW interface to send data.
* @param size Size of data to write to trace buffer.
* @param tmo Timeout for operation (in us). Use ESP_APPTRACE_TMO_INFINITE to wait indefinetly.
*
* @return non-NULL on success, otherwise NULL.
*/
uint8_t *esp_apptrace_buffer_get(esp_apptrace_dest_t dest, size_t size, uint32_t tmo);
/**
* @brief Indicates that the data in buffer are ready to be sent off.
* This function is a counterpart of must be preceeded by esp_apptrace_buffer_get.
*
* @param dest Indicates HW interface to send data. Should be identical to the same parameter in call to esp_apptrace_buffer_get.
* @param ptr Address of trace buffer to release. Should be the value returned by call to esp_apptrace_buffer_get.
* @param tmo Timeout for operation (in us). Use ESP_APPTRACE_TMO_INFINITE to wait indefinetly.
*
* @return ESP_OK on success, otherwise \see esp_err_t
*/
esp_err_t esp_apptrace_buffer_put(esp_apptrace_dest_t dest, uint8_t *ptr, uint32_t tmo);
/**
* @brief Writes data to trace buffer.
*
* @param dest Indicates HW interface to send data.
* @param data Address of data to write to trace buffer.
* @param size Size of data to write to trace buffer.
* @param tmo Timeout for operation (in us). Use ESP_APPTRACE_TMO_INFINITE to wait indefinetly.
*
* @return ESP_OK on success, otherwise \see esp_err_t
*/
esp_err_t esp_apptrace_write(esp_apptrace_dest_t dest, void *data, size_t size, uint32_t tmo);
/**
* @brief vprintf-like function to sent log messages to host via specified HW interface.
*
* @param dest Indicates HW interface to send data.
* @param fmt Address of format string.
* @param ap List of arguments.
*
* @return Number of bytes written.
*/
int esp_apptrace_vprintf_to(esp_apptrace_dest_t dest, uint32_t user_tmo, const char *fmt, va_list ap);
/**
* @brief vprintf-like function to sent log messages to host.
*
* @param fmt Address of format string.
* @param ap List of arguments.
*
* @return Number of bytes written.
*/
int esp_apptrace_vprintf(const char *fmt, va_list ap);
/**
* @brief Flushes remaining data in trace buffer to host.
*
* @param dest Indicates HW interface to flush data on.
* @param tmo Timeout for operation (in us). Use ESP_APPTRACE_TMO_INFINITE to wait indefinetly.
*
* @return ESP_OK on success, otherwise \see esp_err_t
*/
esp_err_t esp_apptrace_flush(esp_apptrace_dest_t dest, uint32_t tmo);
/**
* @brief Flushes remaining data in trace buffer to host without locking internal data.
This is special version of esp_apptrace_flush which should be called from panic handler.
*
* @param dest Indicates HW interface to flush data on.
* @param min_sz Threshold for flushing data. If current filling level is above this value, data will be flushed. TRAX destinations only.
* @param tmo Timeout for operation (in us). Use ESP_APPTRACE_TMO_INFINITE to wait indefinetly.
*
* @return ESP_OK on success, otherwise \see esp_err_t
*/
esp_err_t esp_apptrace_flush_nolock(esp_apptrace_dest_t dest, uint32_t min_sz, uint32_t tmo);
#endif

View file

@ -103,7 +103,33 @@ uint32_t system_get_free_heap_size(void) __attribute__ ((deprecated));
uint32_t esp_random(void);
/**
* @brief Read hardware MAC address.
* @brief Set base MAC address from external storage e.g. flash and EEPROM.
*
* Base MAC address is used to generate the MAC addresses used by the networking interfaces.
* If using base MAC address stored in external storage, call this API to set base MAC
* address from external storage before initializing WiFi/BT/Ethernet.
*
* @param mac base MAC address, length: 6 bytes.
*
* @return ESP_OK on success
*/
esp_err_t esp_base_mac_addr_set_external(uint8_t *mac);
/**
* @brief Return base MAC address set using esp_mac_addr_set_external.
*
* @param mac base MAC address, length: 6 bytes.
*
* Base MAC address is used to generate the MAC addresses used by the networking interfaces.
* If using base MAC address stored in external storage, call this API to set base MAC
* address from external storage before initializing WiFi/BT/Ethernet.
*
* @return ESP_OK on success
*/
esp_err_t esp_base_mac_addr_get_external(uint8_t *mac);
/**
* @brief Read hardware MAC address from efuse.
*
* In WiFi MAC, only ESP32 station MAC is the hardware MAC, ESP32 softAP MAC is a software MAC
* calculated from ESP32 station MAC.

View file

@ -46,7 +46,7 @@
#define ESP_TASKD_EVENT_PRIO (ESP_TASK_PRIO_MAX - 5)
#define ESP_TASKD_EVENT_STACK CONFIG_SYSTEM_EVENT_TASK_STACK_SIZE
#define ESP_TASK_TCPIP_PRIO (ESP_TASK_PRIO_MAX - 7)
#define ESP_TASK_TCPIP_STACK 2048
#define ESP_TASK_TCPIP_STACK CONFIG_TCPIP_TASK_STACK_SIZE
#define ESP_TASK_MAIN_PRIO (ESP_TASK_PRIO_MIN + 1)
#define ESP_TASK_MAIN_STACK CONFIG_MAIN_TASK_STACK_SIZE

View file

@ -20,7 +20,6 @@
#include <stdbool.h>
#include "rom/queue.h"
#include "esp_err.h"
#include "esp_wifi_types.h"
#include "esp_interface.h"
#ifdef __cplusplus

View file

@ -60,15 +60,20 @@ void ets_efuse_program_op(void);
uint32_t ets_efuse_get_8M_clock(void);
/**
* @brief Read spi pad configuration, show gpio number of flash pad, includes 5 pads.
* @brief Read spi flash pin configuration from Efuse
*
* @param null
*
* @return uint32_t: 0, invalid, flash pad decided by strapping
* else, bit[5:0] spiclk, bit[11:6] spiq, bit[17:12] spid, bit[23:18] spics0, bit[29:24] spihd
* @return
* - 0 for default SPI pins.
* - 1 for default HSPI pins.
* - Other values define a custom pin configuration mask. Pins are encoded as per the EFUSE_SPICONFIG_RET_SPICLK,
* EFUSE_SPICONFIG_RET_SPIQ, EFUSE_SPICONFIG_RET_SPID, EFUSE_SPICONFIG_RET_SPICS0, EFUSE_SPICONFIG_RET_SPIHD macros.
* WP pin (for quad I/O modes) is not saved in efuse and not returned by this function.
*/
uint32_t ets_efuse_get_spiconfig(void);
#define EFUSE_SPICONFIG_SPI_DEFAULTS 0
#define EFUSE_SPICONFIG_HSPI_DEFAULTS 1
#define EFUSE_SPICONFIG_RET_SPICLK_MASK 0x3f
#define EFUSE_SPICONFIG_RET_SPICLK_SHIFT 0
#define EFUSE_SPICONFIG_RET_SPICLK(ret) (((ret) >> EFUSE_SPICONFIG_RET_SPICLK_SHIFT) & EFUSE_SPICONFIG_RET_SPICLK_MASK)

View file

@ -279,25 +279,13 @@ esp_rom_spiflash_result_t esp_rom_spiflash_read_user_cmd(uint32_t *status, uint8
*
* @param esp_rom_spiflash_read_mode_t mode : QIO/QOUT/DIO/DOUT/FastRD/SlowRD.
*
* @param uint8_t legacy: In legacy mode, more SPI command is used in line.
* This function does not try to set the QIO Enable bit in the status register, caller is responsible for this.
*
* @return ESP_ROM_SPIFLASH_RESULT_OK : config OK.
* ESP_ROM_SPIFLASH_RESULT_ERR : config error.
* ESP_ROM_SPIFLASH_RESULT_TIMEOUT : config timeout.
*/
esp_rom_spiflash_result_t esp_rom_spiflash_config_readmode(esp_rom_spiflash_read_mode_t mode, bool legacy);
/**
* @brief Config SPI Flash read mode when Flash is running in some mode.
* Please do not call this function in SDK.
*
* @param esp_rom_spiflash_read_mode_t mode : QIO/QOUT/DIO/DOUT/FastRD/SlowRD.
*
* @return ESP_ROM_SPIFLASH_RESULT_OK : config OK.
* ESP_ROM_SPIFLASH_RESULT_ERR : config error.
* ESP_ROM_SPIFLASH_RESULT_TIMEOUT : config timeout.
*/
esp_rom_spiflash_result_t esp_rom_spiflash_master_config_readmode(esp_rom_spiflash_read_mode_t mode);
esp_rom_spiflash_result_t esp_rom_spiflash_config_readmode(esp_rom_spiflash_read_mode_t mode);
/**
* @brief Config SPI Flash clock divisor.
@ -524,6 +512,24 @@ esp_rom_spiflash_result_t esp_rom_spiflash_write_encrypted(uint32_t flash_addr,
esp_rom_spiflash_result_t esp_rom_spiflash_wait_idle(esp_rom_spiflash_chip_t *spi);
/** @brief Enable Quad I/O pin functions
*
* @note Please do not call this function in SDK.
*
* Sets the HD & WP pin functions for Quad I/O modes, based on the
* efuse SPI pin configuration.
*
* @param wp_gpio_num - Number of the WP pin to reconfigure for quad I/O.
*
* @param spiconfig - Pin configuration, as returned from ets_efuse_get_spiconfig().
* - If this parameter is 0, default SPI pins are used and wp_gpio_num parameter is ignored.
* - If this parameter is 1, default HSPI pins are used and wp_gpio_num parameter is ignored.
* - For other values, this parameter encodes the HD pin number and also the CLK pin number. CLK pin selection is used
* to determine if HSPI or SPI peripheral will be used (use HSPI if CLK pin is the HSPI clock pin, otherwise use SPI).
* Both HD & WP pins are configured via GPIO matrix to map to the selected peripheral.
*/
void esp_rom_spiflash_select_qio_pins(uint8_t wp_gpio_num, uint32_t spiconfig);
/** @brief Global esp_rom_spiflash_chip_t structure used by ROM functions
*
*/

View file

@ -86,16 +86,11 @@ SECTIONS
*libesp32.a:panic.o(.literal .text .literal.* .text.*)
*libesp32.a:core_dump.o(.literal .text .literal.* .text.*)
*libesp32.a:heap_alloc_caps.o(.literal .text .literal.* .text.*)
*libesp32.a:app_trace.o(.literal .text .literal.* .text.*)
*libphy.a:(.literal .text .literal.* .text.*)
*librtc.a:(.literal .text .literal.* .text.*)
*libsoc.a:(.literal .text .literal.* .text.*)
*libpp.a:pp.o(.literal .text .literal.* .text.*)
*libpp.a:lmac.o(.literal .text .literal.* .text.*)
*libpp.a:wdev.o(.literal .text .literal.* .text.*)
*libcore.a:ets_timer.o(.literal .text .literal.* .text.*)
*libnet80211.a:ieee80211_misc.o(.literal .text .literal.* .text.*)
*libhal.a:(.literal .text .literal.* .text.*)
*libcoexist.a:(.literal .text .literal.* .text.*)
*libspi_flash.a:spi_flash_rom_patch.o(.literal .text .literal.* .text.*)
_iram_text_end = ABSOLUTE(.);
} > iram0_0_seg
@ -116,6 +111,8 @@ SECTIONS
KEEP(*(.jcr))
*(.dram1 .dram1.*)
*libesp32.a:panic.o(.rodata .rodata.*)
*libesp32.a:app_trace.o(.rodata .rodata.*)
*libphy.a:(.rodata .rodata.*)
_data_end = ABSOLUTE(.);
. = ALIGN(4);
} >dram0_0_seg

View file

@ -1537,6 +1537,7 @@ PROVIDE ( esp_rom_spiflash_read_user_cmd = 0x400621b0 );
PROVIDE ( esp_rom_spiflash_write_encrypted_disable = 0x40062e60 );
PROVIDE ( esp_rom_spiflash_write_encrypted_enable = 0x40062df4 );
PROVIDE ( esp_rom_spiflash_prepare_encrypted_data = 0x40062e1c );
PROVIDE ( esp_rom_spiflash_select_qio_pins = 0x40061ddc );
PROVIDE ( g_rom_spiflash_chip = 0x3ffae270 );
/*

View file

@ -10,7 +10,7 @@ PROVIDE ( esp_rom_spiflash_erase_chip = 0x40062c14 );
PROVIDE ( esp_rom_spiflash_erase_sector = 0x40062ccc );
PROVIDE ( esp_rom_spiflash_lock = 0x400628f0 );
PROVIDE ( esp_rom_spiflash_read = 0x40062ed8 );
PROVIDE ( esp_rom_spiflash_config_readmode = 0x40062944 );
PROVIDE ( esp_rom_spiflash_config_readmode = 0x40062b64 ); /* SPIMasterReadModeCnfig */
PROVIDE ( esp_rom_spiflash_read_status = 0x4006226c );
PROVIDE ( esp_rom_spiflash_read_statushigh = 0x40062448 );
PROVIDE ( esp_rom_spiflash_write = 0x40062d50 );

@ -1 +1 @@
Subproject commit 7910a6872bbdd50e0184cfc5bd2a9a2040231a1b
Subproject commit 53aac75afe219af9feca42aca7f1126d394844c9

View file

@ -38,6 +38,7 @@
#include "esp_core_dump.h"
#include "esp_spi_flash.h"
#include "esp_cache_err_int.h"
#include "esp_app_trace.h"
/*
Panic handlers; these get called when an unhandled exception occurs or the assembly-level
@ -114,6 +115,9 @@ static bool abort_called;
static __attribute__((noreturn)) inline void invoke_abort()
{
abort_called = true;
#if CONFIG_ESP32_APPTRACE_ENABLE
esp_apptrace_flush_nolock(ESP_APPTRACE_DEST_TRAX, ESP_APPTRACE_TRAX_BLOCK_SIZE*CONFIG_ESP32_APPTRACE_ONPANIC_HOST_FLUSH_TRAX_THRESH/100, CONFIG_ESP32_APPTRACE_ONPANIC_HOST_FLUSH_TMO);
#endif
while(1) {
__asm__ ("break 0,0");
*((int*) 0) = 0;
@ -226,6 +230,9 @@ void panicHandler(XtExcFrame *frame)
}
if (esp_cpu_in_ocd_debug_mode()) {
#if CONFIG_ESP32_APPTRACE_ENABLE
esp_apptrace_flush_nolock(ESP_APPTRACE_DEST_TRAX, ESP_APPTRACE_TRAX_BLOCK_SIZE*CONFIG_ESP32_APPTRACE_ONPANIC_HOST_FLUSH_TRAX_THRESH/100, CONFIG_ESP32_APPTRACE_ONPANIC_HOST_FLUSH_TMO);
#endif
setFirstBreakpoint(frame->pc);
return;
}
@ -248,6 +255,9 @@ void xt_unhandled_exception(XtExcFrame *frame)
panicPutStr(" at pc=");
panicPutHex(frame->pc);
panicPutStr(". Setting bp and returning..\r\n");
#if CONFIG_ESP32_APPTRACE_ENABLE
esp_apptrace_flush_nolock(ESP_APPTRACE_DEST_TRAX, ESP_APPTRACE_TRAX_BLOCK_SIZE*CONFIG_ESP32_APPTRACE_ONPANIC_HOST_FLUSH_TRAX_THRESH/100, CONFIG_ESP32_APPTRACE_ONPANIC_HOST_FLUSH_TMO);
#endif
//Stick a hardware breakpoint on the address the handler returns to. This way, the OCD debugger
//will kick in exactly at the context the error happened.
setFirstBreakpoint(frame->pc);
@ -282,11 +292,10 @@ static void reconfigureAllWdts()
TIMERG1.wdt_wprotect = 0;
}
#if CONFIG_ESP32_PANIC_GDBSTUB || CONFIG_ESP32_PANIC_PRINT_HALT || CONFIG_ESP32_ENABLE_COREDUMP
/*
This disables all the watchdogs for when we call the gdbstub.
*/
static void disableAllWdts()
static inline void disableAllWdts()
{
TIMERG0.wdt_wprotect = TIMG_WDT_WKEY_VALUE;
TIMERG0.wdt_config0.en = 0;
@ -296,8 +305,6 @@ static void disableAllWdts()
TIMERG1.wdt_wprotect = 0;
}
#endif
static void esp_panic_wdt_start()
{
if (REG_GET_BIT(RTC_CNTL_WDTCONFIG0_REG, RTC_CNTL_WDT_EN)) {
@ -422,6 +429,12 @@ static void commonErrorHandler(XtExcFrame *frame)
/* With windowed ABI backtracing is easy, let's do it. */
doBacktrace(frame);
#if CONFIG_ESP32_APPTRACE_ENABLE
disableAllWdts();
esp_apptrace_flush_nolock(ESP_APPTRACE_DEST_TRAX, ESP_APPTRACE_TRAX_BLOCK_SIZE*CONFIG_ESP32_APPTRACE_ONPANIC_HOST_FLUSH_TRAX_THRESH/100, CONFIG_ESP32_APPTRACE_ONPANIC_HOST_FLUSH_TMO);
reconfigureAllWdts();
#endif
#if CONFIG_ESP32_PANIC_GDBSTUB
disableAllWdts();
esp_panic_wdt_stop();

View file

@ -36,16 +36,48 @@
static const char* TAG = "system_api";
static uint8_t ext_base_mac_addr[6] = {0};
void system_init()
{
}
esp_err_t esp_base_mac_addr_set_external(uint8_t *mac)
{
if (mac == NULL) {
ESP_LOGE(TAG, "External base MAC address is NULL");
abort();
}
memcpy(ext_base_mac_addr, mac, 6);
return ESP_OK;
}
esp_err_t esp_base_mac_addr_get_external(uint8_t *mac)
{
uint8_t null_mac[6] = {0};
if (memcmp(ext_base_mac_addr, null_mac, 6) == 0) {
ESP_LOGE(TAG, "External MAC address is not set");
abort();
}
memcpy(mac, ext_base_mac_addr, 6);
return ESP_OK;
}
esp_err_t esp_efuse_read_mac(uint8_t* mac)
{
uint32_t mac_low;
uint32_t mac_high;
uint8_t efuse_crc;
uint8_t calc_crc;
uint32_t mac_low = REG_READ(EFUSE_BLK0_RDATA1_REG);
uint32_t mac_high = REG_READ(EFUSE_BLK0_RDATA2_REG);
#ifdef CONFIG_BASE_MAC_STORED_DEFAULT_EFUSE
mac_low = REG_READ(EFUSE_BLK0_RDATA1_REG);
mac_high = REG_READ(EFUSE_BLK0_RDATA2_REG);
mac[0] = mac_high >> 8;
mac[1] = mac_high;
@ -55,6 +87,27 @@ esp_err_t esp_efuse_read_mac(uint8_t* mac)
mac[5] = mac_low;
efuse_crc = mac_high >> 16;
#else
uint8_t version = REG_READ(EFUSE_BLK3_RDATA5_REG) >> 24;
if (version != 1) {
ESP_LOGE(TAG, "Customer efuse MAC address version error, version = %d", version);
abort();
}
mac_low = REG_READ(EFUSE_BLK3_RDATA1_REG);
mac_high = REG_READ(EFUSE_BLK3_RDATA0_REG);
mac[0] = mac_high >> 8;
mac[1] = mac_high >> 16;
mac[2] = mac_high >> 24;
mac[3] = mac_low;
mac[4] = mac_low >> 8;
mac[5] = mac_low >> 16;
efuse_crc = mac_high;
#endif //CONFIG_BASE_MAC_STORED_DEFAULT_EFUSE
calc_crc = esp_crc8(mac, 6);
if (efuse_crc != calc_crc) {
@ -114,7 +167,13 @@ esp_err_t esp_read_mac(uint8_t* mac, esp_mac_type_t type)
|| NUM_MAC_ADDRESS_FROM_EFUSE == TWO_MAC_ADDRESS_FROM_EFUSE, \
"incorrect NUM_MAC_ADDRESS_FROM_EFUSE value");
#if defined(CONFIG_BASE_MAC_STORED_DEFAULT_EFUSE) || defined(CONFIG_BASE_MAC_STORED_CUSTOMER_DEFINED_EFUSE)
esp_efuse_read_mac(efuse_mac);
#endif
#if defined(CONFIG_BASE_MAC_STORED_OTHER_CUSTOMER_DEFINED_PLACE)
esp_base_mac_addr_get_external(efuse_mac);
#endif
switch (type) {
case ESP_MAC_WIFI_STA:

View file

@ -0,0 +1,817 @@
#include <stddef.h>
#include <stdint.h>
#include <string.h>
#include <stdio.h>
#include <stdarg.h>
#include "unity.h"
#include "driver/timer.h"
#include "freertos/FreeRTOS.h"
#include "freertos/semphr.h"
#include "freertos/task.h"
#if CONFIG_ESP32_APPTRACE_ENABLE == 1
#include "esp_app_trace.h"
#define ESP_APPTRACE_TEST_USE_PRINT_LOCK 0
#define ESP_APPTRACE_TEST_PRN_WRERR_MAX 5
#define ESP_APPTRACE_TEST_BLOCKS_BEFORE_CRASH 100
#define ESP_APPTRACE_TEST_BLOCK_SIZE 1024
#define LOG_LOCAL_LEVEL ESP_LOG_VERBOSE
#include "esp_log.h"
const static char *TAG = "esp_apptrace_test";
#if ESP_APPTRACE_TEST_USE_PRINT_LOCK == 1
#define ESP_APPTRACE_TEST_LOG( format, ... ) \
do { \
BaseType_t ret; \
if (xPortInIsrContext()) \
ret = xSemaphoreTakeFromISR(s_print_lock, NULL); \
else \
ret = xSemaphoreTake(s_print_lock, portMAX_DELAY); \
if (ret == pdTRUE) { \
ets_printf(format, ##__VA_ARGS__); \
if (xPortInIsrContext()) \
xSemaphoreGiveFromISR(s_print_lock, NULL); \
else \
xSemaphoreGive(s_print_lock); \
} \
} while(0)
#else
#define ESP_APPTRACE_TEST_LOG( format, ... ) \
do { \
ets_printf(format, ##__VA_ARGS__); \
} while(0)
#endif
#define ESP_APPTRACE_TEST_LOG_LEVEL( _L_, level, format, ... ) \
do { \
if (LOG_LOCAL_LEVEL >= level) { \
ESP_APPTRACE_TEST_LOG(LOG_FORMAT(_L_, format), esp_log_early_timestamp(), TAG, ##__VA_ARGS__); \
} \
} while(0)
#define ESP_APPTRACE_TEST_LOGE( format, ... ) ESP_APPTRACE_TEST_LOG_LEVEL(E, ESP_LOG_ERROR, format, ##__VA_ARGS__)
#define ESP_APPTRACE_TEST_LOGW( format, ... ) ESP_APPTRACE_TEST_LOG_LEVEL(W, ESP_LOG_WARN, format, ##__VA_ARGS__)
#define ESP_APPTRACE_TEST_LOGI( format, ... ) ESP_APPTRACE_TEST_LOG_LEVEL(I, ESP_LOG_INFO, format, ##__VA_ARGS__)
#define ESP_APPTRACE_TEST_LOGD( format, ... ) ESP_APPTRACE_TEST_LOG_LEVEL(D, ESP_LOG_DEBUG, format, ##__VA_ARGS__)
#define ESP_APPTRACE_TEST_LOGV( format, ... ) ESP_APPTRACE_TEST_LOG_LEVEL(V, ESP_LOG_VERBOSE, format, ##__VA_ARGS__)
#define ESP_APPTRACE_TEST_LOGO( format, ... ) ESP_APPTRACE_TEST_LOG_LEVEL(E, ESP_LOG_NONE, format, ##__VA_ARGS__)
#define ESP_APPTRACE_TEST_WRITE(_b_, _s_) esp_apptrace_write(ESP_APPTRACE_DEST_TRAX, _b_, _s_, ESP_APPTRACE_TMO_INFINITE)
#define ESP_APPTRACE_TEST_WRITE_FROM_ISR(_b_, _s_) esp_apptrace_write(ESP_APPTRACE_DEST_TRAX, _b_, _s_, 100UL)
#define ESP_APPTRACE_TEST_WRITE_NOWAIT(_b_, _s_) esp_apptrace_write(ESP_APPTRACE_DEST_TRAX, _b_, _s_, 0)
#define ESP_APPTRACE_TEST_CPUTICKS2US(_t_) ((_t_)/(XT_CLOCK_FREQ/1000000))
typedef struct {
uint8_t *buf;
uint32_t buf_sz;
uint8_t mask;
uint32_t period; // trace write period in us
uint32_t wr_err;
uint32_t wr_cnt;
} esp_apptrace_test_gen_data_t;
typedef struct {
int group;
int id;
void (*isr_func)(void *);
esp_apptrace_test_gen_data_t data;
} esp_apptrace_test_timer_arg_t;
typedef struct {
int nowait;
int core;
int prio;
void (*task_func)(void *);
esp_apptrace_test_gen_data_t data;
volatile int stop;
SemaphoreHandle_t done;
uint32_t timers_num;
esp_apptrace_test_timer_arg_t *timers;
} esp_apptrace_test_task_arg_t;
typedef struct {
uint32_t tasks_num;
esp_apptrace_test_task_arg_t *tasks;
} esp_apptrace_test_cfg_t;
#if ESP_APPTRACE_TEST_USE_PRINT_LOCK == 1
static SemaphoreHandle_t s_print_lock;
#endif
static uint64_t esp_apptrace_test_ts_get();
static void esp_apptrace_test_timer_init(int timer_group, int timer_idx, uint32_t period)
{
timer_config_t config;
uint64_t alarm_val = (period * (TIMER_BASE_CLK / 1000000UL)) / 2;
config.alarm_en = 1;
config.auto_reload = 1;
config.counter_dir = TIMER_COUNT_UP;
config.divider = 1;
config.intr_type = TIMER_INTR_LEVEL;
config.counter_en = TIMER_PAUSE;
/*Configure timer*/
timer_init(timer_group, timer_idx, &config);
/*Stop timer counter*/
timer_pause(timer_group, timer_idx);
/*Load counter value */
timer_set_counter_value(timer_group, timer_idx, 0x00000000ULL);
/*Set alarm value*/
timer_set_alarm_value(timer_group, timer_idx, alarm_val);
/*Enable timer interrupt*/
timer_enable_intr(timer_group, timer_idx);
}
static void esp_apptrace_test_timer_isr(void *arg)
{
esp_apptrace_test_timer_arg_t *tim_arg = (esp_apptrace_test_timer_arg_t *)arg;
uint32_t *ts = (uint32_t *)(tim_arg->data.buf + sizeof(uint32_t));
*ts = (uint32_t)esp_apptrace_test_ts_get();
memset(tim_arg->data.buf + 2 * sizeof(uint32_t), tim_arg->data.wr_cnt & tim_arg->data.mask, tim_arg->data.buf_sz - 2 * sizeof(uint32_t));
int res = ESP_APPTRACE_TEST_WRITE_FROM_ISR(tim_arg->data.buf, tim_arg->data.buf_sz);
if (res != ESP_OK) {
} else {
if (0) {
ets_printf("tim-%d-%d: Written chunk%d %d bytes, %x\n",
tim_arg->group, tim_arg->id, tim_arg->data.wr_cnt, tim_arg->data.buf_sz, tim_arg->data.wr_cnt & tim_arg->data.mask);
}
tim_arg->data.wr_err = 0;
}
tim_arg->data.wr_cnt++;
if (tim_arg->group == 0) {
if (tim_arg->id == 0) {
TIMERG0.int_clr_timers.t0 = 1;
TIMERG0.hw_timer[0].update = 1;
TIMERG0.hw_timer[0].config.alarm_en = 1;
} else {
TIMERG0.int_clr_timers.t1 = 1;
TIMERG0.hw_timer[1].update = 1;
TIMERG0.hw_timer[1].config.alarm_en = 1;
}
}
if (tim_arg->group == 1) {
if (tim_arg->id == 0) {
TIMERG1.int_clr_timers.t0 = 1;
TIMERG1.hw_timer[0].update = 1;
TIMERG1.hw_timer[0].config.alarm_en = 1;
} else {
TIMERG1.int_clr_timers.t1 = 1;
TIMERG1.hw_timer[1].update = 1;
TIMERG1.hw_timer[1].config.alarm_en = 1;
}
}
}
static void esp_apptrace_test_timer_isr_crash(void *arg)
{
esp_apptrace_test_timer_arg_t *tim_arg = (esp_apptrace_test_timer_arg_t *)arg;
if (tim_arg->group == 0) {
if (tim_arg->id == 0) {
TIMERG0.int_clr_timers.t0 = 1;
TIMERG0.hw_timer[0].update = 1;
TIMERG0.hw_timer[0].config.alarm_en = 1;
} else {
TIMERG0.int_clr_timers.t1 = 1;
TIMERG0.hw_timer[1].update = 1;
TIMERG0.hw_timer[1].config.alarm_en = 1;
}
}
if (tim_arg->group == 1) {
if (tim_arg->id == 0) {
TIMERG1.int_clr_timers.t0 = 1;
TIMERG1.hw_timer[0].update = 1;
TIMERG1.hw_timer[0].config.alarm_en = 1;
} else {
TIMERG1.int_clr_timers.t1 = 1;
TIMERG1.hw_timer[1].update = 1;
TIMERG1.hw_timer[1].config.alarm_en = 1;
}
}
if (tim_arg->data.wr_cnt < ESP_APPTRACE_TEST_BLOCKS_BEFORE_CRASH) {
uint32_t *ts = (uint32_t *)(tim_arg->data.buf + sizeof(uint32_t));
*ts = (uint32_t)esp_apptrace_test_ts_get();//xthal_get_ccount();//xTaskGetTickCount();
memset(tim_arg->data.buf + 2 * sizeof(uint32_t), tim_arg->data.wr_cnt & tim_arg->data.mask, tim_arg->data.buf_sz - 2 * sizeof(uint32_t));
int res = ESP_APPTRACE_TEST_WRITE_FROM_ISR(tim_arg->data.buf, tim_arg->data.buf_sz);
if (res != ESP_OK) {
ets_printf("tim-%d-%d: Failed to write trace %d %x!\n", tim_arg->group, tim_arg->id, res, tim_arg->data.wr_cnt & tim_arg->data.mask);
} else {
ets_printf("tim-%d-%d: Written chunk%d %d bytes, %x\n",
tim_arg->group, tim_arg->id, tim_arg->data.wr_cnt, tim_arg->data.buf_sz, tim_arg->data.wr_cnt & tim_arg->data.mask);
tim_arg->data.wr_cnt++;
}
} else {
uint32_t *ptr = 0;
*ptr = 1000;
}
}
static void esp_apptrace_dummy_task(void *p)
{
esp_apptrace_test_task_arg_t *arg = (esp_apptrace_test_task_arg_t *) p;
int res, flags = 0, i;
timer_isr_handle_t *inth = NULL;
TickType_t tmo_ticks = arg->data.period / (1000 * portTICK_PERIOD_MS);
ESP_APPTRACE_TEST_LOGI("%x: run dummy task (period %u us, %u timers)", xTaskGetCurrentTaskHandle(), arg->data.period, arg->timers_num);
if (arg->timers_num > 0) {
inth = pvPortMalloc(arg->timers_num * sizeof(timer_isr_handle_t));
if (!inth) {
ESP_APPTRACE_TEST_LOGE("Failed to alloc timer ISR handles!");
goto on_fail;
}
memset(inth, 0, arg->timers_num * sizeof(timer_isr_handle_t));
for (int i = 0; i < arg->timers_num; i++) {
esp_apptrace_test_timer_init(arg->timers[i].group, arg->timers[i].id, arg->timers[i].data.period);
res = timer_isr_register(arg->timers[i].group, arg->timers[i].id, arg->timers[i].isr_func, &arg->timers[i], flags, &inth[i]);
if (res != ESP_OK) {
ESP_APPTRACE_TEST_LOGE("Failed to timer_isr_register (%d)!", res);
goto on_fail;
}
*(uint32_t *)arg->timers[i].data.buf = (uint32_t)inth[i] | (1 << 31);
ESP_APPTRACE_TEST_LOGI("%x: start timer %x period %u us", xTaskGetCurrentTaskHandle(), inth[i], arg->timers[i].data.period);
res = timer_start(arg->timers[i].group, arg->timers[i].id);
if (res != ESP_OK) {
ESP_APPTRACE_TEST_LOGE("Failed to timer_start (%d)!", res);
goto on_fail;
}
}
}
i = 0;
while (!arg->stop) {
ESP_APPTRACE_TEST_LOGD("%x: dummy task work %d.%d", xTaskGetCurrentTaskHandle(), xPortGetCoreID(), i++);
if (tmo_ticks) {
vTaskDelay(tmo_ticks);
}
}
on_fail:
if (inth) {
for (int i = 0; i < arg->timers_num; i++) {
timer_pause(arg->timers[i].group, arg->timers[i].id);
timer_disable_intr(arg->timers[i].group, arg->timers[i].id);
if (inth[i]) {
esp_intr_free(inth[i]);
}
}
vPortFree(inth);
}
xSemaphoreGive(arg->done);
vTaskDelay(1);
vTaskDelete(NULL);
}
static void esp_apptrace_test_task(void *p)
{
esp_apptrace_test_task_arg_t *arg = (esp_apptrace_test_task_arg_t *) p;
int res, flags = 0;
timer_isr_handle_t *inth = NULL;
TickType_t tmo_ticks = arg->data.period / (1000 * portTICK_PERIOD_MS);
ESP_APPTRACE_TEST_LOGI("%x: run (period %u us, stamp mask %x, %u timers)", xTaskGetCurrentTaskHandle(), arg->data.period, arg->data.mask, arg->timers_num);
if (arg->timers_num > 0) {
inth = pvPortMalloc(arg->timers_num * sizeof(timer_isr_handle_t));
if (!inth) {
ESP_APPTRACE_TEST_LOGE("Failed to alloc timer ISR handles!");
goto on_fail;
}
memset(inth, 0, arg->timers_num * sizeof(timer_isr_handle_t));
for (int i = 0; i < arg->timers_num; i++) {
esp_apptrace_test_timer_init(arg->timers[i].group, arg->timers[i].id, arg->timers[i].data.period);
res = timer_isr_register(arg->timers[i].group, arg->timers[i].id, arg->timers[i].isr_func, &arg->timers[i], flags, &inth[i]);
if (res != ESP_OK) {
ESP_APPTRACE_TEST_LOGE("Failed to timer_isr_register (%d)!", res);
goto on_fail;
}
*(uint32_t *)arg->timers[i].data.buf = ((uint32_t)inth[i]) | (1 << 31) | (xPortGetCoreID() ? 0x1 : 0);
ESP_APPTRACE_TEST_LOGI("%x: start timer %x period %u us", xTaskGetCurrentTaskHandle(), inth[i], arg->timers[i].data.period);
res = timer_start(arg->timers[i].group, arg->timers[i].id);
if (res != ESP_OK) {
ESP_APPTRACE_TEST_LOGE("Failed to timer_start (%d)!", res);
goto on_fail;
}
}
}
*(uint32_t *)arg->data.buf = (uint32_t)xTaskGetCurrentTaskHandle() | (xPortGetCoreID() ? 0x1 : 0);
arg->data.wr_cnt = 0;
arg->data.wr_err = 0;
while (!arg->stop) {
uint32_t *ts = (uint32_t *)(arg->data.buf + sizeof(uint32_t));
*ts = (uint32_t)esp_apptrace_test_ts_get();
memset(arg->data.buf + 2 * sizeof(uint32_t), arg->data.wr_cnt & arg->data.mask, arg->data.buf_sz - 2 * sizeof(uint32_t));
if (arg->nowait) {
res = ESP_APPTRACE_TEST_WRITE_NOWAIT(arg->data.buf, arg->data.buf_sz);
} else {
res = ESP_APPTRACE_TEST_WRITE(arg->data.buf, arg->data.buf_sz);
}
if (res) {
if (arg->data.wr_err++ < ESP_APPTRACE_TEST_PRN_WRERR_MAX) {
ESP_APPTRACE_TEST_LOGE("%x: Failed to write trace %d %x!", xTaskGetCurrentTaskHandle(), res, arg->data.wr_cnt & arg->data.mask);
if (arg->data.wr_err == ESP_APPTRACE_TEST_PRN_WRERR_MAX) {
ESP_APPTRACE_TEST_LOGE("\n");
}
}
} else {
if (0) {
ESP_APPTRACE_TEST_LOGD("%x:%x: Written chunk%d %d bytes, %x", xTaskGetCurrentTaskHandle(), *ts, arg->data.wr_cnt, arg->data.buf_sz, arg->data.wr_cnt & arg->data.mask);
}
arg->data.wr_err = 0;
}
arg->data.wr_cnt++;
if (tmo_ticks) {
vTaskDelay(tmo_ticks);
}
}
on_fail:
if (inth) {
for (int i = 0; i < arg->timers_num; i++) {
timer_pause(arg->timers[i].group, arg->timers[i].id);
timer_disable_intr(arg->timers[i].group, arg->timers[i].id);
if (inth[i]) {
esp_intr_free(inth[i]);
}
}
vPortFree(inth);
}
xSemaphoreGive(arg->done);
vTaskDelay(1);
vTaskDelete(NULL);
}
static void esp_apptrace_test_task_crash(void *p)
{
esp_apptrace_test_task_arg_t *arg = (esp_apptrace_test_task_arg_t *) p;
int res, i;
ESP_APPTRACE_TEST_LOGE("%x: run (period %u us, stamp mask %x, %u timers)", xTaskGetCurrentTaskHandle(), arg->data.period, arg->data.mask, arg->timers_num);
arg->data.wr_cnt = 0;
*(uint32_t *)arg->data.buf = (uint32_t)xTaskGetCurrentTaskHandle();
for (i = 0; i < ESP_APPTRACE_TEST_BLOCKS_BEFORE_CRASH; i++) {
uint32_t *ts = (uint32_t *)(arg->data.buf + sizeof(uint32_t));
*ts = (uint32_t)esp_apptrace_test_ts_get();
memset(arg->data.buf + sizeof(uint32_t), arg->data.wr_cnt & arg->data.mask, arg->data.buf_sz - sizeof(uint32_t));
res = ESP_APPTRACE_TEST_WRITE(arg->data.buf, arg->data.buf_sz);
if (res) {
ESP_APPTRACE_TEST_LOGE("%x: Failed to write trace %d %x!", xTaskGetCurrentTaskHandle(), res, arg->data.wr_cnt & arg->data.mask);
} else {
ESP_APPTRACE_TEST_LOGD("%x: Written chunk%d %d bytes, %x", xTaskGetCurrentTaskHandle(), arg->data.wr_cnt, arg->data.buf_sz, arg->data.wr_cnt & arg->data.mask);
}
arg->data.wr_cnt++;
}
vTaskDelay(500);
uint32_t *ptr = 0;
*ptr = 1000;
xSemaphoreGive(arg->done);
vTaskDelay(1);
vTaskDelete(NULL);
}
static int s_ts_timer_group, s_ts_timer_idx;
static uint64_t esp_apptrace_test_ts_get()
{
uint64_t ts = 0;
timer_get_counter_value(s_ts_timer_group, s_ts_timer_idx, &ts);
return ts;
}
static void esp_apptrace_test_ts_init(int timer_group, int timer_idx)
{
timer_config_t config;
//uint64_t alarm_val = period * (TIMER_BASE_CLK / 1000000UL);
ESP_APPTRACE_TEST_LOGI("Use timer%d.%d for TS", timer_group, timer_idx);
s_ts_timer_group = timer_group;
s_ts_timer_idx = timer_idx;
config.alarm_en = 0;
config.auto_reload = 0;
config.counter_dir = TIMER_COUNT_UP;
config.divider = 1;
config.counter_en = 0;
/*Configure timer*/
timer_init(timer_group, timer_idx, &config);
/*Load counter value */
timer_set_counter_value(timer_group, timer_idx, 0x00000000ULL);
/*Enable timer interrupt*/
timer_start(timer_group, timer_idx);
}
static void esp_apptrace_test_ts_cleanup()
{
timer_config_t config;
config.alarm_en = 0;
config.auto_reload = 0;
config.counter_dir = TIMER_COUNT_UP;
config.divider = 1;
config.counter_en = 0;
/*Configure timer*/
timer_init(s_ts_timer_group, s_ts_timer_idx, &config);
}
static void esp_apptrace_test(esp_apptrace_test_cfg_t *test_cfg)
{
int i, k;
int tims_in_use[TIMER_GROUP_MAX][TIMER_MAX] = {{0, 0}, {0, 0}};
esp_apptrace_test_task_arg_t dummy_task_arg[1];
memset(dummy_task_arg, 0, sizeof(dummy_task_arg));
dummy_task_arg[0].core = 0;
dummy_task_arg[0].prio = 3;
dummy_task_arg[0].task_func = esp_apptrace_test_task_crash;
dummy_task_arg[0].data.buf = NULL;
dummy_task_arg[0].data.buf_sz = 0;
dummy_task_arg[0].data.period = 500000;
dummy_task_arg[0].timers_num = 0;
dummy_task_arg[0].timers = NULL;
#if ESP_APPTRACE_TEST_USE_PRINT_LOCK == 1
s_print_lock = xSemaphoreCreateBinary();
if (!s_print_lock) {
ets_printf("%s: Failed to create print lock!", TAG);
return;
}
xSemaphoreGive(s_print_lock);
#else
#endif
for (i = 0; i < test_cfg->tasks_num; i++) {
test_cfg->tasks[i].data.mask = 0xFF;
test_cfg->tasks[i].stop = 0;
test_cfg->tasks[i].done = xSemaphoreCreateBinary();
if (!test_cfg->tasks[i].done) {
ESP_APPTRACE_TEST_LOGE("Failed to create task completion semaphore!");
goto on_fail;
}
for (k = 0; k < test_cfg->tasks[i].timers_num; k++) {
test_cfg->tasks[i].timers[k].data.mask = 0xFF;
tims_in_use[test_cfg->tasks[i].timers[k].group][test_cfg->tasks[i].timers[k].id] = 1;
}
}
int found = 0;
for (i = 0; i < TIMER_GROUP_MAX; i++) {
for (k = 0; k < TIMER_MAX; k++) {
if (!tims_in_use[i][k]) {
ESP_APPTRACE_TEST_LOGD("Found timer%d.%d", i, k);
found = 1;
break;
}
}
if (found) {
break;
}
}
if (!found) {
ESP_APPTRACE_TEST_LOGE("No free timer for TS!");
goto on_fail;
}
esp_apptrace_test_ts_init(i, k);
for (int i = 0; i < test_cfg->tasks_num; i++) {
char name[30];
TaskHandle_t thnd;
sprintf(name, "apptrace_test%d", i);
xTaskCreatePinnedToCore(test_cfg->tasks[i].task_func, name, 2048, &test_cfg->tasks[i], test_cfg->tasks[i].prio, &thnd, test_cfg->tasks[i].core);
ESP_APPTRACE_TEST_LOGI("Created task %x", thnd);
}
xTaskCreatePinnedToCore(esp_apptrace_dummy_task, "dummy0", 2048, &dummy_task_arg[0], dummy_task_arg[0].prio, NULL, 0);
xTaskCreatePinnedToCore(esp_apptrace_dummy_task, "dummy1", 2048, &dummy_task_arg[0], dummy_task_arg[0].prio, NULL, 1);
for (int i = 0; i < test_cfg->tasks_num; i++) {
//arg1.stop = 1;
xSemaphoreTake(test_cfg->tasks[i].done, portMAX_DELAY);
}
on_fail:
for (int i = 0; i < test_cfg->tasks_num; i++) {
if (test_cfg->tasks[i].done) {
vSemaphoreDelete(test_cfg->tasks[i].done);
}
}
esp_apptrace_test_ts_cleanup();
#if ESP_APPTRACE_TEST_USE_PRINT_LOCK == 1
vSemaphoreDelete(s_print_lock);
#else
#endif
}
static esp_apptrace_test_task_arg_t s_test_tasks[4];
static esp_apptrace_test_timer_arg_t s_test_timers[2];
static uint8_t s_bufs[6][ESP_APPTRACE_TEST_BLOCK_SIZE];
TEST_CASE("App trace test (1 task + 1 crashed timer ISR @ 1 core)", "[trace][ignore]")
{
esp_apptrace_test_cfg_t test_cfg = {
.tasks_num = 1,
.tasks = s_test_tasks,
};
memset(s_test_timers, 0, sizeof(s_test_timers));
memset(s_test_tasks, 0, sizeof(s_test_tasks));
s_test_timers[0].group = TIMER_GROUP_0;
s_test_timers[0].id = TIMER_0;
s_test_timers[0].isr_func = esp_apptrace_test_timer_isr_crash;
s_test_timers[0].data.buf = s_bufs[0];
s_test_timers[0].data.buf_sz = sizeof(s_bufs[0]);
s_test_timers[0].data.period = 1000;
s_test_tasks[0].core = 0;
s_test_tasks[0].prio = 3;
s_test_tasks[0].task_func = esp_apptrace_dummy_task;
s_test_tasks[0].data.buf = NULL;
s_test_tasks[0].data.buf_sz = 0;
s_test_tasks[0].data.period = 1000000;
s_test_tasks[0].timers_num = 1;
s_test_tasks[0].timers = s_test_timers;
esp_apptrace_test(&test_cfg);
}
TEST_CASE("App trace test (1 crashed task)", "[trace][ignore]")
{
esp_apptrace_test_task_arg_t s_test_tasks[1];
esp_apptrace_test_cfg_t test_cfg = {
.tasks_num = 1,
.tasks = s_test_tasks,
};
memset(s_test_tasks, 0, sizeof(s_test_tasks));
s_test_tasks[0].core = 0;
s_test_tasks[0].prio = 3;
s_test_tasks[0].task_func = esp_apptrace_test_task_crash;
s_test_tasks[0].data.buf = s_bufs[0];
s_test_tasks[0].data.buf_sz = sizeof(s_bufs[0]);
s_test_tasks[0].data.period = 6000;
s_test_tasks[0].timers_num = 0;
s_test_tasks[0].timers = NULL;
esp_apptrace_test(&test_cfg);
}
TEST_CASE("App trace test (2 tasks + 1 timer @ each core", "[trace][ignore]")
{
int ntask = 0;
esp_apptrace_test_cfg_t test_cfg = {
.tasks_num = 4,
.tasks = s_test_tasks,
};
memset(s_test_tasks, 0, sizeof(s_test_tasks));
memset(s_test_timers, 0, sizeof(s_test_timers));
s_test_timers[0].group = TIMER_GROUP_0;
s_test_timers[0].id = TIMER_0;
s_test_timers[0].isr_func = esp_apptrace_test_timer_isr;
s_test_timers[0].data.buf = s_bufs[0];
s_test_timers[0].data.buf_sz = sizeof(s_bufs[0]);
s_test_timers[0].data.period = 150;
s_test_timers[1].group = TIMER_GROUP_1;
s_test_timers[1].id = TIMER_0;
s_test_timers[1].isr_func = esp_apptrace_test_timer_isr;
s_test_timers[1].data.buf = s_bufs[1];
s_test_timers[1].data.buf_sz = sizeof(s_bufs[1]);
s_test_timers[1].data.period = 150;
s_test_tasks[ntask].core = 0;
s_test_tasks[ntask].prio = 4;
s_test_tasks[ntask].task_func = esp_apptrace_test_task;
s_test_tasks[ntask].data.buf = s_bufs[2];
s_test_tasks[ntask].data.buf_sz = sizeof(s_bufs[2]);
s_test_tasks[ntask].data.period = 1000;
s_test_tasks[ntask].timers_num = 1;
s_test_tasks[ntask].timers = &s_test_timers[0];
ntask++;
s_test_tasks[ntask].core = 0;
s_test_tasks[ntask].prio = 3;
s_test_tasks[ntask].task_func = esp_apptrace_test_task;
s_test_tasks[ntask].data.buf = s_bufs[3];
s_test_tasks[ntask].data.buf_sz = sizeof(s_bufs[3]);
s_test_tasks[ntask].data.period = 0;
s_test_tasks[ntask].timers_num = 0;
s_test_tasks[ntask].timers = NULL;
ntask++;
s_test_tasks[ntask].core = 1;
s_test_tasks[ntask].prio = 4;
s_test_tasks[ntask].task_func = esp_apptrace_test_task;
s_test_tasks[ntask].data.buf = s_bufs[4];
s_test_tasks[ntask].data.buf_sz = sizeof(s_bufs[4]);
s_test_tasks[ntask].data.period = 1000;
s_test_tasks[ntask].timers_num = 1;
s_test_tasks[ntask].timers = &s_test_timers[1];
ntask++;
s_test_tasks[ntask].core = 1;
s_test_tasks[ntask].prio = 3;
s_test_tasks[ntask].task_func = esp_apptrace_test_task;
s_test_tasks[ntask].data.buf = s_bufs[5];
s_test_tasks[ntask].data.buf_sz = sizeof(s_bufs[5]);
s_test_tasks[ntask].data.period = 0;
s_test_tasks[ntask].timers_num = 0;
s_test_tasks[ntask].timers = NULL;
ntask++;
esp_apptrace_test(&test_cfg);
}
TEST_CASE("App trace test (1 task + 1 timer @ 1 core)", "[trace][ignore]")
{
esp_apptrace_test_cfg_t test_cfg = {
.tasks_num = 1,
.tasks = s_test_tasks,
};
memset(s_test_timers, 0, sizeof(s_test_timers));
memset(s_test_tasks, 0, sizeof(s_test_tasks));
s_test_timers[0].group = TIMER_GROUP_0;
s_test_timers[0].id = TIMER_0;
s_test_timers[0].isr_func = esp_apptrace_test_timer_isr;
s_test_timers[0].data.buf = s_bufs[0];
s_test_timers[0].data.buf_sz = sizeof(s_bufs[0]);
s_test_timers[0].data.period = 150;
s_test_tasks[0].core = 0;
s_test_tasks[0].prio = 3;
s_test_tasks[0].task_func = esp_apptrace_test_task;
s_test_tasks[0].data.buf = s_bufs[1];
s_test_tasks[0].data.buf_sz = sizeof(s_bufs[1]);
s_test_tasks[0].data.period = 0;
s_test_tasks[0].timers_num = 1;
s_test_tasks[0].timers = s_test_timers;
esp_apptrace_test(&test_cfg);
}
TEST_CASE("App trace test (2 tasks (nowait): 1 @ each core)", "[trace][ignore]")
{
esp_apptrace_test_cfg_t test_cfg = {
.tasks_num = 2,
.tasks = s_test_tasks,
};
memset(s_test_tasks, 0, sizeof(s_test_tasks));
s_test_tasks[0].nowait = 1;
s_test_tasks[0].core = 0;
s_test_tasks[0].prio = 3;
s_test_tasks[0].task_func = esp_apptrace_test_task;
s_test_tasks[0].data.buf = s_bufs[0];
s_test_tasks[0].data.buf_sz = sizeof(s_bufs[0]);
s_test_tasks[0].data.period = 6700;
s_test_tasks[0].timers_num = 0;
s_test_tasks[0].timers = NULL;
s_test_tasks[1].nowait = 1;
s_test_tasks[1].core = 1;
s_test_tasks[1].prio = 3;
s_test_tasks[1].task_func = esp_apptrace_test_task;
s_test_tasks[1].data.buf = s_bufs[1];
s_test_tasks[1].data.buf_sz = sizeof(s_bufs[1]);
s_test_tasks[1].data.period = 6700;
s_test_tasks[1].timers_num = 0;
s_test_tasks[1].timers = NULL;
esp_apptrace_test(&test_cfg);
}
TEST_CASE("App trace test (2 tasks: 1 @ each core)", "[trace][ignore]")
{
esp_apptrace_test_cfg_t test_cfg = {
.tasks_num = 2,
.tasks = s_test_tasks,
};
memset(s_test_tasks, 0, sizeof(s_test_tasks));
s_test_tasks[0].core = 0;
s_test_tasks[0].prio = 3;
s_test_tasks[0].task_func = esp_apptrace_test_task;
s_test_tasks[0].data.buf = s_bufs[0];
s_test_tasks[0].data.buf_sz = sizeof(s_bufs[0]);
s_test_tasks[0].data.period = 0;
s_test_tasks[0].timers_num = 0;
s_test_tasks[0].timers = NULL;
s_test_tasks[1].core = 1;
s_test_tasks[1].prio = 3;
s_test_tasks[1].task_func = esp_apptrace_test_task;
s_test_tasks[1].data.buf = s_bufs[1];
s_test_tasks[1].data.buf_sz = sizeof(s_bufs[1]);
s_test_tasks[1].data.period = 0;
s_test_tasks[1].timers_num = 0;
s_test_tasks[1].timers = NULL;
esp_apptrace_test(&test_cfg);
}
TEST_CASE("App trace test (1 task)", "[trace][ignore]")
{
esp_apptrace_test_cfg_t test_cfg = {
.tasks_num = 1,
.tasks = s_test_tasks,
};
memset(s_test_tasks, 0, sizeof(s_test_tasks));
s_test_tasks[0].core = 1;
s_test_tasks[0].prio = 3;
s_test_tasks[0].task_func = esp_apptrace_test_task;
s_test_tasks[0].data.buf = s_bufs[0];
s_test_tasks[0].data.buf_sz = sizeof(s_bufs[0]);
s_test_tasks[0].data.period = 0;
s_test_tasks[0].timers_num = 0;
s_test_tasks[0].timers = NULL;
esp_apptrace_test(&test_cfg);
}
static int esp_logtrace_printf(const char *fmt, ...)
{
va_list ap;
va_start(ap, fmt);
int ret = esp_apptrace_vprintf_to(ESP_APPTRACE_DEST_TRAX, ESP_APPTRACE_TMO_INFINITE, fmt, ap);
va_end(ap);
return ret;
}
typedef struct {
SemaphoreHandle_t done;
} esp_logtrace_task_t;
static void esp_logtrace_task(void *p)
{
esp_logtrace_task_t *arg = (esp_logtrace_task_t *) p;
ESP_APPTRACE_TEST_LOGI("%x: run log test task", xTaskGetCurrentTaskHandle());
int i = 0;
while (1) {
esp_logtrace_printf("sample print %lx %hx %c\n", 2 * i + 0x10, 2 * i + 0x20, (2 * i + 0x30) & 0xFF);
esp_logtrace_printf("sample print %lx %hx %c %lu %hu %d %d %d %d\n", i, i + 0x10, (i + 0x20) & 0xFF, i + 0x30, i + 0x40, i + 0x50, i + 0x60, i + 0x70, i + 0x80);
ESP_LOGI(TAG, "%p: sample print 1", xTaskGetCurrentTaskHandle());
ESP_LOGI(TAG, "%p: sample print 2 %u", xTaskGetCurrentTaskHandle(), (unsigned)i);
ESP_LOGI(TAG, "%p: sample print 4 %c", xTaskGetCurrentTaskHandle(), ((i & 0xFF) % 95) + 32);
ESP_LOGI(TAG, "%p: sample print 5 %f", xTaskGetCurrentTaskHandle(), 1.0);
ESP_LOGI(TAG, "%p: sample print 6 %f", xTaskGetCurrentTaskHandle(), 3.45);
ESP_LOGI(TAG, "%p: logtrace task work %d.%d", xTaskGetCurrentTaskHandle(), xPortGetCoreID(), i);
if (++i == 10000) {
break;
}
}
esp_err_t ret = esp_apptrace_flush(ESP_APPTRACE_DEST_TRAX, ESP_APPTRACE_TMO_INFINITE);
if (ret != ESP_OK) {
ESP_APPTRACE_TEST_LOGE("Failed to flush printf buf (%d)!", ret);
}
ESP_APPTRACE_TEST_LOGI("%x: finished", xTaskGetCurrentTaskHandle());
xSemaphoreGive(arg->done);
vTaskDelay(1);
vTaskDelete(NULL);
}
TEST_CASE("Log trace test (1 task)", "[trace][ignore]")
{
TaskHandle_t thnd;
esp_logtrace_task_t arg1 = {
.done = xSemaphoreCreateBinary(),
};
esp_logtrace_task_t arg2 = {
.done = xSemaphoreCreateBinary(),
};
xTaskCreatePinnedToCore(esp_logtrace_task, "logtrace0", 2048, &arg1, 3, &thnd, 0);
ESP_APPTRACE_TEST_LOGI("Created task %x", thnd);
xTaskCreatePinnedToCore(esp_logtrace_task, "logtrace1", 2048, &arg2, 3, &thnd, 1);
ESP_APPTRACE_TEST_LOGI("Created task %x", thnd);
xSemaphoreTake(arg1.done, portMAX_DELAY);
vSemaphoreDelete(arg1.done);
xSemaphoreTake(arg2.done, portMAX_DELAY);
vSemaphoreDelete(arg2.done);
}
#endif

@ -1 +1 @@
Subproject commit 907273664ada32fc33f3fbfeba99550512c67e4d
Subproject commit 96698a3da9acc6e357741663830f97524b688ade

View file

@ -1,5 +1,5 @@
#
# Component Makefile
#
# (Uses default behaviour of compiling all source files in directory, adding 'include' to include path.)
COMPONENT_SRCDIRS := . eth_phy

View file

@ -204,6 +204,25 @@ uint16_t esp_eth_smi_read(uint32_t reg_num)
return value;
}
esp_err_t esp_eth_smi_wait_value(uint32_t reg_num, uint16_t value, uint16_t value_mask, int timeout_ms)
{
unsigned start = xTaskGetTickCount();
unsigned timeout_ticks = (timeout_ms + portTICK_PERIOD_MS - 1) / portTICK_PERIOD_MS;
uint16_t current_value = 0;
while (timeout_ticks == 0 || (xTaskGetTickCount() - start < timeout_ticks)) {
current_value = esp_eth_smi_read(reg_num);
if ((current_value & value_mask) == (value & value_mask)) {
return ESP_OK;
}
vTaskDelay(1);
}
ESP_LOGE(TAG, "Timed out waiting for PHY register 0x%x to have value 0x%04x (mask 0x%04x). Current value 0x%04x",
reg_num, value, value_mask, current_value);
return ESP_ERR_TIMEOUT;
}
static void emac_set_user_config_data(eth_config_t *config )
{
emac_config.phy_addr = config->phy_addr;
@ -532,7 +551,7 @@ static void emac_set_macaddr_reg(void)
static void emac_check_phy_init(void)
{
emac_config.emac_phy_check_init();
if (emac_config.emac_phy_get_duplex_mode() == ETH_MDOE_FULLDUPLEX) {
if (emac_config.emac_phy_get_duplex_mode() == ETH_MODE_FULLDUPLEX) {
REG_SET_BIT(EMAC_GMACCONFIG_REG, EMAC_GMACDUPLEX);
} else {
REG_CLR_BIT(EMAC_GMACCONFIG_REG, EMAC_GMACDUPLEX);
@ -547,7 +566,7 @@ static void emac_check_phy_init(void)
emac_config.emac_flow_ctrl_partner_support = false;
#else
if (emac_config.emac_flow_ctrl_enable == true) {
if (emac_config.emac_phy_get_partner_pause_enable() == true && emac_config.emac_phy_get_duplex_mode() == ETH_MDOE_FULLDUPLEX) {
if (emac_config.emac_phy_get_partner_pause_enable() == true && emac_config.emac_phy_get_duplex_mode() == ETH_MODE_FULLDUPLEX) {
emac_enable_flowctrl();
emac_config.emac_flow_ctrl_partner_support = true;
} else {
@ -954,7 +973,7 @@ esp_err_t esp_eth_init(eth_config_t *config)
goto _exit;
}
emac_config.emac_phy_power_enable(true);
emac_config.emac_phy_power_enable(true);
//before set emac reg must enable clk
emac_enable_clk(true);

View file

@ -0,0 +1,75 @@
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "eth_phy/phy.h"
#include "eth_phy/phy_reg.h"
#include "driver/gpio.h"
#include "esp_log.h"
static const char *TAG = "phy_common";
void phy_rmii_configure_data_interface_pins(void)
{
// CRS_DRV to GPIO27
PIN_FUNC_SELECT(PERIPHS_IO_MUX_GPIO27_U, FUNC_GPIO27_EMAC_RX_DV);
// TXD0 to GPIO19
PIN_FUNC_SELECT(PERIPHS_IO_MUX_GPIO19_U, FUNC_GPIO19_EMAC_TXD0);
// TX_EN to GPIO21
PIN_FUNC_SELECT(PERIPHS_IO_MUX_GPIO21_U, FUNC_GPIO21_EMAC_TX_EN);
// TXD1 to GPIO22
PIN_FUNC_SELECT(PERIPHS_IO_MUX_GPIO22_U, FUNC_GPIO22_EMAC_TXD1);
// RXD0 to GPIO25
gpio_set_direction(25, GPIO_MODE_INPUT);
// RXD1 to GPIO26
gpio_set_direction(26, GPIO_MODE_INPUT);
// RMII CLK to GPIO0
gpio_set_direction(0, GPIO_MODE_INPUT);
}
void phy_rmii_smi_configure_pins(uint8_t mdc_gpio, uint8_t mdio_gpio)
{
gpio_matrix_out(mdc_gpio, EMAC_MDC_O_IDX, 0, 0);
gpio_matrix_out(mdio_gpio, EMAC_MDO_O_IDX, 0, 0);
gpio_matrix_in(mdio_gpio, EMAC_MDI_I_IDX, 0);
}
void phy_mii_enable_flow_ctrl(void)
{
uint32_t data = esp_eth_smi_read(MII_AUTO_NEG_ADVERTISEMENT_REG);
data |= MII_ASM_DIR | MII_PAUSE;
esp_eth_smi_write(MII_AUTO_NEG_ADVERTISEMENT_REG, data);
}
bool phy_mii_check_link_status(void)
{
if ((esp_eth_smi_read(MII_BASIC_MODE_STATUS_REG) & MII_LINK_STATUS)) {
ESP_LOGD(TAG, "phy_mii_check_link_status(UP)");
return true;
} else {
ESP_LOGD(TAG, "phy_mii_check_link_status(DOWN)");
return false;
}
}
bool phy_mii_get_partner_pause_enable(void)
{
if((esp_eth_smi_read(MII_PHY_LINK_PARTNER_ABILITY_REG) & MII_PARTNER_PAUSE)) {
ESP_LOGD(TAG, "phy_mii_get_partner_pause_enable(TRUE)");
return true;
} else {
ESP_LOGD(TAG, "phy_mii_get_partner_pause_enable(FALSE)");
return false;
}
}

View file

@ -0,0 +1,149 @@
// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "esp_attr.h"
#include "esp_log.h"
#include "esp_eth.h"
#include "eth_phy/phy_lan8720.h"
#include "eth_phy/phy_reg.h"
/* Value of MII_PHY_IDENTIFIER_REGs for Microchip LAN8720
* (Except for bottom 4 bits of ID2, used for model revision)
*/
#define LAN8720_PHY_ID1 0x0007
#define LAN8720_PHY_ID2 0xc0f0
#define LAN8720_PHY_ID2_MASK 0xFFF0
/* LAN8720-specific registers */
#define SW_STRAP_CONTROL_REG (0x9)
#define SW_STRAP_CONFIG_DONE BIT(15)
#define AUTO_MDIX_ENABLE BIT(14)
#define AUTO_NEGOTIATION_ENABLE BIT(13)
#define AN_1 BIT(12)
#define AN_0 BIT(11)
#define LED_CFG BIT(10)
#define RMII_ENHANCED_MODE BIT(9)
#define DEFAULT_STRAP_CONFIG (AUTO_MDIX_ENABLE|AUTO_NEGOTIATION_ENABLE|AN_1|AN_0|LED_CFG)
#define PHY_SPECIAL_CONTROL_STATUS_REG (0x1f)
#define AUTO_NEGOTIATION_DONE BIT(12)
#define SPEED_DUPLEX_INDICATION_10T_HALF 0x04
#define SPEED_DUPLEX_INDICATION_10T_FULL 0x14
#define SPEED_DUPLEX_INDICATION_100T_HALF 0x08
#define SPEED_DUPLEX_INDICATION_100T_FULL 0x18
#define SPEED_INDICATION_100T BIT(3)
#define SPEED_INDICATION_10T BIT(2)
#define DUPLEX_INDICATION_FULL BIT(4)
static const char *TAG = "lan8720";
void phy_lan8720_check_phy_init(void)
{
phy_lan8720_dump_registers();
esp_eth_smi_wait_set(MII_BASIC_MODE_STATUS_REG, MII_AUTO_NEGOTIATION_COMPLETE, 0);
esp_eth_smi_wait_set(PHY_SPECIAL_CONTROL_STATUS_REG, AUTO_NEGOTIATION_DONE, 0);
}
eth_speed_mode_t phy_lan8720_get_speed_mode(void)
{
if(esp_eth_smi_read(PHY_SPECIAL_CONTROL_STATUS_REG) & SPEED_INDICATION_100T) {
ESP_LOGD(TAG, "phy_lan8720_get_speed_mode(100)");
return ETH_SPEED_MODE_100M;
} else {
ESP_LOGD(TAG, "phy_lan8720_get_speed_mode(10)");
return ETH_SPEED_MODE_10M;
}
}
eth_duplex_mode_t phy_lan8720_get_duplex_mode(void)
{
if(esp_eth_smi_read(PHY_SPECIAL_CONTROL_STATUS_REG) & DUPLEX_INDICATION_FULL) {
ESP_LOGD(TAG, "phy_lan8720_get_duplex_mode(FULL)");
return ETH_MODE_FULLDUPLEX;
} else {
ESP_LOGD(TAG, "phy_lan8720_get_duplex_mode(HALF)");
return ETH_MODE_HALFDUPLEX;
}
}
void phy_lan8720_power_enable(bool enable)
{
if (enable) {
esp_eth_smi_write(SW_STRAP_CONTROL_REG, DEFAULT_STRAP_CONFIG | SW_STRAP_CONFIG_DONE);
// TODO: only enable if config.flow_ctrl_enable == true
phy_mii_enable_flow_ctrl();
}
}
void phy_lan8720_init(void)
{
ESP_LOGD(TAG, "phy_lan8720_init()");
phy_lan8720_dump_registers();
esp_eth_smi_write(MII_BASIC_MODE_CONTROL_REG, MII_SOFTWARE_RESET);
esp_err_t res1, res2;
do {
// Call esp_eth_smi_wait_value() with a timeout so it prints an error periodically
res1 = esp_eth_smi_wait_value(MII_PHY_IDENTIFIER_1_REG, LAN8720_PHY_ID1, UINT16_MAX, 1000);
res2 = esp_eth_smi_wait_value(MII_PHY_IDENTIFIER_2_REG, LAN8720_PHY_ID2, LAN8720_PHY_ID2_MASK, 1000);
} while(res1 != ESP_OK || res2 != ESP_OK);
esp_eth_smi_write(SW_STRAP_CONTROL_REG,
DEFAULT_STRAP_CONFIG | SW_STRAP_CONFIG_DONE);
ets_delay_us(300);
// TODO: only enable if config.flow_ctrl_enable == true
phy_mii_enable_flow_ctrl();
}
const eth_config_t phy_lan8720_default_ethernet_config = {
// By default, the PHY address is 0 or 1 based on PHYAD0
// pin. Can also be overriden in software. See datasheet
// for defaults.
.phy_addr = 0,
.mac_mode = ETH_MODE_RMII,
//Only FULLDUPLEX mode support flow ctrl now!
.flow_ctrl_enable = true,
.phy_init = phy_lan8720_init,
.phy_check_init = phy_lan8720_check_phy_init,
.phy_power_enable = phy_lan8720_power_enable,
.phy_check_link = phy_mii_check_link_status,
.phy_get_speed_mode = phy_lan8720_get_speed_mode,
.phy_get_duplex_mode = phy_lan8720_get_duplex_mode,
.phy_get_partner_pause_enable = phy_mii_get_partner_pause_enable,
};
void phy_lan8720_dump_registers()
{
ESP_LOGD(TAG, "LAN8720 Registers:");
ESP_LOGD(TAG, "BCR 0x%04x", esp_eth_smi_read(0x0));
ESP_LOGD(TAG, "BSR 0x%04x", esp_eth_smi_read(0x1));
ESP_LOGD(TAG, "PHY1 0x%04x", esp_eth_smi_read(0x2));
ESP_LOGD(TAG, "PHY2 0x%04x", esp_eth_smi_read(0x3));
ESP_LOGD(TAG, "ANAR 0x%04x", esp_eth_smi_read(0x4));
ESP_LOGD(TAG, "ANLPAR 0x%04x", esp_eth_smi_read(0x5));
ESP_LOGD(TAG, "ANER 0x%04x", esp_eth_smi_read(0x6));
ESP_LOGD(TAG, "MCSR 0x%04x", esp_eth_smi_read(0x17));
ESP_LOGD(TAG, "SM 0x%04x", esp_eth_smi_read(0x18));
ESP_LOGD(TAG, "SECR 0x%04x", esp_eth_smi_read(0x26));
ESP_LOGD(TAG, "CSIR 0x%04x", esp_eth_smi_read(0x27));
ESP_LOGD(TAG, "ISR 0x%04x", esp_eth_smi_read(0x29));
ESP_LOGD(TAG, "IMR 0x%04x", esp_eth_smi_read(0x30));
ESP_LOGD(TAG, "PSCSR 0x%04x", esp_eth_smi_read(0x31));
}

View file

@ -0,0 +1,173 @@
// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "esp_attr.h"
#include "esp_log.h"
#include "esp_eth.h"
#include "eth_phy/phy_tlk110.h"
#include "eth_phy/phy_reg.h"
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
/* Value of MII_PHY_IDENTIFIER_REG for TI TLK110,
Excluding bottom 4 bytes of ID2, used for model revision
*/
#define TLK110_PHY_ID1 0x2000
#define TLK110_PHY_ID2 0xa210
#define TLK110_PHY_ID2_MASK 0xFFF0
/* TLK110-specific registers */
#define SW_STRAP_CONTROL_REG (0x9)
#define SW_STRAP_CONFIG_DONE BIT(15)
#define AUTO_MDIX_ENABLE BIT(14)
#define AUTO_NEGOTIATION_ENABLE BIT(13)
#define AN_1 BIT(12)
#define AN_0 BIT(11)
#define LED_CFG BIT(10)
#define RMII_ENHANCED_MODE BIT(9)
#define DEFAULT_STRAP_CONFIG (AUTO_MDIX_ENABLE|AUTO_NEGOTIATION_ENABLE|AN_1|AN_0|LED_CFG)
#define PHY_STATUS_REG (0x10)
#define AUTO_NEGOTIATION_STATUS BIT(4)
#define DUPLEX_STATUS BIT(2)
#define SPEED_STATUS BIT(1)
#define CABLE_DIAGNOSTIC_CONTROL_REG (0x1e)
#define DIAGNOSTIC_DONE BIT(1)
#define PHY_RESET_CONTROL_REG (0x1f)
#define SOFTWARE_RESET BIT(15)
static const char *TAG = "tlk110";
void phy_tlk110_check_phy_init(void)
{
phy_tlk110_dump_registers();
esp_eth_smi_wait_set(MII_BASIC_MODE_STATUS_REG, MII_AUTO_NEGOTIATION_COMPLETE, 0);
esp_eth_smi_wait_set(PHY_STATUS_REG, AUTO_NEGOTIATION_STATUS, 0);
esp_eth_smi_wait_set(CABLE_DIAGNOSTIC_CONTROL_REG, DIAGNOSTIC_DONE, 0);
}
eth_speed_mode_t phy_tlk110_get_speed_mode(void)
{
if((esp_eth_smi_read(PHY_STATUS_REG) & SPEED_STATUS ) != SPEED_STATUS) {
ESP_LOGD(TAG, "phy_tlk110_get_speed_mode(100)");
return ETH_SPEED_MODE_100M;
} else {
ESP_LOGD(TAG, "phy_tlk110_get_speed_mode(10)");
return ETH_SPEED_MODE_10M;
}
}
eth_duplex_mode_t phy_tlk110_get_duplex_mode(void)
{
if((esp_eth_smi_read(PHY_STATUS_REG) & DUPLEX_STATUS ) == DUPLEX_STATUS) {
ESP_LOGD(TAG, "phy_tlk110_get_duplex_mode(FULL)");
return ETH_MODE_FULLDUPLEX;
} else {
ESP_LOGD(TAG, "phy_tlk110_get_duplex_mode(HALF)");
return ETH_MODE_HALFDUPLEX;
}
}
void phy_tlk110_power_enable(bool enable)
{
if (enable) {
esp_eth_smi_write(SW_STRAP_CONTROL_REG, DEFAULT_STRAP_CONFIG | SW_STRAP_CONFIG_DONE);
// TODO: only do this if config.flow_ctrl_enable == true
phy_mii_enable_flow_ctrl();
}
}
void phy_tlk110_init(void)
{
ESP_LOGD(TAG, "phy_tlk110_init()");
phy_tlk110_dump_registers();
esp_eth_smi_write(PHY_RESET_CONTROL_REG, SOFTWARE_RESET);
esp_err_t res1, res2;
do {
// Call esp_eth_smi_wait_value() with a timeout so it prints an error periodically
res1 = esp_eth_smi_wait_value(MII_PHY_IDENTIFIER_1_REG, TLK110_PHY_ID1, UINT16_MAX, 1000);
res2 = esp_eth_smi_wait_value(MII_PHY_IDENTIFIER_2_REG, TLK110_PHY_ID2, TLK110_PHY_ID2_MASK, 1000);
} while(res1 != ESP_OK || res2 != ESP_OK);
esp_eth_smi_write(SW_STRAP_CONTROL_REG,
DEFAULT_STRAP_CONFIG | SW_STRAP_CONFIG_DONE);
ets_delay_us(300);
// TODO: only do this if config.flow_ctrl_enable == true
phy_mii_enable_flow_ctrl();
}
const eth_config_t phy_tlk110_default_ethernet_config = {
// PHY address configured by PHYADx pins. Default value of 0x1
// is used if all pins are unconnected.
.phy_addr = 0x1,
.mac_mode = ETH_MODE_RMII,
//Only FULLDUPLEX mode support flow ctrl now!
.flow_ctrl_enable = true,
.phy_init = phy_tlk110_init,
.phy_check_init = phy_tlk110_check_phy_init,
.phy_check_link = phy_mii_check_link_status,
.phy_get_speed_mode = phy_tlk110_get_speed_mode,
.phy_get_duplex_mode = phy_tlk110_get_duplex_mode,
.phy_get_partner_pause_enable = phy_mii_get_partner_pause_enable,
.phy_power_enable = phy_tlk110_power_enable,
};
void phy_tlk110_dump_registers()
{
ESP_LOGD(TAG, "TLK110 Registers:");
ESP_LOGD(TAG, "BMCR 0x%04x", esp_eth_smi_read(0x0));
ESP_LOGD(TAG, "BMSR 0x%04x", esp_eth_smi_read(0x1));
ESP_LOGD(TAG, "PHYIDR1 0x%04x", esp_eth_smi_read(0x2));
ESP_LOGD(TAG, "PHYIDR2 0x%04x", esp_eth_smi_read(0x3));
ESP_LOGD(TAG, "ANAR 0x%04x", esp_eth_smi_read(0x4));
ESP_LOGD(TAG, "ANLPAR 0x%04x", esp_eth_smi_read(0x5));
ESP_LOGD(TAG, "ANER 0x%04x", esp_eth_smi_read(0x6));
ESP_LOGD(TAG, "ANNPTR 0x%04x", esp_eth_smi_read(0x7));
ESP_LOGD(TAG, "ANLNPTR 0x%04x", esp_eth_smi_read(0x8));
ESP_LOGD(TAG, "SWSCR1 0x%04x", esp_eth_smi_read(0x9));
ESP_LOGD(TAG, "SWSCR2 0x%04x", esp_eth_smi_read(0xa));
ESP_LOGD(TAG, "SWSCR3 0x%04x", esp_eth_smi_read(0xb));
ESP_LOGD(TAG, "REGCR 0x%04x", esp_eth_smi_read(0xd));
ESP_LOGD(TAG, "ADDAR 0x%04x", esp_eth_smi_read(0xe));
ESP_LOGD(TAG, "PHYSTS 0x%04x", esp_eth_smi_read(0x10));
ESP_LOGD(TAG, "PHYSCR 0x%04x", esp_eth_smi_read(0x11));
ESP_LOGD(TAG, "MISR1 0x%04x", esp_eth_smi_read(0x12));
ESP_LOGD(TAG, "MISR2 0x%04x", esp_eth_smi_read(0x13));
ESP_LOGD(TAG, "FCSCR 0x%04x", esp_eth_smi_read(0x14));
ESP_LOGD(TAG, "RECR 0x%04x", esp_eth_smi_read(0x15));
ESP_LOGD(TAG, "BISCR 0x%04x", esp_eth_smi_read(0x16));
ESP_LOGD(TAG, "RBR 0x%04x", esp_eth_smi_read(0x17));
ESP_LOGD(TAG, "LEDCR 0x%04x", esp_eth_smi_read(0x18));
ESP_LOGD(TAG, "PHYCR 0x%04x", esp_eth_smi_read(0x19));
ESP_LOGD(TAG, "10BTSCR 0x%04x", esp_eth_smi_read(0x1a));
ESP_LOGD(TAG, "BICSR1 0x%04x", esp_eth_smi_read(0x1b));
ESP_LOGD(TAG, "BICSR2 0x%04x", esp_eth_smi_read(0x1c));
ESP_LOGD(TAG, "CDCR 0x%04x", esp_eth_smi_read(0x1e));
ESP_LOGD(TAG, "TRXCPSR 0x%04x", esp_eth_smi_read(0x42));
ESP_LOGD(TAG, "PWRBOCR 0x%04x", esp_eth_smi_read(0xae));
ESP_LOGD(TAG, "VRCR 0x%04x", esp_eth_smi_read(0xD0));
ESP_LOGD(TAG, "ALCDRR1 0x%04x", esp_eth_smi_read(0x155));
ESP_LOGD(TAG, "CDSCR1 0x%04x", esp_eth_smi_read(0x170));
ESP_LOGD(TAG, "CDSCR2 0x%04x", esp_eth_smi_read(0x171));
}

View file

@ -15,6 +15,7 @@
#ifndef __ESP_ETH_H__
#define __ESP_ETH_H__
#include <stdbool.h>
#include <stdint.h>
#include "esp_err.h"
@ -24,7 +25,7 @@ extern "C" {
typedef enum {
ETH_MODE_RMII = 0,
ETH_MDOE_MII,
ETH_MODE_MII,
} eth_mode_t;
typedef enum {
@ -34,7 +35,7 @@ typedef enum {
typedef enum {
ETH_MODE_HALFDUPLEX = 0,
ETH_MDOE_FULLDUPLEX,
ETH_MODE_FULLDUPLEX,
} eth_duplex_mode_t;
typedef enum {
@ -99,9 +100,10 @@ typedef struct {
bool flow_ctrl_enable; /*!< flag of flow ctrl enable */
eth_phy_get_partner_pause_enable_func phy_get_partner_pause_enable; /*!< get partner pause enable */
eth_phy_power_enable_func phy_power_enable; /*!< enable or disable phy power */
} eth_config_t;
/**
* @brief Init ethernet mac
*
@ -173,7 +175,7 @@ void esp_eth_get_mac(uint8_t mac[6]);
void esp_eth_smi_write(uint32_t reg_num, uint16_t value);
/**
* @brief Write phy reg with smi interface.
* @brief Read phy reg with smi interface.
*
* @note phy base addr must be right.
*
@ -183,6 +185,35 @@ void esp_eth_smi_write(uint32_t reg_num, uint16_t value);
*/
uint16_t esp_eth_smi_read(uint32_t reg_num);
/**
* @brief Continuously read a PHY register over SMI interface, wait until the register has the desired value.
*
* @note PHY base address must be right.
*
* @param reg_num: PHY register number
* @param value: Value to wait for (masked with value_mask)
* @param value_mask: Mask of bits to match in the register.
* @param timeout_ms: Timeout to wait for this value (milliseconds). 0 means never timeout.
*
* @return ESP_OK if desired value matches, ESP_ERR_TIMEOUT if timed out.
*/
esp_err_t esp_eth_smi_wait_value(uint32_t reg_num, uint16_t value, uint16_t value_mask, int timeout_ms);
/**
* @brief Continuously read a PHY register over SMI interface, wait until the register has all bits in a mask set.
*
* @note PHY base address must be right.
*
* @param reg_num: PHY register number
* @param value_mask: Value mask to wait for (all bits in this mask must be set)
* @param timeout_ms: Timeout to wait for this value (milliseconds). 0 means never timeout.
*
* @return ESP_OK if desired value matches, ESP_ERR_TIMEOUT if timed out.
*/
static inline esp_err_t esp_eth_smi_wait_set(uint32_t reg_num, uint16_t value_mask, int timeout_ms) {
return esp_eth_smi_wait_value(reg_num, value_mask, value_mask, timeout_ms);
}
/**
* @brief Free emac rx buf.
*

View file

@ -0,0 +1,59 @@
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include "esp_eth.h"
/* Common PHY-management functions.
These are not enough to drive any particular Ethernet PHY, but they provide a common configuration structure and
management functions.
*/
/* Configure fixed pins for RMII data interface.
This configures GPIOs 0, 19, 22, 25, 26, 27 for use with RMII
data interface. These pins cannot be changed, and must be wired to
ethernet functions.
This is not sufficient to fully configure the Ethernet PHY,
MDIO configuration interface pins (such as SMI MDC, MDO, MDI)
must also be configured correctly in the GPIO matrix.
*/
void phy_rmii_configure_data_interface_pins(void);
/* Configure variable pins for SMI (MDIO) ethernet functions.
Calling this function along with mii_configure_default_pins() will
fully configure the GPIOs for the ethernet PHY.
*/
void phy_rmii_smi_configure_pins(uint8_t mdc_gpio, uint8_t mdio_gpio);
/* Enable flow control in standard PHY MII register.
*/
void phy_mii_enable_flow_ctrl(void);
bool phy_mii_check_link_status(void);
bool phy_mii_get_partner_pause_enable(void);
#ifdef __cplusplus
}
#endif

View file

@ -0,0 +1,67 @@
// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include "phy.h"
/* @brief Dump all LAN8720 PHY SMI configuration registers
*
* @note These registers are dumped at 'debug' level, so output
* may not be visible depending on default log levels.
*/
void phy_lan8720_dump_registers();
/* @brief Default LAN8720 phy_check_init function.
*/
void phy_lan8720_check_phy_init(void);
/* @brief Default LAN8720 phy_get_speed_mode function.
*/
eth_speed_mode_t phy_lan8720_get_speed_mode(void);
/* @brief Default LAN8720 phy_get_duplex_mode function.
*/
eth_duplex_mode_t phy_lan8720_get_duplex_mode(void);
/* @brief Default LAN8720 phy_power_enable function.
*
* @note This function may need to be replaced with a custom function
* if the PHY has a GPIO to enable power or start a clock.
*
* Consult the ethernet example to see how this is done.
*/
void phy_lan8720_power_enable(bool);
/* @brief Default LAN8720 phy_init function.
*/
void phy_lan8720_init(void);
/* @brief Default LAN8720 PHY configuration
*
* This configuration is not suitable for use as-is, it will need
* to be modified for your particular PHY hardware setup.
*
* Consult the Ethernet example to see how this is done.
*/
extern const eth_config_t phy_lan8720_default_ethernet_config;
#ifdef __cplusplus
}
#endif

View file

@ -0,0 +1,37 @@
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#pragma once
/* This header contains register/bit masks for the standard
PHY MII registers that should be supported by all PHY models.
*/
#define MII_BASIC_MODE_CONTROL_REG (0x0)
#define MII_SOFTWARE_RESET BIT(15)
#define MII_BASIC_MODE_STATUS_REG (0x1)
#define MII_AUTO_NEGOTIATION_COMPLETE BIT(5)
#define MII_LINK_STATUS BIT(2)
#define MII_PHY_IDENTIFIER_1_REG (0x2)
#define MII_PHY_IDENTIFIER_2_REG (0x3)
#define MII_AUTO_NEG_ADVERTISEMENT_REG (0x4)
#define MII_ASM_DIR BIT(11)
#define MII_PAUSE BIT(10)
#define MII_PHY_LINK_PARTNER_ABILITY_REG (0x5)
#define MII_PARTNER_ASM_DIR BIT(11)
#define MII_PARTNER_PAUSE BIT(10)

View file

@ -0,0 +1,66 @@
// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include "phy.h"
/* @brief Dump all TLK110 PHY SMI configuration registers
*
* @note These registers are dumped at 'debug' level, so output
* may not be visible depending on default log levels.
*/
void phy_tlk110_dump_registers();
/* @brief Default TLK110 phy_check_init function.
*/
void phy_tlk110_check_phy_init(void);
/* @brief Default TLK110 phy_get_speed_mode function.
*/
eth_speed_mode_t phy_tlk110_get_speed_mode(void);
/* @brief Default TLK110 phy_get_duplex_mode function.
*/
eth_duplex_mode_t phy_tlk110_get_duplex_mode(void);
/* @brief Default TLK110 phy_power_enable function.
*
* @note This function may need to be replaced with a custom function
* if the PHY has a GPIO to enable power or start a clock.
*
* Consult the ethernet example to see how this is done.
*/
void phy_tlk110_power_enable(bool);
/* @brief Default TLK110 phy_init function.
*/
void phy_tlk110_init(void);
/* @brief Default TLK110 PHY configuration
*
* This configuration is not suitable for use as-is, it will need
* to be modified for your particular PHY hardware setup.
*
* Consult the Ethernet example to see how this is done.
*/
extern const eth_config_t phy_tlk110_default_ethernet_config;
#ifdef __cplusplus
}
#endif

View file

@ -0,0 +1,130 @@
// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <string.h>
#include "diskio.h" /* FatFs lower layer API */
#include "ffconf.h"
#include "ff.h"
#include "sdmmc_cmd.h"
#include "esp_log.h"
#include <time.h>
#include <sys/time.h>
#include "diskio_spiflash.h"
#include "wear_levelling.h"
static const char* TAG = "ff_diskio_spiflash";
#ifndef MAX_FF_WL_DRIVES
#define MAX_FF_WL_DRIVES 8
#endif // MAX_FF_WL_DRIVES
wl_handle_t ff_wl_handles[MAX_FF_WL_DRIVES] = {
WL_INVALID_HANDLE,
WL_INVALID_HANDLE,
WL_INVALID_HANDLE,
WL_INVALID_HANDLE,
WL_INVALID_HANDLE,
WL_INVALID_HANDLE,
WL_INVALID_HANDLE,
WL_INVALID_HANDLE
};
DSTATUS ff_wl_initialize (BYTE pdrv)
{
return 0;
}
DSTATUS ff_wl_status (BYTE pdrv)
{
return 0;
}
DRESULT ff_wl_read (BYTE pdrv, BYTE *buff, DWORD sector, UINT count)
{
ESP_LOGV(TAG, "ff_wl_read - pdrv=%i, sector=%i, count=%i\n", (unsigned int)pdrv, (unsigned int)sector, (unsigned int)count);
wl_handle_t wl_handle = ff_wl_handles[pdrv];
assert(wl_handle + 1);
esp_err_t err = wl_read(wl_handle, sector * wl_sector_size(wl_handle), buff, count * wl_sector_size(wl_handle));
if (err != ESP_OK) {
ESP_LOGE(TAG, "wl_read failed (%d)", err);
return RES_ERROR;
}
return RES_OK;
}
DRESULT ff_wl_write (BYTE pdrv, const BYTE *buff, DWORD sector, UINT count)
{
ESP_LOGV(TAG, "ff_wl_write - pdrv=%i, sector=%i, count=%i\n", (unsigned int)pdrv, (unsigned int)sector, (unsigned int)count);
wl_handle_t wl_handle = ff_wl_handles[pdrv];
assert(wl_handle + 1);
esp_err_t err = wl_erase_range(wl_handle, sector * wl_sector_size(wl_handle), count * wl_sector_size(wl_handle));
if (err != ESP_OK) {
ESP_LOGE(TAG, "wl_erase_range failed (%d)", err);
return RES_ERROR;
}
err = wl_write(wl_handle, sector * wl_sector_size(wl_handle), buff, count * wl_sector_size(wl_handle));
if (err != ESP_OK) {
ESP_LOGE(TAG, "wl_write failed (%d)", err);
return RES_ERROR;
}
return RES_OK;
}
DRESULT ff_wl_ioctl (BYTE pdrv, BYTE cmd, void *buff)
{
wl_handle_t wl_handle = ff_wl_handles[pdrv];
ESP_LOGV(TAG, "ff_wl_ioctl: cmd=%i\n", cmd);
assert(wl_handle + 1);
switch (cmd) {
case CTRL_SYNC:
return RES_OK;
case GET_SECTOR_COUNT:
*((uint32_t *) buff) = wl_size(wl_handle) / wl_sector_size(wl_handle);
return RES_OK;
case GET_SECTOR_SIZE:
*((uint32_t *) buff) = wl_sector_size(wl_handle);
return RES_OK;
case GET_BLOCK_SIZE:
return RES_ERROR;
}
return RES_ERROR;
}
esp_err_t ff_diskio_register_wl_partition(BYTE pdrv, wl_handle_t flash_handle)
{
if (pdrv >= MAX_FF_WL_DRIVES) return ESP_FAIL;
static const ff_diskio_impl_t wl_impl = {
.init = &ff_wl_initialize,
.status = &ff_wl_status,
.read = &ff_wl_read,
.write = &ff_wl_write,
.ioctl = &ff_wl_ioctl
};
ff_wl_handles[pdrv] = flash_handle;
ff_diskio_register(pdrv, &wl_impl);
return ESP_OK;
}
BYTE ff_diskio_get_pdrv_wl(wl_handle_t flash_handle)
{
for (int i=0 ; i< MAX_FF_WL_DRIVES ; i++)
{
if (flash_handle == ff_wl_handles[i])
{
return i;
}
}
return -1;
}

View file

@ -0,0 +1,39 @@
// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef _DISKIO_SPIFLASH_DEFINED
#define _DISKIO_SPIFLASH_DEFINED
#ifdef __cplusplus
extern "C" {
#endif
#include "integer.h"
#include "wear_levelling.h"
/**
* Register spi flash partition
*
* @param pdrv drive number
* @param flash_handle handle of the wear levelling partition.
*/
esp_err_t ff_diskio_register_wl_partition(BYTE pdrv, wl_handle_t flash_handle);
BYTE ff_diskio_get_pdrv_wl(wl_handle_t flash_handle);
#ifdef __cplusplus
}
#endif
#endif // _DISKIO_SPIFLASH_DEFINED

View file

@ -19,6 +19,7 @@
#include "driver/sdmmc_types.h"
#include "driver/sdmmc_host.h"
#include "ff.h"
#include "wear_levelling.h"
/**
* @brief Register FATFS with VFS component
@ -77,13 +78,17 @@ esp_err_t esp_vfs_fat_unregister() __attribute__((deprecated));
*/
esp_err_t esp_vfs_fat_unregister_path(const char* base_path);
/**
* @brief Configuration arguments for esp_vfs_fat_sdmmc_mount function
* @brief Configuration arguments for esp_vfs_fat_sdmmc_mount and esp_vfs_fat_spiflash_mount functions
*/
typedef struct {
bool format_if_mount_failed; ///< If FAT partition can not be mounted, and this parameter is true, create partition table and format the filesystem
int max_files; ///< Max number of open files
} esp_vfs_fat_sdmmc_mount_config_t;
bool format_if_mount_failed; ///< If FAT partition can not be mounted, and this parameter is true, create partition table and format the filesystem
int max_files; ///< Max number of open files
} esp_vfs_fat_mount_config_t;
// Compatibility definition
typedef esp_vfs_fat_mount_config_t esp_vfs_fat_sdmmc_mount_config_t;
/**
* @brief Convenience function to get FAT filesystem on SD card registered in VFS
@ -114,7 +119,7 @@ typedef struct {
esp_err_t esp_vfs_fat_sdmmc_mount(const char* base_path,
const sdmmc_host_t* host_config,
const sdmmc_slot_config_t* slot_config,
const esp_vfs_fat_sdmmc_mount_config_t* mount_config,
const esp_vfs_fat_mount_config_t* mount_config,
sdmmc_card_t** out_card);
/**
@ -125,3 +130,46 @@ esp_err_t esp_vfs_fat_sdmmc_mount(const char* base_path,
* - ESP_ERR_INVALID_STATE if esp_vfs_fat_sdmmc_mount hasn't been called
*/
esp_err_t esp_vfs_fat_sdmmc_unmount();
/**
* @brief Convenience function to initialize FAT filesystem in SPI flash and register it in VFS
*
* This is an all-in-one function which does the following:
*
* - finds the partition with defined partition_label. Partition label should be
* configured in the partition table.
* - initializes flash wear levelling library on top of the given partition
* - mounts FAT partition using FATFS library on top of flash wear levelling
* library
* - registers FATFS library with VFS, with prefix given by base_prefix variable
*
* This function is intended to make example code more compact.
*
* @param base_path path where FATFS partition should be mounted (e.g. "/spiflash")
* @param partition_label label of the partition which should be used
* @param mount_config pointer to structure with extra parameters for mounting FATFS
* @param[out] wl_handle wear levelling driver handle
* @return
* - ESP_OK on success
* - ESP_ERR_NOT_FOUND if the partition table does not contain FATFS partition with given label
* - ESP_ERR_INVALID_STATE if esp_vfs_fat_spiflash_mount was already called
* - ESP_ERR_NO_MEM if memory can not be allocated
* - ESP_FAIL if partition can not be mounted
* - other error codes from wear levelling library, SPI flash driver, or FATFS drivers
*/
esp_err_t esp_vfs_fat_spiflash_mount(const char* base_path,
const char* partition_label,
const esp_vfs_fat_mount_config_t* mount_config,
wl_handle_t* wl_handle);
/**
* @brief Unmount FAT filesystem and release resources acquired using esp_vfs_fat_spiflash_mount
*
* @param base_path path where partition should be registered (e.g. "/spiflash")
* @param wl_handle wear levelling driver handle returned by esp_vfs_fat_spiflash_mount
*
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_STATE if esp_vfs_fat_spiflash_mount hasn't been called
*/
esp_err_t esp_vfs_fat_spiflash_unmount(const char* base_path, wl_handle_t wl_handle);

View file

@ -5665,6 +5665,9 @@ FRESULT f_mkfs (
/* Create partition table on the physical drive */
/*-----------------------------------------------------------------------*/
#define CLUSTER_SIZE 63
#define SUPPORTED_FLASH_SIZE 0x1000
FRESULT f_fdisk (
BYTE pdrv, /* Physical drive number */
const DWORD* szt, /* Pointer to the size table for each partitions */
@ -5675,18 +5678,21 @@ FRESULT f_fdisk (
BYTE s_hd, e_hd, *p, *buf = (BYTE*)work;
DSTATUS stat;
DWORD sz_disk, sz_part, s_part;
DWORD cluster_size = CLUSTER_SIZE;
stat = disk_initialize(pdrv);
if (stat & STA_NOINIT) return FR_NOT_READY;
if (stat & STA_PROTECT) return FR_WRITE_PROTECTED;
if (disk_ioctl(pdrv, GET_SECTOR_COUNT, &sz_disk)) return FR_DISK_ERR;
/* Determine the CHS without any care of the drive geometry */
for (n = 16; n < 256 && sz_disk / n / 63 > 1024; n *= 2) ;
for (n = 16; n < 256 && sz_disk / n / cluster_size > 1024; n *= 2) ;
if (n == 256) n--;
if (sz_disk < SUPPORTED_FLASH_SIZE) {
cluster_size = 1;
n = sz_disk;
}
e_hd = n - 1;
sz_cyl = 63 * n;
sz_cyl = cluster_size * n;
tot_cyl = sz_disk / sz_cyl;
/* Create partition table */
@ -5699,7 +5705,7 @@ FRESULT f_fdisk (
sz_part = (DWORD)sz_cyl * p_cyl;
if (i == 0) { /* Exclude first track of cylinder 0 */
s_hd = 1;
s_part += 63; sz_part -= 63;
s_part += cluster_size; sz_part -= cluster_size;
} else {
s_hd = 0;
}
@ -5712,7 +5718,7 @@ FRESULT f_fdisk (
p[3] = (BYTE)b_cyl; /* Start cylinder */
p[4] = 0x06; /* System type (temporary setting) */
p[5] = e_hd; /* End head */
p[6] = (BYTE)((e_cyl >> 2) + 63); /* End sector */
p[6] = (BYTE)((e_cyl >> 2) + cluster_size); /* End sector */
p[7] = (BYTE)e_cyl; /* End cylinder */
st_dword(p + 8, s_part); /* Start sector in LBA */
st_dword(p + 12, sz_part); /* Partition size */

View file

@ -179,7 +179,7 @@
#define _MIN_SS 512
#define _MAX_SS 512
#define _MAX_SS 4096
/* These options configure the range of sector size to be supported. (512, 1024,
/ 2048 or 4096) Always set both 512 for most systems, all type of memory cards and
/ harddisk. But a larger value may be required for on-board flash memory and some

View file

@ -34,6 +34,7 @@ esp_err_t esp_vfs_fat_sdmmc_mount(const char* base_path,
{
const size_t workbuf_size = 4096;
void* workbuf = NULL;
FATFS* fs = NULL;
if (s_card != NULL) {
return ESP_ERR_INVALID_STATE;
@ -82,7 +83,6 @@ esp_err_t esp_vfs_fat_sdmmc_mount(const char* base_path,
char drv[3] = {(char)('0' + pdrv), ':', 0};
// connect FATFS to VFS
FATFS* fs;
err = esp_vfs_fat_register(base_path, drv, mount_config->max_files, &fs);
if (err == ESP_ERR_INVALID_STATE) {
// it's okay, already registered with VFS
@ -129,6 +129,9 @@ esp_err_t esp_vfs_fat_sdmmc_mount(const char* base_path,
fail:
sdmmc_host_deinit();
free(workbuf);
if (fs) {
f_mount(NULL, drv, 0);
}
esp_vfs_fat_unregister_path(base_path);
ff_diskio_unregister(pdrv);
free(s_card);

View file

@ -0,0 +1,116 @@
// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <stdlib.h>
#include <string.h>
#include "esp_log.h"
#include "esp_vfs.h"
#include "esp_vfs_fat.h"
#include "diskio.h"
#include "wear_levelling.h"
#include "diskio_spiflash.h"
static const char *TAG = "vfs_fat_spiflash";
esp_err_t esp_vfs_fat_spiflash_mount(const char* base_path,
const char* partition_label,
const esp_vfs_fat_mount_config_t* mount_config,
wl_handle_t* wl_handle)
{
esp_err_t result = ESP_OK;
const size_t workbuf_size = 4096;
void *workbuf = NULL;
esp_partition_t *data_partition = (esp_partition_t *)esp_partition_find_first(ESP_PARTITION_TYPE_DATA, ESP_PARTITION_SUBTYPE_DATA_FAT, partition_label);
if (data_partition == NULL) {
ESP_LOGE(TAG, "Failed to find FATFS partition (type='data', subtype='fat', partition_label='%s'). Check the partition table.", partition_label);
return ESP_ERR_NOT_FOUND;
}
result = wl_mount(data_partition, wl_handle);
if (result != ESP_OK) {
ESP_LOGE(TAG, "failed to mount wear levelling layer. result = %i", result);
return result;
}
// connect driver to FATFS
BYTE pdrv = 0xFF;
if (ff_diskio_get_drive(&pdrv) != ESP_OK || pdrv == 0xFF) {
ESP_LOGD(TAG, "the maximum count of volumes is already mounted");
return ESP_ERR_NO_MEM;
}
ESP_LOGD(TAG, "pdrv=%i\n", pdrv);
char drv[3] = {(char)('0' + pdrv), ':', 0};
result = ff_diskio_register_wl_partition(pdrv, *wl_handle);
if (result != ESP_OK) {
ESP_LOGE(TAG, "ff_diskio_register_wl_partition failed pdrv=%i, error - 0x(%x)", pdrv, result);
goto fail;
}
FATFS *fs;
result = esp_vfs_fat_register(base_path, drv, mount_config->max_files, &fs);
if (result == ESP_ERR_INVALID_STATE) {
// it's okay, already registered with VFS
} else if (result != ESP_OK) {
ESP_LOGD(TAG, "esp_vfs_fat_register failed 0x(%x)", result);
goto fail;
}
// Try to mount partition
FRESULT fresult = f_mount(fs, drv, 1);
if (fresult != FR_OK) {
ESP_LOGW(TAG, "f_mount failed (%d)", fresult);
if (!(fresult == FR_NO_FILESYSTEM && mount_config->format_if_mount_failed)) {
result = ESP_FAIL;
goto fail;
}
workbuf = malloc(workbuf_size);
ESP_LOGI(TAG, "Formatting FATFS partition");
fresult = f_mkfs("", FM_ANY | FM_SFD, workbuf_size, workbuf, workbuf_size);
if (fresult != FR_OK) {
result = ESP_FAIL;
ESP_LOGE(TAG, "f_mkfs failed (%d)", fresult);
goto fail;
}
free(workbuf);
ESP_LOGI(TAG, "Mounting again");
fresult = f_mount(fs, drv, 0);
if (fresult != FR_OK) {
result = ESP_FAIL;
ESP_LOGE(TAG, "f_mount failed after formatting (%d)", fresult);
goto fail;
}
}
return ESP_OK;
fail:
free(workbuf);
esp_vfs_fat_unregister_path(base_path);
ff_diskio_unregister(pdrv);
return result;
}
esp_err_t esp_vfs_fat_spiflash_unmount(const char *base_path, wl_handle_t wl_handle)
{
BYTE s_pdrv = ff_diskio_get_pdrv_wl(wl_handle);
char drv[3] = {(char)('0' + s_pdrv), ':', 0};
f_mount(0, drv, 0);
ff_diskio_unregister(s_pdrv);
// release partition driver
esp_err_t err_drv = wl_unmount(wl_handle);
esp_err_t err = esp_vfs_fat_unregister_path(base_path);
if (err == ESP_OK) err = err_drv;
return err;
}

View file

@ -255,7 +255,6 @@ void vPortStoreTaskMPUSettings( xMPU_SETTINGS *xMPUSettings, const struct xMEMOR
}
#endif
/*
* Returns true if the current core is in ISR context; low prio ISR, med prio ISR or timer tick ISR. High prio ISRs
* aren't detected here, but they normally cannot call C code, so that should not be an issue anyway.

View file

@ -59,3 +59,136 @@ To configure logging output per module at runtime, add calls to ``esp_log_level_
esp_log_level_set("wifi", ESP_LOG_WARN); // enable WARN logs from WiFi stack
esp_log_level_set("dhcpc", ESP_LOG_INFO); // enable INFO logs from DHCP client
Logging to Host via JTAG
^^^^^^^^^^^^^^^^^^^^^^^^
By default logging library uses vprintf-like function to write formatted output to dedicated UART. In general it invloves the following steps:
1. Format string is parsed to obtain type of each argument.
2. According to its type every argument is converted to string representation.
3. Format string combined with converted arguments is sent to UART.
Though implementation of vprintf-like function can be optimised to a certain level, all steps above have to be peformed in any case and every step takes some time (especially item 3). So it is frequent situation when addition of extra logging to the program to diagnose some problem changes its behaviour and problem dissapears or in the worst cases program can not work normally at all and ends up with an error or even hangs.
Possible ways to overcome this problem are to use faster UART bitrates (or another faster interface) and/or move string formatting procedure to the host.
ESP IDF has `Application Tracing` feature which allows to sent arbitrary application data to host via JTAG. This feature can also be used to transfer log information to host using ``esp_apptrace_vprintf`` function. This function does not perform full parsing of the format string and arguments, instead it just calculates number of arguments passed and sends them along with the format string address to the host. On the host log data are processed and printed out by a special Python script.
Config Options and Dependencies
"""""""""""""""""""""""""""""""
Using of the feature depends on two components:
1. Host side: Application tracing is done over JTAG, so it needs OpenOCD to be set up and running on host machine. For instructions how to set it up, please, see :idf:`OpenOCD setup for ESP32` section for details. **NOTE:** `in order to achieve higher data rates you may need to modify JTAG adapter working frequency in OpenOCD config file. Maximum tested stable speed is 26MHz, so you need to have the following statement in your configuration file` ``adapter_khz 26000`` `instead of default` ``adapter_khz 200``. `Actually maximum stable JTAG frequency can depend on host system configuration.`
2. Target side: Application tracing functionality can be enabled by ``CONFIG_ESP32_APPTRACE_ENABLE`` macro via menuconfig. This option enables the module and makes ``esp_apptrace_vprintf`` available for users.
Limitations
"""""""""""
Curent implmentation of logging over JTAG has several limitations:
1. Tracing from ``ESP_EARLY_LOGx`` macros is not supported.
2. No support for printf arguments which size exceeds 4 bytes (e.g. ``double`` and ``uint64_t``).
3. Only strings from .rodata section are supported as format strings and arguments.
4. Maximum number of printf arguments is 256.
How To Use It
"""""""""""""
To use logging via JTAG user needs to perform the following steps:
1. On target side special vprintf-like function needs to be installed. As it was mentioned earlier this function is ``esp_apptrace_vprintf``. It sends log data to the host via JTAG. Example code is shown below.
.. code-block:: c
#include "esp_app_trace.h"
...
void app_main()
{
// set log vprintf handler
esp_log_set_vprintf(esp_apptrace_vprintf);
...
// user code using ESP_LOGx starts here
// all data passed to ESP_LOGx are sent to host
...
// restore log vprintf handler
esp_log_set_vprintf(vprintf);
// flush last data to host
esp_apptrace_flush(ESP_APPTRACE_DEST_TRAX, 100000 /*tmo in us*/);
ESP_LOGI(TAG, "Tracing is finished."); // this will be printed out to UART
while (1);
}
2. Build the program image and download it to target as described in :idf:`Developing With the ESP-IDF` section.
3. Run OpenOCD (see :idf:`OpenOCD setup for ESP32` section).
4. Connect to OpenOCD telnet server. On Linux it can be done using the following command in terminal ``telnet <oocd_host> 4444``. If telnet session is opened on the same machine which runs OpenOCD you can use `localhost` as `<oocd_host>` in the command.
5. Run the following command in OpenOCD telnet session: ``esp108 apptrace start /path/to/trace/file -1 -1 0 0 1``. This command will wait for board reset and transfer tracing data at the highest possible rate.
6. Reset the board. Logging to host will start automatically.
7. ``esp108 apptrace`` command with given arguments will never return (see other command options below), so you must stop it manually by resetting the board or pressing CTRL+C in OpenOCD window (not one with the telnet session).
8. Reset board or press CTRL+C in OpenOCD window (not one with the telnet session) when tracing is completed (for the example code above after the message `"Tracing is finished."` appears on UART).
9. To print out collected log records run the following command in terminal: ``$IDF_PATH/tools/esp_app_trace/logtrace_proc.py /path/to/trace/file /path/to/program/elf/file``.
OpenOCD Application Tracing Command Options
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
Command usage:
``esp108 apptrace [start <outfile> [options] | [stop] | [status] | [dump <outfile>]``
Sub-commands:
* ``start``. Start tracing (continuous streaming).
* ``stop``. Stop tracing.
* ``status``. Get tracing status.
* ``dump``. Dump as much data as possible without waiting for trace memory block switch (post-mortem dump).
Start command syntax:
``start <outfile> [trace_size [stop_tmo [skip_size [poll_period [wait4halt]]]]]``
.. list-table::
:widths: 20 80
:header-rows: 1
* - Argument
- Description
* - outfile
- Path to log trace file to save data
* - trace_size
- Maximum size of data to collect (in bytes). Tracing is stopped after specified amount of data is received. By default -1 (trace size stop trigger is disabled).
* - stop_tmo
- Idle timeout (in ms). Tracing is stopped if there is no data for specified period of time. By default 10 s (-1 to disable this stop trigger).
* - skip_size
- Number of bytes to skip at the start. By default 0.
* - poll_period
- Data polling period (in ms). If greater then 0 then command runs in non-blocking mode, otherwise command line will not be avalable until tracing is stopped. By default 1 ms.
* - wait4halt
- If 0 start tracing immediately, otherwise command waits for the target to be halted (after reset, by breakpoint etc) and then automatically resumes it and starts tracing. By default 0.
Log Trace Processor Command Options
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
Command usage:
``logtrace_proc.py [-h] [--no-errors] <trace_file> <elf_file>``
Positional arguments:
.. list-table::
:widths: 20 80
:header-rows: 1
* - Argument
- Description
* - trace_file
- Path to log trace file
* - elf_file
- Path to program ELF file
Optional arguments:
.. list-table::
:widths: 20 80
:header-rows: 1
* - Argument
- Description
* - -h, --help
- show this help message and exit
* - --no-errors, -n
- Do not print errors

View file

@ -89,6 +89,54 @@ config LWIP_DHCP_DOES_ARP_CHECK
Enabling this option allows check if the offered IP address is not already
in use by another host on the network.
config TCPIP_TASK_STACK_SIZE
int "TCP/IP Task Stack Size"
default 2048
help
Configure TCP/IP task stack size, used by LWIP to process multi-threaded TCP/IP operations.
The default is 2048 bytes, setting this stack too small will result in stack overflow crashes.
menuconfig PPP_SUPPORT
bool "Enable PPP support (new/experimental)"
default n
help
Enable PPP stack. Now only PPP over serial is possible.
PPP over serial support is experimental and unsupported.
config PPP_PAP_SUPPORT
bool "Enable PAP support"
depends on PPP_SUPPORT
default n
help
Enable Password Authentication Protocol (PAP) support
config PPP_CHAP_SUPPORT
bool "Enable CHAP support"
depends on PPP_SUPPORT
default n
help
Enable Challenge Handshake Authentication Protocol (CHAP) support
config PPP_MSCHAP_SUPPORT
bool "Enable MSCHAP support"
depends on PPP_SUPPORT
default n
help
Enable Microsoft version of the Challenge-Handshake Authentication Protocol (MSCHAP) support
config PPP_MPPE_SUPPORT
bool "Enable MPPE support"
depends on PPP_SUPPORT
default n
help
Enable Microsoft Point-to-Point Encryption (MPPE) support
config PPP_DEBUG_ON
bool "Enable PPP debug log output"
depends on PPP_SUPPORT
default n
help
Enable PPP debug log output
endmenu

View file

@ -73,10 +73,10 @@ pppapi_set_default(ppp_pcb *pcb)
static err_t
pppapi_do_ppp_set_auth(struct tcpip_api_call *m)
{
struct pppapi_msg_msg *msg = (struct pppapi_msg_msg *)m;
struct pppapi_msg *msg = (struct pppapi_msg *)m;
ppp_set_auth(msg->ppp, msg->msg.setauth.authtype,
msg->msg.setauth.user, msg->msg.setauth.passwd);
ppp_set_auth(msg->msg.ppp, msg->msg.msg.setauth.authtype,
msg->msg.msg.setauth.user, msg->msg.msg.setauth.passwd);
return ERR_OK;
}
@ -131,10 +131,10 @@ pppapi_set_notify_phase_callback(ppp_pcb *pcb, ppp_notify_phase_cb_fn notify_pha
static err_t
pppapi_do_pppos_create(struct tcpip_api_call *m)
{
struct pppapi_msg_msg *msg = (struct pppapi_msg_msg *)m;
struct pppapi_msg *msg = (struct pppapi_msg *)(m);
msg->ppp = pppos_create(msg->msg.serialcreate.pppif, msg->msg.serialcreate.output_cb,
msg->msg.serialcreate.link_status_cb, msg->msg.serialcreate.ctx_cb);
msg->msg.ppp = pppos_create(msg->msg.msg.serialcreate.pppif, msg->msg.msg.serialcreate.output_cb,
msg->msg.msg.serialcreate.link_status_cb, msg->msg.msg.serialcreate.ctx_cb);
return ERR_OK;
}
@ -247,9 +247,9 @@ pppapi_pppol2tp_create(struct netif *pppif, struct netif *netif, ip_addr_t *ipad
static err_t
pppapi_do_ppp_connect(struct tcpip_api_call *m)
{
struct pppapi_msg_msg *msg = (struct pppapi_msg_msg *)m;
struct pppapi_msg *msg = (struct pppapi_msg *)m;
return ppp_connect(msg->ppp, msg->msg.connect.holdoff);
return ppp_connect(msg->msg.ppp, msg->msg.msg.connect.holdoff);
}
/**
@ -300,9 +300,9 @@ pppapi_listen(ppp_pcb *pcb, struct ppp_addrs *addrs)
static err_t
pppapi_do_ppp_close(struct tcpip_api_call *m)
{
struct pppapi_msg_msg *msg = (struct pppapi_msg_msg *)m;
struct pppapi_msg *msg = (struct pppapi_msg *)m;
return ppp_close(msg->ppp, msg->msg.close.nocarrier);
return ppp_close(msg->msg.ppp, msg->msg.msg.close.nocarrier);
}
/**
@ -349,9 +349,9 @@ pppapi_free(ppp_pcb *pcb)
static err_t
pppapi_do_ppp_ioctl(struct tcpip_api_call *m)
{
struct pppapi_msg_msg *msg = (struct pppapi_msg_msg *)m;
struct pppapi_msg *msg = (struct pppapi_msg *)m;
return ppp_ioctl(msg->ppp, msg->msg.ioctl.cmd, msg->msg.ioctl.arg);
return ppp_ioctl(msg->msg.ppp, msg->msg.msg.ioctl.cmd, msg->msg.msg.ioctl.arg);
}
/**

View file

@ -719,6 +719,8 @@ static u8_t parse_options(u8_t *optptr, s16_t len)
*******************************************************************************/
static s16_t parse_msg(struct dhcps_msg *m, u16_t len)
{
u32_t lease_timer = (dhcps_lease_time * 60)/DHCPS_COARSE_TIMER_SECS;
if (memcmp((char *)m->options, &magic_cookie, sizeof(magic_cookie)) == 0) {
#if DHCPS_DEBUG
DHCPS_LOG("dhcps: len = %d\n", len);
@ -745,7 +747,7 @@ static s16_t parse_msg(struct dhcps_msg *m, u16_t len)
}
client_address.addr = pdhcps_pool->ip.addr;
pdhcps_pool->lease_timer = dhcps_lease_time;
pdhcps_pool->lease_timer = lease_timer;
pnode = pback_node;
goto POOL_CHECK;
} else if (pdhcps_pool->ip.addr == client_address_plus.addr) {
@ -783,7 +785,7 @@ static s16_t parse_msg(struct dhcps_msg *m, u16_t len)
pdhcps_pool->ip.addr = client_address.addr;
memcpy(pdhcps_pool->mac, m->chaddr, sizeof(pdhcps_pool->mac));
pdhcps_pool->lease_timer = dhcps_lease_time;
pdhcps_pool->lease_timer = lease_timer;
pnode = (list_node *)malloc(sizeof(list_node));
memset(pnode , 0x00 , sizeof(list_node));

View file

@ -2,11 +2,26 @@
# Component Makefile
#
COMPONENT_ADD_INCLUDEDIRS := include/lwip include/lwip/port include/lwip/posix apps/ping
COMPONENT_ADD_INCLUDEDIRS := \
include/lwip \
include/lwip/port \
include/lwip/posix \
apps/ping
COMPONENT_SRCDIRS := api apps/sntp apps/ping apps core/ipv4 core/ipv6 core netif port/freertos port/netif port/debug port
ifdef CONFIG_PPP_SUPPORT
LWIP_PPP_DIRS := netif/ppp/polarssl netif/ppp
endif
COMPONENT_SRCDIRS := \
api \
apps/sntp apps/ping apps \
core/ipv4 core/ipv6 core \
$(LWIP_PPP_DIRS) netif \
port/freertos port/netif port/debug port
CFLAGS += -Wno-address # lots of LWIP source files evaluate macros that check address of stack variables
api/tcpip.o apps/dhcpserver.o: CFLAGS += -Wno-unused-variable
apps/dhcpserver.o core/pbuf.o core/tcp_in.o: CFLAGS += -Wno-unused-but-set-variable
netif/ppp/pppos.o: CFLAGS += -Wno-type-limits

View file

@ -166,6 +166,7 @@ enum dhcps_offer_option{
OFFER_END
};
#define DHCPS_COARSE_TIMER_SECS 1
#define DHCPS_MAX_LEASE 0x64
#define DHCPS_LEASE_TIME_DEF (120)

View file

@ -134,6 +134,10 @@ err_t etharp_raw(struct netif *netif, const struct eth_addr *ethsrc_addr,
void etharp_arp_input(struct netif *netif, struct eth_addr *ethaddr, struct pbuf *p);
#if ETHARP_TRUST_IP_MAC
void etharp_ip_input(struct netif *netif, struct pbuf *p);
#endif
#ifdef __cplusplus
}
#endif

View file

@ -503,6 +503,56 @@
---------------------------------
*/
/**
* PPP_SUPPORT==1: Enable PPP.
*/
#define PPP_SUPPORT CONFIG_PPP_SUPPORT
#if PPP_SUPPORT
/**
* PAP_SUPPORT==1: Support PAP.
*/
#define PAP_SUPPORT CONFIG_PPP_PAP_SUPPORT
/**
* CHAP_SUPPORT==1: Support CHAP.
*/
#define CHAP_SUPPORT CONFIG_PPP_CHAP_SUPPORT
/**
* MSCHAP_SUPPORT==1: Support MSCHAP.
*/
#define MSCHAP_SUPPORT CONFIG_PPP_MSCHAP_SUPPORT
/**
* CCP_SUPPORT==1: Support CCP.
*/
#define MPPE_SUPPORT CONFIG_PPP_MPPE_SUPPORT
/**
* PPP_MAXIDLEFLAG: Max Xmit idle time (in ms) before resend flag char.
* TODO: If PPP_MAXIDLEFLAG > 0 and next package is send during PPP_MAXIDLEFLAG time,
* then 0x7E is not added at the begining of PPP package but 0x7E termination
* is always at the end. This behaviour brokes PPP dial with GSM (PPPoS).
* The PPP package should always start and end with 0x7E.
*/
#define PPP_MAXIDLEFLAG 0
/**
* PPP_DEBUG: Enable debugging for PPP.
*/
#define PPP_DEBUG_ON CONFIG_PPP_DEBUG_ON
#if PPP_DEBUG_ON
#define PPP_DEBUG LWIP_DBG_ON
#else
#define PPP_DEBUG LWIP_DBG_OFF
#endif
#endif
/*
--------------------------------------
---------- Checksum options ----------
@ -585,6 +635,18 @@
*/
#define TCPIP_DEBUG LWIP_DBG_OFF
/**
* ETHARP_TRUST_IP_MAC==1: Incoming IP packets cause the ARP table to be
* updated with the source MAC and IP addresses supplied in the packet.
* You may want to disable this if you do not trust LAN peers to have the
* correct addresses, or as a limited approach to attempt to handle
* spoofing. If disabled, lwIP will need to make a new ARP request if
* the peer is not already in the ARP table, adding a little latency.
* The peer *is* in the ARP table if it requested our address before.
* Also notice that this slows down input processing of every IP packet!
*/
#define ETHARP_TRUST_IP_MAC 1
/* Enable all Espressif-only options */

View file

@ -670,8 +670,7 @@ etharp_get_entry(u8_t i, ip4_addr_t **ipaddr, struct netif **netif, struct eth_a
*
* @see pbuf_free()
*/
static void
etharp_ip_input(struct netif *netif, struct pbuf *p)
void etharp_ip_input(struct netif *netif, struct pbuf *p)
{
struct eth_hdr *ethhdr;
struct ip_hdr *iphdr;

View file

@ -435,6 +435,13 @@ sys_init(void)
}
}
/*-----------------------------------------------------------------------------------*/
u32_t
sys_jiffies(void)
{
return xTaskGetTickCount();
}
/*-----------------------------------------------------------------------------------*/
u32_t
sys_now(void)

View file

@ -201,10 +201,14 @@ int mbedtls_net_bind( mbedtls_net_context *ctx, const char *bind_ip, const char
*
* Note: on a blocking socket this function always returns 0!
*/
static int net_would_block( const mbedtls_net_context *ctx )
static int net_would_block( const mbedtls_net_context *ctx, int *errout )
{
int error = mbedtls_net_errno(ctx->fd);
if ( errout ) {
*errout = error;
}
/*
* Never return 'WOULD BLOCK' on a non-blocking socket
*/
@ -260,7 +264,7 @@ int mbedtls_net_accept( mbedtls_net_context *bind_ctx,
}
if ( ret < 0 ) {
if ( net_would_block( bind_ctx ) != 0 ) {
if ( net_would_block( bind_ctx, NULL ) != 0 ) {
return ( MBEDTLS_ERR_SSL_WANT_READ );
}
@ -349,11 +353,10 @@ int mbedtls_net_recv( void *ctx, unsigned char *buf, size_t len )
ret = (int) read( fd, buf, len );
if ( ret < 0 ) {
if ( net_would_block( ctx ) != 0 ) {
if ( net_would_block( ctx, &error ) != 0 ) {
return ( MBEDTLS_ERR_SSL_WANT_READ );
}
error = mbedtls_net_errno(fd);
if ( error == EPIPE || error == ECONNRESET ) {
return ( MBEDTLS_ERR_NET_CONN_RESET );
}
@ -425,11 +428,10 @@ int mbedtls_net_send( void *ctx, const unsigned char *buf, size_t len )
ret = (int) write( fd, buf, len );
if ( ret < 0 ) {
if ( net_would_block( ctx ) != 0 ) {
if ( net_would_block( ctx, &error ) != 0 ) {
return ( MBEDTLS_ERR_SSL_WANT_WRITE );
}
error = mbedtls_net_errno(fd);
if ( error == EPIPE || error == ECONNRESET ) {
return ( MBEDTLS_ERR_NET_CONN_RESET );
}

View file

@ -1,7 +1,7 @@
test/test_nvs
test/coverage
test/coverage.info
*.gcno
*.gcda
*.gcov
*.o
test_nvs_host/test_nvs
test_nvs_host/coverage_report
test_nvs_host/coverage.info
**/*.gcno
**/*.gcda
**/*.gcov
**/*.o

View file

@ -19,7 +19,7 @@ SOURCE_FILES = \
crc.cpp \
main.cpp
CPPFLAGS += -I../include -I../src -I./ -I../../esp32/include -I ../../spi_flash/include -fprofile-arcs -ftest-coverage
CPPFLAGS += -I../include -I../src -I./ -I../../esp32/include -I ../../spi_flash/include -I ../../../tools/catch -fprofile-arcs -ftest-coverage
CFLAGS += -fprofile-arcs -ftest-coverage
CXXFLAGS += -std=c++11 -Wall -Werror
LDFLAGS += -lstdc++ -Wall -fprofile-arcs -ftest-coverage

View file

@ -57,6 +57,7 @@ config APP_OFFSET
default 0x10000 # this is the factory app offset used by the default tables
config PHY_DATA_OFFSET
depends on ESP32_PHY_INIT_DATA_IN_PARTITION
hex
default PARTITION_TABLE_CUSTOM_PHY_DATA_OFFSET if PARTITION_TABLE_CUSTOM
default 0xf000 # this is the factory app offset used by the default tables

View file

@ -21,12 +21,20 @@
#define BBPD_CTRL (DR_REG_BB_BASE + 0x0054)
#define BB_FFT_FORCE_PU (BIT(3))
#define BB_FFT_FORCE_PU_M (BIT(3))
#define BB_FFT_FORCE_PU_V 1
#define BB_FFT_FORCE_PU_S 3
#define BB_FFT_FORCE_PD (BIT(2))
#define BB_FFT_FORCE_PD_M (BIT(2))
#define BB_FFT_FORCE_PD_V 1
#define BB_FFT_FORCE_PD_S 2
#define BB_DC_EST_FORCE_PU (BIT(1))
#define BB_DC_EST_FORCE_PU_M (BIT(1))
#define BB_DC_EST_FORCE_PU_V 1
#define BB_DC_EST_FORCE_PU_S 1
#define BB_DC_EST_FORCE_PD (BIT(0))
#define BB_DC_EST_FORCE_PD_M (BIT(0))
#define BB_DC_EST_FORCE_PD_V 1
#define BB_DC_EST_FORCE_PD_S 0

View file

@ -3151,6 +3151,32 @@
#define DPORT_RECORD_PRO_PDEBUGINST_M ((DPORT_RECORD_PRO_PDEBUGINST_V)<<(DPORT_RECORD_PRO_PDEBUGINST_S))
#define DPORT_RECORD_PRO_PDEBUGINST_V 0xFFFFFFFF
#define DPORT_RECORD_PRO_PDEBUGINST_S 0
/* register layout:
* SIZE [7..0] : Instructions normally complete in the W stage. The size of the instruction in the W is given
* by this field in number of bytes. If it is 8b0 in a given cycle the W stage has no completing
* instruction. This is also known as a bubble cycle. Also see DPORT_PRO_CPU_RECORD_PDEBUGSTATUS_REG.
* ISRC [14..12] : Instruction source.
** LOOP [23..20] : Loopback status.
** CINTLEVEL [27..24]: CINTLEVEL.
*/
#define DPORT_RECORD_PDEBUGINST_SZ_M ((DPORT_RECORD_PDEBUGINST_SZ_V)<<(DPORT_RECORD_PDEBUGINST_SZ_S))
#define DPORT_RECORD_PDEBUGINST_SZ_V 0xFF
#define DPORT_RECORD_PDEBUGINST_SZ_S 0
#define DPORT_RECORD_PDEBUGINST_SZ(_r_) (((_r_)>>DPORT_RECORD_PDEBUGINST_SZ_S) & DPORT_RECORD_PDEBUGINST_SZ_V)
#define DPORT_RECORD_PDEBUGINST_ISRC_M ((DPORT_RECORD_PDEBUGINST_ISRC_V)<<(DPORT_RECORD_PDEBUGINST_ISRC_S))
#define DPORT_RECORD_PDEBUGINST_ISRC_V 0x07
#define DPORT_RECORD_PDEBUGINST_ISRC_S 12
#define DPORT_RECORD_PDEBUGINST_ISRC(_r_) (((_r_)>>DPORT_RECORD_PDEBUGINST_ISRC_S) & DPORT_RECORD_PDEBUGINST_ISRC_V)
// #define DPORT_RECORD_PDEBUGINST_LOOP_M ((DPORT_RECORD_PDEBUGINST_LOOP_V)<<(DPORT_RECORD_PDEBUGINST_LOOP_S))
// #define DPORT_RECORD_PDEBUGINST_LOOP_V 0x0F
// #define DPORT_RECORD_PDEBUGINST_LOOP_S 20
// #define DPORT_RECORD_PDEBUGINST_LOOP(_r_) (((_r_)>>DPORT_RECORD_PDEBUGINST_LOOP_S) & DPORT_RECORD_PDEBUGINST_LOOP_V)
#define DPORT_RECORD_PDEBUGINST_LOOP_REP (BIT(20)) /* loopback will occur */
#define DPORT_RECORD_PDEBUGINST_LOOP (BIT(21)) /* last inst of loop */
#define DPORT_RECORD_PDEBUGINST_CINTL_M ((DPORT_RECORD_PDEBUGINST_CINTL_V)<<(DPORT_RECORD_PDEBUGINST_CINTL_S))
#define DPORT_RECORD_PDEBUGINST_CINTL_V 0x0F
#define DPORT_RECORD_PDEBUGINST_CINTL_S 24
#define DPORT_RECORD_PDEBUGINST_CINTL(_r_) (((_r_)>>DPORT_RECORD_PDEBUGINST_CINTL_S) & DPORT_RECORD_PDEBUGINST_CINTL_V)
#define DPORT_PRO_CPU_RECORD_PDEBUGSTATUS_REG (DR_REG_DPORT_BASE + 0x450)
/* DPORT_RECORD_PRO_PDEBUGSTATUS : RO ;bitpos:[7:0] ;default: 8'b0 ; */
@ -3159,6 +3185,52 @@
#define DPORT_RECORD_PRO_PDEBUGSTATUS_M ((DPORT_RECORD_PRO_PDEBUGSTATUS_V)<<(DPORT_RECORD_PRO_PDEBUGSTATUS_S))
#define DPORT_RECORD_PRO_PDEBUGSTATUS_V 0xFF
#define DPORT_RECORD_PRO_PDEBUGSTATUS_S 0
/* register layout:
* BBCAUSE [5..0]: Indicates cause for bubble cycle. See below for posible values. When DPORT_RECORD_PDEBUGINST_SZ == 0
* INSNTYPE[5..0]: Indicates type of instruction retiring in the W stage. See below for posible values. When DPORT_RECORD_PDEBUGINST_SZ > 0
*/
#define DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_M ((DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_V)<<(DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_S))
#define DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_V 0x3F
#define DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_S 0
#define DPORT_RECORD_PDEBUGSTATUS_BBCAUSE(_r_) (((_r_)>>DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_S) & DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_V)
#define DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_PSO 0x00 /* Power shut off */
#define DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_DEP 0x02 /* Register dependency or resource conflict. See DPORT_XXX_CPU_RECORD_PDEBUGDATA_REG for extra info. */
#define DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_CTL 0x04 /* Control transfer bubble */
#define DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_ICM 0x08 /* I-cache miss (incl uncached miss) */
#define DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_DCM 0x0C /* D-cache miss (excl uncached miss) */
#define DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_EXC0 0x10 /* Exception or interrupt (W stage). See DPORT_XXX_CPU_RECORD_PDEBUGDATA_REG for extra info.
The virtual address of the instruction that was killed appears on DPORT_PRO_CPU_RECORD_PDEBUGPC_REG[31:0] */
#define DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_EXC1 0x11 /* Exception or interrupt (W+1 stage). See DPORT_XXX_CPU_RECORD_PDEBUGDATA_REG for extra info. */
#define DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_RPL 0x14 /* Instruction replay (other). DPORT_XXX_CPU_RECORD_PDEBUGDATA_REG has the PC of the replaying instruction. */
#define DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_ITLB 0x18 /* HW ITLB refill. The refill address and data are available on
DPORT_PRO_CPU_RECORD_PDEBUGLS0ADDR_REG and DPORT_PRO_CPU_RECORD_PDEBUGLS0DATA_REG. */
#define DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_ITLBM 0x1A /* ITLB miss */
#define DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_DTLB 0x1C /* HW DTLB refill. The refill address and data are available on
DPORT_PRO_CPU_RECORD_PDEBUGLS0ADDR_REG and DPORT_PRO_CPU_RECORD_PDEBUGLS0DATA_REG. */
#define DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_DTLBM 0x1E /* DTLB miss */
#define DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_STALL 0x20 /* Stall . The cause of the global stall is further classified in the DPORT_XXX_CPU_RECORD_PDEBUGDATA_REG. */
#define DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_HWMEC 0x24 /* HW-corrected memory error */
#define DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_WAITI 0x28 /* WAITI mode */
#define DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_OTHER 0x3C /* all other bubbles */
#define DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_M ((DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_V)<<(DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_S))
#define DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_V 0x3F
#define DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_S 0
#define DPORT_RECORD_PDEBUGSTATUS_INSNTYPE(_r_) (((_r_)>>DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_S) & DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_V)
#define DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_JX 0x00 /* JX */
#define DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_CALLX 0x04 /* CALLX */
#define DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_CRET 0x08 /* All call returns */
#define DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_ERET 0x0C /* All exception returns */
#define DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_B 0x10 /* Branch taken or loop not taken */
#define DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_J 0x14 /* J */
#define DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_CALL 0x18 /* CALL */
#define DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_BN 0x1C /* Branch not taken */
#define DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_LOOP 0x20 /* Loop instruction (taken) */
#define DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_S32C1I 0x24 /* S32C1I. The address and load data (before the conditional store) are available on the LS signals*/
#define DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_WXSR2LB 0x28 /* WSR/XSR to LBEGIN */
#define DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_WSR2MMID 0x2C /* WSR to MMID */
#define DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_RWXSR 0x30 /* RSR or WSR (except MMID and LBEGIN) or XSR (except LBEGIN) */
#define DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_RWER 0x34 /* RER or WER */
#define DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_DEF 0x3C /* Default */
#define DPORT_PRO_CPU_RECORD_PDEBUGDATA_REG (DR_REG_DPORT_BASE + 0x454)
/* DPORT_RECORD_PRO_PDEBUGDATA : RO ;bitpos:[31:0] ;default: 32'b0 ; */
@ -3167,6 +3239,115 @@
#define DPORT_RECORD_PRO_PDEBUGDATA_M ((DPORT_RECORD_PRO_PDEBUGDATA_V)<<(DPORT_RECORD_PRO_PDEBUGDATA_S))
#define DPORT_RECORD_PRO_PDEBUGDATA_V 0xFFFFFFFF
#define DPORT_RECORD_PRO_PDEBUGDATA_S 0
/* register layout when bubble cycke cause is DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_DEP:
*
* HALT [17]: HALT instruction (TX only)
* MEMW [16]: MEMW, EXTW or EXCW instruction dependency
* REG [12]: register dependencies or resource (e.g.TIE ports) conflicts
* STR [11]: store release (instruction) dependency
* LSU [8] : various LSU dependencies (MHT access, prefetch, cache access insts, s32c1i, etc)
* OTHER[0] : all other hold dependencies resulting from data or resource dependencies
*/
#define DPORT_RECORD_PDEBUGDATA_DEP_HALT (BIT(17))
#define DPORT_RECORD_PDEBUGDATA_DEP_MEMW (BIT(16))
#define DPORT_RECORD_PDEBUGDATA_DEP_REG (BIT(12))
#define DPORT_RECORD_PDEBUGDATA_DEP_STR (BIT(11))
#define DPORT_RECORD_PDEBUGDATA_DEP_LSU (BIT(8))
#define DPORT_RECORD_PDEBUGDATA_DEP_OTHER (BIT(0))
/* register layout when bubble cycke cause is DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_EXCn:
*
* EXCCAUSE[21..16]: Processor exception cause
* EXCVEC [4..0] : Encoded Exception Vector
*/
#define DPORT_RECORD_PDEBUGDATA_EXCCAUSE_M ((DPORT_RECORD_PDEBUGDATA_EXCCAUSE_V)<<(DPORT_RECORD_PDEBUGDATA_EXCCAUSE_S))
#define DPORT_RECORD_PDEBUGDATA_EXCCAUSE_V 0x3F
#define DPORT_RECORD_PDEBUGDATA_EXCCAUSE_S 16
#define DPORT_RECORD_PDEBUGDATA_EXCCAUSE(_r_) (((_r_)>>DPORT_RECORD_PDEBUGDATA_EXCCAUSE_S) & DPORT_RECORD_PDEBUGDATA_EXCCAUSE_V)
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_M ((DPORT_RECORD_PDEBUGDATA_EXCCAUSE_V)<<(DPORT_RECORD_PDEBUGDATA_EXCCAUSE_S))
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_V 0x1F
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_S 0
#define DPORT_RECORD_PDEBUGDATA_EXCVEC(_r_) (((_r_)>>DPORT_RECORD_PDEBUGDATA_EXCCAUSE_S) & DPORT_RECORD_PDEBUGDATA_EXCCAUSE_V)
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_NONE 0x00 /* no vector */
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_RST 0x01 /* Reset */
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_DBG 0x02 /* Debug (repl corresp level “n”) */
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_NMI 0x03 /* NMI (repl corresp level “n”) */
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_USR 0x04 /* User */
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_KRNL 0x05 /* Kernel */
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_DBL 0x06 /* Double */
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_EMEM 0x07 /* Memory Error */
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_OVF4 0x0A /* Window Overflow 4 */
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_UNF4 0x0B /* Window Underflow 4 */
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_OVF8 0x0C /* Window Overflow 8 */
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_UNF8 0x0D /* Window Underflow 8 */
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_OVF12 0x0E /* Window Overflow 12 */
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_UNF12 0x0F /* Window Underflow 12 */
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_INT2 0x10 /* Int Level 2 (n/a if debug/NMI) */
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_INT3 0x11 /* Int Level 3 (n/a if debug/NMI) */
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_INT4 0x12 /* Int Level 4 (n/a if debug/NMI) */
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_INT5 0x13 /* Int Level 5 (n/a if debug/NMI) */
#define DPORT_RECORD_PDEBUGDATA_EXCVEC_INT6 0x14 /* Int Level 6 (n/a if debug/NMI) */
/* register layout when bubble cycke cause is DPORT_RECORD_PDEBUGSTATUS_BBCAUSE_STALL:
*
* ITERDIV[19] : Iterative divide stall.
* ITERMUL[18] : Iterative multiply stall.
* BANKCONFL[16]: Bank-conflict stall.
* BPLOAD[15] : Bypass load stall.
* LSPROC[14] : Load/store miss-processing stall.
* L32R[13] : FastL32R stall.
* BPIFETCH[12] : Bypass I fetch stall.
* RUNSTALL[10] : RunStall.
* TIE[9] : TIE port stall.
* IPIF[8] : Instruction RAM inbound-PIF stall.
* IRAMBUSY[7] : Instruction RAM/ROM busy stall.
* ICM[6] : I-cache-miss stall.
* LSU[4] : The LSU will stall the pipeline under various local memory access conflict situations.
* DCM[3] : D-cache-miss stall.
* BUFFCONFL[2] : Store buffer conflict stall.
* BUFF[1] : Store buffer full stall.
*/
#define DPORT_RECORD_PDEBUGDATA_STALL_ITERDIV (BIT(19))
#define DPORT_RECORD_PDEBUGDATA_STALL_ITERMUL (BIT(18))
#define DPORT_RECORD_PDEBUGDATA_STALL_BANKCONFL (BIT(16))
#define DPORT_RECORD_PDEBUGDATA_STALL_BPLOAD (BIT(15))
#define DPORT_RECORD_PDEBUGDATA_STALL_LSPROC (BIT(14))
#define DPORT_RECORD_PDEBUGDATA_STALL_L32R (BIT(13))
#define DPORT_RECORD_PDEBUGDATA_STALL_BPIFETCH (BIT(12))
#define DPORT_RECORD_PDEBUGDATA_STALL_RUN (BIT(10))
#define DPORT_RECORD_PDEBUGDATA_STALL_TIE (BIT(9))
#define DPORT_RECORD_PDEBUGDATA_STALL_IPIF (BIT(8))
#define DPORT_RECORD_PDEBUGDATA_STALL_IRAMBUSY (BIT(7))
#define DPORT_RECORD_PDEBUGDATA_STALL_ICM (BIT(6))
#define DPORT_RECORD_PDEBUGDATA_STALL_LSU (BIT(4))
#define DPORT_RECORD_PDEBUGDATA_STALL_DCM (BIT(3))
#define DPORT_RECORD_PDEBUGDATA_STALL_BUFFCONFL (BIT(2))
#define DPORT_RECORD_PDEBUGDATA_STALL_BUFF (BIT(1))
/* register layout for DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_RWXSR:
*
* XSR[10] : XSR Instruction
* WSR[9] : WSR Instruction
* RSR[8] : RSR Instruction
* SR[7..0] : Special Register Number
*/
#define DPORT_RECORD_PDEBUGDATA_INSNTYPE_XSR (BIT(10))
#define DPORT_RECORD_PDEBUGDATA_INSNTYPE_WSR (BIT(9))
#define DPORT_RECORD_PDEBUGDATA_INSNTYPE_RSR (BIT(8))
#define DPORT_RECORD_PDEBUGDATA_INSNTYPE_SR_M ((DPORT_RECORD_PDEBUGDATA_INSNTYPE_SR_V)<<(DPORT_RECORD_PDEBUGDATA_INSNTYPE_SR_S))
#define DPORT_RECORD_PDEBUGDATA_INSNTYPE_SR_V 0xFF
#define DPORT_RECORD_PDEBUGDATA_INSNTYPE_SR_S 0
#define DPORT_RECORD_PDEBUGDATA_INSNTYPE_SR(_r_) (((_r_)>>DPORT_RECORD_PDEBUGDATA_INSNTYPE_SR_S) & DPORT_RECORD_PDEBUGDATA_INSNTYPE_SR_V)
/* register layout for DPORT_RECORD_PDEBUGSTATUS_INSNTYPE_RWER:
*
* ER[13..2]: ER Address
* WER[1] : WER Instruction
* RER[0] : RER Instruction
*/
#define DPORT_RECORD_PDEBUGDATA_INSNTYPE_ER_M ((DPORT_RECORD_PDEBUGDATA_INSNTYPE_ER_V)<<(DPORT_RECORD_PDEBUGDATA_INSNTYPE_ER_S))
#define DPORT_RECORD_PDEBUGDATA_INSNTYPE_ER_V 0xFFF
#define DPORT_RECORD_PDEBUGDATA_INSNTYPE_ER_S 2
#define DPORT_RECORD_PDEBUGDATA_INSNTYPE_ER(_r_) (((_r_)>>DPORT_RECORD_PDEBUGDATA_INSNTYPE_ER_S) & DPORT_RECORD_PDEBUGDATA_INSNTYPE_ER_V)
#define DPORT_RECORD_PDEBUGDATA_INSNTYPE_WER (BIT(1))
#define DPORT_RECORD_PDEBUGDATA_INSNTYPE_RER (BIT(0))
#define DPORT_PRO_CPU_RECORD_PDEBUGPC_REG (DR_REG_DPORT_BASE + 0x458)
/* DPORT_RECORD_PRO_PDEBUGPC : RO ;bitpos:[31:0] ;default: 32'b0 ; */
@ -3183,6 +3364,68 @@
#define DPORT_RECORD_PRO_PDEBUGLS0STAT_M ((DPORT_RECORD_PRO_PDEBUGLS0STAT_V)<<(DPORT_RECORD_PRO_PDEBUGLS0STAT_S))
#define DPORT_RECORD_PRO_PDEBUGLS0STAT_V 0xFFFFFFFF
#define DPORT_RECORD_PRO_PDEBUGLS0STAT_S 0
/* register layout:
* TYPE [3..0] : Type of instruction in LS.
* SZ [7..4] : Operand size.
* DTLBM [8] : Data TLB miss.
* DCM [9] : D-cache miss.
* DCH [10] : D-cache hit.
* UC [12] : Uncached.
* WB [13] : Writeback.
* COH [16] : Coherency.
* STCOH [18..17]: Coherent state.
* TGT [23..20] : Local target.
*/
#define DPORT_RECORD_PDEBUGLS0STAT_TYPE_M ((DPORT_RECORD_PDEBUGLS0STAT_TYPE_V)<<(DPORT_RECORD_PDEBUGLS0STAT_TYPE_S))
#define DPORT_RECORD_PDEBUGLS0STAT_TYPE_V 0x0F
#define DPORT_RECORD_PDEBUGLS0STAT_TYPE_S 0
#define DPORT_RECORD_PDEBUGLS0STAT_TYPE(_r_) (((_r_)>>DPORT_RECORD_PDEBUGLS0STAT_TYPE_S) & DPORT_RECORD_PDEBUGLS0STAT_TYPE_V)
#define DPORT_RECORD_PDEBUGLS0STAT_TYPE_NONE 0x00 /* neither */
#define DPORT_RECORD_PDEBUGLS0STAT_TYPE_ITLBR 0x01 /* hw itlb refill */
#define DPORT_RECORD_PDEBUGLS0STAT_TYPE_DTLBR 0x02 /* hw dtlb refill */
#define DPORT_RECORD_PDEBUGLS0STAT_TYPE_LD 0x05 /* load */
#define DPORT_RECORD_PDEBUGLS0STAT_TYPE_STR 0x06 /* store */
#define DPORT_RECORD_PDEBUGLS0STAT_TYPE_L32R 0x08 /* l32r */
#define DPORT_RECORD_PDEBUGLS0STAT_TYPE_S32CLI1 0x0A /* s32ci1 */
#define DPORT_RECORD_PDEBUGLS0STAT_TYPE_CTI 0x0C /* cache test inst */
#define DPORT_RECORD_PDEBUGLS0STAT_TYPE_RWXSR 0x0E /* rsr/wsr/xsr */
#define DPORT_RECORD_PDEBUGLS0STAT_TYPE_RWER 0x0F /* rer/wer */
#define DPORT_RECORD_PDEBUGLS0STAT_SZ_M ((DPORT_RECORD_PDEBUGLS0STAT_SZ_V)<<(DPORT_RECORD_PDEBUGLS0STAT_SZ_S))
#define DPORT_RECORD_PDEBUGLS0STAT_SZ_V 0x0F
#define DPORT_RECORD_PDEBUGLS0STAT_SZ_S 4
#define DPORT_RECORD_PDEBUGLS0STAT_SZ(_r_) (((_r_)>>DPORT_RECORD_PDEBUGLS0STAT_SZ_S) & DPORT_RECORD_PDEBUGLS0STAT_SZ_V)
#define DPORT_RECORD_PDEBUGLS0STAT_SZB(_r_) ((8<<DPORT_RECORD_PDEBUGLS0STAT_SZ(_r_))/8) // in bytes
#define DPORT_RECORD_PDEBUGLS0STAT_DTLBM (BIT(8))
#define DPORT_RECORD_PDEBUGLS0STAT_DCM (BIT(9))
#define DPORT_RECORD_PDEBUGLS0STAT_DCH (BIT(10))
#define DPORT_RECORD_PDEBUGLS0STAT_UC (BIT(12))
#define DPORT_RECORD_PDEBUGLS0STAT_WB (BIT(13))
#define DPORT_RECORD_PDEBUGLS0STAT_COH (BIT(16))
#define DPORT_RECORD_PDEBUGLS0STAT_STCOH_M ((DPORT_RECORD_PDEBUGLS0STAT_STCOH_V)<<(DPORT_RECORD_PDEBUGLS0STAT_STCOH_S))
#define DPORT_RECORD_PDEBUGLS0STAT_STCOH_V 0x03
#define DPORT_RECORD_PDEBUGLS0STAT_STCOH_S 17
#define DPORT_RECORD_PDEBUGLS0STAT_STCOH(_r_) (((_r_)>>DPORT_RECORD_PDEBUGLS0STAT_STCOH_S) & DPORT_RECORD_PDEBUGLS0STAT_STCOH_V)
#define DPORT_RECORD_PDEBUGLS0STAT_STCOH_NONE 0x0 /* neither shared nor exclusive nor modified */
#define DPORT_RECORD_PDEBUGLS0STAT_STCOH_SHARED 0x1 /* shared */
#define DPORT_RECORD_PDEBUGLS0STAT_STCOH_EXCL 0x2 /* exclusive */
#define DPORT_RECORD_PDEBUGLS0STAT_STCOH_MOD 0x3 /* modified */
#define DPORT_RECORD_PDEBUGLS0STAT_TGT_M ((DPORT_RECORD_PDEBUGLS0STAT_TGT_V)<<(DPORT_RECORD_PDEBUGLS0STAT_TGT_S))
#define DPORT_RECORD_PDEBUGLS0STAT_TGT_V 0x0F
#define DPORT_RECORD_PDEBUGLS0STAT_TGT_S 20
#define DPORT_RECORD_PDEBUGLS0STAT_TGT(_r_) (((_r_)>>DPORT_RECORD_PDEBUGLS0STAT_TGT_S) & DPORT_RECORD_PDEBUGLS0STAT_TGT_V)
#define DPORT_RECORD_PDEBUGLS0STAT_TGT_EXT 0x0 /* not to local memory */
#define DPORT_RECORD_PDEBUGLS0STAT_TGT_IRAM0 0x2 /* 001x: InstRAM (0/1) */
#define DPORT_RECORD_PDEBUGLS0STAT_TGT_IRAM1 0x3 /* 001x: InstRAM (0/1) */
#define DPORT_RECORD_PDEBUGLS0STAT_TGT_IROM0 0x4 /* 010x: InstROM (0/1) */
#define DPORT_RECORD_PDEBUGLS0STAT_TGT_IROM1 0x5 /* 010x: InstROM (0/1) */
#define DPORT_RECORD_PDEBUGLS0STAT_TGT_DRAM0 0x0A /* 101x: DataRAM (0/1) */
#define DPORT_RECORD_PDEBUGLS0STAT_TGT_DRAM1 0x0B /* 101x: DataRAM (0/1) */
#define DPORT_RECORD_PDEBUGLS0STAT_TGT_DROM0 0xE /* 111x: DataROM (0/1) */
#define DPORT_RECORD_PDEBUGLS0STAT_TGT_DROM1 0xF /* 111x: DataROM (0/1) */
// #define DPORT_RECORD_PDEBUGLS0STAT_TGT_IRAM(_t_) (((_t_)&0xE)=0x2) /* 001x: InstRAM (0/1) */
// #define DPORT_RECORD_PDEBUGLS0STAT_TGT_IROM(_t_) (((_t_)&0xE)=0x4) /* 010x: InstROM (0/1) */
// #define DPORT_RECORD_PDEBUGLS0STAT_TGT_DRAM(_t_) (((_t_)&0xE)=0x2) /* 101x: DataRAM (0/1) */
// #define DPORT_RECORD_PDEBUGLS0STAT_TGT_DROM(_t_) (((_t_)&0xE)=0x2) /* 111x: DataROM (0/1) */
#define DPORT_PRO_CPU_RECORD_PDEBUGLS0ADDR_REG (DR_REG_DPORT_BASE + 0x460)
/* DPORT_RECORD_PRO_PDEBUGLS0ADDR : RO ;bitpos:[31:0] ;default: 32'b0 ; */

View file

@ -23,75 +23,135 @@ extern "C" {
#define EMAC_EX_CLKOUT_CONF_REG (REG_EMAC_EX_BASE + 0x0000)
#define EMAC_EX_CLK_OUT_DLY_NUM 0x00000003
#define EMAC_EX_CLK_OUT_DLY_NUM_M (EMAC_EX_CLK_OUT_DLY_NUM_V << EMAC_EX_CLK_OUT_DLY_NUM_S)
#define EMAC_EX_CLK_OUT_DLY_NUM_V 0x00000003
#define EMAC_EX_CLK_OUT_DLY_NUM_S 8
#define EMAC_EX_CLK_OUT_H_DIV_NUM 0x0000000F
#define EMAC_EX_CLK_OUT_H_DIV_NUM_M (EMAC_EX_CLK_OUT_H_DIV_NUM_V << EMAC_EX_CLK_OUT_H_DIV_NUM_S)
#define EMAC_EX_CLK_OUT_H_DIV_NUM_V 0x0000000F
#define EMAC_EX_CLK_OUT_H_DIV_NUM_S 4
#define EMAC_EX_CLK_OUT_DIV_NUM 0x0000000F
#define EMAC_EX_CLK_OUT_DIV_NUM_M (EMAC_EX_CLK_OUT_DIV_NUM_V << EMAC_EX_CLK_OUT_DIV_NUM_S)
#define EMAC_EX_CLK_OUT_DIV_NUM_V 0x0000000F
#define EMAC_EX_CLK_OUT_DIV_NUM_S 0
#define EMAC_EX_OSCCLK_CONF_REG (REG_EMAC_EX_BASE + 0x0004)
#define EMAC_EX_OSC_CLK_SEL (BIT(24))
#define EMAC_EX_OSC_CLK_SEL_M (BIT(24))
#define EMAC_EX_OSC_CLK_SEL_V 1
#define EMAC_EX_OSC_CLK_SEL_S 24
#define EMAC_EX_OSC_H_DIV_NUM_100M 0x0000003F
#define EMAC_EX_OSC_H_DIV_NUM_100M_M (EMAC_EX_OSC_H_DIV_NUM_100M_V << EMAC_EX_OSC_H_DIV_NUM_100M_S)
#define EMAC_EX_OSC_H_DIV_NUM_100M_V 0x0000003F
#define EMAC_EX_OSC_H_DIV_NUM_100M_S 18
#define EMAC_EX_OSC_DIV_NUM_100M 0x0000003F
#define EMAC_EX_OSC_DIV_NUM_100M_M (EMAC_EX_OSC_DIV_NUM_100M_V << EMAC_EX_OSC_DIV_NUM_100M_S)
#define EMAC_EX_OSC_DIV_NUM_100M_V 0x0000003F
#define EMAC_EX_OSC_DIV_NUM_100M_S 12
#define EMAC_EX_OSC_H_DIV_NUM_10M 0x0000003F
#define EMAC_EX_OSC_H_DIV_NUM_10M_M (EMAC_EX_OSC_H_DIV_NUM_10M_V << EMAC_EX_OSC_H_DIV_NUM_10M_S)
#define EMAC_EX_OSC_H_DIV_NUM_10M_V 0x0000003F
#define EMAC_EX_OSC_H_DIV_NUM_10M_S 6
#define EMAC_EX_OSC_DIV_NUM_10M 0x0000003F
#define EMAC_EX_OSC_DIV_NUM_10M_M (EMAC_EX_OSC_DIV_NUM_10M_V << EMAC_EX_OSC_DIV_NUM_10M_S)
#define EMAC_EX_OSC_DIV_NUM_10M_V 0x0000003F
#define EMAC_EX_OSC_DIV_NUM_10M_S 0
#define EMAC_EX_CLK_CTRL_REG (REG_EMAC_EX_BASE + 0x0008)
#define EMAC_EX_CLK_EN (BIT(5))
#define EMAC_EX_CLK_EN_M (BIT(5))
#define EMAC_EX_CLK_EN_V 1
#define EMAC_EX_CLK_EN_S 5
#define EMAC_EX_MII_CLK_RX_EN (BIT(4))
#define EMAC_EX_MII_CLK_RX_EN_M (BIT(4))
#define EMAC_EX_MII_CLK_RX_EN_V 1
#define EMAC_EX_MII_CLK_RX_EN_S 4
#define EMAC_EX_MII_CLK_TX_EN (BIT(3))
#define EMAC_EX_MII_CLK_TX_EN_M (BIT(3))
#define EMAC_EX_MII_CLK_TX_EN_V 1
#define EMAC_EX_MII_CLK_TX_EN_S 3
#define EMAC_EX_RX_125_CLK_EN (BIT(2))
#define EMAC_EX_RX_125_CLK_EN_M (BIT(2))
#define EMAC_EX_RX_125_CLK_EN_V 1
#define EMAC_EX_RX_125_CLK_EN_S 2
#define EMAC_EX_INT_OSC_EN (BIT(1))
#define EMAC_EX_INT_OSC_EN_M (BIT(1))
#define EMAC_EX_INT_OSC_EN_V 1
#define EMAC_EX_INT_OSC_EN_S 1
#define EMAC_EX_EXT_OSC_EN (BIT(0))
#define EMAC_EX_EXT_OSC_EN_M (BIT(0))
#define EMAC_EX_EXT_OSC_EN_V 1
#define EMAC_EX_EXT_OSC_EN_S 0
#define EMAC_EX_PHYINF_CONF_REG (REG_EMAC_EX_BASE + 0x000c)
#define EMAC_EX_TX_ERR_OUT_EN (BIT(20))
#define EMAC_EX_TX_ERR_OUT_EN_M (BIT(20))
#define EMAC_EX_TX_ERR_OUT_EN_V 1
#define EMAC_EX_TX_ERR_OUT_EN_S 20
#define EMAC_EX_SCR_SMI_DLY_RX_SYNC (BIT(19))
#define EMAC_EX_SCR_SMI_DLY_RX_SYNC_M (BIT(19))
#define EMAC_EX_SCR_SMI_DLY_RX_SYNC_V 1
#define EMAC_EX_SCR_SMI_DLY_RX_SYNC_S 19
#define EMAC_EX_PMT_CTRL_EN (BIT(18))
#define EMAC_EX_PMT_CTRL_EN_M (BIT(18))
#define EMAC_EX_PMT_CTRL_EN_V 1
#define EMAC_EX_PMT_CTRL_EN_S 18
#define EMAC_EX_SBD_CLK_GATING_EN (BIT(17))
#define EMAC_EX_SBD_CLK_GATING_EN_M (BIT(17))
#define EMAC_EX_SBD_CLK_GATING_EN_V 1
#define EMAC_EX_SBD_CLK_GATING_EN_S 17
#define EMAC_EX_SS_MODE (BIT(16))
#define EMAC_EX_SS_MODE_M (BIT(16))
#define EMAC_EX_SS_MODE_V 1
#define EMAC_EX_SS_MODE_S 16
#define EMAC_EX_PHY_INTF_SEL 0x00000007
#define EMAC_EX_PHY_INTF_SEL_M (EMAC_EX_PHY_INTF_SEL_V << EMAC_EX_PHY_INTF_SEL_S)
#define EMAC_EX_PHY_INTF_SEL_V 0x00000007
#define EMAC_EX_PHY_INTF_SEL_S 13
#define EMAC_EX_REVMII_PHY_ADDR 0x0000001F
#define EMAC_EX_REVMII_PHY_ADDR_M (EMAC_EX_REVMII_PHY_ADDR_V << EMAC_EX_REVMII_PHY_ADDR_S)
#define EMAC_EX_REVMII_PHY_ADDR_V 0x0000001F
#define EMAC_EX_REVMII_PHY_ADDR_S 8
#define EMAC_EX_CORE_PHY_ADDR 0x0000001F
#define EMAC_EX_CORE_PHY_ADDR_M (EMAC_EX_CORE_PHY_ADDR_V << EMAC_EX_CORE_PHY_ADDR_S)
#define EMAC_EX_CORE_PHY_ADDR_V 0x0000001F
#define EMAC_EX_CORE_PHY_ADDR_S 3
#define EMAC_EX_SBD_FLOWCTRL (BIT(2))
#define EMAC_EX_SBD_FLOWCTRL_M (BIT(2))
#define EMAC_EX_SBD_FLOWCTRL_V 1
#define EMAC_EX_SBD_FLOWCTRL_S 2
#define EMAC_EX_EXT_REVMII_RX_CLK_SEL (BIT(1))
#define EMAC_EX_EXT_REVMII_RX_CLK_SEL_M (BIT(1))
#define EMAC_EX_EXT_REVMII_RX_CLK_SEL_V 1
#define EMAC_EX_EXT_REVMII_RX_CLK_SEL_S 1
#define EMAC_EX_INT_REVMII_RX_CLK_SEL (BIT(0))
#define EMAC_EX_INT_REVMII_RX_CLK_SEL_M (BIT(0))
#define EMAC_EX_INT_REVMII_RX_CLK_SEL_V 1
#define EMAC_EX_INT_REVMII_RX_CLK_SEL_S 0
#define EMAC_EX_PHY_INTF_RMII 4
#define EMAC_EX_EMAC_PD_SEL_REG (REG_EMAC_EX_BASE + 0x0010)
#define EMAC_EX_RAM_PD_EN 0x00000003
#define EMAC_EX_RAM_PD_EN_M (EMAC_EX_RAM_PD_EN_V << EMAC_EX_RAM_PD_EN_S)
#define EMAC_EX_RAM_PD_EN_V 0x00000003
#define EMAC_EX_RAM_PD_EN_S 0
#define EMAC_EX_DATE_REG (REG_EMAC_EX_BASE + 0x00fc)
#define EMAC_EX_DATE 0xFFFFFFFF
#define EMAC_EX_DATE_M (EMAC_EX_DATE_V << EMAC_EX_DATE_S)
#define EMAC_EX_DATE_V 0xFFFFFFFF
#define EMAC_EX_DATE_S 0
#define EMAC_EX_DATE_VERSION 0x16042200
#define EMAC_EX_DATE_VERSION_M (EMAC_EX_DATE_VERSION_V << EMAC_EX_DATE_VERSION_S)
#define EMAC_EX_DATE_VERSION_V 0x16042200
#define EMAC_CLK_EN_REG 0x3ff000cc
#define EMAC_CLK_EN_REG_M (EMAC_CLK_EN_REG_V << EMAC_CLK_EN_REG_S)
#define EMAC_CLK_EN_REG_V 0x3ff000cc
#define EMAC_CLK_EN (BIT(14))
#define EMAC_CLK_EN_M (BIT(14))
#define EMAC_CLK_EN_V 1
#ifdef __cplusplus
}

File diff suppressed because it is too large Load diff

View file

@ -22,12 +22,20 @@
#define FE_GEN_CTRL (DR_REG_FE_BASE + 0x0090)
#define FE_IQ_EST_FORCE_PU (BIT(5))
#define FE_IQ_EST_FORCE_PU_M (BIT(5))
#define FE_IQ_EST_FORCE_PU_V 1
#define FE_IQ_EST_FORCE_PU_S 5
#define FE_IQ_EST_FORCE_PD (BIT(4))
#define FE_IQ_EST_FORCE_PD_M (BIT(4))
#define FE_IQ_EST_FORCE_PD_V 1
#define FE_IQ_EST_FORCE_PD_S 4
#define FE2_TX_INTERP_CTRL (DR_REG_FE2_BASE + 0x00f0)
#define FE2_TX_INF_FORCE_PU (BIT(10))
#define FE2_TX_INF_FORCE_PU_M (BIT(10))
#define FE2_TX_INF_FORCE_PU_V 1
#define FE2_TX_INF_FORCE_PU_S 10
#define FE2_TX_INF_FORCE_PD (BIT(9))
#define FE2_TX_INF_FORCE_PD_M (BIT(9))
#define FE2_TX_INF_FORCE_PD_V 1
#define FE2_TX_INF_FORCE_PD_S 9

View file

@ -1,9 +1,9 @@
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
@ -16,19 +16,61 @@
#include "soc.h"
/* The following are the bit fields for PERIPHS_IO_MUX_x_U registers */
/* Output enable in sleep mode */
#define SLP_OE (BIT(0))
#define SLP_OE_M (BIT(0))
#define SLP_OE_V 1
#define SLP_OE_S 0
/* Pin used for wakeup from sleep */
#define SLP_SEL (BIT(1))
#define SLP_SEL_M (BIT(1))
#define SLP_SEL_V 1
#define SLP_SEL_S 1
/* Pulldown enable in sleep mode */
#define SLP_PD (BIT(2))
#define SLP_PD_M (BIT(2))
#define SLP_PD_V 1
#define SLP_PD_S 2
/* Pullup enable in sleep mode */
#define SLP_PU (BIT(3))
#define SLP_PU_M (BIT(3))
#define SLP_PU_V 1
#define SLP_PU_S 3
/* Input enable in sleep mode */
#define SLP_IE (BIT(4))
#define SLP_IE_M (BIT(4))
#define SLP_IE_V 1
#define SLP_IE_S 4
/* Drive strength in sleep mode */
#define SLP_DRV 0x3
#define SLP_DRV_M (SLP_DRV_V << SLP_DRV_S)
#define SLP_DRV_V 0x3
#define SLP_DRV_S 5
/* Pulldown enable */
#define FUN_PD (BIT(7))
#define FUN_PD_M (BIT(7))
#define FUN_PD_V 1
#define FUN_PD_S 7
/* Pullup enable */
#define FUN_PU (BIT(8))
#define FUN_PU_M (BIT(8))
#define FUN_PU_V 1
#define FUN_PU_S 8
/* Input enable */
#define FUN_IE (BIT(9))
#define FUN_IE_M (FUN_IE_V << FUN_IE_S)
#define FUN_IE_V 1
#define FUN_IE_S 9
/* Drive strength */
#define FUN_DRV 0x3
#define FUN_DRV_M (FUN_DRV_V << FUN_DRV_S)
#define FUN_DRV_V 0x3
#define FUN_DRV_S 10
/* Function select (possible values are defined for each pin as FUNC_pinname_function below) */
#define MCU_SEL 0x7
#define MCU_SEL_M (MCU_SEL_V << MCU_SEL_S)
#define MCU_SEL_V 0x7
#define MCU_SEL_S 12
#define PIN_INPUT_ENABLE(PIN_NAME) SET_PERI_REG_MASK(PIN_NAME,FUN_IE)

View file

@ -22,18 +22,34 @@
#define NRXPD_CTRL (DR_REG_NRX_BASE + 0x00d4)
#define NRX_CHAN_EST_FORCE_PU (BIT(7))
#define NRX_CHAN_EST_FORCE_PU_M (BIT(7))
#define NRX_CHAN_EST_FORCE_PU_V 1
#define NRX_CHAN_EST_FORCE_PU_S 7
#define NRX_CHAN_EST_FORCE_PD (BIT(6))
#define NRX_CHAN_EST_FORCE_PD_M (BIT(6))
#define NRX_CHAN_EST_FORCE_PD_V 1
#define NRX_CHAN_EST_FORCE_PD_S 6
#define NRX_RX_ROT_FORCE_PU (BIT(5))
#define NRX_RX_ROT_FORCE_PU_M (BIT(5))
#define NRX_RX_ROT_FORCE_PU_V 1
#define NRX_RX_ROT_FORCE_PU_S 5
#define NRX_RX_ROT_FORCE_PD (BIT(4))
#define NRX_RX_ROT_FORCE_PD_M (BIT(4))
#define NRX_RX_ROT_FORCE_PD_V 1
#define NRX_RX_ROT_FORCE_PD_S 4
#define NRX_VIT_FORCE_PU (BIT(3))
#define NRX_VIT_FORCE_PU_M (BIT(3))
#define NRX_VIT_FORCE_PU_V 1
#define NRX_VIT_FORCE_PU_S 3
#define NRX_VIT_FORCE_PD (BIT(2))
#define NRX_VIT_FORCE_PD_M (BIT(2))
#define NRX_VIT_FORCE_PD_V 1
#define NRX_VIT_FORCE_PD_S 2
#define NRX_DEMAP_FORCE_PU (BIT(1))
#define NRX_DEMAP_FORCE_PU_M (BIT(1))
#define NRX_DEMAP_FORCE_PU_V 1
#define NRX_DEMAP_FORCE_PU_S 1
#define NRX_DEMAP_FORCE_PD (BIT(0))
#define NRX_DEMAP_FORCE_PD_M (BIT(0))
#define NRX_DEMAP_FORCE_PD_V 1
#define NRX_DEMAP_FORCE_PD_S 0

View file

@ -92,6 +92,9 @@ typedef enum {
RTC_FAST_FREQ_8M = 1, //!< Internal 8 MHz RC oscillator
} rtc_fast_freq_t;
/* With the default value of CK8M_DFREQ, 8M clock frequency is 8.5 MHz +/- 7% */
#define RTC_FAST_CLK_FREQ_APPROX 8500000
/**
* @brief Clock source to be calibrated using rtc_clk_cal function
*/
@ -307,6 +310,15 @@ uint32_t rtc_clk_apb_freq_get();
*/
uint32_t rtc_clk_cal(rtc_cal_sel_t cal_clk, uint32_t slow_clk_cycles);
/**
* @brief Measure ratio between XTAL frequency and RTC slow clock frequency
* @param cal_clk slow clock to be measured
* @param slow_clk_cycles number of slow clock cycles to average
* @return average ratio between XTAL frequency and slow clock frequency,
* Q13.19 fixed point format, or 0 if calibration has timed out.
*/
uint32_t rtc_clk_cal_ratio(rtc_cal_sel_t cal_clk, uint32_t slow_clk_cycles);
/**
* @brief Convert time interval from microseconds to RTC_SLOW_CLK cycles
* @param time_in_us Time interval in microseconds

View file

@ -511,6 +511,7 @@
#define RTC_IO_DEBUG_SEL0_M ((RTC_IO_DEBUG_SEL0_V)<<(RTC_IO_DEBUG_SEL0_S))
#define RTC_IO_DEBUG_SEL0_V 0x1F
#define RTC_IO_DEBUG_SEL0_S 0
#define RTC_IO_DEBUG_SEL0_8M 1
#define RTC_IO_DEBUG_SEL0_32K_XTAL 4
#define RTC_IO_DEBUG_SEL0_150K_OSC 5

View file

@ -1,9 +1,9 @@
// Copyright 2010-2016 Espressif Systems (Shanghai) PTE LTD
// Copyright 2010-2017 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
@ -89,8 +89,8 @@
//get field from register, uses field _S & _V to determine mask
#define REG_GET_FIELD(_r, _f) ((REG_READ(_r) >> (_f##_S)) & (_f##_V))
//set field to register, used when _f is not left shifted by _f##_S
#define REG_SET_FIELD(_r, _f, _v) (REG_WRITE((_r),((REG_READ(_r) & ~((_f) << (_f##_S)))|(((_v) & (_f))<<(_f##_S)))))
//set field of a register from variable, uses field _S & _V to determine mask
#define REG_SET_FIELD(_r, _f, _v) (REG_WRITE((_r),((REG_READ(_r) & ~((_f##_V) << (_f##_S)))|(((_v) & (_f##_V))<<(_f##_S)))))
//get field value from a variable, used when _f is not left shifted by _f##_S
#define VALUE_GET_FIELD(_r, _f) (((_r) >> (_f##_S)) & (_f))

View file

@ -67,6 +67,11 @@ static const char* TAG = "rtc_clk";
#define DELAY_SLOW_CLK_SWITCH 300
#define DELAY_8M_ENABLE 50
/* Number of 8M/256 clock cycles to use for XTAL frequency estimation.
* 10 cycles will take approximately 300 microseconds.
*/
#define XTAL_FREQ_EST_CYCLES 10
void rtc_clk_32k_enable(bool enable)
{
@ -422,19 +427,12 @@ void rtc_clk_xtal_freq_update(rtc_xtal_freq_t xtal_freq)
static rtc_xtal_freq_t rtc_clk_xtal_freq_estimate()
{
/* ROM startup code estimates XTAL frequency using an 8MD256 clock and stores
* the value into RTC_APB_FREQ_REG. The value is in Hz, right shifted by 12.
* Use this value to guess the real XTAL frequency.
*
* TODO: make this more robust by calibrating again after setting
* RTC_CNTL_CK8M_DFREQ.
uint64_t cal_val = rtc_clk_cal_ratio(RTC_CAL_8MD256, XTAL_FREQ_EST_CYCLES);
/* cal_val contains period of 8M/256 clock in XTAL clock cycles
* (shifted by RTC_CLK_CAL_FRACT bits).
* Xtal frequency will be (cal_val * 8M / 256) / 2^19
*/
uint32_t apb_freq_reg = READ_PERI_REG(RTC_APB_FREQ_REG);
if (!clk_val_is_valid(apb_freq_reg)) {
SOC_LOGW(TAG, "invalid RTC_APB_FREQ_REG value: 0x%08x", apb_freq_reg);
return RTC_XTAL_FREQ_AUTO;
}
uint32_t freq_mhz = (reg_val_to_clk_val(apb_freq_reg) << 12) / MHZ;
uint32_t freq_mhz = (cal_val * (RTC_FAST_CLK_FREQ_APPROX / MHZ) / 256 ) >> RTC_CLK_CAL_FRACT;
/* Guess the XTAL type. For now, only 40 and 26MHz are supported.
*/
switch (freq_mhz) {
@ -467,6 +465,19 @@ uint32_t rtc_clk_apb_freq_get()
void rtc_clk_init(rtc_clk_config_t cfg)
{
/* If we get a TG WDT system reset while running at 240MHz,
* DPORT_CPUPERIOD_SEL register will be reset to 0 resulting in 120MHz
* APB and CPU frequencies after reset. This will cause issues with XTAL
* frequency estimation, so we switch to XTAL frequency first.
*
* Ideally we would only do this if RTC_CNTL_SOC_CLK_SEL == PLL and
* PLL is configured for 480M, but it takes less time to switch to 40M and
* run the following code than querying the PLL does.
*/
if (REG_GET_FIELD(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_SOC_CLK_SEL) == RTC_CNTL_SOC_CLK_SEL_PLL) {
rtc_clk_cpu_freq_set(RTC_CPU_FREQ_XTAL);
}
/* Set tuning parameters for 8M and 150k clocks.
* Note: this doesn't attempt to set the clocks to precise frequencies.
* Instead, we calibrate these clocks against XTAL frequency later, when necessary.
@ -488,10 +499,16 @@ void rtc_clk_init(rtc_clk_config_t cfg)
/* Estimate XTAL frequency if requested */
rtc_xtal_freq_t xtal_freq = cfg.xtal_freq;
if (xtal_freq == RTC_XTAL_FREQ_AUTO) {
xtal_freq = rtc_clk_xtal_freq_estimate();
if (xtal_freq == RTC_XTAL_FREQ_AUTO) {
SOC_LOGW(TAG, "Can't estimate XTAL frequency, assuming 26MHz");
xtal_freq = RTC_XTAL_FREQ_26M;
if (clk_val_is_valid(READ_PERI_REG(RTC_XTAL_FREQ_REG))) {
/* XTAL frequency has already been set, use existing value */
xtal_freq = rtc_clk_xtal_freq_get();
} else {
/* Not set yet, estimate XTAL frequency based on RTC_FAST_CLK */
xtal_freq = rtc_clk_xtal_freq_estimate();
if (xtal_freq == RTC_XTAL_FREQ_AUTO) {
SOC_LOGW(TAG, "Can't estimate XTAL frequency, assuming 26MHz");
xtal_freq = RTC_XTAL_FREQ_26M;
}
}
}
rtc_clk_xtal_freq_update(xtal_freq);
@ -515,20 +532,3 @@ void rtc_clk_init(rtc_clk_config_t cfg)
* TODO: update the library to use rtc_clk_xtal_freq_get
*/
rtc_xtal_freq_t rtc_get_xtal() __attribute__((alias("rtc_clk_xtal_freq_get")));
/* Referenced in librtc.a:rtc.o.
* TODO: remove
*/
void rtc_uart_div_modify(int latch)
{
}
/* Referenced in librtc.a:rtc.o.
* TODO: remove
*/
void rtc_uart_tx_wait_idle(int uart)
{
}

View file

@ -31,9 +31,8 @@
* once, and TIMG_RTC_CALI_RDY bit is set when counting is done. One-off mode is
* enabled using TIMG_RTC_CALI_START bit.
*/
uint32_t rtc_clk_cal(rtc_cal_sel_t cal_clk, uint32_t slowclk_cycles)
uint32_t rtc_clk_cal_ratio(rtc_cal_sel_t cal_clk, uint32_t slowclk_cycles)
{
rtc_xtal_freq_t xtal_freq = rtc_clk_xtal_freq_get();
/* Enable requested clock (150k clock is always on) */
if (cal_clk == RTC_CAL_32K_XTAL) {
SET_PERI_REG_MASK(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_DIG_XTAL32K_EN);
@ -53,7 +52,7 @@ uint32_t rtc_clk_cal(rtc_cal_sel_t cal_clk, uint32_t slowclk_cycles)
expected_freq = 32768; /* standard 32k XTAL */
} else if (cal_clk == RTC_CAL_8MD256 ||
(cal_clk == RTC_CAL_RTC_MUX && slow_freq == RTC_SLOW_FREQ_8MD256)) {
expected_freq = 8 * MHZ / 256;
expected_freq = RTC_FAST_CLK_FREQ_APPROX / 256;
} else {
expected_freq = 150000; /* 150k internal oscillator */
}
@ -69,7 +68,8 @@ uint32_t rtc_clk_cal(rtc_cal_sel_t cal_clk, uint32_t slowclk_cycles)
/* Wait for calibration to finish up to another us_time_estimate */
int timeout_us = us_time_estimate;
while (!GET_PERI_REG_MASK(TIMG_RTCCALICFG_REG(0), TIMG_RTC_CALI_RDY) &&
timeout_us-- > 0) {
timeout_us > 0) {
timeout_us--;
ets_delay_us(1);
}
if (cal_clk == RTC_CAL_32K_XTAL) {
@ -84,9 +84,16 @@ uint32_t rtc_clk_cal(rtc_cal_sel_t cal_clk, uint32_t slowclk_cycles)
}
uint64_t xtal_cycles = REG_GET_FIELD(TIMG_RTCCALICFG1_REG(0), TIMG_RTC_CALI_VALUE);
uint64_t divider = ((uint64_t)xtal_freq) * slowclk_cycles;
uint64_t period_64 = (xtal_cycles << RTC_CLK_CAL_FRACT) / divider;
uint32_t period = (uint32_t)(period_64 & UINT32_MAX);
uint64_t ratio_64 = (xtal_cycles << RTC_CLK_CAL_FRACT) / slowclk_cycles;
uint32_t ratio = (uint32_t)(ratio_64 & UINT32_MAX);
return ratio;
}
uint32_t rtc_clk_cal(rtc_cal_sel_t cal_clk, uint32_t slowclk_cycles)
{
rtc_xtal_freq_t xtal_freq = rtc_clk_xtal_freq_get();
uint32_t ratio = rtc_clk_cal_ratio(cal_clk, slowclk_cycles);
uint32_t period = ratio / xtal_freq;
return period;
}

View file

@ -82,3 +82,10 @@ TEST_CASE("Output 32k XTAL clock to GPIO25", "[rtc_clk][ignore]")
rtc_clk_32k_enable(true);
pull_out_clk(RTC_IO_DEBUG_SEL0_32K_XTAL);
}
TEST_CASE("Output 8M XTAL clock to GPIO25", "[rtc_clk][ignore]")
{
rtc_clk_8m_enable(true, true);
SET_PERI_REG_MASK(RTC_IO_RTC_DEBUG_SEL_REG, RTC_IO_DEBUG_12M_NO_GATING);
pull_out_clk(RTC_IO_DEBUG_SEL0_8M);
}

View file

@ -87,9 +87,6 @@ extern uint8_t g_rom_spiflash_dummy_len_plus[];
static esp_rom_spiflash_result_t esp_rom_spiflash_enable_write(esp_rom_spiflash_chip_t *spi);
static esp_rom_spiflash_result_t esp_rom_spiflash_enable_qmode(esp_rom_spiflash_chip_t *spi);
static esp_rom_spiflash_result_t esp_rom_spiflash_disable_qmode(esp_rom_spiflash_chip_t *spi);
//only support spi1
static esp_rom_spiflash_result_t esp_rom_spiflash_erase_chip_internal(esp_rom_spiflash_chip_t *spi)
@ -309,65 +306,6 @@ static esp_rom_spiflash_result_t esp_rom_spiflash_enable_write(esp_rom_spiflash_
return ESP_ROM_SPIFLASH_RESULT_OK;
}
static esp_rom_spiflash_result_t esp_rom_spiflash_enable_qmode(esp_rom_spiflash_chip_t *spi)
{
uint32_t flash_status;
uint32_t status;
//read QE bit, not write if QE
if (ESP_ROM_SPIFLASH_RESULT_OK != esp_rom_spiflash_read_statushigh(spi, &status)) {
return ESP_ROM_SPIFLASH_RESULT_ERR;
}
if (status & ESP_ROM_SPIFLASH_QE) {
return ESP_ROM_SPIFLASH_RESULT_OK;
}
//enable 2 byte status writing
SET_PERI_REG_MASK(PERIPHS_SPI_FLASH_CTRL, ESP_ROM_SPIFLASH_TWO_BYTE_STATUS_EN);
if ( ESP_ROM_SPIFLASH_RESULT_OK != esp_rom_spiflash_enable_write(spi)) {
return ESP_ROM_SPIFLASH_RESULT_ERR;
}
esp_rom_spiflash_read_status(spi, &flash_status);
if ( ESP_ROM_SPIFLASH_RESULT_OK != esp_rom_spiflash_write_status(spi, flash_status | ESP_ROM_SPIFLASH_QE)) {
return ESP_ROM_SPIFLASH_RESULT_ERR;
}
return ESP_ROM_SPIFLASH_RESULT_OK;
}
static esp_rom_spiflash_result_t esp_rom_spiflash_disable_qmode(esp_rom_spiflash_chip_t *spi)
{
uint32_t flash_status;
uint32_t status;
//read QE bit, not write if not QE
if (ESP_ROM_SPIFLASH_RESULT_OK != esp_rom_spiflash_read_statushigh(spi, &status)) {
return ESP_ROM_SPIFLASH_RESULT_ERR;
}
//ets_printf("status %08x, line:%u\n", status, __LINE__);
if (!(status & ESP_ROM_SPIFLASH_QE)) {
return ESP_ROM_SPIFLASH_RESULT_OK;
}
//enable 2 byte status writing
SET_PERI_REG_MASK(PERIPHS_SPI_FLASH_CTRL, ESP_ROM_SPIFLASH_TWO_BYTE_STATUS_EN);
if ( ESP_ROM_SPIFLASH_RESULT_OK != esp_rom_spiflash_enable_write(spi)) {
return ESP_ROM_SPIFLASH_RESULT_ERR;
}
esp_rom_spiflash_read_status(spi, &flash_status);
//keep low 8 bit
if ( ESP_ROM_SPIFLASH_RESULT_OK != esp_rom_spiflash_write_status(spi, flash_status & 0xff)) {
return ESP_ROM_SPIFLASH_RESULT_ERR;
}
return ESP_ROM_SPIFLASH_RESULT_OK;
}
static void spi_cache_mode_switch(uint32_t modebit)
{
if ((modebit & SPI_FREAD_QIO) && (modebit & SPI_FASTRD_MODE)) {
@ -431,7 +369,7 @@ esp_rom_spiflash_result_t esp_rom_spiflash_lock()
}
esp_rom_spiflash_result_t esp_rom_spiflash_config_readmode(esp_rom_spiflash_read_mode_t mode, bool legacy)
esp_rom_spiflash_result_t esp_rom_spiflash_config_readmode(esp_rom_spiflash_read_mode_t mode)
{
uint32_t modebit;
@ -453,15 +391,6 @@ esp_rom_spiflash_result_t esp_rom_spiflash_config_readmode(esp_rom_spiflash_read
default : modebit = 0;
}
if ((ESP_ROM_SPIFLASH_QIO_MODE == mode) || (ESP_ROM_SPIFLASH_QOUT_MODE == mode)) {
esp_rom_spiflash_enable_qmode(&g_rom_spiflash_chip);
} else {
//do not need disable QMode in faster boot
if (legacy) {
esp_rom_spiflash_disable_qmode(&g_rom_spiflash_chip);
}
}
SET_PERI_REG_MASK(PERIPHS_SPI_FLASH_CTRL, modebit);
SET_PERI_REG_MASK(SPI_CTRL_REG(0), modebit);
spi_cache_mode_switch(modebit);
@ -668,7 +597,10 @@ esp_rom_spiflash_result_t esp_rom_spiflash_erase_area(uint32_t start_addr, uint3
uint32_t sector_num_per_block;
//set read mode to Fastmode ,not QDIO mode for erase
esp_rom_spiflash_config_readmode(ESP_ROM_SPIFLASH_SLOWRD_MODE, true);
//
// TODO: this is probably a bug as it doesn't re-enable QIO mode, not serious as this
// function is not used in IDF.
esp_rom_spiflash_config_readmode(ESP_ROM_SPIFLASH_SLOWRD_MODE);
//check if area is oversize of flash
if ((start_addr + area_len) > g_rom_spiflash_chip.chip_size) {

6
components/wear_levelling/.gitignore vendored Normal file
View file

@ -0,0 +1,6 @@
**/*.gcno
**/*.gcda
test_wl_host/coverage_report
test_wl_host/coverage.info
**/*.o
test_wl_host/test_wl

View file

@ -0,0 +1,66 @@
// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "esp_log.h"
#include "Partition.h"
static const char *TAG = "wl_partition";
Partition::Partition(const esp_partition_t *partition)
{
this->partition = partition;
}
size_t Partition::chip_size()
{
return this->partition->size;
}
esp_err_t Partition::erase_sector(size_t sector)
{
esp_err_t result = ESP_OK;
result = erase_range(sector * SPI_FLASH_SEC_SIZE, SPI_FLASH_SEC_SIZE);
return result;
}
esp_err_t Partition::erase_range(size_t start_address, size_t size)
{
esp_err_t result = esp_partition_erase_range(this->partition, start_address, size);
if (result == ESP_OK) {
ESP_LOGV(TAG, "erase_range - start_address=0x%08x, size=0x%08x, result=0x%08x", start_address, size, result);
} else {
ESP_LOGE(TAG, "erase_range - start_address=0x%08x, size=0x%08x, result=0x%08x", start_address, size, result);
}
return result;
}
esp_err_t Partition::write(size_t dest_addr, const void *src, size_t size)
{
esp_err_t result = ESP_OK;
result = esp_partition_write(this->partition, dest_addr, src, size);
return result;
}
esp_err_t Partition::read(size_t src_addr, void *dest, size_t size)
{
esp_err_t result = ESP_OK;
result = esp_partition_read(this->partition, src_addr, dest, size);
return result;
}
size_t Partition::sector_size()
{
return SPI_FLASH_SEC_SIZE;
}
Partition::~Partition()
{
}

View file

@ -0,0 +1,42 @@
Wear Levelling APIs
===================
Overview
--------
Most of the flash devices and specially SPI flash devices that are used in ESP32
have sector based organization and have limited amount of erase/modification cycles
per memory sector. To avoid situation when one sector reach the limit of erases when
other sectors was used not often, we have made a component that avoid this situation.
The wear levelling component share the amount of erases between all sectors in the
memory without user interaction.
The wear_levelling component contains APIs related to reading, writing, erasing,
memory mapping data in the external SPI flash through the partition component. It
also has higher-level APIs which work with FAT filesystem defined in
the :doc:`FAT filesystem </api/storage/fatfs>`.
The wear levelling component does not cache data in RAM. Write and erase functions
modify flash directly, and flash contents is consistent when the function returns.
Wear Levelling access APIs
--------------------------
This is the set of APIs for working with data in flash:
- ``wl_mount`` mount wear levelling module for defined partition
- ``wl_unmount`` used to unmount levelling module
- ``wl_erase_range`` used to erase range of addresses in flash
- ``wl_write`` used to write data to the partition
- ``wl_read`` used to read data from the partition
- ``wl_size`` return size of avalible memory in bytes
- ``wl_sector_size`` returns size of one sector
Generally, try to avoid using the raw wear levelling functions in favor of
filesystem-specific functions.
Memory Size
-----------
The memory size calculated in the wear Levelling module based on parameters of
partition. The module use few sectors of flash for internal data.

View file

@ -0,0 +1,81 @@
// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "esp_log.h"
#include "SPI_Flash.h"
#include "esp_spi_flash.h"
static const char *TAG = "spi_flash";
SPI_Flash::SPI_Flash()
{
}
size_t SPI_Flash::chip_size()
{
return spi_flash_get_chip_size();
}
esp_err_t SPI_Flash::erase_sector(size_t sector)
{
esp_err_t result = spi_flash_erase_sector(sector);
if (result == ESP_OK) {
ESP_LOGV(TAG, "erase_sector - sector=0x%08x, result=0x%08x", sector, result);
} else {
ESP_LOGE(TAG, "erase_sector - sector=0x%08x, result=0x%08x", sector, result);
}
return result;
}
esp_err_t SPI_Flash::erase_range(size_t start_address, size_t size)
{
size = (size + SPI_FLASH_SEC_SIZE - 1) / SPI_FLASH_SEC_SIZE;
size = size * SPI_FLASH_SEC_SIZE;
esp_err_t result = spi_flash_erase_range(start_address, size);
if (result == ESP_OK) {
ESP_LOGV(TAG, "erase_range - start_address=0x%08x, size=0x%08x, result=0x%08x", start_address, size, result);
} else {
ESP_LOGE(TAG, "erase_range - start_address=0x%08x, size=0x%08x, result=0x%08x", start_address, size, result);
}
return result;
}
esp_err_t SPI_Flash::write(size_t dest_addr, const void *src, size_t size)
{
esp_err_t result = spi_flash_write(dest_addr, src, size);
if (result == ESP_OK) {
ESP_LOGV(TAG, "write - dest_addr=0x%08x, size=0x%08x, result=0x%08x", dest_addr, size, result);
} else {
ESP_LOGE(TAG, "write - dest_addr=0x%08x, size=0x%08x, result=0x%08x", dest_addr, size, result);
}
return result;
}
esp_err_t SPI_Flash::read(size_t src_addr, void *dest, size_t size)
{
esp_err_t result = spi_flash_read(src_addr, dest, size);
if (result == ESP_OK) {
ESP_LOGV(TAG, "read - src_addr=0x%08x, size=0x%08x, result=0x%08x", src_addr, size, result);
} else {
ESP_LOGE(TAG, "read - src_addr=0x%08x, size=0x%08x, result=0x%08x", src_addr, size, result);
}
return result;
}
size_t SPI_Flash::sector_size()
{
return SPI_FLASH_SEC_SIZE;
}
SPI_Flash::~SPI_Flash()
{
}

View file

@ -0,0 +1,478 @@
// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <stdio.h>
#include "esp_log.h"
#include "WL_Flash.h"
#include <stdlib.h>
#include "crc32.h"
#include <string.h>
static const char *TAG = "wl_flash";
#ifndef WL_CFG_CRC_CONST
#define WL_CFG_CRC_CONST UINT32_MAX
#endif // WL_CFG_CRC_CONST
#define WL_RESULT_CHECK(result) \
if (result != ESP_OK) { \
ESP_LOGE(TAG,"%s(%d): result = 0x%08x", __FUNCTION__, __LINE__, result); \
return (result); \
}
#ifndef _MSC_VER // MSVS has different format for this define
static_assert(sizeof(wl_state_t) % 32 == 0, "wl_state_t structure size must be multiple of flash encryption unit size");
#endif // _MSC_VER
WL_Flash::WL_Flash()
{
}
WL_Flash::~WL_Flash()
{
free(this->temp_buff);
}
esp_err_t WL_Flash::config(wl_config_t *cfg, Flash_Access *flash_drv)
{
ESP_LOGV(TAG, "%s start_addr=0x%08x, full_mem_size=0x%08x, page_size=0x%08x, sector_size=0x%08x, updaterate=0x%08x, wr_size=0x%08x, version=0x%08x, temp_buff_size=0x%08x", __func__,
(uint32_t) cfg->start_addr,
cfg->full_mem_size,
cfg->page_size,
cfg->sector_size,
cfg->updaterate,
cfg->wr_size,
cfg->version,
(uint32_t) cfg->temp_buff_size);
cfg->crc = crc32::crc32_le(WL_CFG_CRC_CONST, (const unsigned char *)cfg, sizeof(wl_config_t) - sizeof(cfg->crc));
esp_err_t result = ESP_OK;
memcpy(&this->cfg, cfg, sizeof(wl_config_t));
this->configured = false;
if (cfg == NULL) {
result = ESP_ERR_INVALID_ARG;
}
this->flash_drv = flash_drv;
if (flash_drv == NULL) {
result = ESP_ERR_INVALID_ARG;
}
if ((this->cfg.sector_size % this->cfg.temp_buff_size) != 0) {
result = ESP_ERR_INVALID_ARG;
}
if (this->cfg.page_size < this->cfg.sector_size) {
result = ESP_ERR_INVALID_ARG;
}
WL_RESULT_CHECK(result);
this->temp_buff = (uint8_t *)malloc(this->cfg.temp_buff_size);
this->state_size = this->cfg.sector_size;
if (this->state_size < (sizeof(wl_state_t) + (this->cfg.full_mem_size / this->cfg.sector_size)*this->cfg.wr_size)) {
this->state_size = ((sizeof(wl_state_t) + (this->cfg.full_mem_size / this->cfg.sector_size) * this->cfg.wr_size) + this->cfg.sector_size - 1) / this->cfg.sector_size;
this->state_size = this->state_size * this->cfg.sector_size;
}
this->cfg_size = (sizeof(wl_config_t) + this->cfg.sector_size - 1) / this->cfg.sector_size;
this->cfg_size = cfg_size * this->cfg.sector_size;
this->addr_cfg = this->cfg.start_addr + this->cfg.full_mem_size - this->cfg_size;
this->addr_state1 = this->cfg.start_addr + this->cfg.full_mem_size - this->state_size * 2 - this->cfg_size; // allocate data at the end of memory
this->addr_state2 = this->cfg.start_addr + this->cfg.full_mem_size - this->state_size * 1 - this->cfg_size; // allocate data at the end of memory
this->flash_size = ((this->cfg.full_mem_size - this->state_size * 2 - this->cfg_size) / this->cfg.page_size - 1) * this->cfg.page_size; // -1 remove dummy block
ESP_LOGV(TAG, "%s - this->addr_state1=0x%08x", __func__, (uint32_t) this->addr_state1);
ESP_LOGV(TAG, "%s - this->addr_state2=0x%08x", __func__, (uint32_t) this->addr_state2);
this->configured = true;
return ESP_OK;
}
esp_err_t WL_Flash::init()
{
esp_err_t result = ESP_OK;
if (this->configured == false) {
ESP_LOGW(TAG, "WL_Flash: not configured, call config() first");
return ESP_ERR_INVALID_STATE;
}
// If flow will be interrupted by error, then this flag will be false
this->initialized = false;
// Init states if it is first time...
this->flash_drv->read(this->addr_state1, &this->state, sizeof(wl_state_t));
wl_state_t sa_copy;
wl_state_t *state_copy = &sa_copy;
result = this->flash_drv->read(this->addr_state2, state_copy, sizeof(wl_state_t));
WL_RESULT_CHECK(result);
int check_size = sizeof(wl_state_t) - sizeof(uint32_t);
// Chech CRC and recover state
uint32_t crc1 = crc32::crc32_le(WL_CFG_CRC_CONST, (uint8_t *)&this->state, check_size);
uint32_t crc2 = crc32::crc32_le(WL_CFG_CRC_CONST, (uint8_t *)state_copy, check_size);
ESP_LOGD(TAG, "%s - config ID=%i, stored ID=%i, access_count=%i, block_size=%i, max_count=%i, pos=%i, move_count=%i",
__func__,
this->cfg.version,
this->state.version,
this->state.access_count,
this->state.block_size,
this->state.max_count,
this->state.pos,
this->state.move_count);
ESP_LOGD(TAG, "%s starts: crc1=%i, crc2 = %i, this->state.crc=%i, state_copy->crc=%i", __func__, crc1, crc2, this->state.crc, state_copy->crc);
if ((crc1 == this->state.crc) && (crc2 == state_copy->crc)) {
// The state is OK. Check the ID
if (this->state.version != this->cfg.version) {
result = this->initSections();
WL_RESULT_CHECK(result);
result = this->recoverPos();
WL_RESULT_CHECK(result);
} else {
if (crc1 != crc2) {// we did not update second structure.
result = this->flash_drv->erase_range(this->addr_state2, this->state_size);
WL_RESULT_CHECK(result);
result = this->flash_drv->write(this->addr_state2, &this->state, sizeof(wl_state_t));
WL_RESULT_CHECK(result);
for (size_t i = 0; i < ((this->cfg.full_mem_size / this->cfg.sector_size)*this->cfg.wr_size); i++) {
uint8_t pos_bits = 0;
result = this->flash_drv->read(this->addr_state1 + sizeof(wl_state_t) + i, &pos_bits, 1);
WL_RESULT_CHECK(result);
if (pos_bits != 0xff) {
result = this->flash_drv->write(this->addr_state2 + sizeof(wl_state_t) + i, &pos_bits, 1);
WL_RESULT_CHECK(result);
}
}
}
ESP_LOGD(TAG, "%s: crc1=%i, crc2 = %i, result=%i", __func__, crc1, crc2, result);
result = this->recoverPos();
WL_RESULT_CHECK(result);
}
} else if ((crc1 != this->state.crc) && (crc2 != state_copy->crc)) { // This is just new flash
result = this->initSections();
WL_RESULT_CHECK(result);
result = this->recoverPos();
WL_RESULT_CHECK(result);
} else {
// recover broken state
if (crc1 == this->state.crc) {// we have to recover state 2
result = this->flash_drv->erase_range(this->addr_state2, this->state_size);
WL_RESULT_CHECK(result);
result = this->flash_drv->write(this->addr_state2, &this->state, sizeof(wl_state_t));
WL_RESULT_CHECK(result);
for (size_t i = 0; i < ((this->cfg.full_mem_size / this->cfg.sector_size) * this->cfg.wr_size); i++) {
uint8_t pos_bits = 0;
result = this->flash_drv->read(this->addr_state1 + sizeof(wl_state_t) + i, &pos_bits, 1);
WL_RESULT_CHECK(result);
if (pos_bits != 0xff) {
result = this->flash_drv->write(this->addr_state2 + sizeof(wl_state_t) + i, &pos_bits, 1);
WL_RESULT_CHECK(result);
}
}
result = this->flash_drv->read(this->addr_state2, &this->state, sizeof(wl_state_t));
WL_RESULT_CHECK(result);
} else { // we have to recover state 1
result = this->flash_drv->erase_range(this->addr_state1, this->state_size);
WL_RESULT_CHECK(result);
result = this->flash_drv->write(this->addr_state1, state_copy, sizeof(wl_state_t));
WL_RESULT_CHECK(result);
for (size_t i = 0; i < ((this->cfg.full_mem_size / this->cfg.sector_size) * this->cfg.wr_size); i++) {
uint8_t pos_bits = 0;
result = this->flash_drv->read(this->addr_state2 + sizeof(wl_state_t) + i, &pos_bits, 1);
WL_RESULT_CHECK(result);
if (pos_bits != 0xff) {
result = this->flash_drv->write(this->addr_state1 + sizeof(wl_state_t) + i, &pos_bits, 1);
WL_RESULT_CHECK(result);
}
}
result = this->flash_drv->read(this->addr_state1, &this->state, sizeof(wl_state_t));
WL_RESULT_CHECK(result);
this->state.pos = this->state.max_pos - 1;
}
// done. We have recovered the state
// If we have a new configuration, we will overwrite it
if (this->state.version != this->cfg.version) {
result = this->initSections();
WL_RESULT_CHECK(result);
}
}
if (result != ESP_OK) {
this->initialized = false;
ESP_LOGE(TAG, "%s: returned 0x%x", __func__, result);
return result;
}
this->initialized = true;
return ESP_OK;
}
esp_err_t WL_Flash::recoverPos()
{
esp_err_t result = ESP_OK;
size_t position = 0;
for (size_t i = 0; i < this->state.max_pos; i++) {
uint8_t pos_bits = 0;
result = this->flash_drv->read(this->addr_state1 + sizeof(wl_state_t) + i * this->cfg.wr_size, &pos_bits, 1);
WL_RESULT_CHECK(result);
position = i;
if (pos_bits == 0xff) {
break; // we have found position
}
}
this->state.pos = position;
if (this->state.pos == this->state.max_pos) {
this->state.pos--;
}
ESP_LOGD(TAG, "%s - this->state.pos=0x%08x, result=%08x", __func__, this->state.pos, result);
return result;
}
esp_err_t WL_Flash::initSections()
{
esp_err_t result = ESP_OK;
this->state.pos = 0;
this->state.access_count = 0;
this->state.move_count = 0;
// max count
this->state.max_count = this->flash_size / this->state_size * this->cfg.updaterate;
if (this->cfg.updaterate != 0) {
this->state.max_count = this->cfg.updaterate;
}
this->state.version = this->cfg.version;
this->state.block_size = this->cfg.page_size;
this->used_bits = 0;
this->state.max_pos = 1 + this->flash_size / this->cfg.page_size;
this->state.crc = crc32::crc32_le(WL_CFG_CRC_CONST, (uint8_t *)&this->state, sizeof(wl_state_t) - sizeof(uint32_t));
result = this->flash_drv->erase_range(this->addr_state1, this->state_size);
WL_RESULT_CHECK(result);
result = this->flash_drv->write(this->addr_state1, &this->state, sizeof(wl_state_t));
WL_RESULT_CHECK(result);
// write state copy
result = this->flash_drv->erase_range(this->addr_state2, this->state_size);
WL_RESULT_CHECK(result);
result = this->flash_drv->write(this->addr_state2, &this->state, sizeof(wl_state_t));
WL_RESULT_CHECK(result);
result = this->flash_drv->erase_range(this->addr_cfg, this->cfg_size);
WL_RESULT_CHECK(result);
result = this->flash_drv->write(this->addr_cfg, &this->cfg, sizeof(wl_config_t));
WL_RESULT_CHECK(result);
ESP_LOGD(TAG, "%s - this->state->max_count=%08x, this->state->max_pos=%08x", __func__, this->state.max_count, this->state.max_pos);
ESP_LOGD(TAG, "%s - result=%08x", __func__, result);
return result;
}
esp_err_t WL_Flash::updateWL()
{
esp_err_t result = ESP_OK;
this->state.access_count++;
if (this->state.access_count < this->state.max_count) {
return result;
}
// Here we have to move the block and increase the state
this->state.access_count = 0;
ESP_LOGV(TAG, "%s - access_count=0x%08x, pos=0x%08x", __func__, this->state.access_count, this->state.pos);
// copy data to dummy block
size_t data_addr = this->state.pos + 1; // next block, [pos+1] copy to [pos]
if (data_addr >= this->state.max_pos) {
data_addr = 0;
}
data_addr = this->cfg.start_addr + data_addr * this->cfg.page_size;
this->dummy_addr = this->cfg.start_addr + this->state.pos * this->cfg.page_size;
result = this->flash_drv->erase_range(this->dummy_addr, this->cfg.page_size);
if (result != ESP_OK) {
ESP_LOGE(TAG, "%s - erase wl dummy sector result=%08x", __func__, result);
this->state.access_count = this->state.max_count - 1; // we will update next time
return result;
}
size_t copy_count = this->cfg.page_size / this->cfg.temp_buff_size;
for (size_t i = 0; i < copy_count; i++) {
result = this->flash_drv->read(data_addr + i * this->cfg.temp_buff_size, this->temp_buff, this->cfg.temp_buff_size);
if (result != ESP_OK) {
ESP_LOGE(TAG, "%s - not possible to read buffer, will try next time, result=%08x", __func__, result);
this->state.access_count = this->state.max_count - 1; // we will update next time
return result;
}
result = this->flash_drv->write(this->dummy_addr + i * this->cfg.temp_buff_size, this->temp_buff, this->cfg.temp_buff_size);
if (result != ESP_OK) {
ESP_LOGE(TAG, "%s - not possible to write buffer, will try next time, result=%08x", __func__, result);
this->state.access_count = this->state.max_count - 1; // we will update next time
return result;
}
}
// done... block moved.
// Here we will update structures...
// Update bits and save to flash:
uint32_t byte_pos = this->state.pos * this->cfg.wr_size;
this->used_bits = 0;
// write state to mem. We updating only affected bits
result |= this->flash_drv->write(this->addr_state1 + sizeof(wl_state_t) + byte_pos, &this->used_bits, 1);
if (result != ESP_OK) {
ESP_LOGE(TAG, "%s - update position 1 result=%08x", __func__, result);
this->state.access_count = this->state.max_count - 1; // we will update next time
return result;
}
result |= this->flash_drv->write(this->addr_state2 + sizeof(wl_state_t) + byte_pos, &this->used_bits, 1);
if (result != ESP_OK) {
ESP_LOGE(TAG, "%s - update position 2 result=%08x", __func__, result);
this->state.access_count = this->state.max_count - 1; // we will update next time
return result;
}
this->state.pos++;
if (this->state.pos >= this->state.max_pos) {
this->state.pos = 0;
// one loop more
this->state.move_count++;
if (this->state.move_count >= (this->state.max_pos - 1)) {
this->state.move_count = 0;
}
// write main state
this->state.crc = crc32::crc32_le(WL_CFG_CRC_CONST, (uint8_t *)&this->state, sizeof(wl_state_t) - sizeof(uint32_t));
result = this->flash_drv->erase_range(this->addr_state1, this->state_size);
WL_RESULT_CHECK(result);
result = this->flash_drv->write(this->addr_state1, &this->state, sizeof(wl_state_t));
WL_RESULT_CHECK(result);
result = this->flash_drv->erase_range(this->addr_state2, this->state_size);
WL_RESULT_CHECK(result);
result = this->flash_drv->write(this->addr_state2, &this->state, sizeof(wl_state_t));
WL_RESULT_CHECK(result);
ESP_LOGD(TAG, "%s - move_count=%08x", __func__, this->state.move_count);
}
// Save structures to the flash... and check result
if (result == ESP_OK) {
ESP_LOGV(TAG, "%s - result=%08x", __func__, result);
} else {
ESP_LOGE(TAG, "%s - result=%08x", __func__, result);
}
return result;
}
size_t WL_Flash::calcAddr(size_t addr)
{
size_t result = (this->flash_size - this->state.move_count * this->cfg.page_size + addr) % this->flash_size;
size_t dummy_addr = this->state.pos * this->cfg.page_size;
if (result < dummy_addr) {
} else {
result += this->cfg.page_size;
}
ESP_LOGV(TAG, "%s - addr=0x%08x -> result=0x%08x", __func__, (uint32_t) addr, (uint32_t) result);
return result;
}
size_t WL_Flash::chip_size()
{
if (!this->configured) {
return 0;
}
return this->flash_size;
}
size_t WL_Flash::sector_size()
{
if (!this->configured) {
return 0;
}
return this->cfg.sector_size;
}
esp_err_t WL_Flash::erase_sector(size_t sector)
{
esp_err_t result = ESP_OK;
if (!this->initialized) {
return ESP_ERR_INVALID_STATE;
}
ESP_LOGV(TAG, "%s - sector=0x%08x", __func__, (uint32_t) sector);
result = this->updateWL();
WL_RESULT_CHECK(result);
size_t virt_addr = this->calcAddr(sector * this->cfg.sector_size);
result = this->flash_drv->erase_sector((this->cfg.start_addr + virt_addr) / this->cfg.sector_size);
WL_RESULT_CHECK(result);
return result;
}
esp_err_t WL_Flash::erase_range(size_t start_address, size_t size)
{
esp_err_t result = ESP_OK;
if (!this->initialized) {
return ESP_ERR_INVALID_STATE;
}
ESP_LOGV(TAG, "%s - start_address=0x%08x, size=0x%08x", __func__, (uint32_t) start_address, (uint32_t) size);
size_t erase_count = (size + this->cfg.sector_size - 1) / this->cfg.sector_size;
size_t start_sector = start_address / this->cfg.sector_size;
for (size_t i = 0; i < erase_count; i++) {
result = this->erase_sector(start_sector + i);
WL_RESULT_CHECK(result);
}
ESP_LOGV(TAG, "%s - result=%08x", __func__, result);
return result;
}
esp_err_t WL_Flash::write(size_t dest_addr, const void *src, size_t size)
{
esp_err_t result = ESP_OK;
if (!this->initialized) {
return ESP_ERR_INVALID_STATE;
}
ESP_LOGV(TAG, "%s - dest_addr=0x%08x, size=0x%08x", __func__, (uint32_t) dest_addr, (uint32_t) size);
uint32_t count = (size - 1) / this->cfg.page_size;
for (size_t i = 0; i < count; i++) {
size_t virt_addr = this->calcAddr(dest_addr + i * this->cfg.page_size);
result = this->flash_drv->write(this->cfg.start_addr + virt_addr, &((uint8_t *)src)[i * this->cfg.page_size], size);
WL_RESULT_CHECK(result);
}
size_t virt_addr_last = this->calcAddr(dest_addr + count * this->cfg.page_size);
result = this->flash_drv->write(this->cfg.start_addr + virt_addr_last, &((uint8_t *)src)[count * this->cfg.page_size], size - count * this->cfg.page_size);
WL_RESULT_CHECK(result);
return result;
}
esp_err_t WL_Flash::read(size_t src_addr, void *dest, size_t size)
{
esp_err_t result = ESP_OK;
if (!this->initialized) {
return ESP_ERR_INVALID_STATE;
}
ESP_LOGV(TAG, "%s - src_addr=0x%08x, size=0x%08x", __func__, (uint32_t) src_addr, (uint32_t) size);
uint32_t count = (size - 1) / this->cfg.page_size;
for (size_t i = 0; i < count; i++) {
size_t virt_addr = this->calcAddr(src_addr + i * this->cfg.page_size);
result = this->flash_drv->read(this->cfg.start_addr + virt_addr, &((uint8_t *)dest)[i * this->cfg.page_size], size);
WL_RESULT_CHECK(result);
}
size_t virt_addr_last = this->calcAddr(src_addr + count * this->cfg.page_size);
result = this->flash_drv->read(this->cfg.start_addr + virt_addr_last, &((uint8_t *)dest)[count * this->cfg.page_size], size - count * this->cfg.page_size);
WL_RESULT_CHECK(result);
return result;
}
Flash_Access *WL_Flash::get_drv()
{
return this->flash_drv;
}
wl_config_t *WL_Flash::get_cfg()
{
return &this->cfg;
}
esp_err_t WL_Flash::flush()
{
esp_err_t result = ESP_OK;
this->state.access_count = this->state.max_count - 1;
result = this->updateWL();
ESP_LOGV(TAG, "%s - result=%08x", __func__, result);
return result;
}

View file

@ -0,0 +1 @@
COMPONENT_PRIV_INCLUDEDIRS := private_include

View file

@ -0,0 +1,20 @@
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "crc32.h"
#include "rom/crc.h"
unsigned int crc32::crc32_le(unsigned int crc, unsigned char const *buf, unsigned int len)
{
return ::crc32_le(crc, buf, len);
}

View file

@ -0,0 +1,26 @@
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef _crc32_H_
#define _crc32_H_
/**
* @brief This class is used to access crc32 module
*
*/
class crc32
{
public:
static unsigned int crc32_le(unsigned int crc, unsigned char const *buf, unsigned int len);
};
#endif // _crc32_H_

View file

@ -0,0 +1,89 @@
Wear Levelling Component
========================
Wear Levelling Component (WLC) it is a software component that is implemented to prevent situation when some sectors in flash memory used by erase operations more then others. The component shares access attempts between all avalible sectors.
The WLC do not have internal cache. When write operation is finished, that means that data was really stored to the flash.
As a parameter the WLC requires the driver to access the flash device. The driver has to implement Flash_Access interface.
The WLC Files
^^^^^^^^^^^^^^^
The WLC consist of few components that are implemented in different files. The list and brief description of these components written below.
- Flash_Access - memory access interface. Used to access the memory. A classes WL_Flash, Partition, SPI_Flash, Flash_Emulator are implements this interface.
- SPI_Flash - class implements the Flash_Access interface to provide access to the flash memory.
- Partition - class implements the Flash_Access interface to provide access to the partition.
- Flash_Emulator - class implements the Flash_Access interface to provide test functionality for WLC testing.
- WL_Flash - the main class that implements wear levelling functionality.
- WL_State - contains state structure of the WLC.
- WL_Config - contains structure to configure the WLC component at startup.
- wear_levelling - wrapper API class that provides "C" interface to access the memory through the WLC
Flash_Access Interface
^^^^^^^^^^^^^^^^^^^^^^
In the component exist virtual interface Flash_Access. This interface implement main basic functions:
- read - read memory to the buffer.
- write - writes buffer to the memory.
- erase - erase one sector.
- erase_range - erase range of memory. The address of rage must be rounded to the sector size.
- chip_size - returns the equivalent amount of memory.
- sector_size - returns the sector size.
- flush - stores current state to the flash, if needed.
The WLC implements this interface for the user, and requires this interface to access the memory.
Structure wl_config_t to Configure the WLC at startup
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
The wl_config_t contains configuration parameters for the WLC component.
- start_addr - offset in the flash memory. The WLC will place all data after this address.
- full_mem_size - amount of memory that was allocated and can be used by WLC
- sector_size - flash memory sector size
- page_size - size of memory for relocation at once. Must be N*sector_size, where N > 0.
- updaterate - amount of erase cycles to execute the relocation procedure.
- wr_size - smalest possible write access size without erasing of sector.
- version - version of the WLC component.
- temp_buff_size - amount of memory that the WLC will allocate internally. Must be > 0.
Internal Memory Organization
^^^^^^^^^^^^^^^^^^^^^^^^^^^^
The WLC divide the memory that are define by start_addr and full_mem_size to three regions:
- Configuration
- Data
- States
The Configuration region used to store configuration information. The user can use it to recover the WLC from memory dump.
The Data - is a region where user data stored.
The States - is a region where the WLC stores internal information about the WLC state. The States region contains two copies of the WLC states. It is implemented to prevent situation when the device is shut down
during operation when the device stores the states. If one of copies is wrong, the WLC can recover the state from another. The broken copy will be overwritten by another.
Main Idea
^^^^^^^^^
The WLC has two access addresses: virtual address and real address. The virtual address used by user to access the WLC, the real address used by the WLC to access the real memory.
The WLC makes the conversion between virtual and real addresses.
The Data region divided to N pages (page could be equal to the sector size). One page defined as dummy page. For user will be available only N-1 pages.
The WLC has two internal counters to calculate virtual and real addresses: erase counter and move counter.
Every erase operation will be counted by erase counter. When this counter reached the *updaterate* number the page after Dummy page will be moved to the Dummy page, and Dummy page will be changed to this one. The erase counter will
be cleared and move counter will be incremented. This procedure will be repeated again and again.
When the Dummy page will be at last page in the memory and erase counter will reach the updaterate, the move counter will be cleared and the state will be stored to the State memory.
Bellow shown the example with 4 available memory pages. Every state after updaterate erases. The X is a Dummy page.
- X 0 1 2 - start position
- 0 X 1 2 - first move, the page 0 and Dummy page change the places
- 0 1 X 2 - second move, the page 1 and Dummy page change the places
- 0 1 2 X -
- X 1 2 0 - state stored to the memory
- 1 X 2 0 -
- 1 2 X 0 -
- 1 2 0 X -
- X 2 0 1 - state stored to the memory
- 2 X 0 1 -
- 2 0 X 1 -
- 2 0 1 X -
- X 0 1 2 - state stored to the memory, the memory made full cycle.
As we see, if user will write data only to one address, amount of erase cycles will be shared between the full memory. The price for that is a one memory page that will not be used by user.

View file

@ -0,0 +1,136 @@
// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef _wear_levelling_H_
#define _wear_levelling_H_
#include "esp_log.h"
#include "esp_partition.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief wear levelling handle
*/
typedef int32_t wl_handle_t;
#define WL_INVALID_HANDLE -1
/**
* @brief Mount WL for defined partition
*
* @param partition that will be used for access
* @param out_handle handle of the WL instance
*
* @return
* - ESP_OK, if the allocation was successfully;
* - ESP_ERR_INVALID_ARG, if WL allocation was unsuccessful;
* - ESP_ERR_NO_MEM, if there was no memory to allocate WL components;
*/
esp_err_t wl_mount(const esp_partition_t *partition, wl_handle_t *out_handle);
/**
* @brief Unmount WL for defined partition
*
* @param handle WL partition handle
*
* @return
* - ESP_OK, if the operation completed successfully;
* - or one of error codes from lower-level flash driver.
*/
esp_err_t wl_unmount(wl_handle_t handle);
/**
* @brief Erase part of the WL storage
*
* @param handle WL handle that are related to the partition
* @param start_addr Address where erase operation should start. Must be aligned
* to the result of function wl_sector_size(...).
* @param size Size of the range which should be erased, in bytes.
* Must be divisible by result of function wl_sector_size(...)..
*
* @return
* - ESP_OK, if the range was erased successfully;
* - ESP_ERR_INVALID_ARG, if iterator or dst are NULL;
* - ESP_ERR_INVALID_SIZE, if erase would go out of bounds of the partition;
* - or one of error codes from lower-level flash driver.
*/
esp_err_t wl_erase_range(wl_handle_t handle, size_t start_addr, size_t size);
/**
* @brief Write data to the WL storage
*
* Before writing data to flash, corresponding region of flash needs to be erased.
* This can be done using wl_erase_range function.
*
* @param handle WL handle that are related to the partition
* @param dest_addr Address where the data should be written, relative to the
* beginning of the partition.
* @param src Pointer to the source buffer. Pointer must be non-NULL and
* buffer must be at least 'size' bytes long.
* @param size Size of data to be written, in bytes.
*
* @note Prior to writing to WL storage, make sure it has been erased with
* wl_erase_range call.
*
* @return
* - ESP_OK, if data was written successfully;
* - ESP_ERR_INVALID_ARG, if dst_offset exceeds partition size;
* - ESP_ERR_INVALID_SIZE, if write would go out of bounds of the partition;
* - or one of error codes from lower-level flash driver.
*/
esp_err_t wl_write(wl_handle_t handle, size_t dest_addr, const void *src, size_t size);
/**
* @brief Read data from the WL storage
*
* @param handle WL module instance that was initialized before
* @param dest Pointer to the buffer where data should be stored.
* Pointer must be non-NULL and buffer must be at least 'size' bytes long.
* @param src_addr Address of the data to be read, relative to the
* beginning of the partition.
* @param size Size of data to be read, in bytes.
*
* @return
* - ESP_OK, if data was read successfully;
* - ESP_ERR_INVALID_ARG, if src_offset exceeds partition size;
* - ESP_ERR_INVALID_SIZE, if read would go out of bounds of the partition;
* - or one of error codes from lower-level flash driver.
*/
esp_err_t wl_read(wl_handle_t handle, size_t src_addr, void *dest, size_t size);
/**
* @brief Get size of the WL storage
*
* @param handle WL module handle that was initialized before
* @return usable size, in bytes
*/
size_t wl_size(wl_handle_t handle);
/**
* @brief Get sector size of the WL instance
*
* @param handle WL module handle that was initialized before
* @return sector size, in bytes
*/
size_t wl_sector_size(wl_handle_t handle);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // _wear_levelling_H_

View file

@ -0,0 +1,44 @@
// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef _Flash_Access_H_
#define _Flash_Access_H_
#include "esp_err.h"
/**
* @brief Universal flash access interface class
*
*/
class Flash_Access
{
public:
virtual size_t chip_size() = 0;
virtual esp_err_t erase_sector(size_t sector) = 0;
virtual esp_err_t erase_range(size_t start_address, size_t size) = 0;
virtual esp_err_t write(size_t dest_addr, const void *src, size_t size) = 0;
virtual esp_err_t read(size_t src_addr, void *dest, size_t size) = 0;
virtual size_t sector_size() = 0;
virtual esp_err_t flush()
{
return ESP_OK;
};
virtual ~Flash_Access() {};
};
#endif // _Flash_Access_H_

Some files were not shown because too many files have changed in this diff Show more