Make NodeMCU compile and link for ESP32.

A fair bit of reshuffling with include paths and overrides was necessary, as
the two RTOS SDKs (ESP8266 and ESP32) don't have the same header structure
(or even libraries for that matter). Uses the xtensa-esp108-elf toolchain
to build.

Completely untested beyond linking, as I still can't flash the ESP32 module
I have :(  I'd be most surprised if it does anything useful at this point
considering I've spent almost no time on the linker script or UART setup.

Anything using espconn has been ifdef'd out since espconn is not (and
probably will not be) available. Notably this includes the entire net module
as well as coap, mqtt and enduser_setup.

Many (most?) hardware bus drivers and related modules are also ifdef'd
out for now due to hardware differences. Functions surrounding sleep,
rtc and RF modes have also been hit by the ifdef hammer. Grep'ing for
__ESP8266__ and/or FIXME is a quick way of finding these places. With
time I hope all of these will be reinstated.
This commit is contained in:
Johny Mattsson 2016-06-09 18:40:56 +10:00
parent 0df2eda6c0
commit 224788b642
70 changed files with 868 additions and 144 deletions

7
.gitmodules vendored
View File

@ -1,3 +1,6 @@
[submodule "rtos-sdk"]
path = rtos-sdk
[submodule "esp8266-rtos-sdk"]
path = esp8266-rtos-sdk
url = https://github.com/espressif/ESP8266_RTOS_SDK.git
[submodule "esp32-rtos-sdk"]
path = esp32-rtos-sdk
url = https://github.com/espressif/ESP32_RTOS_SDK.git

View File

@ -12,22 +12,61 @@
%: s.%
%: SCCS/s.%
# Set up flags and paths based on hardware target
HW?=ESP8266
ifeq ($(HW),ESP8266)
TARGET=esp8266
TARGET_SDK_LIBS=espconn cirom mirom nopoll
TARGET_LDFLAGS=-u _UserExceptionVectorOverride -Wl,--wrap=printf
LD_FILE=$(LDDIR)/nodemcu.ld
AR = xtensa-lx106-elf-ar
CC = xtensa-lx106-elf-gcc
NM = xtensa-lx106-elf-nm
CPP = xtensa-lx106-elf-cpp
OBJCOPY = xtensa-lx106-elf-objcopy
else ifeq ($(HW),ESP32)
TARGET=esp32
TARGET_SDK_LIBS=rtc c m driver
TARGET_LDFLAGS=
LD_FILE=$(LDDIR)/nodemcu32.ld
AR = xtensa-esp108-elf-ar
CC = xtensa-esp108-elf-gcc
NM = xtensa-esp108-elf-nm
CPP = xtensa-esp108-elf-cpp
OBJCOPY = xtensa-esp108-elf-objcopy
else
$(error Unsupported hardware platform: $(HW))
endif
# Ensure we search "our" SDK before the tool-chain's SDK (if any)
TOP_DIR:=$(abspath $(dir $(lastword $(MAKEFILE_LIST))))
SDKDIR:=$(TOP_DIR)/rtos-sdk
SDKDIR:=$(TOP_DIR)/$(TARGET)-rtos-sdk
# This is, sadly, the cleanest way to resolve the different non-standard
# conventions for sized integers across the various components.
BASIC_TYPES=-Du32_t=uint32_t -Du16_t=uint16_t -Du8_t=uint8_t -Ds32_t=int32_t -Ds16_t=int16_t -Duint32=uint32_t -Duint16=uint16_t -Duint8=uint8_t -Dsint32=int32_t -Dsint16=int16_t -Dsint8=int8_t
# Include dirs, ensure the overrides come first
INCLUDE_DIRS=$(TOP_DIR)/sdk-overrides/include $(SDKDIR)/include $(SDKDIR)/include/espressif $(SDKDIR)/include/lwip $(SDKDIR)/include/lwip/ipv4 $(SDKDIR)/include/lwip/ipv6 $(SDKDIR)/extra_include
INCLUDE_DIRS=\
$(TOP_DIR)/sdk-overrides/include \
$(TOP_DIR)/sdk-overrides/$(TARGET)-include \
$(SDKDIR)/include \
$(SDKDIR)/include/espressif \
$(SDKDIR)/include/espressif/$(TARGET) \
$(SDKDIR)/include/$(TARGET) \
$(SDKDIR)/include/lwip \
$(SDKDIR)/include/lwip/ipv4 \
$(SDKDIR)/include/lwip/ipv6 \
$(SDKDIR)/extra_include \
$(SDKDIR)/third_party/include \
$(SDKDIR)/third_party/include/lwip \
$(SDKDIR)/third_party/include/lwip/ipv4 \
$(SDKDIR)/third_party/include/lwip/ipv6 \
$(SDKDIR)/driver_lib/include \
# ... and we have to mark them all as system include dirs rather than the usual
# -I for user include dir, or the esp-open-sdk toolchain headers wreak havoc
CCFLAGS:=$(addprefix -isystem,$(INCLUDE_DIRS)) $(BASIC_TYPES)
CCFLAGS:=$(addprefix -isystem,$(INCLUDE_DIRS)) $(BASIC_TYPES) -D__$(HW)__
LDFLAGS:= -L$(SDKDIR)/lib -L$(SDKDIR)/ld $(LDFLAGS)
@ -39,12 +78,8 @@ else
ESPPORT = $(COMPORT)
endif
CCFLAGS += -Os -ffunction-sections -fno-jump-tables -fdata-sections
AR = xtensa-lx106-elf-ar
CC = xtensa-lx106-elf-gcc
NM = xtensa-lx106-elf-nm
CPP = xtensa-lx106-elf-cpp
OBJCOPY = xtensa-lx106-elf-objcopy
FIRMWAREDIR = ../bin/
FIRMWAREDIR = ../bin/$(TARGET)/
#############################################################
ESPTOOL ?= ../tools/esptool.py
@ -53,7 +88,7 @@ ESPTOOL ?= ../tools/esptool.py
CSRCS ?= $(wildcard *.c)
ASRCs ?= $(wildcard *.s)
ASRCS ?= $(wildcard *.S)
SUBDIRS ?= $(filter-out rtos-sdk, $(patsubst %/,%,$(dir $(wildcard */Makefile))))
SUBDIRS ?= $(filter-out esp8266-rtos-sdk esp32-rtos-sdk, $(patsubst %/,%,$(dir $(wildcard */Makefile))))
ODIR := .output
OBJODIR := $(ODIR)/$(TARGET)/$(FLAVOR)/obj
@ -126,8 +161,18 @@ $$(IMAGEODIR)/$(1).out: $$(OBJS) $$(DEP_OBJS_$(1)) $$(DEP_LIBS_$(1)) $$(DEPENDS_
endef
$(BINODIR)/%.bin: $(IMAGEODIR)/%.out
@mkdir -p $(BINODIR)
@mkdir -p $(BINODIR) $(FIRMWAREDIR)
ifeq ($(HW),ESP8266)
$(ESPTOOL) elf2image $< -o $(FIRMWAREDIR)
else ifeq ($(HW),ESP32)
@$(OBJCOPY) --only-section .text -O binary $< eagle.app.v7.text.bin
@$(OBJCOPY) --only-section .data -O binary $< eagle.app.v7.data.bin
@$(OBJCOPY) --only-section .rodata -O binary $< eagle.app.v7.rodata.bin
@$(OBJCOPY) --only-section .irom0.text -O binary $< eagle.app.v7.irom0text.bin
@$(OBJCOPY) --only-section .drom0.text -O binary $< eagle.app.v7.drom0text.bin
@python $(SDKDIR)/tools/gen_appbin.py $< $(LD_FILE) 0 0 unused_app_cpu.bin $(FIRMWAREDIR)
@rm -f eagle.app.v7.*.bin
endif
#############################################################
# Rules base
@ -144,13 +189,6 @@ clobber: $(SPECIAL_CLOBBER)
$(foreach d, $(SUBDIRS), $(MAKE) -C $(d) clobber;)
$(RM) -r $(ODIR)
flash:
ifndef PDIR
$(MAKE) -C ./app flash
else
$(ESPTOOL) --port $(ESPPORT) write_flash 0x00000 $(FIRMWAREDIR)0x00000.bin 0x10000 $(FIRMWAREDIR)0x10000.bin
endif
.subdirs:
@set -e; $(foreach d, $(SUBDIRS), $(MAKE) -C $(d);)

View File

@ -11,7 +11,6 @@
# subdir/lib to be extracted and rolled up into
# a generated lib/image xxx.a ()
#
TARGET = eagle
#FLAVOR = release
FLAVOR = debug
@ -63,8 +62,6 @@ ifeq ($(FLAVOR),release)
TARGET_LDFLAGS += -Os
endif
LD_FILE = $(LDDIR)/nodemcu.ld
COMPONENTS_eagle.app.v6 = \
user/libuser.a \
driver/libdriver.a \
@ -93,23 +90,19 @@ COMPONENTS_eagle.app.v6 = \
SELECTED_MODULE_SYMS=$(filter %_module_selected %module_selected1,$(shell $(NM) modules/.output/$(TARGET)/$(FLAVOR)/lib/libmodules.a))
USED_SDK_LIBS= \
cirom \
crypto \
espconn \
freertos \
gcc \
json \
lwip \
main \
mirom \
net80211 \
nopoll \
phy \
pp \
smartconfig \
ssl \
wpa \
wps \
$(TARGET_SDK_LIBS) \
LINKFLAGS_eagle.app.v6 = \
-Wl,--gc-sections \
@ -119,10 +112,9 @@ LINKFLAGS_eagle.app.v6 = \
-Wl,@$(LDDIR)/defsym.rom \
-T$(LDDIR)/extrasyms.rom \
-Wl,--no-check-sections \
-Wl,--wrap=printf \
-Wl,-static \
$(TARGET_LDFLAGS) \
$(addprefix -u , $(SELECTED_MODULE_SYMS)) \
-u _UserExceptionVectorOverride \
-Wl,--start-group \
-lhal \
$(addprefix -l,$(USED_SDK_LIBS)) \

View File

@ -6,6 +6,7 @@
* -1.7976931348623e+308 */
# define FPCONV_G_FMT_BUFSIZE 32
#if 0
#ifdef USE_INTERNAL_FPCONV
static inline void fpconv_init()
{
@ -14,6 +15,7 @@ static inline void fpconv_init()
#else
extern inline void fpconv_init();
#endif
#endif
extern int fpconv_g_fmt(char*, double, int);
extern double fpconv_strtod(const char*, char**);

View File

@ -1,6 +1,7 @@
#include "user_config.h"
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include "coap.h"
#include "uri.h"

View File

@ -2,6 +2,7 @@
#include "c_types.h"
#include "coap.h"
#include "coap_timer.h"
#include "hash.h"
#include "node.h"

View File

@ -1,3 +1,6 @@
// No espconn on ESP32
#ifdef __ESP8266__
#include <string.h>
#include "coap_io.h"
#include "node.h"
@ -69,3 +72,5 @@ coap_tid_t coap_send_confirmed(struct espconn *pesp_conn, coap_pdu_t *pdu) {
coap_timer_start(&gQueue);
return node->id;
}
#endif

View File

@ -1,6 +1,10 @@
// No espconn on ESP32
#ifdef __ESP8266__
#include "node.h"
#include "coap_timer.h"
#include "coap_io.h"
#include "esp_timer.h"
#include "esp_system.h"
static os_timer_t coap_timer;
static coap_tick_t basetime = 0;
@ -76,3 +80,4 @@ void coap_timer_start(coap_queue_t ** queue){
coap_timer_setup(queue, (*queue)->t);
}
}
#endif

View File

@ -1,6 +1,7 @@
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include "esp_libc.h"
#include "coap.h"
#include "lua.h"
@ -196,7 +197,13 @@ static uint32_t id = 0;
static const coap_endpoint_path_t path_id = {2, {"v1", "id"}};
static int handle_get_id(const coap_endpoint_t *ep, coap_rw_buffer_t *scratch, const coap_packet_t *inpkt, coap_packet_t *outpkt, uint8_t id_hi, uint8_t id_lo)
{
#if defined(__ESP8266__)
id = system_get_chip_id();
#elif defined(__ESP32__)
uint8_t tmp;
system_get_chip_id (&tmp); // TODO: deal with failure
id = tmp;
#endif
return coap_make_response(scratch, outpkt, (const uint8_t *)(&id), sizeof(uint32_t), id_hi, id_lo, &inpkt->tok, COAP_RSPCODE_CONTENT, COAP_CONTENTTYPE_TEXT_PLAIN);
}

View File

@ -1,5 +1,6 @@
#include <string.h>
#include <stdlib.h>
#include "esp_libc.h"
#include "node.h"
static inline coap_queue_t *

View File

@ -1,5 +1,6 @@
#include <stdlib.h>
#include "pdu.h"
#include "esp_libc.h"
coap_pdu_t * coap_new_pdu(void) {
coap_pdu_t *pdu = NULL;

View File

@ -34,6 +34,7 @@
#include "mem.h"
#include <string.h>
#include <errno.h>
#include <stdlib.h>
#ifdef MD2_ENABLE
#include "ssl/ssl_crypto.h"

View File

@ -1,3 +1,5 @@
#ifdef __ESP8266__
#include "ets_sys.h"
#include "osapi.h"
#include "eagle_soc.h"
@ -41,3 +43,5 @@ gpio16_input_get(void)
{
return (uint8)(READ_PERI_REG(RTC_GPIO_IN_DATA) & 1);
}
#endif

View File

@ -8,6 +8,8 @@
* Modification history:
* 2014/5/1, v1.0 create this file.
*******************************************************************************/
#ifdef __ESP8266__
#include "ets_sys.h"
#include "os_type.h"
#include "osapi.h"
@ -162,3 +164,4 @@ key_intr_handler(void *arg)
}
}
#endif

View File

@ -8,6 +8,9 @@
* Modification history:
* 2014/5/1, v1.0 create this file.
*******************************************************************************/
// ESP32 has own pwm driver in libdriver.a
#ifdef __ESP8266__
#include "platform.h"
#include "ets_sys.h"
@ -62,8 +65,8 @@ LOCAL uint16 pwm_gpio = 0;
LOCAL uint8 pwm_channel_num = 0;
LOCAL void ICACHE_RAM_ATTR pwm_tim1_intr_handler(os_param_t p);
#define TIMER_OWNER ((os_param_t) 'P')
LOCAL void ICACHE_RAM_ATTR pwm_tim1_intr_handler(uint32_t p);
#define TIMER_OWNER ((uint32_t) 'P')
LOCAL void ICACHE_FLASH_ATTR
pwm_insert_sort(struct pwm_single_param pwm[], uint8 n)
@ -318,7 +321,7 @@ pwm_get_freq(uint8 channel)
* Returns : NONE
*******************************************************************************/
LOCAL void ICACHE_RAM_ATTR
pwm_tim1_intr_handler(os_param_t p)
pwm_tim1_intr_handler(uint32_t p)
{
(void)p;
@ -465,3 +468,4 @@ pwm_exist(uint8 channel){
}
return false;
}
#endif

View File

@ -9,6 +9,7 @@
*
* Philip Gladstone, N1DQ
*/
#ifdef __ESP8266__
#include "platform.h"
#include "c_types.h"
@ -319,3 +320,4 @@ int rotary_getpos(uint32_t channel)
return GET_LAST_STATUS(d).pos;
}
#endif

View File

@ -1,3 +1,5 @@
/* Sigma-delta only on the ESP8266 */
#ifdef __ESP8266__
#include "driver/sigma_delta.h"
#include "esp8266/gpio_register.h"
@ -32,3 +34,5 @@ void sigma_delta_set_prescale_target( sint16 prescale, sint16 target )
(GPIO_SIGMA_DELTA_PRESCALE_SET(prescale) & prescale_mask) |
(GPIO_SIGMA_DELTA_TARGET_SET(target) & target_mask));
}
#endif

View File

@ -1,3 +1,4 @@
#ifdef __ESP8266__
#include "driver/spi.h"
#include "platform.h"
@ -499,7 +500,6 @@ static uint8 idx = 0;
static uint8 spi_flg = 0;
#define SPI_MISO
#define SPI_QUEUE_LEN 8
os_event_t * spiQueue;
#define MOSI 0
#define MISO 1
#define STATUS_R_IN_WR 2
@ -585,6 +585,7 @@ void spi_slave_isr_handler(void *para)
#ifdef SPI_SLAVE_DEBUG
os_event_t * spiQueue;
void ICACHE_FLASH_ATTR
set_miso_data()
@ -677,4 +678,4 @@ void ICACHE_FLASH_ATTR
#endif
#endif

View File

@ -29,7 +29,7 @@
// For event signalling
static task_handle_t sig = 0;
static task_handle_t tsk = 0;
// UartDev is defined and initialized in rom code.
extern UartDevice UartDev;
@ -270,8 +270,8 @@ uart0_rx_intr_handler(void *para)
got_input = true;
}
if (got_input && sig)
task_post_low (sig, false);
if (got_input && tsk)
task_post_low (tsk, false);
}
static void
@ -310,13 +310,13 @@ uart_stop_autobaud()
* Parameters : UartBautRate uart0_br - uart0 bautrate
* UartBautRate uart1_br - uart1 bautrate
* uint8 task_prio - task priority to signal on input
* os_signal_t sig_input - signal to post
* task_handle_t tsk_input - task to notify
* Returns : NONE
*******************************************************************************/
void ICACHE_FLASH_ATTR
uart_init(UartBautRate uart0_br, UartBautRate uart1_br, os_signal_t sig_input)
uart_init(UartBautRate uart0_br, UartBautRate uart1_br, task_handle_t tsk_input)
{
sig = sig_input;
tsk = tsk_input;
// rom use 74880 baut_rate, here reinitialize
UartDev.baut_rate = uart0_br;

View File

@ -12,6 +12,9 @@
* FIXME: support null characters in responses.
*/
// No espconn on ESP32
#ifdef __ESP8266__
#include "osapi.h"
#include "user_interface.h"
#include "espconn.h"
@ -553,3 +556,4 @@ void ICACHE_FLASH_ATTR http_callback_example( char * response, int http_status,
os_printf( "response=%s<EOF>\n", response );
}
}
#endif

View File

@ -1,7 +1,10 @@
#ifndef SPI_APP_H
#define SPI_APP_H
#include "spi_register.h"
#ifdef __ESP8266__
# include "spi_register.h"
#endif
#include "eagle_soc.h"
#include "rom.h"
#include "osapi.h"
#include "uart.h"

View File

@ -6,6 +6,26 @@
#include "c_types.h"
#include "ets_sys.h"
/* Change GPIO pin output by setting, clearing, or disabling pins.
* In general, it is expected that a bit will be set in at most one
* of these masks. If a bit is clear in all masks, the output state
* remains unchanged.
*
* There is no particular ordering guaranteed; so if the order of
* writes is significant, calling code should divide a single call
* into multiple calls.
*/
void gpio_output_set(uint32_t set_mask, uint32_t clear_mask, uint32_t enable_mask, uint32_t disable_mask);
/* Set the specified GPIO register to the specified value.
* This is a very general and powerful interface that is not
* expected to be used during normal operation. It is intended
* mainly for debug, or for unusual requirements.
*/
void gpio_register_set(uint32_t reg_id, uint32_t value);
// SHA1 is assumed to match the netbsd sha1.h headers
#define SHA1_DIGEST_LENGTH 20
#define SHA1_DIGEST_STRING_LENGTH 41
@ -125,6 +145,17 @@ int ets_printf(const char *format, ...) __attribute__ ((format (printf, 1, 2)))
void ets_str2macaddr (uint8_t *dst, const char *str);
typedef void (*ETSTimerFunc)(void *arg);
typedef struct ETSTimer
{
struct ETSTimer *timer_next;
void *timer_handle;
uint32_t timer_expire;
uint32_t timer_period;
ETSTimerFunc timer_func;
bool timer_repeat_flag;
void *timer_arg;
} ETSTimer;
void ets_timer_disarm (ETSTimer *a);
void ets_timer_setfn (ETSTimer *t, ETSTimerFunc *fn, void *parg);
@ -134,8 +165,6 @@ void Cache_Read_Disable(void);
void ets_intr_lock(void);
void ets_intr_unlock(void);
void ets_install_putc1(void *routine);
int rand(void);
void srand(unsigned int);

View File

@ -343,7 +343,7 @@ static inline uint32_t rtc_time_get_calibration(void)
if (!cal)
{
// Make a first guess, most likely to be rather bad, but better then nothing.
#ifndef BOOTLOADER_CODE // This will pull in way too much of the system for the bootloader to handle.
#if !defined(BOOTLOADER_CODE) && defined(__ESP8266__) // This will pull in way too much of the system for the bootloader to handle.
ets_delay_us(200);
cal=system_rtc_clock_cali_proc();
rtc_mem_write(RTC_CALIBRATION_POS,cal);
@ -583,7 +583,7 @@ static inline void rtc_time_tmrfn(void* arg)
static inline void rtc_time_install_timer(void)
{
static ETSTimer tmr;
static os_timer_t tmr;
os_timer_setfn(&tmr,rtc_time_tmrfn,NULL);
os_timer_arm(&tmr,10000,1);

View File

@ -47,7 +47,7 @@
//#define LUA_USE_MODULES_RTCMEM
//#define LUA_USE_MODULES_RTCTIME
//#define LUA_USE_MODULES_SIGMA_DELTA
//#define LUA_USE_MODULES_SNTP
#define LUA_USE_MODULES_SNTP
#define LUA_USE_MODULES_SPI
//#define LUA_USE_MODULES_STRUCT
#define LUA_USE_MODULES_TMR

View File

@ -6,13 +6,19 @@
#include "c_types.h"
#include "user_interface.h"
#include <stdlib.h>
// Lua: read(id) , return system adc
static int adc_sample( lua_State* L )
{
unsigned id = luaL_checkinteger( L, 1 );
MOD_CHECK_ID( adc, id );
#if defined(__ESP8266__)
unsigned val = 0xFFFF & system_adc_read();
#elif defined(__ESP32__)
// TODO: support reading the 8 ADC channels via system_adc1_read()
unsigned val = 0;
#endif
lua_pushinteger( L, val );
return 1;
}

View File

@ -1,5 +1,8 @@
// Module for coapwork
// No espconn on ESP32
#ifdef __ESP8266__
#include "module.h"
#include "lauxlib.h"
#include "platform.h"
@ -607,3 +610,4 @@ int luaopen_coap( lua_State *L )
}
NODEMCU_MODULE(COAP, "coap", coap_map, luaopen_coap);
#endif

View File

@ -5,6 +5,7 @@
#include "lauxlib.h"
#include "platform.h"
#include "c_types.h"
#include "esp_libc.h"
#include <stdlib.h>
#include "flash_fs.h"
#include "../crypto/digests.h"

View File

@ -3,7 +3,6 @@
#include "module.h"
#include "lauxlib.h"
#include "platform.h"
#include "cpu_esp8266.h"
#include "dht.h"
#define NUM_DHT GPIO_PIN_NUM

View File

@ -33,6 +33,9 @@
* Additions & fixes: Johny Mattsson <jmattsson@dius.com.au>
*/
// No espconn on ESP32
#ifdef __ESP8266__
#include "module.h"
#include "lauxlib.h"
#include "lwip/tcp.h"
@ -1528,3 +1531,4 @@ static const LUA_REG_TYPE enduser_setup_map[] = {
};
NODEMCU_MODULE(ENDUSER_SETUP, "enduser_setup", enduser_setup_map, NULL);
#endif

View File

@ -22,10 +22,15 @@
#ifdef GPIO_INTERRUPT_ENABLE
#if defined(__ESP8266__)
// We also know that the non-level interrupt types are < LOLEVEL, and that
// HILEVEL is > LOLEVEL. Since this is burned into the hardware it is not
// going to change.
#define INTERRUPT_TYPE_IS_LEVEL(x) ((x) >= GPIO_PIN_INTR_LOLEVEL)
# define INTERRUPT_TYPE_IS_LEVEL(x) ((x) >= GPIO_PIN_INTR_LOLEVEL)
#elif defined(__ESP32__)
// There appears to be no level interrupt support on the ESP32?
# define INTERRUPT_TYPE_IS_LEVEL(x) 0
#endif
static int gpio_cb_ref[GPIO_PIN_NUM];
@ -65,10 +70,17 @@ static void gpio_intr_callback_task (task_param_t param, task_prio_t priority)
static int lgpio_trig( lua_State* L )
{
unsigned pin = luaL_checkinteger( L, 1 );
static const char * const opts[] = {"none", "up", "down", "both", "low", "high", NULL};
static const char * const opts[] = {"none", "up", "down", "both",
#ifdef __ESP8266__
"low", "high",
#endif
NULL};
static const int opts_type[] = {
GPIO_PIN_INTR_DISABLE, GPIO_PIN_INTR_POSEDGE, GPIO_PIN_INTR_NEGEDGE,
GPIO_PIN_INTR_ANYEDGE, GPIO_PIN_INTR_LOLEVEL, GPIO_PIN_INTR_HILEVEL
GPIO_PIN_INTR_ANYEDGE
#ifdef __ESP8266__
,GPIO_PIN_INTR_LOLEVEL, GPIO_PIN_INTR_HILEVEL
#endif
};
luaL_argcheck(L, platform_gpio_exists(pin) && pin>0, 1, "Invalid interrupt pin");

View File

@ -6,7 +6,6 @@
#include "module.h"
#include "lauxlib.h"
#include "platform.h"
#include "cpu_esp8266.h"
#include "httpclient.h"
static int http_callback_registry = LUA_NOREF;

View File

@ -1,3 +1,6 @@
// No espconn on ESP32
#ifdef __ESP8266__
// Module for mqtt
#include "module.h"
@ -74,7 +77,7 @@ typedef struct lmqtt_userdata
uint8_t secure;
#endif
bool connected; // indicate socket connected, not mqtt prot connected.
ETSTimer mqttTimer;
os_timer_t mqttTimer;
tConnState connState;
}lmqtt_userdata;
@ -687,7 +690,7 @@ static int mqtt_socket_client( lua_State* L )
mud->event_timeout = 0;
mud->connState = MQTT_INIT;
mud->connected = false;
memset(&mud->mqttTimer, 0, sizeof(ETSTimer));
memset(&mud->mqttTimer, 0, sizeof(os_timer_t));
memset(&mud->mqtt_state, 0, sizeof(mqtt_state_t));
memset(&mud->connect_info, 0, sizeof(mqtt_connect_info_t));
@ -1615,3 +1618,4 @@ int luaopen_mqtt( lua_State *L )
}
NODEMCU_MODULE(MQTT, "mqtt", mqtt_map, luaopen_mqtt);
#endif

View File

@ -1,5 +1,8 @@
// Module for network
// No espconn on ESP32
#ifdef __ESP8266__
#include "module.h"
#include "lauxlib.h"
#include "platform.h"
@ -1788,3 +1791,4 @@ int luaopen_net( lua_State *L ) {
}
NODEMCU_MODULE(NET, "net", net_map, luaopen_net);
#endif

View File

@ -47,6 +47,7 @@ static int node_restart( lua_State* L )
return 0;
}
#ifdef __ESP8266__
// Lua: dsleep( us, option )
static int node_deepsleep( lua_State* L )
{
@ -89,13 +90,33 @@ static int node_deepsleep( lua_State* L )
// }
// Lua: info()
#endif
static uint32_t system_chip_id (lua_State *L)
{
#if defined(__ESP8266__)
(void)L;
return system_get_chip_id ();
#elif defined(__ESP32__)
uint8_t id = 0;
if (!system_get_chip_id (&id))
return luaL_error (L, "failed to read chip id");
return id;
#endif
}
static int node_info( lua_State* L )
{
lua_pushinteger(L, NODE_VERSION_MAJOR);
lua_pushinteger(L, NODE_VERSION_MINOR);
lua_pushinteger(L, NODE_VERSION_REVISION);
lua_pushinteger(L, system_get_chip_id()); // chip id
lua_pushinteger(L, system_chip_id(L)); // chip id
#if defined(__ESP8266__)
lua_pushinteger(L, spi_flash_get_id()); // flash id
#elif defined(__ESP32__)
lua_pushinteger (L, 0); // flash id not readable on ESP32?
#endif
#if defined(FLASH_SAFE_API)
lua_pushinteger(L, flash_safe_get_size_byte() / 1024); // flash size in KB
#else
@ -109,8 +130,7 @@ static int node_info( lua_State* L )
// Lua: chipid()
static int node_chipid( lua_State* L )
{
uint32_t id = system_get_chip_id();
lua_pushinteger(L, id);
lua_pushinteger(L, system_chip_id (L));
return 1;
}
@ -123,6 +143,7 @@ static int node_chipid( lua_State* L )
// return 1;
// }
#ifdef __ESP8266__
// Lua: flashid()
static int node_flashid( lua_State* L )
{
@ -130,6 +151,7 @@ static int node_flashid( lua_State* L )
lua_pushinteger( L, id );
return 1;
}
#endif
// Lua: flashsize()
static int node_flashsize( lua_State* L )
@ -558,6 +580,7 @@ static int node_setcpufreq(lua_State* L)
return 1;
}
#ifdef __ESP8266__
// Lua: code, reason [, exccause, epc1, epc2, epc3, excvaddr, depc ] = bootreason()
static int node_bootreason (lua_State *L)
{
@ -572,6 +595,7 @@ static int node_bootreason (lua_State *L)
lua_pushinteger (L, arr[i]);
return n;
}
#endif
// Lua: restore()
static int node_restore (lua_State *L)
@ -692,10 +716,13 @@ static const LUA_REG_TYPE node_task_map[] = {
static const LUA_REG_TYPE node_map[] =
{
{ LSTRKEY( "restart" ), LFUNCVAL( node_restart ) },
#ifdef __ESP8266__
{ LSTRKEY( "dsleep" ), LFUNCVAL( node_deepsleep ) },
{ LSTRKEY( "flashid" ), LFUNCVAL( node_flashid ) },
{ LSTRKEY( "bootreason" ), LFUNCVAL( node_bootreason) },
#endif
{ LSTRKEY( "info" ), LFUNCVAL( node_info ) },
{ LSTRKEY( "chipid" ), LFUNCVAL( node_chipid ) },
{ LSTRKEY( "flashid" ), LFUNCVAL( node_flashid ) },
{ LSTRKEY( "flashsize" ), LFUNCVAL( node_flashsize) },
{ LSTRKEY( "heap" ), LFUNCVAL( node_heap ) },
#ifdef DEVKIT_VERSION_0_9
@ -710,13 +737,13 @@ static const LUA_REG_TYPE node_map[] =
{ LSTRKEY( "CPU80MHZ" ), LNUMVAL( CPU80MHZ ) },
{ LSTRKEY( "CPU160MHZ" ), LNUMVAL( CPU160MHZ ) },
{ LSTRKEY( "setcpufreq" ), LFUNCVAL( node_setcpufreq) },
{ LSTRKEY( "bootreason" ), LFUNCVAL( node_bootreason) },
{ LSTRKEY( "restore" ), LFUNCVAL( node_restore) },
#ifdef LUA_OPTIMIZE_DEBUG
{ LSTRKEY( "stripdebug" ), LFUNCVAL( node_stripdebug ) },
#endif
{ LSTRKEY( "egc" ), LROVAL( node_egc_map ) },
{ LSTRKEY( "task" ), LROVAL( node_task_map ) },
#define DEVELOPMENT_TOOLS
#ifdef DEVELOPMENT_TOOLS
{ LSTRKEY( "osprint" ), LFUNCVAL( node_osprint ) },
#endif

View File

@ -15,7 +15,7 @@
#include "lauxlib.h"
#include "platform.h"
#include "hw_timer.h"
#include "cpu_esp8266.h"
#include "platform.h"
typedef struct {
int ref;
@ -31,9 +31,9 @@ typedef struct {
static DATA *data;
extern char _flash_used_end[];
#define TIMER_OWNER ((os_param_t) 'p')
#define TIMER_OWNER ((uint32_t) 'p')
static void ICACHE_RAM_ATTR hw_timer_cb(os_param_t p)
static void ICACHE_RAM_ATTR hw_timer_cb(uint32_t p)
{
(void) p;
uint32_t stackaddr;

View File

@ -6,6 +6,8 @@
* Philip Gladstone, N1DQ
*/
#ifdef __ESP8266__
#include "module.h"
#include "lauxlib.h"
#include "platform.h"
@ -47,7 +49,7 @@ typedef struct {
int longpress_delay_us;
uint32_t last_event_time;
int callback[CALLBACK_COUNT];
ETSTimer timer;
os_timer_t timer;
} DATA;
static DATA *data[ROTARY_CHANNEL_COUNT];
@ -403,3 +405,4 @@ static const LUA_REG_TYPE rotary_map[] = {
};
NODEMCU_MODULE(ROTARY, "rotary", rotary_map, rotary_open);
#endif

View File

@ -80,6 +80,7 @@ static int rtctime_get (lua_State *L)
return 2;
}
#ifdef __ESP8266__
static void do_sleep_opt (lua_State *L, int idx)
{
if (lua_isnumber (L, idx))
@ -113,14 +114,17 @@ static int rtctime_dsleep_aligned (lua_State *L)
rtctime_deep_sleep_until_aligned_us (align_us, min_us); // does not return
return 0;
}
#endif
// Module function map
static const LUA_REG_TYPE rtctime_map[] = {
{ LSTRKEY("set"), LFUNCVAL(rtctime_set) },
{ LSTRKEY("get"), LFUNCVAL(rtctime_get) },
#ifdef __ESP8266__
{ LSTRKEY("dsleep"), LFUNCVAL(rtctime_dsleep) },
{ LSTRKEY("dsleep_aligned"), LFUNCVAL(rtctime_dsleep_aligned) },
#endif
{ LNILKEY, LNILVAL }
};

View File

@ -1,5 +1,7 @@
// Module for interfacing with sigma-delta hardware
#ifdef __ESP8266__
#include "module.h"
#include "lauxlib.h"
#include "platform.h"
@ -85,3 +87,4 @@ static const LUA_REG_TYPE sigma_delta_map[] =
};
NODEMCU_MODULE(SIGMA_DELTA, "sigma_delta", sigma_delta_map, NULL);
#endif

View File

@ -78,6 +78,7 @@ typedef struct{
}timer_struct_t;
typedef timer_struct_t* ptimer_t;
#ifdef __ESP8266__
// The previous implementation extended the rtc counter to 64 bits, and then
// applied rtc2sec with the current calibration value to that 64 bit value.
// This means that *ALL* clock ticks since bootup are counted with the *current*
@ -90,10 +91,12 @@ typedef timer_struct_t* ptimer_t;
static uint32_t rtc_time_cali=0;
static uint32_t last_rtc_time=0;
static uint64_t last_rtc_time_us=0;
static os_timer_t rtc_timer;
static sint32_t soft_watchdog = -1;
#endif
static timer_struct_t alarm_timers[NUM_TMR];
static os_timer_t rtc_timer;
static task_handle_t callback_task;
@ -161,14 +164,14 @@ static int tmr_register(lua_State* L){
sint32_t ref = luaL_ref(L, LUA_REGISTRYINDEX);
ptimer_t tmr = &alarm_timers[id];
if(!(tmr->mode & TIMER_IDLE_FLAG) && tmr->mode != TIMER_MODE_OFF)
ets_timer_disarm(&tmr->os);
os_timer_disarm(&tmr->os);
//there was a bug in this part, the second part of the following condition was missing
if(tmr->lua_ref != LUA_NOREF && tmr->lua_ref != ref)
luaL_unref(L, LUA_REGISTRYINDEX, tmr->lua_ref);
tmr->lua_ref = ref;
tmr->mode = mode|TIMER_IDLE_FLAG;
tmr->interval = interval;
ets_timer_setfn(&tmr->os, alarm_timer_common, (void*)id);
os_timer_setfn(&tmr->os, alarm_timer_common, (void*)id);
return 0;
}
@ -182,7 +185,7 @@ static int tmr_start(lua_State* L){
lua_pushboolean(L, 0);
}else{
tmr->mode &= ~TIMER_IDLE_FLAG;
ets_timer_arm_new(&tmr->os, tmr->interval, tmr->mode==TIMER_MODE_AUTO, 1);
os_timer_arm(&tmr->os, tmr->interval, tmr->mode==TIMER_MODE_AUTO);
lua_pushboolean(L, 1);
}
return 1;
@ -202,7 +205,7 @@ static int tmr_stop(lua_State* L){
//we return false if the timer is idle (of not registered)
if(!(tmr->mode & TIMER_IDLE_FLAG) && tmr->mode != TIMER_MODE_OFF){
tmr->mode |= TIMER_IDLE_FLAG;
ets_timer_disarm(&tmr->os);
os_timer_disarm(&tmr->os);
lua_pushboolean(L, 1);
}else{
lua_pushboolean(L, 0);
@ -216,7 +219,7 @@ static int tmr_unregister(lua_State* L){
MOD_CHECK_ID(tmr,id);
ptimer_t tmr = &alarm_timers[id];
if(!(tmr->mode & TIMER_IDLE_FLAG) && tmr->mode != TIMER_MODE_OFF)
ets_timer_disarm(&tmr->os);
os_timer_disarm(&tmr->os);
if(tmr->lua_ref != LUA_NOREF)
luaL_unref(L, LUA_REGISTRYINDEX, tmr->lua_ref);
tmr->lua_ref = LUA_NOREF;
@ -234,8 +237,8 @@ static int tmr_interval(lua_State* L){
if(tmr->mode != TIMER_MODE_OFF){
tmr->interval = interval;
if(!(tmr->mode&TIMER_IDLE_FLAG)){
ets_timer_disarm(&tmr->os);
ets_timer_arm_new(&tmr->os, tmr->interval, tmr->mode==TIMER_MODE_AUTO, 1);
os_timer_disarm(&tmr->os);
os_timer_arm(&tmr->os, tmr->interval, tmr->mode==TIMER_MODE_AUTO);
}
}
return 0;
@ -266,6 +269,7 @@ static int tmr_wdclr( lua_State* L ){
return 0;
}
#ifdef __ESP8266__
//system_rtc_clock_cali_proc() returns
//a fixed point value (12 bit fraction part)
//it tells how many rtc clock ticks represent 1us.
@ -317,6 +321,7 @@ static int tmr_softwd( lua_State* L ){
soft_watchdog = luaL_checkinteger(L, 1);
return 0;
}
#endif
// Module function map
@ -324,8 +329,10 @@ static const LUA_REG_TYPE tmr_map[] = {
{ LSTRKEY( "delay" ), LFUNCVAL( tmr_delay ) },
{ LSTRKEY( "now" ), LFUNCVAL( tmr_now ) },
{ LSTRKEY( "wdclr" ), LFUNCVAL( tmr_wdclr ) },
#ifdef __ESP8266__
{ LSTRKEY( "softwd" ), LFUNCVAL( tmr_softwd ) },
{ LSTRKEY( "time" ), LFUNCVAL( tmr_time ) },
#endif
{ LSTRKEY( "register" ), LFUNCVAL( tmr_register ) },
{ LSTRKEY( "alarm" ), LFUNCVAL( tmr_alarm ) },
{ LSTRKEY( "start" ), LFUNCVAL( tmr_start ) },
@ -344,14 +351,16 @@ int luaopen_tmr( lua_State *L ){
for(i=0; i<NUM_TMR; i++){
alarm_timers[i].lua_ref = LUA_NOREF;
alarm_timers[i].mode = TIMER_MODE_OFF;
ets_timer_disarm(&alarm_timers[i].os);
os_timer_disarm(&alarm_timers[i].os);
}
#ifdef __ESP8266__
last_rtc_time=system_get_rtc_time(); // Right now is time 0
last_rtc_time_us=0;
ets_timer_disarm(&rtc_timer);
ets_timer_setfn(&rtc_timer, rtc_callback, NULL);
ets_timer_arm_new(&rtc_timer, 1000, 1, 1);
os_timer_disarm(&rtc_timer);
os_timer_setfn(&rtc_timer, rtc_callback, NULL);
os_timer_arm(&rtc_timer, 1000, 1);
#endif
callback_task = task_get_id (run_callback);
return 0;

View File

@ -262,6 +262,7 @@ static int wifi_getchannel( lua_State* L )
return 1;
}
#ifdef __ESP8266__
/**
* wifi.setphymode()
* Description:
@ -372,6 +373,7 @@ static int wifi_sleep(lua_State* L)
}
return 2;
}
#endif
// Lua: mac = wifi.xx.getmac()
static int wifi_getmac( lua_State* L, uint8_t mode )
@ -487,6 +489,7 @@ static int wifi_setip( lua_State* L, uint8_t mode )
return 1;
}
#ifdef __ESP8266__
// Lua: realtype = sleeptype(type)
static int wifi_sleeptype( lua_State* L )
{
@ -506,6 +509,7 @@ static int wifi_sleeptype( lua_State* L )
lua_pushinteger( L, type );
return 1;
}
#endif
// Lua: wifi.sta.getmac()
static int wifi_station_getmac( lua_State* L ){
@ -897,6 +901,7 @@ static int wifi_station_listap( lua_State* L )
unregister_lua_cb(L, &wifi_scan_succeed);
}
}
#ifdef __ESP8266__
// Lua: wifi.sta.gethostname()
static int wifi_sta_gethostname( lua_State* L )
@ -933,6 +938,7 @@ static int wifi_sta_sethostname_lua( lua_State* L )
luaL_argcheck(L, wifi_sta_sethostname(hostname, len), 1, "Invalid hostname");
return 0;
}
#endif
// Lua: wifi.sta.status()
static int wifi_station_status( lua_State* L )
@ -1228,8 +1234,10 @@ static const LUA_REG_TYPE wifi_station_map[] = {
{ LSTRKEY( "getmac" ), LFUNCVAL( wifi_station_getmac ) },
{ LSTRKEY( "setmac" ), LFUNCVAL( wifi_station_setmac ) },
{ LSTRKEY( "getap" ), LFUNCVAL( wifi_station_listap ) },
#ifdef __ESP8266__
{ LSTRKEY( "sethostname" ), LFUNCVAL( wifi_sta_sethostname_lua ) },
{ LSTRKEY( "gethostname" ), LFUNCVAL( wifi_sta_gethostname ) },
#endif
{ LSTRKEY( "getrssi" ), LFUNCVAL( wifi_station_getrssi ) },
{ LSTRKEY( "status" ), LFUNCVAL( wifi_station_status ) },
#if defined(WIFI_STATION_STATUS_MONITOR_ENABLE)
@ -1266,14 +1274,16 @@ static const LUA_REG_TYPE wifi_map[] = {
{ LSTRKEY( "setmode" ), LFUNCVAL( wifi_setmode ) },
{ LSTRKEY( "getmode" ), LFUNCVAL( wifi_getmode ) },
{ LSTRKEY( "getchannel" ), LFUNCVAL( wifi_getchannel ) },
#ifdef __ESP8266__
{ LSTRKEY( "setphymode" ), LFUNCVAL( wifi_setphymode ) },
{ LSTRKEY( "getphymode" ), LFUNCVAL( wifi_getphymode ) },
{ LSTRKEY( "sleep" ), LFUNCVAL( wifi_sleep ) },
{ LSTRKEY( "sleeptype" ), LFUNCVAL( wifi_sleeptype ) },
#endif
#ifdef WIFI_SMART_ENABLE
{ LSTRKEY( "startsmart" ), LFUNCVAL( wifi_start_smart ) },
{ LSTRKEY( "stopsmart" ), LFUNCVAL( wifi_exit_smart ) },
#endif
{ LSTRKEY( "sleeptype" ), LFUNCVAL( wifi_sleeptype ) },
{ LSTRKEY( "sta" ), LROVAL( wifi_station_map ) },
{ LSTRKEY( "ap" ), LROVAL( wifi_ap_map ) },
@ -1285,6 +1295,7 @@ static const LUA_REG_TYPE wifi_map[] = {
{ LSTRKEY( "SOFTAP" ), LNUMVAL( SOFTAP_MODE ) },
{ LSTRKEY( "STATIONAP" ), LNUMVAL( STATIONAP_MODE ) },
#ifdef __ESP8266__
{ LSTRKEY( "PHYMODE_B" ), LNUMVAL( PHY_MODE_11B ) },
{ LSTRKEY( "PHYMODE_G" ), LNUMVAL( PHY_MODE_11G ) },
{ LSTRKEY( "PHYMODE_N" ), LNUMVAL( PHY_MODE_11N ) },
@ -1292,6 +1303,7 @@ static const LUA_REG_TYPE wifi_map[] = {
{ LSTRKEY( "NONE_SLEEP" ), LNUMVAL( NONE_SLEEP_T ) },
{ LSTRKEY( "LIGHT_SLEEP" ), LNUMVAL( LIGHT_SLEEP_T ) },
{ LSTRKEY( "MODEM_SLEEP" ), LNUMVAL( MODEM_SLEEP_T ) },
#endif
{ LSTRKEY( "OPEN" ), LNUMVAL( AUTH_OPEN ) },
//{ LSTRKEY( "WEP" ), LNUMVAL( AUTH_WEP ) },
@ -1310,6 +1322,7 @@ static const LUA_REG_TYPE wifi_map[] = {
{ LNILKEY, LNILVAL }
};
#ifdef __ESP8266__
static void wifi_change_default_host_name(task_param_t param, task_prio_t priority)
{
#ifndef WIFI_STA_HOSTNAME
@ -1342,10 +1355,13 @@ static void wifi_change_default_host_name(task_param_t param, task_prio_t priori
#endif
}
#endif
int luaopen_wifi( lua_State *L )
{
#ifdef __ESP8266__
task_post_low(task_get_id(wifi_change_default_host_name), FALSE);
#endif
#if defined(WIFI_SDK_EVENT_MONITOR_ENABLE)
wifi_eventmon_init();
#endif

View File

@ -3,7 +3,7 @@
#include "platform.h"
#include <stdlib.h>
#include <string.h>
#include "esp_misc.h"
#include "user_interface.h"
#include "rom.h"
/**

73
app/platform/cpu_esp32.h Normal file
View File

@ -0,0 +1,73 @@
#ifndef _CPU_ESP32_H_
#define _CPU_ESP32_H_
#include <stdint.h>
#include <stdbool.h>
#include "user_config.h"
#include <spi_flash.h>
#include <eagle_soc.h>
#include <gpio.h>
#include <gpio/io_mux_reg.h>
#include <gpio/gpio_reg.h>
#include "flash_api.h"
#include "pin_map.h"
/* FIXME: real numbers here! */
#define NUM_GPIO GPIO_PIN_NUM
#define NUM_SPI 2
#define NUM_UART 1
#define NUM_PWM GPIO_PIN_NUM
#define NUM_ADC 1
#define NUM_CAN 0
#define NUM_I2C 1
#define NUM_OW GPIO_PIN_NUM
#define NUM_TMR 7
#if defined(FLASH_512K)
# define FLASH_SEC_NUM 0x80 // 4MByte: 0x400, 2MByte: 0x200, 1MByte: 0x100, 512KByte: 0x80
#elif defined(FLASH_1M)
# define FLASH_SEC_NUM 0x100
#elif defined(FLASH_2M)
# define FLASH_SEC_NUM 0x200
#elif defined(FLASH_4M)
# define FLASH_SEC_NUM 0x400
#elif defined(FLASH_8M)
# define FLASH_SEC_NUM 0x800
#elif defined(FLASH_16M)
# define FLASH_SEC_NUM 0x1000
#elif defined(FLASH_AUTOSIZE)
# if defined(FLASH_SAFE_API)
# define FLASH_SEC_NUM (flash_safe_get_sec_num())
# else
# define FLASH_SEC_NUM (flash_rom_get_sec_num())
# endif // defined(FLASH_SAFE_API)
#else
# define FLASH_SEC_NUM 0x80
#endif
#define SYS_PARAM_SEC_NUM 4
#define SYS_PARAM_SEC_START (FLASH_SEC_NUM - SYS_PARAM_SEC_NUM)
#define INTERNAL_FLASH_SECTOR_SIZE SPI_FLASH_SEC_SIZE
// #define INTERNAL_FLASH_SECTOR_ARRAY { 0x4000, 0x4000, 0x4000, 0x4000, 0x10000, 0x20000, 0x20000, 0x20000, 0x20000, 0x20000 }
#define INTERNAL_FLASH_WRITE_UNIT_SIZE 4
#define INTERNAL_FLASH_READ_UNIT_SIZE 4
#define INTERNAL_FLASH_SIZE ( (SYS_PARAM_SEC_START) * INTERNAL_FLASH_SECTOR_SIZE )
// TODO: double-check flash mapped address
#define INTERNAL_FLASH_MAPPED_ADDRESS 0x40084000
#if defined(FLASH_SAFE_API)
#define flash_write flash_safe_write
#define flash_erase flash_safe_erase_sector
#define flash_read flash_safe_read
#else
#define flash_write spi_flash_write
#define flash_erase spi_flash_erase_sector
#define flash_read spi_flash_read
#endif // defined(FLASH_SAFE_API)
#endif

View File

@ -23,26 +23,27 @@
#define NUM_TMR 7
#if defined(FLASH_512K)
#define FLASH_SEC_NUM 0x80 // 4MByte: 0x400, 2MByte: 0x200, 1MByte: 0x100, 512KByte: 0x80
# define FLASH_SEC_NUM 0x80 // 4MByte: 0x400, 2MByte: 0x200, 1MByte: 0x100, 512KByte: 0x80
#elif defined(FLASH_1M)
#define FLASH_SEC_NUM 0x100
# define FLASH_SEC_NUM 0x100
#elif defined(FLASH_2M)
#define FLASH_SEC_NUM 0x200
# define FLASH_SEC_NUM 0x200
#elif defined(FLASH_4M)
#define FLASH_SEC_NUM 0x400
# define FLASH_SEC_NUM 0x400
#elif defined(FLASH_8M)
#define FLASH_SEC_NUM 0x800
# define FLASH_SEC_NUM 0x800
#elif defined(FLASH_16M)
#define FLASH_SEC_NUM 0x1000
# define FLASH_SEC_NUM 0x1000
#elif defined(FLASH_AUTOSIZE)
#if defined(FLASH_SAFE_API)
#define FLASH_SEC_NUM (flash_safe_get_sec_num())
# if defined(FLASH_SAFE_API)
# define FLASH_SEC_NUM (flash_safe_get_sec_num())
# else
# define FLASH_SEC_NUM (flash_rom_get_sec_num())
# endif // defined(FLASH_SAFE_API)
#else
#define FLASH_SEC_NUM (flash_rom_get_sec_num())
#endif // defined(FLASH_SAFE_API)
#else
#define FLASH_SEC_NUM 0x80
# define FLASH_SEC_NUM 0x80
#endif
#define SYS_PARAM_SEC_NUM 4
#define SYS_PARAM_SEC_START (FLASH_SEC_NUM - SYS_PARAM_SEC_NUM)
@ -54,9 +55,6 @@
#define INTERNAL_FLASH_SIZE ( (SYS_PARAM_SEC_START) * INTERNAL_FLASH_SECTOR_SIZE )
#define INTERNAL_FLASH_MAPPED_ADDRESS 0x40200000
// SpiFlashOpResult spi_flash_erase_sector(uint16 sec);
// SpiFlashOpResult spi_flash_write(uint32 des_addr, uint32 *src_addr, uint32 size);
// SpiFlashOpResult spi_flash_read(uint32 src_addr, uint32 *des_addr, uint32 size);
#if defined(FLASH_SAFE_API)
#define flash_write flash_safe_write
#define flash_erase flash_safe_erase_sector

View File

@ -7,6 +7,8 @@
#include "flash_api.h"
#include "spi_flash.h"
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
uint32_t flash_detect_size_byte(void)
{

View File

@ -2,7 +2,7 @@
#define __FLASH_API_H__
#include "ets_sys.h"
#include "user_config.h"
#include "cpu_esp8266.h"
#include "platform.h"
#define FLASH_SIZE_2MBIT (2 * 1024 * 1024)
#define FLASH_SIZE_4MBIT (4 * 1024 * 1024)
@ -20,15 +20,21 @@
#define FLASH_SIZE_8MBYTE (FLASH_SIZE_64MBIT / 8)
#define FLASH_SIZE_16MBYTE (FLASH_SIZE_128MBIT/ 8)
#define FLASH_SAFEMODE_ENTER() \
#if defined(__ESP8266__)
# define FLASH_SAFEMODE_ENTER() \
do { \
extern SpiFlashChip flashchip; \
flashchip.chip_size = FLASH_SIZE_16MBYTE
#define FLASH_SAFEMODE_LEAVE() \
# define FLASH_SAFEMODE_LEAVE() \
flashchip.chip_size = flash_rom_get_size_byte(); \
} while(0)
#elif defined(__ESP32__)
// TODO: is there something similar to SpiFlashChip available on the ESP32?
# define FLASH_SAFEMODE_ENTER() do{}while(0)
# define FLASH_SAFEMODE_LEAVE() do{}while(0)
#endif
/******************************************************************************
* ROM Function definition

View File

@ -12,7 +12,7 @@
*
* The owner parameter should be a unique value per module using this API
* It could be a pointer to a bit of data or code
* e.g. #define OWNER ((os_param_t) module_init)
* e.g. #define OWNER ((uint32_t) module_init)
* where module_init is a function. For builtin modules, it might be
* a small numeric value that is known not to clash.
*******************************************************************************/
@ -37,20 +37,20 @@ typedef enum { //timer interrupt mode
TM_EDGE_INT = 0, //edge interrupt
} TIMER_INT_MODE;
static os_param_t the_owner;
static os_param_t callback_arg;
static void (* user_hw_timer_cb)(os_param_t);
static uint32_t the_owner;
static uint32_t callback_arg;
static void (* user_hw_timer_cb)(uint32_t);
#define VERIFY_OWNER(owner) if (owner != the_owner) { if (the_owner) { return 0; } the_owner = owner; }
/******************************************************************************
* FunctionName : platform_hw_timer_arm_ticks
* Description : set a trigger timer delay for this timer.
* Parameters : os_param_t owner
* Parameters : uint32_t owner
* uint32 ticks :
* Returns : true if it worked
*******************************************************************************/
bool ICACHE_RAM_ATTR platform_hw_timer_arm_ticks(os_param_t owner, uint32_t ticks)
bool ICACHE_RAM_ATTR platform_hw_timer_arm_ticks(uint32_t owner, uint32_t ticks)
{
VERIFY_OWNER(owner);
RTC_REG_WRITE(FRC1_LOAD_ADDRESS, ticks);
@ -61,7 +61,7 @@ bool ICACHE_RAM_ATTR platform_hw_timer_arm_ticks(os_param_t owner, uint32_t tick
/******************************************************************************
* FunctionName : platform_hw_timer_arm_us
* Description : set a trigger timer delay for this timer.
* Parameters : os_param_t owner
* Parameters : uint32_t owner
* uint32 microseconds :
* in autoload mode
* 50 ~ 0x7fffff; for FRC1 source.
@ -70,7 +70,7 @@ bool ICACHE_RAM_ATTR platform_hw_timer_arm_ticks(os_param_t owner, uint32_t tick
* 10 ~ 0x7fffff;
* Returns : true if it worked
*******************************************************************************/
bool ICACHE_RAM_ATTR platform_hw_timer_arm_us(os_param_t owner, uint32_t microseconds)
bool ICACHE_RAM_ATTR platform_hw_timer_arm_us(uint32_t owner, uint32_t microseconds)
{
VERIFY_OWNER(owner);
RTC_REG_WRITE(FRC1_LOAD_ADDRESS, US_TO_RTC_TIMER_TICKS(microseconds));
@ -81,13 +81,13 @@ bool ICACHE_RAM_ATTR platform_hw_timer_arm_us(os_param_t owner, uint32_t microse
/******************************************************************************
* FunctionName : platform_hw_timer_set_func
* Description : set the func, when trigger timer is up.
* Parameters : os_param_t owner
* void (* user_hw_timer_cb_set)(os_param_t):
* Parameters : uint32_t owner
* void (* user_hw_timer_cb_set)(uint32_t):
timer callback function
* os_param_t arg
* uint32_t arg
* Returns : true if it worked
*******************************************************************************/
bool platform_hw_timer_set_func(os_param_t owner, void (* user_hw_timer_cb_set)(os_param_t), os_param_t arg)
bool platform_hw_timer_set_func(uint32_t owner, void (* user_hw_timer_cb_set)(uint32_t), uint32_t arg)
{
VERIFY_OWNER(owner);
callback_arg = arg;
@ -112,10 +112,10 @@ static void ICACHE_RAM_ATTR hw_timer_nmi_cb(void)
/******************************************************************************
* FunctionName : platform_hw_timer_get_delay_ticks
* Description : figure out how long since th last timer interrupt
* Parameters : os_param_t owner
* Parameters : uint32_t owner
* Returns : the number of ticks
*******************************************************************************/
uint32_t ICACHE_RAM_ATTR platform_hw_timer_get_delay_ticks(os_param_t owner)
uint32_t ICACHE_RAM_ATTR platform_hw_timer_get_delay_ticks(uint32_t owner)
{
VERIFY_OWNER(owner);
@ -125,7 +125,7 @@ uint32_t ICACHE_RAM_ATTR platform_hw_timer_get_delay_ticks(os_param_t owner)
/******************************************************************************
* FunctionName : platform_hw_timer_init
* Description : initialize the hardware isr timer
* Parameters : os_param_t owner
* Parameters : uint32_t owner
* FRC1_TIMER_SOURCE_TYPE source_type:
* FRC1_SOURCE, timer use frc1 isr as isr source.
* NMI_SOURCE, timer use nmi isr as isr source.
@ -134,7 +134,7 @@ uint32_t ICACHE_RAM_ATTR platform_hw_timer_get_delay_ticks(os_param_t owner)
* 1, autoload mode,
* Returns : true if it worked
*******************************************************************************/
bool platform_hw_timer_init(os_param_t owner, FRC1_TIMER_SOURCE_TYPE source_type, bool autoload)
bool platform_hw_timer_init(uint32_t owner, FRC1_TIMER_SOURCE_TYPE source_type, bool autoload)
{
VERIFY_OWNER(owner);
if (autoload) {
@ -162,10 +162,10 @@ bool platform_hw_timer_init(os_param_t owner, FRC1_TIMER_SOURCE_TYPE source_type
/******************************************************************************
* FunctionName : platform_hw_timer_close
* Description : ends use of the hardware isr timer
* Parameters : os_param_t owner
* Parameters : uint32_t owner
* Returns : true if it worked
*******************************************************************************/
bool ICACHE_RAM_ATTR platform_hw_timer_close(os_param_t owner)
bool ICACHE_RAM_ATTR platform_hw_timer_close(uint32_t owner)
{
VERIFY_OWNER(owner);

View File

@ -20,17 +20,17 @@ typedef enum {
NMI_SOURCE = 1,
} FRC1_TIMER_SOURCE_TYPE;
bool ICACHE_RAM_ATTR platform_hw_timer_arm_ticks(os_param_t owner, uint32_t ticks);
bool ICACHE_RAM_ATTR platform_hw_timer_arm_ticks(uint32_t owner, uint32_t ticks);
bool ICACHE_RAM_ATTR platform_hw_timer_arm_us(os_param_t owner, uint32_t microseconds);
bool ICACHE_RAM_ATTR platform_hw_timer_arm_us(uint32_t owner, uint32_t microseconds);
bool platform_hw_timer_set_func(os_param_t owner, void (* user_hw_timer_cb_set)(os_param_t), os_param_t arg);
bool platform_hw_timer_set_func(uint32_t owner, void (* user_hw_timer_cb_set)(uint32_t), uint32_t arg);
bool platform_hw_timer_init(os_param_t owner, FRC1_TIMER_SOURCE_TYPE source_type, bool autoload);
bool platform_hw_timer_init(uint32_t owner, FRC1_TIMER_SOURCE_TYPE source_type, bool autoload);
bool ICACHE_RAM_ATTR platform_hw_timer_close(os_param_t owner);
bool ICACHE_RAM_ATTR platform_hw_timer_close(uint32_t owner);
uint32_t ICACHE_RAM_ATTR platform_hw_timer_get_delay_ticks(os_param_t owner);
uint32_t ICACHE_RAM_ATTR platform_hw_timer_get_delay_ticks(uint32_t owner);
#endif

View File

@ -17,6 +17,7 @@ typedef struct {
uint8 intr_type;
} pin_rec;
#define DECLARE_PIN(n,p) { (PERIPHS_IO_MUX_##p##_U - PERIPHS_IO_MUX), n, FUNC_GPIO##n, GPIO_PIN_INTR_DISABLE}
#if defined(__ESP8266__)
static const pin_rec pin_map[] = {
{PAD_XPD_DCDC_CONF - PERIPHS_IO_MUX, 16, 0, GPIO_PIN_INTR_DISABLE},
DECLARE_PIN( 5, GPIO5),
@ -32,6 +33,11 @@ static const pin_rec pin_map[] = {
DECLARE_PIN( 9, SD_DATA2),
DECLARE_PIN(10, SD_DATA3)
};
#elif defined(__ESP32__)
// FIXME: fill in
static const pin_rec pin_map[] = {};
#endif
void get_pin_map(void) {
/*
* Flash copy of the pin map. This has to be copied to RAM to be accessible from the ISR.

View File

@ -6,8 +6,14 @@
#include "user_config.h"
#include "gpio.h"
#define GPIO_PIN_NUM 13
#define GPIO_PIN_NUM_INV 17
#if defined(__ESP8266__)
# define GPIO_PIN_NUM 13
# define GPIO_PIN_NUM_INV 17
#elif defined (__ESP32__)
// FIXME: real numbers here...
# define GPIO_PIN_NUM 33
# define GPIO_PIN_NUM_INV 17
#endif
extern uint32_t pin_mux[GPIO_PIN_NUM];
extern uint8_t pin_num[GPIO_PIN_NUM];

View File

@ -42,6 +42,7 @@ int platform_init()
return PLATFORM_OK;
}
#ifdef __ESP2866__
// ****************************************************************************
// KEY_LED functions
uint8_t platform_key_led( uint8_t level){
@ -53,6 +54,7 @@ uint8_t platform_key_led( uint8_t level){
gpio16_output_set(level);
return temp;
}
#endif
// ****************************************************************************
// GPIO functions
@ -107,6 +109,7 @@ int platform_gpio_mode( unsigned pin, unsigned mode, unsigned pull )
if (pin >= NUM_GPIO)
return -1;
#ifdef __ESP8266__
if(pin == 0){
if(mode==PLATFORM_GPIO_INPUT)
gpio16_input_conf();
@ -115,6 +118,7 @@ int platform_gpio_mode( unsigned pin, unsigned mode, unsigned pull )
return 1;
}
#endif
#ifdef LUA_USE_MODULES_PWM
platform_pwm_close(pin); // closed from pwm module, if it is used in pwm
@ -156,11 +160,14 @@ int platform_gpio_write( unsigned pin, unsigned level )
// NODE_DBG("Function platform_gpio_write() is called. pin:%d, level:%d\n",GPIO_ID_PIN(pin_num[pin]),level);
if (pin >= NUM_GPIO)
return -1;
#ifdef __ESP8266__
if(pin == 0){
gpio16_output_conf();
gpio16_output_set(level);
return 1;
}
#endif
GPIO_OUTPUT_SET(GPIO_ID_PIN(pin_num[pin]), level);
}
@ -171,10 +178,12 @@ int platform_gpio_read( unsigned pin )
if (pin >= NUM_GPIO)
return -1;
#ifdef __ESP8266__
if(pin == 0){
// gpio16_input_conf();
return 0x1 & gpio16_input_get();
}
#endif
// GPIO_DIS_OUTPUT(pin_num[pin]);
return 0x1 & GPIO_INPUT_GET(GPIO_ID_PIN(pin_num[pin]));
@ -448,15 +457,20 @@ uint32_t platform_pwm_get_clock( unsigned pin )
// NODE_DBG("Function platform_pwm_get_clock() is called.\n");
if( pin >= NUM_PWM)
return 0;
#ifdef __ESP8266__ // FIXME
if(!pwm_exist(pin))
return 0;
return (uint32_t)pwm_get_freq(pin);
#else
return 0;
#endif
}
// Set the PWM clock
uint32_t platform_pwm_set_clock( unsigned pin, uint32_t clock )
{
#ifdef __ESP8266__ // FIXME
// NODE_DBG("Function platform_pwm_set_clock() is called.\n");
if( pin >= NUM_PWM)
return 0;
@ -466,10 +480,14 @@ uint32_t platform_pwm_set_clock( unsigned pin, uint32_t clock )
pwm_set_freq((uint16_t)clock, pin);
pwm_start();
return (uint32_t)pwm_get_freq( pin );
#else
return 0;
#endif
}
uint32_t platform_pwm_get_duty( unsigned pin )
{
#ifdef __ESP8266__ // FIXME
// NODE_DBG("Function platform_pwm_get_duty() is called.\n");
if( pin < NUM_PWM){
if(!pwm_exist(pin))
@ -477,12 +495,14 @@ uint32_t platform_pwm_get_duty( unsigned pin )
// return NORMAL_DUTY(pwm_get_duty(pin));
return pwms_duty[pin];
}
#endif
return 0;
}
// Set the PWM duty
uint32_t platform_pwm_set_duty( unsigned pin, uint32_t duty )
{
#ifdef __ESP8266__ // FIXME
// NODE_DBG("Function platform_pwm_set_duty() is called.\n");
if ( pin < NUM_PWM)
{
@ -494,12 +514,14 @@ uint32_t platform_pwm_set_duty( unsigned pin, uint32_t duty )
}
pwm_start();
pwms_duty[pin] = NORMAL_DUTY(pwm_get_duty(pin));
#endif
return pwms_duty[pin];
}
uint32_t platform_pwm_setup( unsigned pin, uint32_t frequency, unsigned duty )
{
uint32_t clock;
#ifdef __ESP8266__ // FIXME
if ( pin < NUM_PWM)
{
platform_gpio_mode(pin, PLATFORM_GPIO_OUTPUT, PLATFORM_GPIO_FLOAT); // disable gpio interrupt first
@ -516,6 +538,7 @@ uint32_t platform_pwm_setup( unsigned pin, uint32_t frequency, unsigned duty )
if (!pwm_start()) {
return 0;
}
#endif
return clock;
}
@ -524,13 +547,16 @@ void platform_pwm_close( unsigned pin )
// NODE_DBG("Function platform_pwm_stop() is called.\n");
if ( pin < NUM_PWM)
{
#ifdef __ESP8266__ // FIXME
pwm_delete(pin);
#endif
pwm_start();
}
}
bool platform_pwm_start( unsigned pin )
{
#ifdef __ESP8266__ // FIXME
// NODE_DBG("Function platform_pwm_start() is called.\n");
if ( pin < NUM_PWM)
{
@ -539,12 +565,13 @@ bool platform_pwm_start( unsigned pin )
pwm_set_duty(DUTY(pwms_duty[pin]), pin);
return pwm_start();
}
#endif
return FALSE;
}
void platform_pwm_stop( unsigned pin )
{
#ifdef __ESP8266__ // FIXME
// NODE_DBG("Function platform_pwm_stop() is called.\n");
if ( pin < NUM_PWM)
{
@ -553,6 +580,7 @@ void platform_pwm_stop( unsigned pin )
pwm_set_duty(0, pin);
pwm_start();
}
#endif
}
@ -561,6 +589,7 @@ void platform_pwm_stop( unsigned pin )
uint8_t platform_sigma_delta_setup( uint8_t pin )
{
#ifdef __ESP8266__ // FIXME
if (pin < 1 || pin > NUM_GPIO)
return 0;
@ -575,11 +604,13 @@ uint8_t platform_sigma_delta_setup( uint8_t pin )
(GPIO_REG_READ(GPIO_PIN_ADDR(GPIO_ID_PIN(pin_num[pin]))) &(~GPIO_PIN_SOURCE_MASK)) |
GPIO_PIN_SOURCE_SET( SIGMA_AS_PIN_SOURCE ));
#endif
return 1;
}
uint8_t platform_sigma_delta_close( uint8_t pin )
{
#ifdef __ESP8266__ // FIXME
if (pin < 1 || pin > NUM_GPIO)
return 0;
@ -593,11 +624,13 @@ uint8_t platform_sigma_delta_close( uint8_t pin )
(GPIO_REG_READ(GPIO_PIN_ADDR(GPIO_ID_PIN(pin_num[pin]))) &(~GPIO_PIN_SOURCE_MASK)) |
GPIO_PIN_SOURCE_SET( GPIO_AS_PIN_SOURCE ));
#endif
return 1;
}
void platform_sigma_delta_set_pwmduty( uint8_t duty )
{
#ifdef __ESP8266__ // FIXME
uint8_t target = 0, prescale = 0;
target = duty > 128 ? 256 - duty : duty;
@ -605,16 +638,21 @@ void platform_sigma_delta_set_pwmduty( uint8_t duty )
//freq = 80000 (khz) /256 /duty_target * (prescale+1)
sigma_delta_set_prescale_target( prescale, duty );
#endif
}
void platform_sigma_delta_set_prescale( uint8_t prescale )
{
#ifdef __ESP8266__ // FIXME
sigma_delta_set_prescale_target( prescale, -1 );
#endif
}
void platform_sigma_delta_set_target( uint8_t target )
{
#ifdef __ESP8266__ // FIXME
sigma_delta_set_prescale_target( -1, target );
#endif
}
@ -673,7 +711,9 @@ int platform_i2c_recv_byte( unsigned id, int ack ){
// SPI platform interface
uint32_t platform_spi_setup( uint8_t id, int mode, unsigned cpol, unsigned cpha, uint32_t clock_div)
{
#ifdef __ESP8266__ // FIXME
spi_master_init( id, cpol, cpha, clock_div );
#endif
return 1;
}
@ -682,7 +722,9 @@ int platform_spi_send( uint8_t id, uint8_t bitlen, spi_data_type data )
if (bitlen > 32)
return PLATFORM_ERR;
#ifdef __ESP8266__ // FIXME
spi_mast_transaction( id, 0, 0, bitlen, data, 0, 0, 0 );
#endif
return PLATFORM_OK;
}
@ -691,9 +733,13 @@ spi_data_type platform_spi_send_recv( uint8_t id, uint8_t bitlen, spi_data_type
if (bitlen > 32)
return 0;
#ifdef __ESP8266__ // FIXME
spi_mast_set_mosi( id, 0, bitlen, data );
spi_mast_transaction( id, 0, 0, 0, 0, bitlen, 0, -1 );
return spi_mast_get_miso( id, 0, bitlen );
#else
return 0;
#endif
}
int platform_spi_set_mosi( uint8_t id, uint16_t offset, uint8_t bitlen, spi_data_type data )
@ -701,8 +747,9 @@ int platform_spi_set_mosi( uint8_t id, uint16_t offset, uint8_t bitlen, spi_data
if (offset + bitlen > 512)
return PLATFORM_ERR;
#ifdef __ESP8266__ // FIXME
spi_mast_set_mosi( id, offset, bitlen, data );
#endif
return PLATFORM_OK;
}
@ -711,7 +758,11 @@ spi_data_type platform_spi_get_miso( uint8_t id, uint16_t offset, uint8_t bitlen
if (offset + bitlen > 512)
return 0;
#ifdef __ESP8266__ // FIXME
return spi_mast_get_miso( id, offset, bitlen );
#else
return 0;
#endif
}
int platform_spi_transaction( uint8_t id, uint8_t cmd_bitlen, spi_data_type cmd_data,
@ -725,7 +776,9 @@ int platform_spi_transaction( uint8_t id, uint8_t cmd_bitlen, spi_data_type cmd_
(miso_bitlen > 512))
return PLATFORM_ERR;
#ifdef __ESP8266__ // FIXME
spi_mast_transaction( id, cmd_bitlen, cmd_data, addr_bitlen, addr_data, mosi_bitlen, dummy_bitlen, miso_bitlen );
#endif
return PLATFORM_OK;
}
@ -808,6 +861,7 @@ int platform_flash_erase_sector( uint32_t sector_id )
uint32_t platform_flash_mapped2phys (uint32_t mapped_addr)
{
#ifdef __ESP8266__
uint32_t cache_ctrl = READ_PERI_REG(CACHE_FLASH_CTRL_REG);
if (!(cache_ctrl & CACHE_FLASH_ACTIVE))
return -1;
@ -815,4 +869,8 @@ uint32_t platform_flash_mapped2phys (uint32_t mapped_addr)
bool b1 = (cache_ctrl & CACHE_FLASH_MAPPED1) ? 1 : 0;
uint32_t meg = (b1 << 1) | b0;
return mapped_addr - INTERNAL_FLASH_MAPPED_ADDRESS + meg * 0x100000;
#else
// FIXME
return mapped_addr - INTERNAL_FLASH_MAPPED_ADDRESS;
#endif
}

View File

@ -3,7 +3,11 @@
#ifndef __PLATFORM_H__
#define __PLATFORM_H__
#include "cpu_esp8266.h"
#if defined(__ESP8266__)
# include "cpu_esp8266.h"
#elif defined(__ESP32__)
# include "cpu_esp32.h"
#endif
#include "c_types.h"
#include "driver/pwm.h"

View File

@ -2,8 +2,10 @@
#include <stdlib.h>
#include <string.h>
#include "user_interface.h"
#include "user_config.h"
#include "smart.h"
#include "esp_wifi.h"
#include "esp_libc.h"
#define ADDR_MAP_NUM 10

View File

@ -4,6 +4,8 @@
#include "task/task.h"
#include "mem.h"
#include "user_config.h"
#include <stdlib.h>
#include <string.h>
#include "freertos/queue.h"
#include "freertos/semphr.h"

View File

@ -31,6 +31,7 @@
* @author Johny Mattsson <jmattsson@dius.com.au>
*/
#ifdef __ESP8266__
/* Exception handler for supporting non-32bit wide loads from mapped SPI flash
* (well, technically any mapped memory that can do 32bit loads). Pure assembly
@ -57,7 +58,6 @@
* the load functionality.
*/
/* frame save area, a0->a15, but a1=>sar */
.section ".data"
.align 4
@ -199,3 +199,5 @@ _UserExceptionVectorOverride:
1:call0 cause3_handler /* handle loads with rfe, stores will return here */
2:rsr a0, EXCSAVE1 /* restore a0 before we chain */
j _UserExceptionVector /* and off we go to rtos */
#endif

View File

@ -32,6 +32,14 @@
#define SIG_LUA 0
#define SIG_UARTINPUT 1
#ifdef __ESP32__
void system_soft_wdt_feed (void)
{
// FIXME this shouldn't go here, and it needs to tickle hardware watchdog
}
#endif
extern void call_user_start (void);

View File

@ -38,6 +38,7 @@
* have a minimal replacement printf() which omits the explicit flash-support
* support, and just calls the internal SDK function print() directly.
*/
#ifdef __ESP8266__
.section ".iram0.text"
.type __wrap_printf,@function
.globl __wrap_printf
@ -67,6 +68,7 @@ __wrap_printf:
l32i a0, a1, 0 /* restore return address into a0 */
addi a1, a1, 48 /* release the stack */
ret /* all done */
#endif
/* Flag for controlling whether SDK printf()s are suppressed or not.
* This is to provide an RTOS-safe reimplementation of system_set_os_print(). */

1
esp32-rtos-sdk Submodule

@ -0,0 +1 @@
Subproject commit 8a83c7b706eecf80236a441b15bc2f80799ced78

294
ld/nodemcu32.ld Normal file
View File

@ -0,0 +1,294 @@
/* boot.bin @ 0x00000 */
/* drom0.bin @ 0xX4000 */
/* irom0_flash.bin @ 0xX0000+0x40000 */
/* Flash Map */
/* |..|...............|...........................................|..| */
/* ^ ^ ^ ^ */
/* |_boot.bin(0x0000) |_irom0_flash.bin(0xX0000+0x40000) | */
/* |_drom0.bin(0xX4000) |_system param area(Flash size - 0x4000) */
/* RAM Map */
/* Pro CPU iRAM, Total len 0x28000 */
/* |......................................................| */
/* ^ */
/* |_iram1_0 : 0x40040000 (0x20000) */
/* |........| */
/* ^ */
/* |_cache for Pro CPU : (0x8000) */
/* Share Memory, Total len 0x28000 */
/* |..........| */
/* ^ */
/* |_dram0_0 : 0x3FFD8000 (dynamic len) */
/* |................................................| */
/* ^ */
/* |_ heap area */
/* |.....| */
/* ^ */
/* |_ used for Pro CPU's rom code : 0x3FFFC000 (0x4000) */
/* NOTICE: */
/* 1. drom0.bin + irom0_flash.bin = user.ota */
/* 2. drom0.bin and irom0_flash.bin must locate at 0xX4000 and 0xX0000+0x40000, */
/* here 0xX0000 must 256KB align. */
/* 3. Make sure each user.ota not overlap other. */
/* 4. Make sure each user.ota not overlap system param area or user param area. */
/* 5. We support a maximum of 5 user.ota */
/* 6. We support 1MB/2MB/4MB/8MB/16MB flash, */
/* but make suer user.ota not exceed 16MB. */
/* 7. rodata at drom0_0, drom0.bin. */
/* 8. Pay attention to any modification. */
MEMORY
{
dport0_0_seg : org = 0x3FF00000, len = 0x10
dram0_0_seg : org = 0x3FFD8000, len = 0x24000
iram1_0_seg : org = 0x40040000, len = 0x20000
irom0_0_seg : org = 0x40080010, len = 0x37FFF0
drom0_0_seg : org = 0x3FE04010, len = 0x3BFF0
}
PHDRS
{
dport0_0_phdr PT_LOAD;
dram0_0_phdr PT_LOAD;
iram1_0_phdr PT_LOAD;
irom0_0_phdr PT_LOAD;
drom0_0_phdr PT_LOAD;
}
/* Default entry point: */
ENTRY(call_user_start)
EXTERN(_Level2Vector)
EXTERN(_Level3Vector)
EXTERN(_Level4Vector)
EXTERN(_Level5Vector)
EXTERN(_DebugExceptionVector)
EXTERN(_NMIExceptionVector)
EXTERN(_KernelExceptionVector)
EXTERN(_DoubleExceptionVector)
PROVIDE(_memmap_vecbase_reset = 0x40000000);
/* Various memory-map dependent cache attribute settings: */
_memmap_cacheattr_wb_base = 0x00000110;
_memmap_cacheattr_wt_base = 0x00000110;
_memmap_cacheattr_bp_base = 0x00000220;
_memmap_cacheattr_unused_mask = 0xFFFFF00F;
_memmap_cacheattr_wb_trapnull = 0x2222211F;
_memmap_cacheattr_wba_trapnull = 0x2222211F;
_memmap_cacheattr_wbna_trapnull = 0x2222211F;
_memmap_cacheattr_wt_trapnull = 0x2222211F;
_memmap_cacheattr_bp_trapnull = 0x2222222F;
_memmap_cacheattr_wb_strict = 0xFFFFF11F;
_memmap_cacheattr_wt_strict = 0xFFFFF11F;
_memmap_cacheattr_bp_strict = 0xFFFFF22F;
_memmap_cacheattr_wb_allvalid = 0x22222112;
_memmap_cacheattr_wt_allvalid = 0x22222112;
_memmap_cacheattr_bp_allvalid = 0x22222222;
PROVIDE(_memmap_cacheattr_reset = _memmap_cacheattr_wb_trapnull);
SECTIONS
{
.dport0.rodata : ALIGN(4)
{
_dport0_rodata_start = ABSOLUTE(.);
*(.dport0.rodata)
*(.dport.rodata)
_dport0_rodata_end = ABSOLUTE(.);
} >dport0_0_seg :dport0_0_phdr
.dport0.literal : ALIGN(4)
{
_dport0_literal_start = ABSOLUTE(.);
*(.dport0.literal)
*(.dport.literal)
_dport0_literal_end = ABSOLUTE(.);
} >dport0_0_seg :dport0_0_phdr
.dport0.data : ALIGN(4)
{
_dport0_data_start = ABSOLUTE(.);
*(.dport0.data)
*(.dport.data)
_dport0_data_end = ABSOLUTE(.);
} >dport0_0_seg :dport0_0_phdr
.drom0.text : ALIGN(4)
{
_drom0_text_start = ABSOLUTE(.);
*(.drom0.literal .drom0.text.literal .drom0.text)
*(.rodata*)
_drom0_text_end = ABSOLUTE(.);
} >drom0_0_seg :drom0_0_phdr
.data : ALIGN(4)
{
_data_start = ABSOLUTE(.);
*(.data)
*(.data.*)
*(.gnu.linkonce.d.*)
*(.data1)
*(.sdata)
*(.sdata.*)
*(.gnu.linkonce.s.*)
*(.sdata2)
*(.sdata2.*)
*(.gnu.linkonce.s2.*)
*(.jcr)
_data_end = ABSOLUTE(.);
} >dram0_0_seg :dram0_0_phdr
.rodata : ALIGN(4)
{
_rodata_start = ABSOLUTE(.);
*(.gnu.linkonce.r.*)
__XT_EXCEPTION_TABLE__ = ABSOLUTE(.);
*(.xt_except_table)
*(.gcc_except_table)
*(.gnu.linkonce.e.*)
*(.gnu.version_r)
*(.eh_frame)
. = (. + 3) & ~ 3;
/* C++ constructor and destructor tables, properly ordered: */
__init_array_start = ABSOLUTE(.);
KEEP (*crtbegin.o(.ctors))
KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors))
KEEP (*(SORT(.ctors.*)))
KEEP (*(.ctors))
__init_array_end = ABSOLUTE(.);
KEEP (*crtbegin.o(.dtors))
KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors))
KEEP (*(SORT(.dtors.*)))
KEEP (*(.dtors))
/* C++ exception handlers table: */
__XT_EXCEPTION_DESCS__ = ABSOLUTE(.);
*(.xt_except_desc)
*(.gnu.linkonce.h.*)
__XT_EXCEPTION_DESCS_END__ = ABSOLUTE(.);
*(.xt_except_desc_end)
*(.dynamic)
*(.gnu.version_d)
. = ALIGN(4); /* this table MUST be 4-byte aligned */
_bss_table_start = ABSOLUTE(.);
LONG(_bss_start)
LONG(_bss_end)
_bss_table_end = ABSOLUTE(.);
_rodata_end = ABSOLUTE(.);
} >dram0_0_seg :dram0_0_phdr
.UserExceptionVector.literal : AT(LOADADDR(.rodata) + (ADDR(.UserExceptionVector.literal) - ADDR(.rodata))) ALIGN(4)
{
_UserExceptionVector_literal_start = ABSOLUTE(.);
*(.UserExceptionVector.literal)
_UserExceptionVector_literal_end = ABSOLUTE(.);
} >dram0_0_seg :dram0_0_phdr
.bss ALIGN(8) (NOLOAD) : ALIGN(4)
{
. = ALIGN (8);
_bss_start = ABSOLUTE(.);
*(.dynsbss)
*(.sbss)
*(.sbss.*)
*(.gnu.linkonce.sb.*)
*(.scommon)
*(.sbss2)
*(.sbss2.*)
*(.gnu.linkonce.sb2.*)
*(.dynbss)
*(.bss)
*(.bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
. = ALIGN (8);
_bss_end = ABSOLUTE(.);
} >dram0_0_seg :dram0_0_phdr
.share.mem (NOLOAD) : ALIGN(4)
{
_share_mem_start = ABSOLUTE(.);
*(.share.mem)
_share_mem_end = ABSOLUTE(.);
_heap_sentry = ABSOLUTE(.);
} >dram0_0_seg :dram0_0_phdr
_end = 0x3fffc000;
.text : ALIGN(4)
{
_stext = .;
_text_start = ABSOLUTE(.);
. = 0x0;
*(.WindowVectors.text)
. = 0x180;
*(.Level2InterruptVector.text)
. = 0x1c0;
*(.Level3InterruptVector.text)
. = 0x200;
*(.Level4InterruptVector.text)
. = 0x240;
*(.Level5InterruptVector.text)
. = 0x280;
*(.DebugExceptionVector.text)
. = 0x2c0;
*(.NMIExceptionVector.text)
. = 0x300;
*(.KernelExceptionVector.text)
. = 0x340;
*(.UserExceptionVector.text)
. = 0x3c0;
*(.DoubleExceptionVector.text)
. = 0x400;
*(.UserEnter.literal);
*(.UserEnter.text);
. = ALIGN (16);
*(.entry.text)
*(.init.literal)
*(.init)
*(.iram1.*)
*libmain.a:(.literal .text .literal.* .text.*)
*libfreertos.a:(.literal .text .literal.* .text.*)
*libpp.a:(.literal .text .literal.* .text.*)
*(.stub .gnu.warning .gnu.linkonce.literal.* .gnu.linkonce.t.*.literal .gnu.linkonce.t.*)
*(.fini.literal)
*(.fini)
*(.gnu.version)
_text_end = ABSOLUTE(.);
_etext = .;
} >iram1_0_seg :iram1_0_phdr
.irom0.text : ALIGN(4)
{
_irom0_text_start = ABSOLUTE(.);
*(.irom0.literal .irom.literal .irom.text.literal .irom0.text .irom.text)
*(.literal .text .literal.* .text.*)
/* Link-time arrays containing the defs for the included modules */
. = ALIGN(4);
lua_libs = ABSOLUTE(.);
/* Allow either empty define or defined-to-1 to include the module */
KEEP(*(.lua_libs))
LONG(0) LONG(0) /* Null-terminate the array */
lua_rotable = ABSOLUTE(.);
KEEP(*(.lua_rotable))
LONG(0) LONG(0) /* Null-terminate the array */
_irom0_text_end = ABSOLUTE(.);
_flash_used_end = ABSOLUTE(.);
} >irom0_0_seg :irom0_0_phdr
.lit4 : ALIGN(4)
{
_lit4_start = ABSOLUTE(.);
*(*.lit4)
*(.lit4.*)
*(.gnu.linkonce.lit4.*)
_lit4_end = ABSOLUTE(.);
} >iram1_0_seg :iram1_0_phdr
}
INCLUDE "pro.rom.addr.ld"

View File

@ -0,0 +1,4 @@
#ifndef _SDK_OVERRIDES_ESP_LIBC_H_
#define _SDK_OVERRIDES_ESP_LIBC_H_
void *zalloc(size_t n);
#endif

View File

@ -0,0 +1 @@
../../esp32-rtos-sdk/include

View File

@ -0,0 +1,27 @@
#ifndef _SDK_OVERRIDES_ETS_SYS_H_
#define _SDK_OVERRIDES_ETS_SYS_H_
#include_next <ets_sys.h>
#include <freertos/xtensa_api.h>
#define ETS_UART_INTR_ATTACH(fn,arg) xt_set_interrupt_handler(ETS_UART_INUM, fn, arg)
#define ETS_UART_INTR_ENABLE() xt_ints_on(1 << ETS_UART_INUM)
#define ETS_UART_INTR_DISABLE() xt_ints_off(1 << ETS_UART_INUM)
#define ETS_SPI_INTR_ATTACH(fn,arg) xt_set_interrupt_handler(ETS_SPI_INUM, fn, arg)
#define ETS_SPI_INTR_ENABLE() xt_ints_on(1 << ETS_SPI_INUM)
#define ETS_SPI_INTR_DISABLE() xt_ints_off(1 << ETS_SPI_INUM)
#define ETS_GPIO_INTR_ATTACH(fn,arg) xt_set_interrupt_handler(ETS_GPIO_INUM, fn, arg)
#define ETS_GPIO_INTR_ENABLE() xt_ints_on(1 << ETS_GPIO_INUM)
#define ETS_GPIO_INTR_DISABLE() xt_ints_off(1 << ETS_GPIO_INUM)
#define ETS_FRC_TIMER1_INTR_ATTACH(fn,arg) xt_set_interrupt_handler(ETS_FRC_TIMER1_INUM, fn, arg)
#define ETS_FRC1_INTR_ENABLE() xt_ints_on(1 << ETS_FRC_TIMER1_INUM)
#define ETS_FRC1_INTR_DISABLE() xt_ints_off(1 << ETS_FRC_TIMER1_INUM)
// FIXME: double-check this is the correct bit!
#define TM1_EDGE_INT_ENABLE() SET_PERI_REG_MASK(EDGE_INT_ENABLE_REG, BIT1)
#define TM1_EDGE_INT_DISABLE() CLEAR_PERI_REG_MASK(EDGE_INT_ENABLE_REG, BIT1)
#endif

View File

@ -0,0 +1,17 @@
#ifndef _SDK_OVERRIDES_GPIO_H_
#define _SDK_OVERRIDES_GPIO_H_
#include_next <gpio.h>
#define GPIO_STATUS_W1TC_ADDRESS GPIO_STATUS_W1TC
#define GPIO_STATUS_ADDRESS GPIO_STATUS
#define GPIO_OUT_W1TS_ADDRESS GPIO_OUT_W1TS
#define GPIO_OUT_W1TC_ADDRESS GPIO_OUT_W1TC
#define GPIO_ENABLE_W1TC_ADDRESS GPIO_ENABLE_W1TC
#define GPIO_ENABLE_ADDRESS GPIO_ENABLE
// FIXME: how does this apply to the ESP32?
#define GPIO_PIN_SOURCE_SET(x) 0
#define GPIO_PIN_SOURCE_MASK 0
#endif

View File

@ -5,14 +5,8 @@
#include "os_type.h"
#include "espressif/esp_timer.h"
// FIXME, these need to change/go together with the task implementation
typedef uint32_t os_signal_t;
typedef uint32_t os_event_t;
typedef uint32_t os_param_t;
#include "freertos/portmacro.h"
#include_next "esp8266/ets_sys.h"
#include_next "ets_sys.h"
#define ets_vsprintf vsprintf

View File

@ -2,7 +2,7 @@
#define _SDK_OVERRIDE_EAGLE_SOC_H_
#include_next "esp8266/eagle_soc.h"
#include_next "eagle_soc.h"
#define GPIO_AS_PIN_SOURCE 0
#define SIGMA_AS_PIN_SOURCE (~GPIO_AS_PIN_SOURCE)

View File

@ -1,5 +1,5 @@
#ifndef _SDK_OVERRIDES_OS_TYPE_H_
#define _SDK_OVERRIDES_OS_TYPE_H_
#define ETSTimer os_timer_t
#define ETSTimerFunc os_timer_func_t
//#define ETSTimer os_timer_t
//#define ETSTimerFunc os_timer_func_t
#endif

View File

@ -1,7 +1,7 @@
#ifndef _SDK_OVERRIDE_OSAPI_H_
#define _SDK_OVERRIDE_OSAPI_H_
#include "rom.h"
#include "user_interface.h"
#include "user_config.h"
void call_user_start(void);

View File

@ -1,14 +1,25 @@
#ifndef SDK_OVERRIDES_INCLUDE_USER_INTERFACE_H_
#define SDK_OVERRIDES_INCLUDE_USER_INTERFACE_H_
#define ets_timer_arm_new(tmr, ms, rpt, isms) os_timer_arm(tmr,ms,rpt)
#include <espressif/esp_system.h>
#include "espressif/esp_system.h"
#include "espressif/esp_misc.h"
#include "espressif/esp_wifi.h"
#include "espressif/esp_sta.h"
#include "espressif/esp_softap.h"
#include "espressif/esp_timer.h"
/* The SDKs claim ets_delay_us only takes a uint16_t, not a uint32_t. Until
* we have cleaned up our act and stopped using excessive hard-delays, we
* need our own prototype for it.
*
* Also, our ets_printf() prototype is better.
*/
#define ets_delay_us ets_delay_us_sdk
#define ets_printf ets_print_sdk
#include <espressif/esp_misc.h>
#undef ets_printf
#undef ets_delay_us
#include "rom.h"
#include <espressif/esp_wifi.h>
#include <espressif/esp_sta.h>
#include <espressif/esp_softap.h>
#include <espressif/esp_timer.h>
static inline void system_set_os_print(uint8_t onoff) {
extern uint8_t os_printf_enabled;