Merge branch 'feature/spiffs' into experiments/spi_flash_reimplement

This commit is contained in:
sheinz 2016-07-16 00:19:21 +03:00
commit fb187eae08
62 changed files with 2653 additions and 371 deletions

4
.gitmodules vendored
View file

@ -10,7 +10,9 @@
[submodule "bootloader/rboot"]
path = bootloader/rboot
url = https://github.com/raburton/rboot.git
[submodule "extras/spiffs/spiffs"]
path = extras/spiffs/spiffs
url = https://github.com/pellepl/spiffs.git
[submodule "examples/posix_fs/fs-test"]
path = examples/posix_fs/fs-test
url = https://github.com/sheinz/fs-test

View file

@ -34,6 +34,13 @@
#define configUSE_TICK_HOOK 0
#endif
#ifndef configCPU_CLOCK_HZ
/* This is the _default_ clock speed for the CPU. Can be either 80MHz
* or 160MHz, and the system will set the clock speed to match at startup.
Note that it's possible to change the clock speed at runtime, so you
can/should use sdk_system_get_cpu_frequency() in order to determine the
current CPU frequency, in preference to this macro.
*/
#define configCPU_CLOCK_HZ ( ( unsigned long ) 80000000 )
#endif
#ifndef configTICK_RATE_HZ

View file

@ -210,7 +210,8 @@ $(FW_FILE): $(PROGRAM_OUT) $(FIRMWARE_DIR)
$(Q) $(ESPTOOL) elf2image --version=2 $(ESPTOOL_ARGS) $< -o $(FW_FILE)
flash: $(FW_FILE)
$(ESPTOOL) -p $(ESPPORT) --baud $(ESPBAUD) write_flash $(ESPTOOL_ARGS) 0x0 $(RBOOT_BIN) 0x1000 $(RBOOT_CONF) 0x2000 $(FW_FILE)
$(ESPTOOL) -p $(ESPPORT) --baud $(ESPBAUD) write_flash $(ESPTOOL_ARGS) \
0x0 $(RBOOT_BIN) 0x1000 $(RBOOT_CONF) 0x2000 $(FW_FILE) $(SPIFFS_ESPTOOL_ARGS)
erase_flash:
$(ESPTOOL) -p $(ESPPORT) --baud $(ESPBAUD) erase_flash

View file

@ -21,11 +21,13 @@
#include "esp/spi_regs.h"
#include "esp/dport_regs.h"
#include "esp/wdev_regs.h"
#include "esp/hwrand.h"
#include "os_version.h"
#include "espressif/esp_common.h"
#include "espressif/phy_info.h"
#include "sdk_internal.h"
#include "esplibs/libmain.h"
/* This is not declared in any header file (but arguably should be) */
@ -344,8 +346,8 @@ static __attribute__((noinline)) void user_start_phase2(void) {
sdk_phy_info_t phy_info, default_phy_info;
sdk_system_rtc_mem_read(0, &sdk_rst_if, sizeof(sdk_rst_if));
if (sdk_rst_if.version > 3) {
// Bad version number. Probably garbage.
if (sdk_rst_if.reason > 3) {
// Bad reason. Probably garbage.
bzero(&sdk_rst_if, sizeof(sdk_rst_if));
}
buf = malloc(sizeof(sdk_rst_if));
@ -356,8 +358,8 @@ static __attribute__((noinline)) void user_start_phase2(void) {
get_otp_mac_address(sdk_info.sta_mac_addr);
sdk_wifi_softap_cacl_mac(sdk_info.softap_mac_addr, sdk_info.sta_mac_addr);
sdk_info._unknown0 = 0x0104a8c0;
sdk_info._unknown1 = 0x00ffffff;
sdk_info._unknown2 = 0x0104a8c0;
sdk_info._unknown4 = 0x00ffffff;
sdk_info._unknown8 = 0x0104a8c0;
init_g_ic();
read_saved_phy_info(&phy_info);
@ -378,6 +380,12 @@ static __attribute__((noinline)) void user_start_phase2(void) {
init_networking(&phy_info, sdk_info.sta_mac_addr);
srand(hwrand()); /* seed libc rng */
// Set intial CPU clock speed to 160MHz if necessary
_Static_assert(configCPU_CLOCK_HZ == 80000000 || configCPU_CLOCK_HZ == 160000000, "FreeRTOSConfig must define initial clock speed as either 80MHz or 160MHz");
sdk_system_update_cpu_freq(configCPU_CLOCK_HZ / 1000000);
// Call gcc constructor functions
void (**ctor)(void);
for ( ctor = &__init_array_start; ctor != &__init_array_end; ++ctor) {

View file

@ -20,7 +20,7 @@
#include "esp/rom.h"
#include "esp/uart.h"
#include "espressif/esp_common.h"
#include "sdk_internal.h"
#include "esplibs/libmain.h"
/* Forward declarations */
static void IRAM fatal_handler_prelude(void);

View file

@ -178,7 +178,7 @@ static void _spi_buf_prepare(uint8_t bus, size_t len, spi_endianness_t e, spi_wo
if (e == SPI_LITTLE_ENDIAN || word_size == SPI_32BIT) return;
size_t count = word_size == SPI_16BIT ? (len + 1) / 2 : (len + 3) / 4;
uint32_t *data = (uint32_t *)&SPI(bus).W0;
uint32_t *data = (uint32_t *)SPI(bus).W;
for (size_t i = 0; i < count; i ++)
{
data[i] = word_size == SPI_16BIT
@ -193,14 +193,14 @@ static void _spi_buf_transfer(uint8_t bus, const void *out_data, void *in_data,
_wait(bus);
size_t bytes = len * (uint8_t)word_size;
_set_size(bus, bytes);
memcpy((void *)&SPI(bus).W0, out_data, bytes);
memcpy((void *)SPI(bus).W, out_data, bytes);
_spi_buf_prepare(bus, len, e, word_size);
_start(bus);
_wait(bus);
if (in_data)
{
_spi_buf_prepare(bus, len, e, word_size);
memcpy(in_data, (void *)&SPI(bus).W0, bytes);
memcpy(in_data, (void *)SPI(bus).W, bytes);
}
}

View file

@ -90,6 +90,10 @@ _Static_assert(sizeof(struct DPORT_REGS) == 0x60, "DPORT_REGS is the wrong size"
/* Details for CLOCKGATE_WATCHDOG register */
// Set and then cleared during sdk_system_restart_in_nmi().
// Not sure what this does. May be related to ESPSAR.UNKNOWN_48
#define DPORT_CLOCKGATE_WATCHDOG_UNKNOWN_8 BIT(8)
/* Comment found in pvvx/mp3_decode headers: "use clockgate_watchdog(flg) { if(flg) 0x3FF00018 &= 0x77; else 0x3FF00018 |= 8; }". Not sure what this means or does. */
#define DPORT_CLOCKGATE_WATCHDOG_DISABLE BIT(3)

View file

@ -5,7 +5,9 @@
*/
#ifndef _ESP_ROM_H
#define _ESP_ROM_H
#include <stdint.h>
#include "esp/types.h"
#include "flashchip.h"
#ifdef __cplusplus
extern "C" {
@ -21,8 +23,19 @@ void Cache_Read_Disable(void);
*/
void Cache_Read_Enable(uint32_t odd_even, uint32_t mb_count, uint32_t no_idea);
/* Low-level SPI flash read/write routines */
int Enable_QMode(sdk_flashchip_t *chip);
int Disable_QMode(sdk_flashchip_t *chip);
int SPI_page_program(sdk_flashchip_t *chip, uint32_t dest_addr, uint32_t *src_addr, uint32_t size);
int SPI_read_data(sdk_flashchip_t *chip, uint32_t src_addr, uint32_t *dest_addr, uint32_t size);
int SPI_write_enable(sdk_flashchip_t *chip);
int SPI_sector_erase(sdk_flashchip_t *chip, uint32_t addr);
int SPI_read_status(sdk_flashchip_t *chip, uint32_t *status);
int SPI_write_status(sdk_flashchip_t *chip, uint32_t status);
int Wait_SPI_Idle(sdk_flashchip_t *chip);
#ifdef __cplusplus
}
#endif
#endif
#endif /* _ESP_ROM_H */

View file

@ -31,7 +31,8 @@ struct RTC_REGS {
uint32_t volatile CTRL0; // 0x00
uint32_t volatile COUNTER_ALARM; // 0x04
uint32_t volatile RESET_REASON0; // 0x08 //FIXME: need better name
uint32_t volatile _unknownc[2]; // 0x0c - 0x10
uint32_t volatile _unknownc; // 0x0c
uint32_t volatile _unknown10; // 0x10
uint32_t volatile RESET_REASON1; // 0x14 //FIXME: need better name
uint32_t volatile RESET_REASON2; // 0x18 //FIXME: need better name
uint32_t volatile COUNTER; // 0x1c
@ -40,7 +41,10 @@ struct RTC_REGS {
uint32_t volatile INT_ENABLE; // 0x28
uint32_t volatile _unknown2c; // 0x2c
uint32_t volatile SCRATCH[4]; // 0x30 - 3c
uint32_t volatile _unknown40[10]; // 0x40 - 0x64
uint32_t volatile _unknown40; // 0x40
uint32_t volatile _unknown44; // 0x44
uint32_t volatile _unknown48; // 0x48
uint32_t volatile _unknown4c[7]; // 0x4c - 0x64
uint32_t volatile GPIO_OUT; // 0x68
uint32_t volatile _unknown6c[2]; // 0x6c - 0x70
uint32_t volatile GPIO_ENABLE; // 0x74

View file

@ -0,0 +1,39 @@
/* esp/sar_regs.h
*
* ESP8266 register definitions for the "sar" region (0x3FF2xxx)
*
* The 0x60000D00 register region is referred to as "sar" by some old header
* files. Apparently referenced both by ROM I2C functions as well as ADC
* config/read functions.
*
* Not compatible with ESP SDK register access code.
*/
#ifndef _ESP_SAR_REGS_H
#define _ESP_SAR_REGS_H
#include "esp/types.h"
#include "common_macros.h"
#define SAR_BASE 0x60000d00
// Unfortunately,
// esp-open-sdk/xtensa-lx106-elf/xtensa-lx106-elf/sysroot/usr/include/xtensa/config/specreg.h
// already has a "SAR" macro definition which would conflict with this, so
// we'll use "ESPSAR" instead..
#define ESPSAR (*(struct SAR_REGS *)(SAR_BASE))
/* Note: This memory region is not currently well understood. Pretty much all
* of the definitions here are from reverse-engineering the Espressif SDK code,
* many are just educated guesses, and almost certainly some are misleading or
* wrong. If you can improve on any of this, please contribute!
*/
struct SAR_REGS {
uint32_t volatile _unknown0[18]; // 0x00 - 0x44
uint32_t volatile UNKNOWN_48; // 0x48 : used by sdk_system_restart_in_nmi()
} __attribute__ (( packed ));
_Static_assert(sizeof(struct SAR_REGS) == 0x4c, "SAR_REGS is the wrong size");
#endif /* _ESP_SAR_REGS_H */

View file

@ -46,22 +46,7 @@ struct SPI_REGS {
uint32_t volatile SLAVE1; // 0x34
uint32_t volatile SLAVE2; // 0x38
uint32_t volatile SLAVE3; // 0x3c
uint32_t volatile W0; // 0x40
uint32_t volatile W1; // 0x44
uint32_t volatile W2; // 0x48
uint32_t volatile W3; // 0x4c
uint32_t volatile W4; // 0x50
uint32_t volatile W5; // 0x54
uint32_t volatile W6; // 0x58
uint32_t volatile W7; // 0x5c
uint32_t volatile W8; // 0x60
uint32_t volatile W9; // 0x64
uint32_t volatile W10; // 0x68
uint32_t volatile W11; // 0x6c
uint32_t volatile W12; // 0x70
uint32_t volatile W13; // 0x74
uint32_t volatile W14; // 0x78
uint32_t volatile W15; // 0x7c
uint32_t volatile W[16]; // 0x40 - 0x7c
uint32_t volatile _unused[28]; // 0x80 - 0xec
uint32_t volatile EXT0; // 0xf0
uint32_t volatile EXT1; // 0xf4
@ -73,6 +58,19 @@ _Static_assert(sizeof(struct SPI_REGS) == 0x100, "SPI_REGS is the wrong size");
/* Details for CMD register */
#define SPI_CMD_READ BIT(31)
#define SPI_CMD_WRITE_ENABLE BIT(30)
#define SPI_CMD_WRITE_DISABLE BIT(29)
#define SPI_CMD_READ_ID BIT(28)
#define SPI_CMD_READ_SR BIT(27)
#define SPI_CMD_WRITE_SR BIT(26)
#define SPI_CMD_PP BIT(25)
#define SPI_CMD_SE BIT(24)
#define SPI_CMD_BE BIT(23)
#define SPI_CMD_CE BIT(22)
#define SPI_CMD_DP BIT(21)
#define SPI_CMD_RES BIT(20)
#define SPI_CMD_HPM BIT(19)
#define SPI_CMD_USR BIT(18)
/* Details for CTRL0 register */

39
core/include/flashchip.h Normal file
View file

@ -0,0 +1,39 @@
/* flashchip.h
*
* sdk_flashchip_t structure used by the SDK and some bootrom routines
*
* This is in a separate include file because it's referenced by several other
* headers which are otherwise independent of each other.
*
* Part of esp-open-rtos
* Copyright (C) 2015 Alex Stewart and Angus Gratton
* BSD Licensed as described in the file LICENSE
*/
#ifndef _FLASHCHIP_H
#define _FLASHCHIP_H
/* SDK/bootrom uses this structure internally to account for flash size.
chip_size field is initialised during startup from the flash size
saved in the image header (on the first 8 bytes of SPI flash).
Other field are initialised to hardcoded values by the SDK.
** NOTE: This structure is passed to some bootrom routines and is therefore
fixed. Be very careful if you want to change it that you do not break
things. **
Based on RE work by @foogod at
http://esp8266-re.foogod.com/wiki/Flashchip_%28IoT_RTOS_SDK_0.9.9%29
*/
typedef struct {
uint32_t device_id;
uint32_t chip_size; /* in bytes */
uint32_t block_size; /* in bytes */
uint32_t sector_size; /* in bytes */
uint32_t page_size; /* in bytes */
uint32_t status_mask;
} sdk_flashchip_t;
#endif /* _FLASHCHIP_H */

View file

@ -4,6 +4,7 @@
#include "espressif/esp_wifi.h"
#include "espressif/spi_flash.h"
#include "espressif/phy_info.h"
#include "etstimer.h"
#include "lwip/netif.h"
///////////////////////////////////////////////////////////////////////////////
@ -13,31 +14,38 @@
// 'info' is declared in app_main.o at .bss+0x4
struct sdk_info_st {
uint32_t _unknown0;
uint32_t _unknown1;
uint32_t _unknown2;
uint8_t _unknown3[12];
uint8_t softap_mac_addr[6];
uint8_t sta_mac_addr[6];
uint32_t _unknown0; // 0x00
uint32_t _unknown4; // 0x04
uint32_t _unknown8; // 0x08
ip_addr_t ipaddr; // 0x0c
ip_addr_t netmask; // 0x10
ip_addr_t gw; // 0x14
uint8_t softap_mac_addr[6]; // 0x18
uint8_t sta_mac_addr[6]; // 0x1e
};
extern struct sdk_info_st sdk_info;
// 'rst_if' is declared in user_interface.o at .bss+0xfc
struct sdk_rst_if_st {
uint32_t version;
uint8_t _unknown[28];
};
extern struct sdk_rst_if_st sdk_rst_if;
extern struct sdk_rst_info sdk_rst_if;
// 'g_ic' is declared in libnet80211/ieee80211.o at .bss+0x0
// See also: http://esp8266-re.foogod.com/wiki/G_ic_(IoT_RTOS_SDK_0.9.9)
struct sdk_g_ic_netif_info {
struct netif *netif;
//TODO: rest of this structure is unknown.
struct netif *netif; // 0x00
ETSTimer timer; // 0x04 - 0x20
uint8_t _unknown20[28]; // 0x20 - 0x3c
uint32_t _unknown3c; // 0x3c (referenced by sdk_wifi_station_disconnect)
uint8_t _unknown40[6]; // 0x40 - 0x46
uint8_t _unknown46[66]; // 0x46 - 0x88
struct sdk_netif_conninfo *_unknown88; // 0x88
uint32_t _unknown8c; // 0x8c
struct sdk_netif_conninfo *conninfo[6]; // 0x90 - 0xa8
uint8_t _unknowna8[16]; // 0xa8 - 0xb8
uint8_t _unknownb8; // 0xb8 (referenced by sdk_wifi_station_connect / sdk_wifi_station_disconnect)
uint8_t _unknownb9; // 0xb9 (referenced by sdk_wifi_station_connect / sdk_wifi_station_disconnect)
uint8_t connect_status; // 0xba (referenced by sdk_system_station_got_ip_set / sdk_wifi_station_disconnect)
};
// This is the portion of g_ic which is not loaded/saved to the flash ROM, and
@ -197,7 +205,6 @@ extern struct sdk_g_ic_st sdk_g_ic;
///////////////////////////////////////////////////////////////////////////////
_Static_assert(sizeof(struct sdk_info_st) == 0x24, "info_st is the wrong size!");
_Static_assert(sizeof(struct sdk_rst_if_st) == 0x20, "sdk_rst_if_st is the wrong size!");
_Static_assert(sizeof(struct sdk_g_ic_volatile_st) == 0x1d8, "sdk_g_ic_volatile_st is the wrong size!");
_Static_assert(sizeof(struct sdk_g_ic_saved_st) == 0x370, "sdk_g_ic_saved_st is the wrong size!");
_Static_assert(sizeof(struct sdk_g_ic_st) == 0x548, "sdk_g_ic_st is the wrong size!");
@ -221,7 +228,6 @@ void sdk_pp_soft_wdt_init(void);
int sdk_register_chipv6_phy(sdk_phy_info_t *);
void sdk_sleep_reset_analog_rtcreg_8266(void);
uint32_t sdk_system_get_checksum(uint8_t *, uint32_t);
void sdk_system_restart_in_nmi(void);
void sdk_wDevEnableRx(void);
void sdk_wDev_Initialize(void);
void sdk_wifi_mode_set(uint8_t);

View file

@ -11,9 +11,6 @@
#ifndef _XTENSA_OPS_H
#define _XTENSA_OPS_H
// GCC macros for reading, writing, and exchanging Xtensa processor special
// registers:
/* Read stack pointer to variable.
*
* Note that the compiler will push a stack frame (minimum 16 bytes)
@ -28,8 +25,18 @@
*/
#define RETADDR(var) asm volatile ("mov %0, a0" : "=r" (var))
// GCC macros for reading, writing, and exchanging Xtensa processor special
// registers:
#define RSR(var, reg) asm volatile ("rsr %0, " #reg : "=r" (var));
#define WSR(var, reg) asm volatile ("wsr %0, " #reg : : "r" (var));
#define XSR(var, reg) asm volatile ("xsr %0, " #reg : "+r" (var));
// GCC macros for performing associated "*sync" opcodes
#define ISYNC() asm volatile ( "isync" )
#define RSYNC() asm volatile ( "rsync" )
#define ESYNC() asm volatile ( "esync" )
#define DSYNC() asm volatile ( "dsync" )
#endif /* _XTENSA_OPS_H */

View file

@ -41,7 +41,7 @@ IRAM caddr_t _sbrk_r (struct _reent *r, int incr)
}
/* syscall implementation for stdio write to UART */
long _write_r(struct _reent *r, int fd, const char *ptr, int len )
__attribute__((weak)) long _write_r(struct _reent *r, int fd, const char *ptr, int len )
{
if(fd != r->_stdout->_file) {
r->_errno = EBADF;
@ -79,10 +79,23 @@ __attribute__((weak)) long _read_r( struct _reent *r, int fd, char *ptr, int len
/* Stub syscall implementations follow, to allow compiling newlib functions that
pull these in via various codepaths
*/
__attribute__((alias("syscall_returns_enosys"))) int _open_r(struct _reent *r, const char *pathname, int flags, int mode);
__attribute__((alias("syscall_returns_enosys"))) int _fstat_r(struct _reent *r, int fd, void *buf);
__attribute__((alias("syscall_returns_enosys"))) int _close_r(struct _reent *r, int fd);
__attribute__((alias("syscall_returns_enosys"))) off_t _lseek_r(struct _reent *r, int fd, off_t offset, int whence);
__attribute__((weak, alias("syscall_returns_enosys")))
int _open_r(struct _reent *r, const char *pathname, int flags, int mode);
__attribute__((weak, alias("syscall_returns_enosys")))
int _close_r(struct _reent *r, int fd);
__attribute__((weak, alias("syscall_returns_enosys")))
int _unlink_r(struct _reent *r, const char *path);
__attribute__((weak, alias("syscall_returns_enosys")))
int _fstat_r(struct _reent *r, int fd, void *buf);
__attribute__((weak, alias("syscall_returns_enosys")))
int _stat_r(struct _reent *r, const char *pathname, void *buf);
__attribute__((weak, alias("syscall_returns_enosys")))
off_t _lseek_r(struct _reent *r, int fd, off_t offset, int whence);
/* Generic stub for any newlib syscall that fails with errno ENOSYS
("Function not implemented") and a return value equivalent to

View file

@ -2,6 +2,7 @@
*
* This sample code is in the public domain.
*/
#include <stdlib.h>
#include "espressif/esp_common.h"
#include "esp/uart.h"
#include "FreeRTOS.h"

View file

@ -2,6 +2,8 @@
*
* This sample code is in the public domain.
*/
#include <stdio.h>
#include <stdlib.h>
#include "espressif/esp_common.h"
#include "esp/uart.h"
#include "FreeRTOS.h"
@ -13,29 +15,30 @@
* to read and print a new temperature and humidity measurement
* from a sensor attached to GPIO pin 4.
*/
int const dht_gpio = 4;
uint8_t const dht_gpio = 4;
void dhtMeasurementTask(void *pvParameters)
{
int8_t temperature = 0;
int8_t humidity = 0;
int16_t temperature = 0;
int16_t humidity = 0;
// DHT sensors that come mounted on a PCB generally have
// pull-up resistors on the data pin. It is recommended
// to provide an external pull-up resistor otherwise...
gpio_set_pullup(dht_gpio, false, false);
// DHT sensors that come mounted on a PCB generally have
// pull-up resistors on the data pin. It is recommended
// to provide an external pull-up resistor otherwise...
gpio_set_pullup(dht_gpio, false, false);
while(1) {
while(1) {
if (dht_read_data(dht_gpio, &humidity, &temperature)) {
printf("Humidity: %d%% Temp: %dC\n",
humidity / 10,
temperature / 10);
} else {
printf("Could not read data from sensor\n");
}
if (dht_fetch_data(dht_gpio, &humidity, &temperature)) {
printf("Humidity: %i%% Temp: %iC\n", humidity, temperature);
} else {
printf("Could not read data from sensor...");
// Three second delay...
vTaskDelay(3000 / portTICK_RATE_MS);
}
// Three second delay...
vTaskDelay(3000 / portTICK_RATE_MS);
}
}
void user_init(void)

View file

@ -1,4 +1,4 @@
PROGRAM=http_get_mbedtls
COMPONENTS = FreeRTOS lwip core extras/mbedtls
EXTRA_COMPONENTS = extras/mbedtls
include ../../common.mk

View file

@ -0,0 +1,11 @@
PROGRAM=posix_fs_example
PROGRAM_EXTRA_SRC_FILES=./fs-test/fs_test.c
EXTRA_COMPONENTS = extras/spiffs
FLASH_SIZE = 32
# spiffs configuration
SPIFFS_BASE_ADDR = 0x200000
SPIFFS_SIZE = 0x100000
include ../../common.mk

View file

@ -0,0 +1,10 @@
# POSIX file access example
This example runs several file system tests on ESP8266.
It uses fs-test library to perform file operations test. fs-test library uses
only POSIX file functions so can be run on host system as well.
Currently included tests:
* File system load test. Perform multiple file operations in random order.
* File system speed test. Measures files read/write speed.

@ -0,0 +1 @@
Subproject commit 2ad547adc5f725594b3c6752f036ff4401b221fc

View file

@ -0,0 +1,55 @@
#include "espressif/esp_common.h"
#include "esp/uart.h"
#include "esp/timer.h"
#include "FreeRTOS.h"
#include "task.h"
#include "esp8266.h"
#include <stdio.h>
#include "esp_spiffs.h"
#include "spiffs.h"
#include "fs-test/fs_test.h"
static fs_time_t get_current_time()
{
return timer_get_count(FRC2) / 5000; // to get roughly 1ms resolution
}
void test_task(void *pvParameters)
{
esp_spiffs_init();
esp_spiffs_mount();
SPIFFS_unmount(&fs); // FS must be unmounted before formating
if (SPIFFS_format(&fs) == SPIFFS_OK) {
printf("Format complete\n");
} else {
printf("Format failed\n");
}
esp_spiffs_mount();
while (1) {
vTaskDelay(5000 / portTICK_RATE_MS);
if (fs_load_test_run(100)) {
printf("PASS\n");
} else {
printf("FAIL\n");
}
vTaskDelay(5000 / portTICK_RATE_MS);
float write_rate, read_rate;
if (fs_speed_test_run(get_current_time, &write_rate, &read_rate)) {
printf("Read speed: %.0f bytes/s\n", read_rate * 1000);
printf("Write speed: %.0f bytes/s\n", write_rate * 1000);
} else {
printf("FAIL\n");
}
}
}
void user_init(void)
{
uart_set_baud(0, 115200);
xTaskCreate(test_task, (signed char *)"test_task", 1024, NULL, 2, NULL);
}

View file

@ -1,4 +1,4 @@
# Simple makefile for simple example
PROGRAM=pwm_test
COMPONENTS = FreeRTOS lwip core extras/pwm
EXTRA_COMPONENTS = extras/pwm
include ../../common.mk

View file

@ -4,6 +4,8 @@ FLASH_SIZE = 32
# spiffs configuration
SPIFFS_BASE_ADDR = 0x200000
SPIFFS_SIZE = 0x100000
SPIFFS_SIZE = 0x010000
include ../../common.mk
$(eval $(call make_spiffs_image,files))

View file

@ -0,0 +1 @@
This file will go to SPIFFS image.

View file

@ -4,171 +4,95 @@
#include "task.h"
#include "esp8266.h"
#include "fcntl.h"
#include "unistd.h"
#include "spiffs.h"
#include "esp_spiffs.h"
#define TEST_FILE_NAME_LEN 16
#define TEST_FILES 32
#define TEST_FILE_MAX_SIZE 8192
typedef struct {
char name[TEST_FILE_NAME_LEN];
uint16_t size;
uint8_t first_data_byte;
} TestFile;
static TestFile test_files[TEST_FILES];
inline static void fill_test_data(uint8_t *src, uint16_t size, uint8_t first_byte)
static void example_read_file_posix()
{
while (size--) {
*src++ = first_byte++;
}
}
const int buf_size = 0xFF;
uint8_t buf[buf_size];
static bool write_test_files()
{
uint8_t *buf = (uint8_t*)malloc(TEST_FILE_MAX_SIZE);
bool result = true;
for (uint8_t i = 0; i < TEST_FILES; i++) {
sprintf(test_files[i].name, "file_%d.dat", i);
spiffs_file f = SPIFFS_open(&fs, test_files[i].name,
SPIFFS_CREAT|SPIFFS_RDWR|SPIFFS_TRUNC, 0);
if (f < 0) {
printf("Open file operation failed\n");
result = false;
break;
}
test_files[i].size = rand() % TEST_FILE_MAX_SIZE;
test_files[i].first_data_byte = rand() % 256;
fill_test_data(buf, test_files[i].size, test_files[i].first_data_byte);
printf("Writing file %s size=%d\n", test_files[i].name,
test_files[i].size);
int32_t written = SPIFFS_write(&fs, f, buf, test_files[i].size);
if (written != test_files[i].size) {
printf("Write file operation failed, written=%d\n", written);
result = false;
break;
}
SPIFFS_close(&fs, f);
}
free(buf);
return result;
}
inline static bool verify_test_data(uint8_t *data, uint16_t size,
uint8_t first_byte)
{
while (size--) {
if (*data++ != first_byte++) {
return false;
}
}
return true;
}
static bool verify_test_files()
{
uint8_t *buf = (uint8_t*)malloc(TEST_FILE_MAX_SIZE);
bool result = true;
for (uint8_t i = 0; i < TEST_FILES; i++) {
printf("Verifying file %s\n", test_files[i].name);
spiffs_file f = SPIFFS_open(&fs, test_files[i].name, SPIFFS_RDONLY, 0);
if (f < 0) {
printf("Open file operation failed\n");
result = false;
break;
}
int32_t n = SPIFFS_read(&fs, f, buf, test_files[i].size);
if (n != test_files[i].size) {
printf("Read file operation failed\n");
result = false;
break;
}
if (!verify_test_data(buf, test_files[i].size,
test_files[i].first_data_byte)) {
printf("Data verification failed\n");
result = false;
break;
}
SPIFFS_close(&fs, f);
int fd = open("test.txt", O_RDONLY);
if (fd < 0) {
printf("Error opening file\n");
return;
}
free(buf);
return result;
int read_bytes = read(fd, buf, buf_size);
printf("Read %d bytes\n", read_bytes);
buf[read_bytes] = '\0'; // zero terminate string
printf("Data: %s\n", buf);
close(fd);
}
static bool cleanup_test_files()
static void example_read_file_spiffs()
{
bool result = true;
const int buf_size = 0xFF;
uint8_t buf[buf_size];
for (uint8_t i = 0; i < TEST_FILES; i++) {
printf("Removing file %s\n", test_files[i].name);
if (SPIFFS_remove(&fs, test_files[i].name) != SPIFFS_OK) {
printf("Remove file operation failed\n");
result = false;
break;
}
spiffs_file fd = SPIFFS_open(&fs, "other.txt", SPIFFS_RDONLY, 0);
if (fd < 0) {
printf("Error opening file\n");
return;
}
return result;
int read_bytes = SPIFFS_read(&fs, fd, buf, buf_size);
printf("Read %d bytes\n", read_bytes);
buf[read_bytes] = '\0'; // zero terminate string
printf("Data: %s\n", buf);
SPIFFS_close(&fs, fd);
}
inline static void print_info()
static void example_write_file()
{
uint8_t buf[] = "Example data, written by ESP8266";
int fd = open("other.txt", O_WRONLY|O_CREAT, 0);
if (fd < 0) {
printf("Error opening file\n");
return;
}
int written = write(fd, buf, sizeof(buf));
printf("Written %d bytes\n", written);
close(fd);
}
static void example_fs_info()
{
uint32_t total, used;
SPIFFS_info(&fs, &total, &used);
printf("FS total=%d bytes, used=%d bytes\n", total, used);
printf("FS %d %% used\n", 100 * used/total);
// File system structure visualisation
// SPIFFS_vis(&fs);
printf("Total: %d bytes, used: %d bytes", total, used);
}
void test_task(void *pvParameters)
{
bool result = true;
esp_spiffs_mount();
esp_spiffs_unmount(); // FS must be unmounted before formating
if (SPIFFS_format(&fs) == SPIFFS_OK) {
printf("Format complete\n");
} else {
printf("Format failed\n");
esp_spiffs_init();
if (esp_spiffs_mount() != SPIFFS_OK) {
printf("Error mount SPIFFS\n");
}
esp_spiffs_mount();
while (1) {
vTaskDelay(5000 / portTICK_RATE_MS);
vTaskDelay(2000 / portTICK_RATE_MS);
result = write_test_files();
example_write_file();
if (result) {
result = verify_test_files();
}
example_read_file_posix();
print_info();
example_read_file_spiffs();
if (result) {
result = cleanup_test_files();
}
example_fs_info();
if (result) {
printf("Test passed!\n");
} else {
printf("Test failed!\n");
while (1) {
vTaskDelay(1);
}
}
printf("\n\n");
}
}

View file

@ -1,4 +1,4 @@
PROGRAM=tls_server
COMPONENTS = FreeRTOS lwip core extras/mbedtls
EXTRA_COMPONENTS = extras/mbedtls
include ../../common.mk

View file

@ -6,23 +6,26 @@
*/
#include "dht.h"
#include "FreeRTOS.h"
#include "string.h"
#include "task.h"
#include "esp/gpio.h"
#include <espressif/esp_misc.h> // sdk_os_delay_us
#ifndef DEBUG_DHT
#define DEBUG_DHT 0
#endif
// DHT timer precision in microseconds
#define DHT_TIMER_INTERVAL 2
#define DHT_DATA_BITS 40
#if DEBUG_DHT
// #define DEBUG_DHT
#ifdef DEBUG_DHT
#define debug(fmt, ...) printf("%s" fmt "\n", "dht: ", ## __VA_ARGS__);
#else
#define debug(fmt, ...) /* (do nothing) */
#endif
/*
/*
* Note:
* A suitable pull-up resistor should be connected to the selected GPIO line
*
@ -32,17 +35,17 @@
*
*
* Initializing communications with the DHT requires four 'phases' as follows:
*
*
* Phase A - MCU pulls signal low for at least 18000 us
* Phase B - MCU allows signal to float back up and waits 20-40us for DHT to pull it low
* Phase C - DHT pulls signal low for ~80us
* Phase D - DHT lets signal float back up for ~80us
*
*
* After this, the DHT transmits its first bit by holding the signal low for 50us
* and then letting it float back high for a period of time that depends on the data bit.
* duration_data_high is shorter than 50us for a logic '0' and longer than 50us for logic '1'.
*
* There are a total of 40 data bits trasnmitted sequentially. These bits are read into a byte array
* There are a total of 40 data bits transmitted sequentially. These bits are read into a byte array
* of length 5. The first and third bytes are humidity (%) and temperature (C), respectively. Bytes 2 and 4
* are zero-filled and the fifth is a checksum such that:
*
@ -50,95 +53,144 @@
*
*/
/*
* @pin the selected GPIO pin
* @interval how frequently the pin state is checked in microseconds
* @timeout maximum length of time to wait for the expected pin state
* @expected_pin_state high (true) or low (false) pin state
* @counter pointer to external uint8_t for tallying the duration waited for the pin state
*/
bool dht_await_pin_state(uint8_t pin, uint8_t interval, uint8_t timeout, bool expected_pin_state, uint8_t * counter) {
for (*counter = 0; *counter < timeout; *counter+=interval) {
if (gpio_read(pin) == expected_pin_state) return true;
sdk_os_delay_us(interval);
/**
* Wait specified time for pin to go to a specified state.
* If timeout is reached and pin doesn't go to a requested state
* false is returned.
* The elapsed time is returned in pointer 'duration' if it is not NULL.
*/
static bool dht_await_pin_state(uint8_t pin, uint32_t timeout,
bool expected_pin_state, uint32_t *duration)
{
for (uint32_t i = 0; i < timeout; i += DHT_TIMER_INTERVAL) {
// need to wait at least a single interval to prevent reading a jitter
sdk_os_delay_us(DHT_TIMER_INTERVAL);
if (gpio_read(pin) == expected_pin_state) {
if (duration) {
*duration = i;
}
return true;
}
}
return false;
}
/*
*
*
* @pin the selected GPIO pin
* @humidity pointer to external int8_t to store resulting humidity value
* @temperature pointer to external int8_t to store resulting temperature value
*/
bool dht_fetch_data(int8_t pin, int8_t * humidity, int8_t * temperature) {
int8_t data[40] = {0};
int8_t result[5] = {0};
uint8_t i = 0;
uint8_t init_phase_duration = 0;
uint8_t duration_data_low = 0;
uint8_t duration_data_high = 0;
gpio_enable(pin, GPIO_OUT_OPEN_DRAIN);
taskENTER_CRITICAL();
/**
* Request data from DHT and read raw bit stream.
* The function call should be protected from task switching.
* Return false if error occurred.
*/
static inline bool dht_fetch_data(uint8_t pin, bool bits[DHT_DATA_BITS])
{
uint32_t low_duration;
uint32_t high_duration;
// Phase 'A' pulling signal low to initiate read sequence
gpio_write(pin, 0);
sdk_os_delay_us(20000);
gpio_write(pin, 1);
// Step through Phase 'B' at 2us intervals, 40us max
if (dht_await_pin_state(pin, 2, 40, false, &init_phase_duration)) {
// Step through Phase 'C ' at 2us intervals, 88us max
if (dht_await_pin_state(pin, 2, 88, true, &init_phase_duration)) {
// Step through Phase 'D' at 2us intervals, 88us max
if (dht_await_pin_state(pin, 2, 88, false, &init_phase_duration)) {
// Read in each of the 40 bits of data...
for (i = 0; i < 40; i++) {
if (dht_await_pin_state(pin, 2, 60, true, &duration_data_low)) {
if (dht_await_pin_state(pin, 2, 75, false, &duration_data_high)) {
data[i] = duration_data_high > duration_data_low;
}
}
}
taskEXIT_CRITICAL();
for (i = 0; i < 40; i++) {
// Read each bit into 'result' byte array...
result[i/8] <<= 1;
result[i/8] |= data[i];
}
if (result[4] == ((result[0] + result[1] + result[2] + result[3]) & 0xFF)) {
// Data valid, checksum succeeded...
*humidity = result[0];
*temperature = result[2];
debug("Successfully retrieved sensor data...");
return true;
} else {
debug("Checksum failed, invalid data received from sensor...");
}
} else {
debug("Initialization error, problem in phase 'D'...");
}
} else {
debug("Initialization error, problem in phase 'C'...");
}
} else {
debug("Initialization error, problem in phase 'B'...");
// Step through Phase 'B', 40us
if (!dht_await_pin_state(pin, 40, false, NULL)) {
debug("Initialization error, problem in phase 'B'\n");
return false;
}
taskEXIT_CRITICAL();
return false;
// Step through Phase 'C', 88us
if (!dht_await_pin_state(pin, 88, true, NULL)) {
debug("Initialization error, problem in phase 'C'\n");
return false;
}
// Step through Phase 'D', 88us
if (!dht_await_pin_state(pin, 88, false, NULL)) {
debug("Initialization error, problem in phase 'D'\n");
return false;
}
// Read in each of the 40 bits of data...
for (int i = 0; i < DHT_DATA_BITS; i++) {
if (!dht_await_pin_state(pin, 65, true, &low_duration)) {
debug("LOW bit timeout\n");
return false;
}
if (!dht_await_pin_state(pin, 75, false, &high_duration)){
debug("HIGHT bit timeout\n");
return false;
}
bits[i] = high_duration > low_duration;
}
return true;
}
/**
* Pack two data bytes into single value and take into account sign bit.
*/
static inline int16_t dht_convert_data(uint8_t msb, uint8_t lsb)
{
int16_t data;
#if DHT_TYPE == DHT22
data = msb & 0x7F;
data <<= 8;
data |= lsb;
if (msb & BIT(7)) {
data = 0 - data; // convert it to negative
}
#elif DHT_TYPE == DHT11
data = msb * 10;
#else
#error "Unsupported DHT type"
#endif
return data;
}
bool dht_read_data(uint8_t pin, int16_t *humidity, int16_t *temperature)
{
bool bits[DHT_DATA_BITS];
uint8_t data[DHT_DATA_BITS/8] = {0};
bool result;
gpio_enable(pin, GPIO_OUT_OPEN_DRAIN);
taskENTER_CRITICAL();
result = dht_fetch_data(pin, bits);
taskEXIT_CRITICAL();
if (!result) {
return false;
}
for (uint8_t i = 0; i < DHT_DATA_BITS; i++) {
// Read each bit into 'result' byte array...
data[i/8] <<= 1;
data[i/8] |= bits[i];
}
if (data[4] != ((data[0] + data[1] + data[2] + data[3]) & 0xFF)) {
debug("Checksum failed, invalid data received from sensor\n");
return false;
}
*humidity = dht_convert_data(data[0], data[1]);
*temperature = dht_convert_data(data[2], data[3]);
debug("Sensor data: humidity=%d, temp=%d\n", *humidity, *temperature);
return true;
}
bool dht_read_float_data(uint8_t pin, float *humidity, float *temperature)
{
int16_t i_humidity, i_temp;
if (dht_read_data(pin, &i_humidity, &i_temp)) {
*humidity = (float)i_humidity / 10;
*temperature = (float)i_temp / 10;
return true;
}
return false;
}

View file

@ -5,13 +5,34 @@
*
*/
#ifndef __DTH_H__
#ifndef __DHT_H__
#define __DHT_H__
#include "FreeRTOS.h"
#include <stdint.h>
#include <stdbool.h>
bool dht_wait_for_pin_state(uint8_t pin, uint8_t interval, uint8_t timeout, bool expected_pin_sate, uint8_t * counter);
bool dht_fetch_data(int8_t pin, int8_t * humidity, int8_t * temperature);
#define DHT11 11
#define DHT22 22
#endif
// Type of sensor to use
#define DHT_TYPE DHT22
/**
* Read data from sensor on specified pin.
*
* Humidity and temperature is returned as integers.
* For example: humidity=625 is 62.5 %
* temperature=24.4 is 24.4 degrees Celsius
*
*/
bool dht_read_data(uint8_t pin, int16_t *humidity, int16_t *temperature);
/**
* Float version of dht_read_data.
*
* Return values as floating point values.
*/
bool dht_read_float_data(uint8_t pin, float *humidity, float *temperature);
#endif // __DHT_H__

View file

@ -35,7 +35,7 @@ int sendPacket(MQTTClient* c, int length, Timer* timer)
while (sent < length && !expired(timer))
{
rc = c->ipstack->mqttwrite(c->ipstack, &c->buf[sent], length, left_ms(timer));
rc = c->ipstack->mqttwrite(c->ipstack, &c->buf[sent], length - sent, left_ms(timer));
if (rc < 0) // there was an error writing the data
break;
sent += rc;
@ -70,7 +70,9 @@ int decodePacket(MQTTClient* c, int* value, int timeout)
}
rc = c->ipstack->mqttread(c->ipstack, &i, 1, timeout);
if (rc != 1)
goto exit;
{
goto exit;
}
*value += (i & 127) * multiplier;
multiplier *= 128;
} while ((i & 128) != 0);
@ -79,6 +81,7 @@ exit:
}
// Return packet type. If no packet avilable, return FAILURE, or READ_ERROR if timeout
int readPacket(MQTTClient* c, Timer* timer)
{
int rc = FAILURE;
@ -89,20 +92,19 @@ int readPacket(MQTTClient* c, Timer* timer)
/* 1. read the header byte. This has the packet type in it */
if (c->ipstack->mqttread(c->ipstack, c->readbuf, 1, left_ms(timer)) != 1)
goto exit;
len = 1;
/* 2. read the remaining length. This is variable in itself */
decodePacket(c, &rem_len, left_ms(timer));
len += MQTTPacket_encode(c->readbuf + 1, rem_len); /* put the original remaining length back into the buffer */
/* 3. read the rest of the buffer using a callback to supply the rest of the data */
if (rem_len > 0 && (c->ipstack->mqttread(c->ipstack, c->readbuf + len, rem_len, left_ms(timer)) != rem_len))
{
rc = READ_ERROR;
goto exit;
}
header.byte = c->readbuf[0];
rc = header.bits.type;
exit:
//dmsg_printf("readPacket=%d\r\n", rc);
return rc;
}
@ -212,10 +214,10 @@ exit:
}
int cycle(MQTTClient* c, Timer* timer)
int cycle(MQTTClient* c, Timer* timer)
{
// read the socket, see what work is due
unsigned short packet_type = readPacket(c, timer);
int packet_type = readPacket(c, timer);
int len = 0,
rc = SUCCESS;
@ -266,11 +268,17 @@ int cycle(MQTTClient* c, Timer* timer)
case PUBCOMP:
break;
case PINGRESP:
{
c->ping_outstanding = 0;
c->fail_count = 0;
}
{
c->ping_outstanding = 0;
c->fail_count = 0;
break;
}
case READ_ERROR:
{
c->isconnected = 0; // we simulate a disconnect if reading error
rc = DISCONNECTED; // so that the outer layer will reconnect and recover
break;
}
}
if (c->isconnected)
rc = keepalive(c);

View file

@ -27,7 +27,7 @@
enum QoS { QOS0, QOS1, QOS2 };
// all failure return codes must be negative
enum returnCode {DISCONNECTED = -3, BUFFER_OVERFLOW = -2, FAILURE = -1, SUCCESS = 0 };
enum returnCode {READ_ERROR = -4, DISCONNECTED = -3, BUFFER_OVERFLOW = -2, FAILURE = -1, SUCCESS = 0 };
void NewTimer(Timer*);

View file

@ -249,7 +249,7 @@ bool rboot_verify_image(uint32_t initial_offset, uint32_t *image_length, const c
/* sanity limit on how far we can read */
uint32_t end_limit = offset + 0x100000;
image_header_t image_header __attribute__((aligned(4)));
if(sdk_spi_flash_read(offset, &image_header, sizeof(image_header_t))) {
if(sdk_spi_flash_read(offset, (uint32_t *)&image_header, sizeof(image_header_t))) {
error = "Flash fail";
goto fail;
}
@ -271,7 +271,7 @@ bool rboot_verify_image(uint32_t initial_offset, uint32_t *image_length, const c
{
/* read section header */
section_header_t header __attribute__((aligned(4)));
if(sdk_spi_flash_read(offset, &header, sizeof(section_header_t))) {
if(sdk_spi_flash_read(offset, (uint32_t *)&header, sizeof(section_header_t))) {
error = "Flash fail";
goto fail;
}
@ -359,7 +359,7 @@ bool rboot_digest_image(uint32_t offset, uint32_t image_length, rboot_digest_upd
{
uint8_t buf[32] __attribute__((aligned(4)));
for(int i = 0; i < image_length; i += sizeof(buf)) {
if(sdk_spi_flash_read(offset+i, buf, sizeof(buf)))
if(sdk_spi_flash_read(offset+i, (uint32_t *)buf, sizeof(buf)))
return false;
uint32_t digest_len = sizeof(buf);
if(i + digest_len > image_length)

View file

@ -608,6 +608,8 @@ sntp_send_request(ip_addr_t *server_addr)
sntp_initialize_request(sntpmsg);
/* send request */
udp_sendto(sntp_pcb, p, server_addr, SNTP_PORT);
pbuf_free(p);
/* set up receive timeout: try next server or retry on timeout */
sys_timeout((u32_t)SNTP_RECV_TIMEOUT, sntp_try_next_server, NULL);
#if SNTP_CHECK_RESPONSE >= 1

153
extras/spiffs/README.md Normal file
View file

@ -0,0 +1,153 @@
# SPIFFS ESP8266 File system
This component adds file system support for ESP8266. File system of choice
for ESP8266 is [SPIFFS](https://github.com/pellepl/spiffs).
It was specifically designed to use with SPI NOR flash on embedded systems.
The main advantage of SPIFFS is wear leveling, which prolongs life time
of a flash memory.
## Features
* SPIFFS - embedded file system for NOR flash memory.
* POSIX file operations.
* Static files upload to ESP8266 file system within build process.
* SPIFFS singleton configuration. Only one instance of FS on a device.
## Usage
In order to use file system in a project the following steps should be made:
* Add SPIFFS component in a project Makefile `EXTRA_COMPONENTS = extras/spiffs`
* Specify your flash size in the Makefile `FLASH_SIZE = 32`
* Specify the start address of file system region on the flash memory
`SPIFFS_BASE_ADDR = 0x200000`
* If you want to upload files to a file system during flash process specify
the directory with files `$(eval $(call make_spiffs_image,files))`
In the end the Makefile should look like:
```
PROGRAM=spiffs_example
EXTRA_COMPONENTS = extras/spiffs
FLASH_SIZE = 32
SPIFFS_BASE_ADDR = 0x200000
SPIFFS_SIZE = 0x100000
include ../../common.mk
$(eval $(call make_spiffs_image,files))
```
Note: Macro call to prepare SPIFFS image for flashing should go after
`include common.mk`
### Files upload
To upload files to a file system during flash process the following macro is
used:
```
$(eval $(call make_spiffs_image,files))
```
It enables the build of a helper utility **mkspiffs**. This utility creates
an SPIFFS image with files in the specified directory.
The SPIFFS image is created during build stage, after `make` is run.
The image is flashed into the device along with firmware during flash stage,
after `make flash` is run.
**mkspiffs** utility uses the same SPIFFS source code and the same
configuration as ESP8266. So the created image should always be compatible
with SPIFFS on a device.
The build process will catch any changes in files directory and rebuild the
image each time `make` is run.
The build process will handle SPIFFS_SIZE change and rebuild **mkspiffs**
utility and the image.
## Example
### Mount
```
esp_spiffs_init(); // allocate memory buffers
if (esp_spiffs_mount() != SPIFFS_OK) {
printf("Error mounting SPIFFS\n");
}
```
### Format
Formatting SPIFFS is a little bit awkward. Before formatting SPIFFS must be
mounted and unmounted.
```
esp_spiffs_init();
if (esp_spiffs_mount() != SPIFFS_OK) {
printf("Error mount SPIFFS\n");
}
SPIFFS_unmount(&fs); // FS must be unmounted before formating
if (SPIFFS_format(&fs) == SPIFFS_OK) {
printf("Format complete\n");
} else {
printf("Format failed\n");
}
esp_spiffs_mount();
```
### POSIX read
Nothing special here.
```
const int buf_size = 0xFF;
uint8_t buf[buf_size];
int fd = open("test.txt", O_RDONLY);
if (fd < 0) {
printf("Error opening file\n");
}
read(fd, buf, buf_size);
printf("Data: %s\n", buf);
close(fd);
```
### SPIFFS read
SPIFFS interface is intended to be as close to POSIX as possible.
```
const int buf_size = 0xFF;
uint8_t buf[buf_size];
spiffs_file fd = SPIFFS_open(&fs, "other.txt", SPIFFS_RDONLY, 0);
if (fd < 0) {
printf("Error opening file\n");
}
SPIFFS_read(&fs, fd, buf, buf_size);
printf("Data: %s\n", buf);
SPIFFS_close(&fs, fd);
```
### POSIX write
```
uint8_t buf[] = "Example data, written by ESP8266";
int fd = open("other.txt", O_WRONLY|O_CREAT, 0);
if (fd < 0) {
printf("Error opening file\n");
}
write(fd, buf, sizeof(buf));
close(fd);
```
## Resources
[SPIFFS](https://github.com/pellepl/spiffs)

View file

@ -14,4 +14,44 @@ spiffs_CFLAGS = $(CFLAGS)
spiffs_CFLAGS += -DSPIFFS_BASE_ADDR=$(SPIFFS_BASE_ADDR)
spiffs_CFLAGS += -DSPIFFS_SIZE=$(SPIFFS_SIZE)
# Create an SPIFFS image of specified directory and flash it with
# the rest of the firmware.
#
# Argumens:
# $(1) - directory with files which go into spiffs image
#
# Example:
# $(eval $(call make_spiffs_image,files))
define make_spiffs_image
SPIFFS_IMAGE = $(addprefix $(FIRMWARE_DIR),spiffs.bin)
MKSPIFFS_DIR = $(ROOT)/extras/spiffs/mkspiffs
MKSPIFFS = $$(MKSPIFFS_DIR)/mkspiffs
SPIFFS_FILE_LIST = $(shell find $(1))
all: $$(SPIFFS_IMAGE)
clean: clean_spiffs_img clean_mkspiffs
$$(SPIFFS_IMAGE): $$(MKSPIFFS) $$(SPIFFS_FILE_LIST)
$$< $(1) $$@
# Rebuild SPIFFS if Makefile is changed, where SPIFF_SIZE is defined
$$(spiffs_ROOT)spiffs_config.h: Makefile
$$(Q) touch $$@
# if SPIFFS_SIZE in Makefile is changed rebuild mkspiffs
$$(MKSPIFFS): Makefile
$$(MAKE) -C $$(MKSPIFFS_DIR) clean
$$(MAKE) -C $$(MKSPIFFS_DIR) SPIFFS_SIZE=$(SPIFFS_SIZE)
clean_spiffs_img:
$$(Q) rm -f $$(SPIFFS_IMAGE)
clean_mkspiffs:
$$(Q) $$(MAKE) -C $$(MKSPIFFS_DIR) clean
SPIFFS_ESPTOOL_ARGS = $(SPIFFS_BASE_ADDR) $$(SPIFFS_IMAGE)
endef
$(eval $(call component_compile_rules,spiffs))

View file

@ -12,12 +12,26 @@
#include "common_macros.h"
#include "FreeRTOS.h"
#include "esp/rom.h"
#include <esp/uart.h>
#include <fcntl.h>
spiffs fs;
static void *work_buf = 0;
static void *fds_buf = 0;
static void *cache_buf = 0;
typedef struct {
void *buf;
uint32_t size;
} fs_buf_t;
static fs_buf_t work_buf = {0};
static fs_buf_t fds_buf = {0};
static fs_buf_t cache_buf = {0};
/**
* Number of file descriptors opened at the same time
*/
#define ESP_SPIFFS_FD_NUMBER 5
#define ESP_SPIFFS_CACHE_PAGES 5
// ROM functions
@ -286,6 +300,29 @@ static s32_t esp_spiffs_erase(u32_t addr, u32_t size)
return SPIFFS_OK;
}
void esp_spiffs_init()
{
work_buf.size = 2 * SPIFFS_CFG_LOG_PAGE_SZ();
fds_buf.size = SPIFFS_buffer_bytes_for_filedescs(&fs, ESP_SPIFFS_FD_NUMBER);
cache_buf.size= SPIFFS_buffer_bytes_for_cache(&fs, ESP_SPIFFS_CACHE_PAGES);
work_buf.buf = malloc(work_buf.size);
fds_buf.buf = malloc(fds_buf.size);
cache_buf.buf = malloc(cache_buf.size);
}
void esp_spiffs_deinit()
{
free(work_buf.buf);
work_buf.buf = 0;
free(fds_buf.buf);
fds_buf.buf = 0;
free(cache_buf.buf);
cache_buf.buf = 0;
}
int32_t esp_spiffs_mount()
{
spiffs_config config = {0};
@ -294,18 +331,13 @@ int32_t esp_spiffs_mount()
config.hal_write_f = esp_spiffs_write;
config.hal_erase_f = esp_spiffs_erase;
size_t workBufSize = 2 * SPIFFS_CFG_LOG_PAGE_SZ();
size_t fdsBufSize = SPIFFS_buffer_bytes_for_filedescs(&fs, 5);
size_t cacheBufSize = SPIFFS_buffer_bytes_for_cache(&fs, 5);
printf("SPIFFS size: %d\n", SPIFFS_SIZE);
printf("SPIFFS memory, work_buf_size=%d, fds_buf_size=%d, cache_buf_size=%d\n",
work_buf.size, fds_buf.size, cache_buf.size);
work_buf = malloc(workBufSize);
fds_buf = malloc(fdsBufSize);
cache_buf = malloc(cacheBufSize);
printf("spiffs memory, work_buf_size=%d, fds_buf_size=%d, cache_buf_size=%d\n",
workBufSize, fdsBufSize, cacheBufSize);
int32_t err = SPIFFS_mount(&fs, &config, work_buf, fds_buf, fdsBufSize,
cache_buf, cacheBufSize, 0);
int32_t err = SPIFFS_mount(&fs, &config, (uint8_t*)work_buf.buf,
(uint8_t*)fds_buf.buf, fds_buf.size,
cache_buf.buf, cache_buf.size, 0);
if (err != SPIFFS_OK) {
printf("Error spiffs mount: %d\n", err);
@ -314,15 +346,95 @@ int32_t esp_spiffs_mount()
return err;
}
void esp_spiffs_unmount()
#define FD_OFFSET 3
// This implementation replaces implementation in core/newlib_syscals.c
long _write_r(struct _reent *r, int fd, const char *ptr, int len )
{
SPIFFS_unmount(&fs);
free(work_buf);
free(fds_buf);
free(cache_buf);
work_buf = 0;
fds_buf = 0;
cache_buf = 0;
if(fd != r->_stdout->_file) {
long ret = SPIFFS_write(&fs, (spiffs_file)(fd - FD_OFFSET),
(char*)ptr, len);
return ret;
}
for(int i = 0; i < len; i++) {
/* Auto convert CR to CRLF, ignore other LFs (compatible with Espressif SDK behaviour) */
if(ptr[i] == '\r')
continue;
if(ptr[i] == '\n')
uart_putc(0, '\r');
uart_putc(0, ptr[i]);
}
return len;
}
// This implementation replaces implementation in core/newlib_syscals.c
long _read_r( struct _reent *r, int fd, char *ptr, int len )
{
int ch, i;
if(fd != r->_stdin->_file) {
long ret = SPIFFS_read(&fs, (spiffs_file)(fd - FD_OFFSET), ptr, len);
return ret;
}
uart_rxfifo_wait(0, 1);
for(i = 0; i < len; i++) {
ch = uart_getc_nowait(0);
if (ch < 0) break;
ptr[i] = ch;
}
return i;
}
int _open_r(struct _reent *r, const char *pathname, int flags, int mode)
{
uint32_t spiffs_flags = SPIFFS_RDONLY;
if (flags & O_CREAT) spiffs_flags |= SPIFFS_CREAT;
if (flags & O_APPEND) spiffs_flags |= SPIFFS_APPEND;
if (flags & O_TRUNC) spiffs_flags |= SPIFFS_TRUNC;
if (flags & O_RDONLY) spiffs_flags |= SPIFFS_RDONLY;
if (flags & O_WRONLY) spiffs_flags |= SPIFFS_WRONLY;
int ret = SPIFFS_open(&fs, pathname, spiffs_flags, mode);
if (ret > 0) {
return ret + FD_OFFSET;
}
return ret;
}
int _close_r(struct _reent *r, int fd)
{
return SPIFFS_close(&fs, (spiffs_file)(fd - FD_OFFSET));
}
int _unlink_r(struct _reent *r, const char *path)
{
return SPIFFS_remove(&fs, path);
}
int _fstat_r(struct _reent *r, int fd, void *buf)
{
spiffs_stat s;
struct stat *sb = (struct stat*)buf;
int result = SPIFFS_fstat(&fs, (spiffs_file)(fd - FD_OFFSET), &s);
sb->st_size = s.size;
return result;
}
int _stat_r(struct _reent *r, const char *pathname, void *buf)
{
spiffs_stat s;
struct stat *sb = (struct stat*)buf;
int result = SPIFFS_stat(&fs, pathname, &s);
sb->st_size = s.size;
return result;
}
off_t _lseek_r(struct _reent *r, int fd, off_t offset, int whence)
{
return SPIFFS_lseek(&fs, (spiffs_file)(fd - FD_OFFSET), offset, whence);
}

View file

@ -13,16 +13,27 @@
extern spiffs fs;
/**
* Provide SPIFFS with all necessary configuration, allocate memory buffers
* and mount SPIFFS.
* Prepare for SPIFFS mount.
*
* The function allocates all the necessary buffers.
*/
void esp_spiffs_init();
/**
* Free all memory buffers that were used by SPIFFS.
*
* The function should be called after SPIFFS unmount if the file system is not
* going to need any more.
*/
void esp_spiffs_deinit();
/**
* Mount SPIFFS.
*
* esp_spiffs_init must be called first.
*
* Return SPIFFS return code.
*/
int32_t esp_spiffs_mount();
/**
* Unmount SPIFFS and free all allocated buffers.
*/
void esp_spiffs_unmount();
#endif // __ESP_SPIFFS_H__

View file

@ -0,0 +1,37 @@
# Check if SPIFFS_SIZE defined only if not cleaning
ifneq ($(MAKECMDGOALS),clean)
ifndef SPIFFS_SIZE
define ERROR_MSG
Variable SPIFFS_SIZE is not defined.
Cannot build mkspiffs without SPIFFS_SIZE.
Please specify it in your application Makefile.
endef
$(error $(ERROR_MSG))
endif
endif
SOURCES := spiffs_hydrogen.c
SOURCES += spiffs_cache.c
SOURCES += spiffs_gc.c
SOURCES += spiffs_check.c
SOURCES += spiffs_nucleus.c
SOURCES += mkspiffs.c
OBJECTS := $(SOURCES:.c=.o)
VPATH = ../spiffs/src
CFLAGS += -I..
CFLAGS += -DSPIFFS_BASE_ADDR=0 # for image base addr is start of the image
CFLAGS += -DSPIFFS_SIZE=$(SPIFFS_SIZE)
all: mkspiffs
mkspiffs: $(OBJECTS)
clean:
@rm -f mkspiffs
@rm -f *.o
.PHONY: all clean

View file

@ -0,0 +1,34 @@
# mkspiffs Create spiffs image
mkspiffs is a command line utility to create an image of SPIFFS in order
to write to flash.
## Usage
mkspiffs will be built automatically if you include the following line in your
makefile:
```
$(eval $(call make_spiffs_image,files))
```
where *files* is the directory with files that should go into SPIFFS image.
Or you can build mkspiffs manually with:
```
make SPIFFS_SIZE=0x100000
```
mkspiffs cannot be built without specifying SPIFFS size because it uses the
same SPIFFS sources as the firmware. And for the firmware SPIFFS size is
compile time defined.
Please note that if you change SPIFFS_SIZE you need to rebuild mkspiffs.
The easiest way is to run `make clean` for you project.
To manually generate SPIFFS image from directory, run:
```
mkspiffs DIRECTORY IMAGE_NAME
```

View file

@ -0,0 +1,243 @@
/**
* The MIT License (MIT)
*
* Copyright (c) 2016 sheinz (https://github.com/sheinz)
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include <fcntl.h>
#include <unistd.h>
#include <stdio.h>
#include <sys/types.h>
#include <sys/dir.h>
#include <sys/dirent.h>
#include <stdint.h>
#include <stdbool.h>
#include <stdlib.h>
#include <string.h>
#include "spiffs_config.h"
#include "../spiffs/src/spiffs.h"
static spiffs fs;
static void *image = 0;
static void *work_buf = 0;
static void *fds_buf = 0;
static void *cache_buf = 0;
static void print_usage(const char *prog_name, const char *error_msg)
{
if (error_msg) {
printf("Error: %s\n", error_msg);
}
printf("Usage: ");
printf("\t%s DIRECTORY IMAGE_NAME\n\n", prog_name);
printf("Example:\n");
printf("\t%s ./my_files spiffs.img\n\n", prog_name);
}
static s32_t _read_data(u32_t addr, u32_t size, u8_t *dst)
{
memcpy(dst, (uint8_t*)image + addr, size);
return SPIFFS_OK;
}
static s32_t _write_data(u32_t addr, u32_t size, u8_t *src)
{
memcpy((uint8_t*)image + addr, src, size);
return SPIFFS_OK;
}
static s32_t _erase_data(u32_t addr, u32_t size)
{
memset((uint8_t*)image + addr, 0xFF, size);
return SPIFFS_OK;
}
static bool init_spiffs(bool allocate_mem)
{
spiffs_config config = {0};
printf("Initializing SPIFFS, size=%d\n", SPIFFS_SIZE);
config.hal_read_f = _read_data;
config.hal_write_f = _write_data;
config.hal_erase_f = _erase_data;
int workBufSize = 2 * SPIFFS_CFG_LOG_PAGE_SZ();
int fdsBufSize = SPIFFS_buffer_bytes_for_filedescs(&fs, 5);
int cacheBufSize = SPIFFS_buffer_bytes_for_cache(&fs, 5);
if (allocate_mem) {
image = malloc(SPIFFS_SIZE);
work_buf = malloc(workBufSize);
fds_buf = malloc(fdsBufSize);
cache_buf = malloc(cacheBufSize);
printf("spiffs memory, work_buf_size=%d, fds_buf_size=%d, cache_buf_size=%d\n",
workBufSize, fdsBufSize, cacheBufSize);
}
int32_t err = SPIFFS_mount(&fs, &config, work_buf, fds_buf, fdsBufSize,
cache_buf, cacheBufSize, 0);
if (err != SPIFFS_OK) {
printf("Error spiffs mount: %d\n", err);
return false;
}
return true;
}
static bool format_spiffs()
{
SPIFFS_unmount(&fs);
if (SPIFFS_format(&fs) == SPIFFS_OK) {
printf("Format complete\n");
} else {
printf("Failed to format SPIFFS\n");
return false;
}
if (!init_spiffs(false)) {
printf("Failed to mount SPIFFS\n");
return false;
}
return true;
}
static void spiffs_free()
{
free(image);
image = NULL;
free(work_buf);
work_buf = NULL;
free(fds_buf);
fds_buf = NULL;
free(cache_buf);
cache_buf = NULL;
}
static bool process_file(const char *src_file, const char *dst_file)
{
int fd;
const int buf_size = 256;
uint8_t buf[buf_size];
int data_len;
fd = open(src_file, O_RDONLY);
if (fd < 0) {
printf("Error openning file: %s\n", src_file);
}
spiffs_file out_fd = SPIFFS_open(&fs, dst_file,
SPIFFS_O_CREAT | SPIFFS_O_WRONLY, 0);
while ((data_len = read(fd, buf, buf_size)) != 0) {
if (SPIFFS_write(&fs, out_fd, buf, data_len) != data_len) {
printf("Error writing to SPIFFS file\n");
break;
}
}
SPIFFS_close(&fs, out_fd);
close(fd);
return true;
}
static bool process_directory(const char *direcotry)
{
DIR *dp;
struct dirent *ep;
char path[256];
dp = opendir(direcotry);
if (dp != NULL) {
while ((ep = readdir(dp)) != 0) {
if (!strcmp(ep->d_name, ".") ||
!strcmp(ep->d_name, "..")) {
continue;
}
if (ep->d_type != DT_REG) {
continue; // not a regular file
}
sprintf(path, "%s/%s", direcotry, ep->d_name);
printf("Processing file %s\n", path);
if (!process_file(path, ep->d_name)) {
printf("Error processing file\n");
break;
}
}
closedir(dp);
} else {
printf("Error reading direcotry: %s\n", direcotry);
}
return true;
}
static bool write_image(const char *out_file)
{
int fd;
int size = SPIFFS_SIZE;
uint8_t *p = (uint8_t*)image;
fd = open(out_file, O_WRONLY | O_CREAT | O_TRUNC, 0666);
if (fd < 0) {
printf("Error creating file %s\n", out_file);
return false;
}
printf("Writing image to file: %s\n", out_file);
while (size != 0) {
write(fd, p, SPIFFS_CFG_LOG_PAGE_SZ());
p += SPIFFS_CFG_LOG_PAGE_SZ();
size -= SPIFFS_CFG_LOG_PAGE_SZ();
}
close(fd);
return true;
}
int main(int argc, char *argv[])
{
int result = 0;
if (argc != 3) {
print_usage(argv[0], NULL);
return -1;
}
if (init_spiffs(/*allocate_mem=*/true)) {
if (format_spiffs()) {
if (process_directory(argv[1])) {
if (!write_image(argv[2])) {
printf("Error writing image\n");
}
} else {
printf("Error processing direcotry\n");
}
} else {
printf("Error formating spiffs\n");
}
} else {
printf("Error initialising SPIFFS\n");
}
spiffs_free();
return result;
}

View file

@ -27,6 +27,8 @@ void sdk_os_delay_us(uint16_t us);
void sdk_os_install_putc1(void (*p)(char c));
void sdk_os_putc(char c);
void sdk_gpio_output_set(uint32_t set_mask, uint32_t clear_mask, uint32_t enable_mask, uint32_t disable_mask);
#ifdef __cplusplus
}
#endif

View file

@ -54,8 +54,8 @@ uint32_t sdk_system_get_chip_id(void);
uint32_t sdk_system_rtc_clock_cali_proc(void);
uint32_t sdk_system_get_rtc_time(void);
bool sdk_system_rtc_mem_read(uint8_t src, void *dst, uint16_t n);
bool sdk_system_rtc_mem_write(uint8_t dst, const void *src, uint16_t n);
bool sdk_system_rtc_mem_read(uint32_t src_addr, void *des_addr, uint16_t save_size);
bool sdk_system_rtc_mem_write(uint32_t des_addr, void *src_addr, uint16_t save_size);
void sdk_system_uart_swap(void);
void sdk_system_uart_de_swap(void);

View file

@ -0,0 +1,8 @@
#ifndef _OSAPI_H_
#define _OSAPI_H_
void sdk_os_timer_setfn(ETSTimer *ptimer, ETSTimerFunc *pfunction, void *parg);
void sdk_os_timer_arm(ETSTimer *ptimer, uint32_t milliseconds, bool repeat_flag);
void sdk_os_timer_disarm(ETSTimer *ptimer);
#endif

View file

@ -1,6 +1,61 @@
/*
* Copyright (c) 1991, 1993
* The Regents of the University of California. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 4. Neither the name of the University nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE REGENTS AND CONTRIBUTORS ``AS IS'' AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE REGENTS OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
* SUCH DAMAGE.
*
*/
#ifndef _SYS_QUEUE_H_
#define _SYS_QUEUE_H_
/*
* Note: This header file comes to us from the Espressif
* SDK. Espressif adapted it from BSD's queue.h. The BSD copyright
* notice and the following extract from the explanatory statement
* were re-added by esp-open-rtos.
*
* FreeBSD version of this header:
* https://svnweb.freebsd.org/base/head/sys/sys/queue.h?view=markup
*
* ****
*
* A singly-linked list is headed by a single forward pointer. The elements
* are singly linked for minimum space and pointer manipulation overhead at
* the expense of O(n) removal for arbitrary elements. New elements can be
* added to the list after an existing element or at the head of the list.
* Elements being removed from the head of the list should use the explicit
* macro for this purpose for optimum efficiency. A singly-linked list may
* only be traversed in the forward direction. Singly-linked lists are ideal
* for applications with large datasets and few or no removals or for
* implementing a LIFO queue.
*
* For details on the use of these macros, see the queue(3) manual page.
*
*/
#define QMD_SAVELINK(name, link)
#define TRASHIT(x)

View file

@ -6,6 +6,8 @@
#ifndef __SPI_FLASH_H__
#define __SPI_FLASH_H__
#include "flashchip.h"
#ifdef __cplusplus
extern "C" {
#endif
@ -34,7 +36,7 @@ sdk_SpiFlashOpResult sdk_spi_flash_erase_sector(uint16_t sec);
src is pointer to a buffer to read bytes from. Should be 4-byte aligned.
size is length of buffer in bytes. Should be a multiple of 4.
*/
sdk_SpiFlashOpResult sdk_spi_flash_write(uint32_t des_addr, const void *src, uint32_t size);
sdk_SpiFlashOpResult sdk_spi_flash_write(uint32_t des_addr, uint32_t *src, uint32_t size);
/* Read data from flash.
@ -42,31 +44,14 @@ sdk_SpiFlashOpResult sdk_spi_flash_write(uint32_t des_addr, const void *src, uin
des is pointer to a buffer to read bytes into. Should be 4-byte aligned.
size is number of bytes to read. Should be a multiple of 4.
*/
sdk_SpiFlashOpResult sdk_spi_flash_read(uint32_t src_addr, void *des, uint32_t size);
sdk_SpiFlashOpResult sdk_spi_flash_read(uint32_t src_addr, uint32_t *des, uint32_t size);
/* SDK uses this structure internally to account for flash size.
chip_size field is initialised during startup from the flash size
saved in the image header (on the first 8 bytes of SPI flash).
Other field are initialised to hardcoded values by the SDK.
Based on RE work by @foogod at
http://esp8266-re.foogod.com/wiki/Flashchip_%28IoT_RTOS_SDK_0.9.9%29
See flashchip.h for more info.
*/
typedef struct {
uint32_t device_id;
uint32_t chip_size; /* in bytes */
uint32_t block_size; /* in bytes */
uint32_t sector_size; /* in bytes */
uint32_t page_size; /* in bytes */
uint32_t status_mask;
} sdk_flashchip_t;
extern sdk_flashchip_t sdk_flashchip;
#ifdef __cplusplus
}
#endif

View file

@ -0,0 +1,27 @@
#ifndef __USER_INTERFACE_H__
#define __USER_INTERFACE_H__
#include <stddef.h>
#include <stdint.h>
#include <stdbool.h>
#include "espressif/esp_wifi.h"
enum sdk_dhcp_status {
DHCP_STOPPED,
DHCP_STARTED
};
uint8_t sdk_system_get_boot_version(void);
uint32_t sdk_system_get_userbin_addr(void);
uint8_t sdk_system_get_boot_mode(void);
bool sdk_system_restart_enhance(uint8_t bin_type, uint32_t bin_addr);
bool sdk_system_upgrade_userbin_set(uint8_t userbin);
uint8_t sdk_system_upgrade_userbin_check(void);
bool sdk_system_upgrade_flag_set(uint8_t flag);
uint8_t sdk_system_upgrade_flag_check(void);
bool sdk_system_upgrade_reboot(void);
bool sdk_wifi_station_dhcpc_start(void);
bool sdk_wifi_station_dhcpc_stop(void);
enum sdk_dhcp_status sdk_wifi_station_dhcpc_status(void);
#endif

39
include/etstimer.h Normal file
View file

@ -0,0 +1,39 @@
/* Structures and constants used by some SDK routines
*
* Part of esp-open-rtos
* Copyright (C) 2015 Superhouse Automation Pty Ltd
* BSD Licensed as described in the file LICENSE
*/
/* Note: The following definitions are normally found (in the non-RTOS SDK) in
* the ets_sys.h distributed by Espressif. Unfortunately, they are not found
* anywhere in the RTOS SDK headers, and differ substantially from the non-RTOS
* versions, so the structures defined here had to be obtained by careful
* examination of the code found in the Espressif RTOS SDK.
*/
/* Note also: These cannot be included in esp8266/ets_sys.h, because it is
* included from FreeRTOS.h, creating an (unnecessary) circular dependency.
* They have therefore been put into their own header file instead.
*/
#ifndef _ETSTIMER_H
#define _ETSTIMER_H
#include "FreeRTOS.h"
#include "timers.h"
#include "esp/types.h"
typedef void ETSTimerFunc(void *);
typedef struct ETSTimer_st {
struct ETSTimer_st *timer_next;
xTimerHandle timer_handle;
uint32_t _unknown;
uint32_t timer_ms;
ETSTimerFunc *timer_func;
bool timer_repeat;
void *timer_arg;
} ETSTimer;
#endif /* _ETSTIMER_H */

15
open_esplibs/README.md Normal file
View file

@ -0,0 +1,15 @@
# Open Espressif Libs
These are functional recreations of the MIT licensed binary Espressif SDK libraries found in `lib`. They keep the same functionality as the SDK libraries (possibly with bugfixes or other minor tweaks), but are compiled from source.
Most of the reverse engineering work so far has been by Alex Stewart (@foogod).
See http://esp8266-re.foogod.com/wiki/ for more technical details of SDK library internals.
# Disabling
The open ESP libs are compiled in by default, and they automatically replace any binary SDK symbols (functions, etc.) with the same names.
To compile using the binary SDK libraries only, override the COMPONENTS list in parameters.mk to remove the open_esplibs component, or add -DOPEN_ESPLIBS=0 to CPPFLAGS.
To selectively replace some functionality with binary SDK functionality for debugging, edit the header file open_esplibs/include/open_esplibs.h

15
open_esplibs/component.mk Normal file
View file

@ -0,0 +1,15 @@
# Component makefile for "open Espressif libs"
INC_DIRS += $(open_esplibs_ROOT)include
$(eval $(call component_compile_rules,open_esplibs))
# args for passing into compile rule generation
open_esplibs_libmain_ROOT = $(open_esplibs_libmain_DEFAULT_ROOT)libmain
open_esplibs_libmain_INC_DIR =
open_esplibs_libmain_SRC_DIR = $(open_esplibs_libmain_ROOT)
open_esplibs_libmain_EXTRA_SRC_FILES =
open_esplibs_libmain_CFLAGS = $(CFLAGS)
$(eval $(call component_compile_rules,open_esplibs_libmain))

View file

@ -0,0 +1,31 @@
/* Internal function declarations for Espressif SDK libmain functions.
These are internal-facing declarations, it is not recommended to include these headers in your program.
(look at the headers in include/espressif/ instead and use these whenever possible.)
Copyright (C) 2015 Espressif Systems. Derived from MIT Licensed SDK libraries.
BSD Licensed as described in the file LICENSE.
*/
#include "sdk_internal.h"
#ifndef _ESPLIBS_LIBMAIN_H
#define _ESPLIBS_LIBMAIN_H
#include "sdk_internal.h"
// misc.c
int sdk_os_get_cpu_frequency(void);
/* Don't call this function from user code, it doesn't change the CPU
* speed. Call sdk_system_update_cpu_freq() instead. */
void sdk_os_update_cpu_frequency(int freq);
// user_interface.c
void sdk_system_restart_in_nmi(void);
int sdk_system_get_test_result(void);
void sdk_wifi_param_save_protect(struct sdk_g_ic_saved_st *data);
bool sdk_system_overclock(void);
bool sdk_system_restoreclock(void);
uint32_t sdk_system_relative_time(uint32_t reltime);
#endif /* _ESPLIBS_LIBMAIN_H */

View file

@ -0,0 +1,22 @@
/* Internal function declarations for Espressif SDK libnet80211 functions.
These are internal-facing declarations, it is not recommended to include these headers in your program.
(look at the headers in include/espressif/ instead and use these whenever possible.)
Copyright (C) 2015 Espressif Systems. Derived from MIT Licensed SDK libraries.
BSD Licensed as described in the file LICENSE.
*/
#ifndef _ESPLIBS_LIBNET80211_H
#define _ESPLIBS_LIBNET80211_H
// Defined in wl_cnx.o
extern ETSTimer sdk_sta_con_timer;
// Defined in ieee80211_sta.o: .irom0.text+0xcc4
bool sdk_wifi_station_stop(void);
// Defined in ieee80211_hostap.o: .irom0.text+0x1184
bool sdk_wifi_softap_stop(void);
#endif /* _ESPLIBS_LIBNET80211_H */

View file

@ -0,0 +1,16 @@
/* Internal function declarations for Espressif SDK libphy functions.
These are internal-facing declarations, it is not recommended to include these headers in your program.
(look at the headers in include/espressif/ instead and use these whenever possible.)
Copyright (C) 2015 Espressif Systems. Derived from MIT Licensed SDK libraries.
BSD Licensed as described in the file LICENSE.
*/
#ifndef _ESPLIBS_LIBPHY_H
#define _ESPLIBS_LIBPHY_H
// Defined in phy_chip_v6_ana.o: .irom0.text+0x12d8
uint32_t sdk_test_tout(bool);
#endif /* _ESPLIBS_LIBPHY_H */

View file

@ -0,0 +1,40 @@
/* Internal function declarations for Espressif SDK libpp functions.
These are internal-facing declarations, it is not recommended to include these headers in your program.
(look at the headers in include/espressif/ instead and use these whenever possible.)
Copyright (C) 2015 Espressif Systems. Derived from MIT Licensed SDK libraries.
BSD Licensed as described in the file LICENSE.
*/
#ifndef _ESPLIBS_LIBPP_H
#define _ESPLIBS_LIBPP_H
// Located in wdev.o
extern uint32_t sdk_WdevTimOffSet;
// Defined in pp.o: .irom0.text+0xa08
void sdk_ppRecycleRxPkt(void *);
// Defined in pm.o: .irom0.text+0x74
uint32_t sdk_pm_rtc_clock_cali_proc(void);
// Defined in pm.o: .irom0.text+0xb8
void sdk_pm_set_sleep_time(uint32_t);
// Defined in pm.o: .irom0.text+0x1758
uint8_t sdk_pm_is_waked(void);
// Defined in pm.o: .irom0.text+0x1774
bool sdk_pm_is_open(void);
// Defined in pm.o: .irom0.text+0x19ac
bool sdk_pm_post(int);
// Defined in wdev.o: .irom0.text+0x450
void sdk_wDev_MacTim1SetFunc(void (*func)(void));
// Defined in wdev.o: .text+0x4a8
void sdk_wDev_MacTim1Arm(uint32_t);
#endif /* _ESPLIBS_LIBPP_H */

View file

@ -0,0 +1,39 @@
#ifndef _OPEN_ESPLIBS_H
#define _OPEN_ESPLIBS_H
// This header includes conditional defines to control which bits of the
// Open-Source libraries get built when building esp-open-rtos. This can be
// useful for quickly troubleshooting whether a bug is due to the
// reimplementation of Espressif libraries, or something else.
#ifndef OPEN_ESPLIBS
#define OPEN_ESPLIBS 1
#endif
#ifndef OPEN_LIBMAIN
#define OPEN_LIBMAIN (OPEN_ESPLIBS)
#endif
#ifndef OPEN_LIBMAIN_MISC
#define OPEN_LIBMAIN_MISC (OPEN_LIBMAIN)
#endif
#ifndef OPEN_LIBMAIN_OS_CPU_A
#define OPEN_LIBMAIN_OS_CPU_A (OPEN_LIBMAIN)
#endif
#ifndef OPEN_LIBMAIN_SPI_FLASH
#define OPEN_LIBMAIN_SPI_FLASH (OPEN_LIBMAIN)
#endif
#ifndef OPEN_LIBMAIN_TIMERS
#define OPEN_LIBMAIN_TIMERS (OPEN_LIBMAIN)
#endif
#ifndef OPEN_LIBMAIN_UART
#define OPEN_LIBMAIN_UART (OPEN_LIBMAIN)
#endif
#ifndef OPEN_LIBMAIN_XTENSA_CONTEXT
#define OPEN_LIBMAIN_XTENSA_CONTEXT (OPEN_LIBMAIN)
#endif
#ifndef OPEN_LIBMAIN_USER_INTERFACE
#define OPEN_LIBMAIN_USER_INTERFACE (OPEN_LIBMAIN)
#endif
#endif /* _OPEN_ESPLIBS_H */

View file

@ -0,0 +1,70 @@
/* Recreated Espressif libmain misc.o contents.
Copyright (C) 2015 Espressif Systems. Derived from MIT Licensed SDK libraries.
BSD Licensed as described in the file LICENSE
*/
#include "open_esplibs.h"
#if OPEN_LIBMAIN_MISC
// The contents of this file are only built if OPEN_LIBMAIN_MISC is set to true
#include "espressif/esp_misc.h"
#include "esp/gpio_regs.h"
#include "esp/rtc_regs.h"
#include "sdk_internal.h"
#include "xtensa/hal.h"
static int cpu_freq = 80;
void (*sdk__putc1)(char);
int IRAM sdk_os_get_cpu_frequency(void) {
return cpu_freq;
}
void sdk_os_update_cpu_frequency(int freq) {
cpu_freq = freq;
}
void sdk_ets_update_cpu_frequency(int freq) __attribute__ (( alias ("sdk_os_update_cpu_frequency") ));
void sdk_os_delay_us(uint16_t us) {
uint32_t start_ccount = xthal_get_ccount();
uint32_t delay_ccount = cpu_freq * us;
while (xthal_get_ccount() - start_ccount < delay_ccount) {}
}
void sdk_ets_delay_us(uint16_t us) __attribute__ (( alias ("sdk_os_delay_us") ));
void sdk_os_install_putc1(void (*p)(char)) {
sdk__putc1 = p;
}
void sdk_os_putc(char c) {
sdk__putc1(c);
}
void sdk_gpio_output_set(uint32_t set_mask, uint32_t clear_mask, uint32_t enable_mask, uint32_t disable_mask) {
GPIO.OUT_SET = set_mask;
GPIO.OUT_CLEAR = clear_mask;
GPIO.ENABLE_OUT_SET = enable_mask;
GPIO.ENABLE_OUT_CLEAR = disable_mask;
}
uint8_t sdk_rtc_get_reset_reason(void) {
uint8_t reason;
reason = FIELD2VAL(RTC_RESET_REASON1_CODE, RTC.RESET_REASON1);
if (reason == 5) {
if (FIELD2VAL(RTC_RESET_REASON2_CODE, RTC.RESET_REASON2) == 1) {
reason = 6;
} else {
if (FIELD2VAL(RTC_RESET_REASON2_CODE, RTC.RESET_REASON2) != 8) {
reason = 0;
}
}
}
RTC.RESET_REASON0 &= ~RTC_RESET_REASON0_BIT21;
return reason;
}
#endif /* OPEN_LIBMAIN_MISC */

View file

@ -0,0 +1,132 @@
/* Recreated Espressif libmain os_cpu_o contents.
Copyright (C) 2015 Espressif Systems. Derived from MIT Licensed SDK libraries.
BSD Licensed as described in the file LICENSE
*/
#include "open_esplibs.h"
#if OPEN_LIBMAIN_OS_CPU_A
// The contents of this file are only built if OPEN_LIBMAIN_OS_CPU_A is set to true
#include "esp/types.h"
#include "FreeRTOS.h"
#include "task.h"
#include "xtensa_ops.h"
#include "common_macros.h"
#include "esplibs/libmain.h"
// xPortSysTickHandle is defined in FreeRTOS/Source/portable/esp8266/port.c but
// does not exist in any header files.
void xPortSysTickHandle(void);
/* The following "functions" manipulate the stack at a low level and thus cannot be coded directly in C */
void IRAM vPortYield(void) {
asm(" wsr a0, excsave1 \n\
addi sp, sp, -80 \n\
s32i a0, sp, 4 \n\
addi a0, sp, 80 \n\
s32i a0, sp, 16 \n\
rsr a0, ps \n\
s32i a0, sp, 8 \n\
rsr a0, excsave1 \n\
s32i a0, sp, 12 \n\
movi a0, _xt_user_exit \n\
s32i a0, sp, 0 \n\
call0 sdk__xt_int_enter \n\
call0 vPortEnterCritical \n\
call0 vTaskSwitchContext \n\
call0 vPortExitCritical \n\
call0 sdk__xt_int_exit \n\
");
}
void IRAM sdk__xt_int_enter(void) {
asm(" s32i a12, sp, 60 \n\
s32i a13, sp, 64 \n\
mov a12, a0 \n\
call0 sdk__xt_context_save \n\
movi a0, pxCurrentTCB \n\
l32i a0, a0, 0 \n\
s32i sp, a0, 0 \n\
mov a0, a12 \n\
");
}
void IRAM sdk__xt_int_exit(void) {
asm(" s32i a14, sp, 68 \n\
s32i a15, sp, 72 \n\
movi sp, pxCurrentTCB \n\
l32i sp, sp, 0 \n\
l32i sp, sp, 0 \n\
movi a14, pxCurrentTCB \n\
l32i a14, a14, 0 \n\
addi a15, sp, 80 \n\
s32i a15, a14, 0 \n\
call0 sdk__xt_context_restore \n\
l32i a14, sp, 68 \n\
l32i a15, sp, 72 \n\
l32i a0, sp, 0 \n\
");
}
void IRAM sdk__xt_timer_int(void) {
uint32_t trigger_ccount;
uint32_t current_ccount;
uint32_t ccount_interval = portTICK_RATE_MS * sdk_os_get_cpu_frequency() * 1000;
do {
RSR(trigger_ccount, ccompare0);
WSR(trigger_ccount + ccount_interval, ccompare0);
ESYNC();
xPortSysTickHandle();
ESYNC();
RSR(current_ccount, ccount);
} while (current_ccount - trigger_ccount > ccount_interval);
}
void IRAM sdk__xt_timer_int1(void) {
vTaskSwitchContext();
}
#define INTENABLE_CCOMPARE BIT(6)
void IRAM sdk__xt_tick_timer_init(void) {
uint32_t ints_enabled;
uint32_t current_ccount;
uint32_t ccount_interval = portTICK_RATE_MS * sdk_os_get_cpu_frequency() * 1000;
RSR(current_ccount, ccount);
WSR(current_ccount + ccount_interval, ccompare0);
ints_enabled = 0;
XSR(ints_enabled, intenable);
WSR(ints_enabled | INTENABLE_CCOMPARE, intenable);
}
void IRAM sdk__xt_isr_unmask(uint32_t mask) {
uint32_t ints_enabled;
ints_enabled = 0;
XSR(ints_enabled, intenable);
WSR(ints_enabled | mask, intenable);
}
void IRAM sdk__xt_isr_mask(uint32_t mask) {
uint32_t ints_enabled;
ints_enabled = 0;
XSR(ints_enabled, intenable);
WSR(ints_enabled & mask, intenable);
}
uint32_t IRAM sdk__xt_read_ints(void) {
uint32_t ints_enabled;
RSR(ints_enabled, intenable);
return ints_enabled;
}
void IRAM sdk__xt_clear_ints(uint32_t mask) {
WSR(mask, intclear);
}
#endif /* OPEN_LIBMAIN_OS_CPU_A */

View file

@ -0,0 +1,193 @@
/* Recreated Espressif libmain os_cpu_o contents.
Copyright (C) 2015 Espressif Systems. Derived from MIT Licensed SDK libraries.
BSD Licensed as described in the file LICENSE
*/
#include "open_esplibs.h"
#if OPEN_LIBMAIN_SPI_FLASH
// The contents of this file are only built if OPEN_LIBMAIN_SPI_FLASH is set to true
#include "FreeRTOS.h"
#include "common_macros.h"
#include "esp/spi_regs.h"
#include "esp/rom.h"
#include "sdk_internal.h"
#include "espressif/spi_flash.h"
sdk_flashchip_t sdk_flashchip = {
0x001640ef, // device_id
4 * 1024 * 1024, // chip_size
65536, // block_size
4096, // sector_size
256, // page_size
0x0000ffff, // status_mask
};
// NOTE: This routine appears to be completely unused in the SDK
int IRAM sdk_SPIReadModeCnfig(uint32_t mode) {
uint32_t ctrl_bits;
SPI(0).CTRL0 &= ~(SPI_CTRL0_FASTRD_MODE | SPI_CTRL0_DOUT_MODE | SPI_CTRL0_QOUT_MODE | SPI_CTRL0_DIO_MODE | SPI_CTRL0_QIO_MODE);
if (mode == 0) {
ctrl_bits = SPI_CTRL0_FASTRD_MODE | SPI_CTRL0_QIO_MODE;
} else if (mode == 1) {
ctrl_bits = SPI_CTRL0_FASTRD_MODE | SPI_CTRL0_QOUT_MODE;
} else if (mode == 2) {
ctrl_bits = SPI_CTRL0_FASTRD_MODE | SPI_CTRL0_DIO_MODE;
} else if (mode == 3) {
ctrl_bits = SPI_CTRL0_FASTRD_MODE | SPI_CTRL0_DOUT_MODE;
} else if (mode == 4) {
ctrl_bits = SPI_CTRL0_FASTRD_MODE;
} else {
ctrl_bits = 0;
}
if (mode == 0 || mode == 1) {
Enable_QMode(&sdk_flashchip);
} else {
Disable_QMode(&sdk_flashchip);
}
SPI(0).CTRL0 |= ctrl_bits;
return 0;
}
sdk_SpiFlashOpResult IRAM sdk_SPIWrite(uint32_t des_addr, uint32_t *src_addr, uint32_t size) {
uint32_t first_page_portion;
uint32_t pos;
uint32_t full_pages;
uint32_t bytes_remaining;
if (des_addr + size <= sdk_flashchip.chip_size) {
first_page_portion = sdk_flashchip.page_size - (des_addr % sdk_flashchip.page_size);
if (size < first_page_portion) {
if (SPI_page_program(&sdk_flashchip, des_addr, src_addr, size)) {
return SPI_FLASH_RESULT_ERR;
} else {
return SPI_FLASH_RESULT_OK;
}
}
} else {
return SPI_FLASH_RESULT_ERR;
}
if (SPI_page_program(&sdk_flashchip, des_addr, src_addr, first_page_portion)) {
return SPI_FLASH_RESULT_ERR;
}
pos = first_page_portion;
bytes_remaining = size - first_page_portion;
full_pages = bytes_remaining / sdk_flashchip.page_size;
if (full_pages) {
for (int i = 0; i != full_pages; i++) {
if (SPI_page_program(&sdk_flashchip, des_addr + pos, src_addr + (pos / 4), sdk_flashchip.page_size)) {
return SPI_FLASH_RESULT_ERR;
}
pos += sdk_flashchip.page_size;
}
bytes_remaining = size - pos;
}
if (SPI_page_program(&sdk_flashchip, des_addr + pos, src_addr + (pos / 4), bytes_remaining)) {
return SPI_FLASH_RESULT_ERR;
}
return SPI_FLASH_RESULT_OK;
}
sdk_SpiFlashOpResult IRAM sdk_SPIRead(uint32_t src_addr, uint32_t *des_addr, uint32_t size) {
if (SPI_read_data(&sdk_flashchip, src_addr, des_addr, size)) {
return SPI_FLASH_RESULT_ERR;
} else {
return SPI_FLASH_RESULT_OK;
}
}
sdk_SpiFlashOpResult IRAM sdk_SPIEraseSector(uint16_t sec) {
if (sec >= sdk_flashchip.chip_size / sdk_flashchip.sector_size) {
return SPI_FLASH_RESULT_ERR;
}
if (SPI_write_enable(&sdk_flashchip)) {
return SPI_FLASH_RESULT_ERR;
}
if (SPI_sector_erase(&sdk_flashchip, sdk_flashchip.sector_size * sec)) {
return SPI_FLASH_RESULT_ERR;
}
return SPI_FLASH_RESULT_OK;
}
uint32_t IRAM sdk_spi_flash_get_id(void) {
uint32_t result;
portENTER_CRITICAL();
Cache_Read_Disable();
Wait_SPI_Idle(&sdk_flashchip);
SPI(0).W[0] = 0;
SPI(0).CMD = SPI_CMD_READ_ID;
while (SPI(0).CMD != 0) {}
result = SPI(0).W[0] & 0x00ffffff;
Cache_Read_Enable(0, 0, 1);
portEXIT_CRITICAL();
return result;
}
sdk_SpiFlashOpResult IRAM sdk_spi_flash_read_status(uint32_t *status) {
sdk_SpiFlashOpResult result;
portENTER_CRITICAL();
Cache_Read_Disable();
result = SPI_read_status(&sdk_flashchip, status);
Cache_Read_Enable(0, 0, 1);
portEXIT_CRITICAL();
return result;
}
sdk_SpiFlashOpResult IRAM sdk_spi_flash_write_status(uint32_t status) {
sdk_SpiFlashOpResult result;
portENTER_CRITICAL();
Cache_Read_Disable();
result = SPI_write_status(&sdk_flashchip, status);
Cache_Read_Enable(0, 0, 1);
portEXIT_CRITICAL();
return result;
}
sdk_SpiFlashOpResult IRAM sdk_spi_flash_erase_sector(uint16_t sec) {
sdk_SpiFlashOpResult result;
portENTER_CRITICAL();
Cache_Read_Disable();
result = sdk_SPIEraseSector(sec);
Cache_Read_Enable(0, 0, 1);
portEXIT_CRITICAL();
return result;
}
sdk_SpiFlashOpResult IRAM sdk_spi_flash_write(uint32_t des_addr, uint32_t *src_addr, uint32_t size) {
sdk_SpiFlashOpResult result;
if (!src_addr) {
return SPI_FLASH_RESULT_ERR;
}
if (size & 3) {
size = (size & ~3) + 4;
}
portENTER_CRITICAL();
Cache_Read_Disable();
result = sdk_SPIWrite(des_addr, src_addr, size);
Cache_Read_Enable(0, 0, 1);
portEXIT_CRITICAL();
return result;
}
sdk_SpiFlashOpResult IRAM sdk_spi_flash_read(uint32_t src_addr, uint32_t *des_addr, uint32_t size) {
sdk_SpiFlashOpResult result;
if (!des_addr) {
return SPI_FLASH_RESULT_ERR;
}
portENTER_CRITICAL();
Cache_Read_Disable();
result = sdk_SPIRead(src_addr, des_addr, size);
Cache_Read_Enable(0, 0, 1);
portEXIT_CRITICAL();
return result;
}
#endif /* OPEN_LIBMAIN_SPI_FLASH */

View file

@ -0,0 +1,100 @@
/* Recreated Espressif libmain timers.o contents.
Copyright (C) 2015 Espressif Systems. Derived from MIT Licensed SDK libraries.
BSD Licensed as described in the file LICENSE
*/
#include "open_esplibs.h"
#if OPEN_LIBMAIN_TIMERS
// The contents of this file are only built if OPEN_LIBMAIN_TIMERS is set to true
#include "etstimer.h"
#include "stdio.h"
struct timer_list_st {
struct timer_list_st *next;
ETSTimer *timer;
};
static struct timer_list_st *timer_list;
static uint8_t armed_timer_count;
void sdk_os_timer_setfn(ETSTimer *ptimer, ETSTimerFunc *pfunction, void *parg) {
struct timer_list_st *entry = 0;
struct timer_list_st *new_entry;
struct timer_list_st **tailptr;
if (timer_list) {
for (entry = timer_list; ; entry = entry->next) {
if (entry->timer == ptimer) {
if (ptimer->timer_arg == parg && ptimer->timer_func == pfunction) {
return;
}
if (ptimer->timer_handle) {
if (!xTimerDelete(ptimer->timer_handle, 50)) {
printf("Timer Delete Failed\n");
}
armed_timer_count--;
}
ptimer->timer_func = pfunction;
ptimer->timer_arg = parg;
ptimer->timer_handle = 0;
ptimer->timer_ms = 0;
return;
}
if (!entry->next) {
break;
}
}
}
ptimer->timer_func = pfunction;
ptimer->timer_arg = parg;
ptimer->timer_handle = 0;
ptimer->timer_ms = 0;
new_entry = (struct timer_list_st *)pvPortMalloc(8);
new_entry->timer = ptimer;
new_entry->next = 0;
tailptr = &entry->next;
if (!timer_list) {
tailptr = &timer_list;
}
*tailptr = new_entry;
}
void sdk_os_timer_arm(ETSTimer *ptimer, uint32_t milliseconds, bool repeat_flag) {
if (!ptimer->timer_handle) {
ptimer->timer_repeat = repeat_flag;
ptimer->timer_ms = milliseconds;
ptimer->timer_handle = xTimerCreate(0, milliseconds/10, repeat_flag, ptimer->timer_arg, ptimer->timer_func);
armed_timer_count++;
if (!ptimer->timer_handle) {
//FIXME: should print an error? (original code doesn't)
return;
}
}
if (ptimer->timer_repeat != repeat_flag) {
ptimer->timer_repeat = repeat_flag;
// FIXME: This is wrong. The original code is directly modifying
// internal FreeRTOS structures to try to change the uxAutoReload of an
// existing timer. The correct way to do this is probably to use
// xTimerDelete and then xTimerCreate to recreate the timer with a
// different uxAutoReload setting.
((uint32_t *)ptimer->timer_handle)[7] = repeat_flag;
}
if (ptimer->timer_ms != milliseconds) {
ptimer->timer_ms = milliseconds;
xTimerChangePeriod(ptimer->timer_handle, milliseconds/10, 10);
}
if (!xTimerStart(ptimer->timer_handle, 50)) {
printf("Timer Start Failed\n");
}
}
void sdk_os_timer_disarm(ETSTimer *ptimer) {
if (ptimer->timer_handle) {
if (!xTimerStop(ptimer->timer_handle, 50)) {
printf("Timer Stop Failed\n");
}
}
}
#endif /* OPEN_LIBMAIN_TIMERS */

View file

@ -0,0 +1,27 @@
/* Recreated Espressif libmain uart.o contents.
Copyright (C) 2015 Espressif Systems. Derived from MIT Licensed SDK libraries.
BSD Licensed as described in the file LICENSE
*/
#include "open_esplibs.h"
#if OPEN_LIBMAIN_UART
// The contents of this file are only built if OPEN_LIBMAIN_UART is set to true
#include "espressif/sdk_private.h"
#include "esp/uart_regs.h"
void sdk_uart_buff_switch(void) {
/* No-Op */
}
void sdk_uart_div_modify(uint32_t uart_no, uint32_t new_divisor) {
UART(uart_no).CLOCK_DIVIDER = new_divisor;
UART(uart_no).CONF0 |= (UART_CONF0_TXFIFO_RESET | UART_CONF0_RXFIFO_RESET);
UART(uart_no).CONF0 &= ~(UART_CONF0_TXFIFO_RESET | UART_CONF0_RXFIFO_RESET);
}
void sdk_Uart_Init(void) {
/* No-Op */
}
#endif /* OPEN_LIBMAIN_UART */

View file

@ -0,0 +1,553 @@
/* Recreated Espressif libmain user_interface.o contents.
Copyright (C) 2015 Espressif Systems. Derived from MIT Licensed SDK libraries.
BSD Licensed as described in the file LICENSE
*/
#include "open_esplibs.h"
#if OPEN_LIBMAIN_USER_INTERFACE
// The contents of this file are only built if OPEN_LIBMAIN_USER_INTERFACE is set to true
#include "FreeRTOS.h"
#include "task.h"
#include "string.h"
#include "lwip/dhcp.h"
#include "esp/types.h"
#include "esp/rom.h"
#include "esp/dport_regs.h"
#include "esp/rtcmem_regs.h"
#include "esp/iomux_regs.h"
#include "esp/sar_regs.h"
#include "esp/wdev_regs.h"
#include "etstimer.h"
#include "espressif/sdk_private.h"
#include "espressif/esp_system.h"
#include "espressif/esp_wifi.h"
#include "espressif/esp_sta.h"
#include "espressif/esp_softap.h"
#include "espressif/esp_misc.h"
#include "espressif/osapi.h"
#include "espressif/user_interface.h"
#include "sdk_internal.h"
#include "esplibs/libmain.h"
#include "esplibs/libpp.h"
#include "esplibs/libphy.h"
#include "esplibs/libnet80211.h"
// Structure for the data contained in the last sector of Flash which contains
// meta-info about the saved wifi param sectors.
struct param_dir_st {
uint8_t current_sector; // 0x00
uint32_t cksum_magic; // 0x04
uint32_t save_count; // 0x08
uint32_t cksum_len[2]; // 0x0c
uint32_t cksum_value[2]; // 0x14
};
_Static_assert(sizeof(struct param_dir_st) == 28, "param_dir_st is the wrong size");
enum sdk_dhcp_status sdk_dhcpc_flag = DHCP_STARTED;
bool sdk_cpu_overclock;
struct sdk_rst_info sdk_rst_if;
sdk_wifi_promiscuous_cb_t sdk_promiscuous_cb;
static uint8_t _system_upgrade_flag; // Ldata009
// Prototypes for static functions
static bool _check_boot_version(void);
static void _deep_sleep_phase2(void *timer_arg);
static struct netif *_get_netif(uint32_t mode);
// Linker-created values used by sdk_system_print_meminfo
extern uint32_t _data_start, _data_end;
extern uint32_t _rodata_start, _rodata_end;
extern uint32_t _bss_start, _bss_end;
extern uint32_t _heap_start;
#define _rom_reset_vector ((void (*)(void))0x40000080)
void IRAM sdk_system_restart_in_nmi(void) {
uint32_t buf[8];
sdk_system_rtc_mem_read(0, buf, 32);
if (buf[0] != 2) {
memset(buf, 0, 32);
buf[0] = 3;
sdk_system_rtc_mem_write(0, buf, 32);
}
if (!sdk_NMIIrqIsOn) {
portENTER_CRITICAL();
do {
DPORT.DPORT0 = SET_FIELD(DPORT.DPORT0, DPORT_DPORT0_FIELD0, 0);
} while (DPORT.DPORT0 & 1);
}
ESPSAR.UNKNOWN_48 |= 3;
DPORT.CLOCKGATE_WATCHDOG |= DPORT_CLOCKGATE_WATCHDOG_UNKNOWN_8;
ESPSAR.UNKNOWN_48 &= ~3;
DPORT.CLOCKGATE_WATCHDOG &= ~DPORT_CLOCKGATE_WATCHDOG_UNKNOWN_8;
Cache_Read_Disable();
DPORT.SPI_CACHE_RAM &= ~(DPORT_SPI_CACHE_RAM_BANK0 | DPORT_SPI_CACHE_RAM_BANK1);
// This calls directly to 0x40000080, the "reset" exception vector address.
_rom_reset_vector();
}
bool IRAM sdk_system_rtc_mem_write(uint32_t des_addr, void *src_addr, uint16_t save_size) {
uint32_t volatile *src_buf = (uint32_t *)src_addr;
if (des_addr > 191) {
return false;
}
if ((intptr_t)src_addr & 3) {
return false;
}
if ((768 - (des_addr * 4)) < save_size) {
return false;
}
if ((save_size & 3) != 0) {
save_size = (save_size & ~3) + 4;
}
for (uint8_t i = 0; i < (save_size >> 2); i++) {
RTCMEM_SYSTEM[i] = src_buf[i];
}
return true;
}
bool IRAM sdk_system_rtc_mem_read(uint32_t src_addr, void *des_addr, uint16_t save_size) {
uint32_t *dest_buf = (uint32_t *)des_addr;
if (src_addr > 191) {
return false;
}
if ((intptr_t)des_addr & 3) {
return false;
}
if ((768 - (src_addr * 4)) < save_size) {
return false;
}
if ((save_size & 3) != 0) {
save_size = (save_size & ~3) + 4;
}
for (uint8_t i = 0; i < (save_size >> 2); i++) {
dest_buf[i] = RTCMEM_SYSTEM[i];
}
return true;
}
void sdk_system_pp_recycle_rx_pkt(void *eb) {
sdk_ppRecycleRxPkt(eb);
}
uint16_t sdk_system_adc_read(void) {
return sdk_test_tout(false);
}
void sdk_system_restart(void) {
if (sdk_wifi_get_opmode() != 2) {
sdk_wifi_station_stop();
}
if (sdk_wifi_get_opmode() != 1) {
sdk_wifi_softap_stop();
}
vTaskDelay(6);
IOMUX_GPIO12 |= IOMUX_PIN_PULLUP;
sdk_wDev_MacTim1SetFunc(sdk_system_restart_in_nmi);
sdk_wDev_MacTim1Arm(3);
}
void sdk_system_restore(void) {
struct sdk_g_ic_saved_st *buf;
buf = malloc(sizeof(struct sdk_g_ic_saved_st));
memset(buf, 0xff, sizeof(struct sdk_g_ic_saved_st));
memcpy(buf, &sdk_g_ic.s, 8);
sdk_wifi_param_save_protect(buf);
free(buf);
}
uint8_t sdk_system_get_boot_version(void) {
return sdk_g_ic.s.boot_info & 0x1f;
}
static bool _check_boot_version(void) {
uint8_t ver = sdk_system_get_boot_version();
if (ver < 3 || ver == 31) {
printf("failed: need boot >= 1.3\n");
return false;
}
return true;
}
int sdk_system_get_test_result(void) {
if (_check_boot_version()) {
return (sdk_g_ic.s.boot_info >> 5) & 1;
} else {
return -1;
}
}
uint32_t sdk_system_get_userbin_addr(void) {
uint8_t buf[8];
uint16_t unknown_var = 0; //FIXME: read but never written?
uint32_t addr;
uint32_t flash_size_code;
if (!(sdk_g_ic.s.boot_info >> 7)) {
if (sdk_g_ic.s._unknown1d8 & 0x4) {
addr = sdk_g_ic.s.user1_addr[0] | (sdk_g_ic.s.user1_addr[1] << 8) |
(sdk_g_ic.s.user1_addr[2] << 16);
} else {
addr = sdk_g_ic.s.user0_addr[0] | (sdk_g_ic.s.user0_addr[1] << 8) | (sdk_g_ic.s.user0_addr[2] << 16);
}
} else {
if (!sdk_system_upgrade_userbin_check()) {
addr = 0x00001000;
} else {
sdk_spi_flash_read(0, (uint32_t *)buf, 8);
flash_size_code = buf[3] >> 4;
if (flash_size_code >= 2 && flash_size_code < 5) {
flash_size_code = 0x81;
} else if (flash_size_code == 1) {
flash_size_code = 0x41;
} else {
// FIXME: In the original code, this loads from a local stack
// variable, which is never actually assigned to anywhere.
// It's unclear what this value is actually supposed to be.
flash_size_code = unknown_var;
}
addr = flash_size_code << 12;
}
}
return addr;
}
uint8_t sdk_system_get_boot_mode(void) {
int boot_version = sdk_g_ic.s.boot_info & 0x1f;
if (boot_version < 3 || boot_version == 0x1f) {
return 1;
}
return sdk_g_ic.s.boot_info >> 7;
}
bool sdk_system_restart_enhance(uint8_t bin_type, uint32_t bin_addr) {
uint32_t current_addr;
if (!_check_boot_version()) {
return false;
}
if (bin_type == 0) {
current_addr = sdk_system_get_userbin_addr();
printf("restart to use user bin @ %x\n", bin_addr);
sdk_g_ic.s.user1_addr[0] = bin_addr;
sdk_g_ic.s.user1_addr[1] = bin_addr >> 8;
sdk_g_ic.s.user1_addr[2] = bin_addr >> 16;
sdk_g_ic.s.user0_addr[0] = current_addr;
sdk_g_ic.s.user0_addr[1] = current_addr >> 8;
sdk_g_ic.s.user0_addr[2] = current_addr >> 16;
sdk_g_ic.s._unknown1d8 = (sdk_g_ic.s._unknown1d8 & 0xfb) | 0x04;
sdk_g_ic.s.boot_info &= 0x7f;
sdk_wifi_param_save_protect(&sdk_g_ic.s);
sdk_system_restart();
return true;
} else {
if (bin_type != 1) {
printf("don't supported type.\n");
return false;
}
if (!sdk_system_get_test_result()) {
printf("test already passed.\n");
return false;
}
printf("reboot to use test bin @ %x\n", bin_addr);
sdk_g_ic.s.user0_addr[0] = bin_addr;
sdk_g_ic.s.user0_addr[1] = bin_addr >> 8;
sdk_g_ic.s.user0_addr[2] = bin_addr >> 16;
sdk_g_ic.s.boot_info &= 0xbf;
sdk_wifi_param_save_protect(&sdk_g_ic.s);
sdk_system_restart();
return true;
}
}
bool sdk_system_upgrade_userbin_set(uint8_t userbin) {
uint8_t userbin_val, userbin_mask;
uint8_t boot_ver = sdk_system_get_boot_version();
if (userbin >= 2) {
return false;
} else {
if (boot_ver == 2 || boot_ver == 0x1f) {
userbin_val = userbin & 0x0f;
userbin_mask = 0xf0;
} else {
userbin_val = userbin & 0x03;
userbin_mask = 0xfc;
}
sdk_g_ic.s._unknown1d8 = (sdk_g_ic.s._unknown1d8 & userbin_mask) | userbin_val;
return true;
}
}
uint8_t sdk_system_upgrade_userbin_check(void) {
uint8_t boot_ver = sdk_system_get_boot_version();
if (boot_ver != 0x1f && boot_ver != 2) {
if ((sdk_g_ic.s._unknown1d8 & 0x03) == 1) {
if (sdk_g_ic.s._unknown1d8 & 0x4) {
return 1;
} else {
return 0;
}
} else {
if (sdk_g_ic.s._unknown1d8 & 0x4) {
return 0;
} else {
return 1;
}
}
} else {
if ((sdk_g_ic.s._unknown1d8 & 0x0f) == 1) {
return 1;
} else {
return 0;
}
}
}
bool sdk_system_upgrade_flag_set(uint8_t flag) {
if (flag < 3) {
_system_upgrade_flag = flag;
return true;
}
return false;
}
uint8_t sdk_system_upgrade_flag_check(void) {
return _system_upgrade_flag;
}
bool sdk_system_upgrade_reboot(void) {
uint8_t boot_ver = sdk_system_get_boot_version();
uint8_t new__unknown1d8;
if (_system_upgrade_flag != 2) {
return false;
}
printf("reboot to use");
if (boot_ver != 2 && boot_ver != 0x1f) {
sdk_g_ic.s.boot_info = (sdk_g_ic.s.boot_info & 0x7f) | 0x80;
sdk_g_ic.s._unknown1d8 = (sdk_g_ic.s._unknown1d8 & 0xfb) | 0x04;
if ((sdk_g_ic.s._unknown1d8 & 0x03) == 1) {
printf("1\n");
new__unknown1d8 = sdk_g_ic.s._unknown1d8 & 0xfc;
} else {
printf("2\n");
new__unknown1d8 = (sdk_g_ic.s._unknown1d8 & 0xfc) | 0x01;
}
} else {
if ((sdk_g_ic.s._unknown1d8 & 0x0f) == 1) {
printf("1\n");
new__unknown1d8 = sdk_g_ic.s._unknown1d8 & 0xf0;
} else {
printf("2\n");
new__unknown1d8 = (sdk_g_ic.s._unknown1d8 & 0xf0) | 0x01;
}
}
sdk_g_ic.s._unknown1d8 = new__unknown1d8;
sdk_wifi_param_save_protect(&sdk_g_ic.s);
sdk_system_restart();
return true;
}
static void _deep_sleep_phase2(void *timer_arg) {
uint32_t time_in_us = (uint32_t)timer_arg;
printf("deep sleep %ds\n\n", time_in_us / 1000000);
while (FIELD2VAL(UART_STATUS_TXFIFO_COUNT, UART(0).STATUS)) {}
while (FIELD2VAL(UART_STATUS_TXFIFO_COUNT, UART(1).STATUS)) {}
RTC.CTRL0 = 0;
RTC.CTRL0 &= 0xffffbfff;
RTC.CTRL0 |= 0x00000030;
RTC._unknown44 = 0x00000004;
RTC._unknownc = 0x00010010;
RTC._unknown48 = (RTC._unknown48 & 0xffff01ff) | 0x0000fc00;
RTC._unknown48 = (RTC._unknown48 & 0xfffffe00) | 0x00000080;
RTC.COUNTER_ALARM = RTC.COUNTER + 136;
RTC.RESET_REASON2 = 0x00000008;
RTC.RESET_REASON0 = 0x00100000;
sdk_os_delay_us(200);
RTC.GPIO_CFG[2] = 0x00000011;
RTC.GPIO_CFG[3] = 0x00000003;
RTC._unknownc = 0x000640c8;
RTC.CTRL0 &= 0xffffffcf;
sdk_pm_rtc_clock_cali_proc();
sdk_pm_set_sleep_time(time_in_us);
RTC.GPIO_CFG[2] = 0x00000011;
RTC.GPIO_CFG[3] = 0x00000003;
DPORT.INT_ENABLE &= ~(DPORT_INT_ENABLE_WDT);
_xt_isr_mask(1 << ETS_WDT_INUM);
RTC._unknown40 = 0xffffffff;
RTC._unknown44 = 0x00000020;
RTC._unknown10 = 0x00000000;
if (time_in_us == 0) {
RTC.RESET_REASON2 = 0x00000000;
} else {
RTC.RESET_REASON2 = 0x00000008;
}
RTC.RESET_REASON0 = 0x00100000;
}
void sdk_system_deep_sleep(uint32_t time_in_us) {
if (sdk_wifi_get_opmode() != 2) {
sdk_wifi_station_stop();
}
if (sdk_wifi_get_opmode() != 1) {
sdk_wifi_softap_stop();
}
sdk_os_timer_disarm(&sdk_sta_con_timer);
sdk_os_timer_setfn(&sdk_sta_con_timer, _deep_sleep_phase2, (void *)time_in_us);
sdk_os_timer_arm(&sdk_sta_con_timer, 100, 0);
}
bool sdk_system_update_cpu_freq(uint8_t freq) {
if (freq == 80) {
DPORT.CPU_CLOCK &= ~(DPORT_CPU_CLOCK_X2);
sdk_os_update_cpu_frequency(80);
} else if (freq == 160) {
DPORT.CPU_CLOCK |= DPORT_CPU_CLOCK_X2;
sdk_os_update_cpu_frequency(160);
} else {
return false;
}
return true;
}
uint8_t sdk_system_get_cpu_freq(void) {
return sdk_os_get_cpu_frequency();
}
bool sdk_system_overclock(void) {
if (sdk_system_get_cpu_freq() == 80) {
sdk_cpu_overclock = true;
sdk_system_update_cpu_freq(160);
return true;
}
return false;
}
bool sdk_system_restoreclock(void) {
if (sdk_system_get_cpu_freq() == 160 && sdk_cpu_overclock) {
sdk_cpu_overclock = false;
sdk_system_update_cpu_freq(80);
return true;
}
return false;
}
uint32_t sdk_system_get_time(void) {
return WDEV.SYS_TIME + sdk_WdevTimOffSet;
}
uint32_t sdk_system_relative_time(uint32_t reltime) {
return WDEV.SYS_TIME - reltime;
}
void sdk_system_station_got_ip_set(struct ip_addr *ip, struct ip_addr *mask, struct ip_addr *gw) {
uint8_t *ip_bytes = (uint8_t *)&ip->addr;
uint8_t *mask_bytes = (uint8_t *)&mask->addr;
uint8_t *gw_bytes = (uint8_t *)&gw->addr;
uint32_t gpio_mask;
sdk_g_ic.v.station_netif_info->connect_status = STATION_GOT_IP;
printf("ip:%d.%d.%d.%d,mask:%d.%d.%d.%d,gw:%d.%d.%d.%d", ip_bytes[0], ip_bytes[1], ip_bytes[2], ip_bytes[3], mask_bytes[0], mask_bytes[1], mask_bytes[2], mask_bytes[3], gw_bytes[0], gw_bytes[1], gw_bytes[2], gw_bytes[3]);
printf("\n");
if ((sdk_g_ic.s.wifi_led_enable == 1) && (sdk_g_ic.s.wifi_mode == 1)) {
sdk_os_timer_disarm(&sdk_sta_con_timer);
gpio_mask = 1 << sdk_g_ic.s.wifi_led_gpio;
sdk_gpio_output_set(0, gpio_mask, gpio_mask, 0);
}
}
void sdk_system_print_meminfo(void) {
printf("%s: 0x%x ~ 0x%x, len: %d\n", "data ", _data_start, _data_end, _data_end - _data_start);
printf("%s: 0x%x ~ 0x%x, len: %d\n", "rodata", _rodata_start, _rodata_end, _rodata_end - _rodata_start);
printf("%s: 0x%x ~ 0x%x, len: %d\n", "bss ", _bss_start, _bss_end, _bss_end - _bss_start);
printf("%s: 0x%x ~ 0x%x, len: %d\n", "heap ", _heap_start, 0x3fffc000, 0x3fffc000 - _heap_start);
}
uint32_t sdk_system_get_free_heap_size(void) {
return xPortGetFreeHeapSize();
}
uint32_t sdk_system_get_chip_id(void) {
uint32_t mac0 = DPORT.OTP_MAC0 & 0xff000000;
uint32_t mac1 = DPORT.OTP_MAC1 & 0x00ffffff;
return (mac1 << 8) | (mac0 >> 24);
}
uint32_t sdk_system_rtc_clock_cali_proc(void) {
return sdk_pm_rtc_clock_cali_proc();
}
uint32_t sdk_system_get_rtc_time(void) {
return RTC.COUNTER;
}
struct sdk_rst_info *sdk_system_get_rst_info(void) {
return &sdk_rst_if;
}
static struct netif *_get_netif(uint32_t mode) {
struct sdk_g_ic_netif_info *info;
if (mode >= 2) {
return NULL;
}
if (mode == 0) {
info = sdk_g_ic.v.station_netif_info;
} else {
info = sdk_g_ic.v.softap_netif_info;
}
if (info) {
return info->netif;
}
return NULL;
}
bool sdk_wifi_station_dhcpc_start(void) {
struct netif *netif = _get_netif(0);
if (sdk_wifi_get_opmode() == 2) {
return false;
}
if (netif && sdk_dhcpc_flag == DHCP_STOPPED) {
sdk_info.ipaddr.addr = 0;
sdk_info.netmask.addr = 0;
sdk_info.gw.addr = 0;
netif_set_addr(netif, &sdk_info.ipaddr, &sdk_info.netmask, &sdk_info.gw);
if (dhcp_start(netif)) {
return false;
}
}
sdk_dhcpc_flag = DHCP_STARTED;
return true;
}
bool sdk_wifi_station_dhcpc_stop(void) {
struct netif *netif = _get_netif(0);
if (sdk_wifi_get_opmode() == 2) {
return false;
}
if (netif && sdk_dhcpc_flag == DHCP_STARTED) {
dhcp_stop(netif);
}
sdk_dhcpc_flag = DHCP_STOPPED;
return true;
}
enum sdk_dhcp_status sdk_wifi_station_dhcpc_status(void) {
return sdk_dhcpc_flag;
}
#endif /* OPEN_LIBMAIN_USER_INTERFACE */

View file

@ -0,0 +1,51 @@
/* Recreated Espressif libmain xtensa_context.o contents.
Copyright (C) 2015 Espressif Systems. Derived from MIT Licensed SDK libraries.
BSD Licensed as described in the file LICENSE
*/
#include "open_esplibs.h"
#if OPEN_LIBMAIN_XTENSA_CONTEXT
// The contents of this file are only built if OPEN_LIBMAIN_XTENSA_CONTEXT is set to true
.section .iram1.text, "ax", @progbits
.balign 4
.global sdk__xt_context_save
.type sdk__xt_context_save, @function
sdk__xt_context_save:
s32i a2, sp, 20
s32i a3, sp, 24
s32i a4, sp, 28
s32i a5, sp, 32
s32i a6, sp, 36
s32i a7, sp, 40
s32i a8, sp, 44
s32i a9, sp, 48
s32i a10, sp, 52
s32i a11, sp, 56
rsr a3, sar
s32i a3, sp, 76
ret
.balign 4
.global sdk__xt_context_restore
.type sdk__xt_context_restore, @function
sdk__xt_context_restore:
l32i a3, sp, 76
l32i a2, sp, 20
wsr a3, sar
l32i a3, sp, 24
l32i a4, sp, 28
l32i a5, sp, 32
l32i a6, sp, 36
l32i a7, sp, 40
l32i a8, sp, 44
l32i a9, sp, 48
l32i a10, sp, 52
l32i a11, sp, 56
l32i a12, sp, 60
l32i a13, sp, 64
ret
#endif /* OPEN_LIBMAIN_XTENSA_CONTEXT */

View file

@ -60,7 +60,7 @@ OBJDUMP = $(CROSS)objdump
# Source components to compile and link. Each of these are subdirectories
# of the root, with a 'component.mk' file.
COMPONENTS ?= $(EXTRA_COMPONENTS) FreeRTOS lwip core
COMPONENTS ?= $(EXTRA_COMPONENTS) FreeRTOS lwip core open_esplibs
# binary esp-iot-rtos SDK libraries to link. These are pre-processed prior to linking.
SDK_LIBS ?= main net80211 phy pp wpa
@ -114,7 +114,7 @@ else ifeq ($(FLAVOR),sdklike)
# the output of the compiler used to build the SDK libs (for comparison of
# disassemblies when coding replacement routines). It is not normally
# intended to be used otherwise.
CFLAGS += -O2 -Os -fno-inline -fno-ipa-cp -fno-toplevel-reorder
CFLAGS += -O2 -Os -fno-inline -fno-ipa-cp -fno-toplevel-reorder -fno-caller-saves -fconserve-stack
LDFLAGS += -O2
else
C_CXX_FLAGS += -g -O2