summaryrefslogtreecommitdiffstatshomepage
path: root/esp8266
diff options
context:
space:
mode:
Diffstat (limited to 'esp8266')
-rw-r--r--esp8266/Makefile35
-rw-r--r--esp8266/README.md10
-rw-r--r--esp8266/axtls_helpers.c66
-rw-r--r--esp8266/eagle.rom.addr.v6.ld16
-rw-r--r--esp8266/esp8266.ld2
-rw-r--r--esp8266/esp_mphal.c64
-rw-r--r--esp8266/esp_mphal.h26
-rw-r--r--esp8266/esponewire.c99
-rw-r--r--esp8266/esponewire.h (renamed from esp8266/utils.c)34
-rw-r--r--esp8266/etshal.h4
-rw-r--r--esp8266/help.c70
-rw-r--r--esp8266/intr.c (renamed from esp8266/utils.h)18
-rw-r--r--esp8266/main.c4
-rw-r--r--esp8266/modesp.c44
-rw-r--r--esp8266/modmachine.c62
-rw-r--r--esp8266/modnetwork.c170
-rw-r--r--esp8266/modonewire.c77
-rw-r--r--esp8266/modpyb.c85
-rw-r--r--esp8266/modpyb.h18
-rw-r--r--esp8266/modpybi2c.c323
-rw-r--r--esp8266/modpybpin.c206
-rw-r--r--esp8266/modpybpwm.c2
-rw-r--r--esp8266/modpybrtc.c48
-rw-r--r--esp8266/modpybrtc.h3
-rw-r--r--esp8266/modpybspi.c34
-rw-r--r--esp8266/modpybuart.c75
-rw-r--r--esp8266/moduos.c16
-rw-r--r--esp8266/mpconfigport.h16
-rw-r--r--esp8266/qstrdefsport.h198
-rw-r--r--esp8266/scripts/_boot.py9
-rw-r--r--esp8266/scripts/flashbdev.py68
-rw-r--r--esp8266/scripts/inisetup.py46
-rw-r--r--esp8266/scripts/main.py1
-rw-r--r--esp8266/scripts/neopixel.py24
-rw-r--r--esp8266/scripts/ntptime.py34
-rw-r--r--esp8266/scripts/onewire.py (renamed from esp8266/tests/onewire.py)110
-rw-r--r--esp8266/scripts/port_diag.py19
-rw-r--r--esp8266/scripts/webrepl.py62
-rw-r--r--esp8266/scripts/webrepl_setup.py80
-rw-r--r--esp8266/scripts/websocket_helper.py75
-rw-r--r--esp8266/tests/neopixel.py64
-rw-r--r--esp8266/uart.c50
-rw-r--r--esp8266/uart.h2
43 files changed, 1451 insertions, 1018 deletions
diff --git a/esp8266/Makefile b/esp8266/Makefile
index d6ab96974d..d8786301a8 100644
--- a/esp8266/Makefile
+++ b/esp8266/Makefile
@@ -3,6 +3,8 @@ include ../py/mkenv.mk
# qstr definitions (must come before including py.mk)
QSTR_DEFS = qstrdefsport.h #$(BUILD)/pins_qstr.h
+MICROPY_PY_USSL = 1
+
# include py core make definitions
include ../py/py.mk
@@ -30,14 +32,14 @@ UART_OS = 0
CFLAGS_XTENSA = -fsingle-precision-constant -Wdouble-promotion \
-D__ets__ -DICACHE_FLASH \
-fno-inline-functions \
- -Wl,-EL -mlongcalls -mtext-section-literals \
+ -Wl,-EL -mlongcalls -mtext-section-literals -mforce-l32 \
-DLWIP_OPEN_SRC
CFLAGS = $(INC) -Wall -Wpointer-arith -Werror -ansi -std=gnu99 -nostdlib -DUART_OS=$(UART_OS) \
- $(CFLAGS_XTENSA) $(COPT) $(CFLAGS_EXTRA)
+ $(CFLAGS_XTENSA) $(CFLAGS_MOD) $(COPT) $(CFLAGS_EXTRA)
LDFLAGS = -nostdlib -T esp8266.ld -Map=$(@:.elf=.map) --cref
-LIBS = -L$(ESP_SDK)/lib -lmain -ljson -lssl -llwip_open -lpp -lnet80211 -lwpa -lphy -lnet80211
+LIBS = -L$(ESP_SDK)/lib -lmain -ljson -llwip_open -lpp -lnet80211 -lwpa -lphy -lnet80211 $(LDFLAGS_MOD)
LIBGCC_FILE_NAME = $(shell $(CC) $(CFLAGS) -print-libgcc-file-name)
LIBS += -L$(dir $(LIBGCC_FILE_NAME)) -lgcc
@@ -48,26 +50,28 @@ CFLAGS += -g
COPT = -O0
else
CFLAGS += -fdata-sections -ffunction-sections
-COPT += -Os -mforce-l32 -DNDEBUG
+COPT += -Os -DNDEBUG
LDFLAGS += --gc-sections
endif
SRC_C = \
strtoll.c \
main.c \
+ help.c \
esp_mphal.c \
gccollect.c \
lexerstr32.c \
uart.c \
esppwm.c \
+ esponewire.c \
espneopixel.c \
+ intr.c \
modpyb.c \
modpybpin.c \
modpybpwm.c \
modpybrtc.c \
modpybadc.c \
modpybuart.c \
- modpybi2c.c \
modpybspi.c \
modesp.c \
modnetwork.c \
@@ -75,17 +79,18 @@ SRC_C = \
moduos.c \
modmachine.c \
modonewire.c \
- utils.c \
ets_alt_task.c \
$(BUILD)/frozen.c \
- fatfs_port.o \
+ fatfs_port.c \
+ axtls_helpers.c \
STM_SRC_C = $(addprefix stmhal/,\
pybstdio.c \
+ input.c \
)
EXTMOD_SRC_C = $(addprefix extmod/,\
- modlwip.o \
+ modlwip.c \
)
LIB_SRC_C = $(addprefix lib/,\
@@ -112,6 +117,7 @@ LIB_SRC_C = $(addprefix lib/,\
netutils/netutils.c \
timeutils/timeutils.c \
utils/pyexec.c \
+ utils/pyhelp.c \
utils/printf.c \
fatfs/ff.c \
fatfs/option/ccsbcs.c \
@@ -129,6 +135,11 @@ OBJ += $(addprefix $(BUILD)/, $(EXTMOD_SRC_C:.c=.o))
OBJ += $(addprefix $(BUILD)/, $(LIB_SRC_C:.c=.o))
#OBJ += $(BUILD)/pins_$(BOARD).o
+# List of sources for qstr extraction
+SRC_QSTR += $(SRC_C) $(STM_SRC_C) $(EXTMOD_SRC_C)
+# Append any auto-generated sources that are needed by sources listed in SRC_QSTR
+SRC_QSTR_AUTO_DEPS +=
+
all: $(BUILD)/firmware-combined.bin
CONFVARS_FILE = $(BUILD)/confvars
@@ -154,7 +165,7 @@ deploy: $(BUILD)/firmware-combined.bin
#$(Q)esptool.py --port $(PORT) --baud $(BAUD) write_flash --flash_size=8m 0 $(BUILD)/firmware.elf-0x00000.bin 0x9000 $(BUILD)/firmware.elf-0x0[1-f]000.bin
reset:
- echo -e "\r\nimport pyb; pyb.hard_reset()\r\n" >$(PORT)
+ echo -e "\r\nimport machine; machine.reset()\r\n" >$(PORT)
$(BUILD)/firmware-combined.bin: $(BUILD)/firmware.elf
$(ECHO) "Create $@"
@@ -193,3 +204,9 @@ $(BUILD)/firmware.elf: $(OBJ)
# $(call compile_c)
include ../py/mkrules.mk
+
+axtls:
+ cd ../lib/axtls; cp config/upyconfig config/.config
+ cd ../lib/axtls; make oldconfig -B
+ cd ../lib/axtls; make clean
+ cd ../lib/axtls; make all CC="$(CC)" LD="$(LD)" AR="$(AR)" CFLAGS_EXTRA="$(CFLAGS_XTENSA) -Dabort=abort_ -DRT_MAX_PLAIN_LENGTH=1024 -DRT_EXTRA=3072"
diff --git a/esp8266/README.md b/esp8266/README.md
index 3518cedd54..e187d4da17 100644
--- a/esp8266/README.md
+++ b/esp8266/README.md
@@ -13,15 +13,12 @@ Currently implemented features include:
- Builtin modules: gc, array, collections, io, struct, sys, esp, network,
many more.
- Arbitrary-precision long integers and 30-bit precision floats.
-- Basic WiFi support.
+- WiFi support.
- Sockets using modlwip.
- GPIO and bit-banging I2C, SPI support.
- 1-Wire and WS2812 (aka Neopixel) protocols support.
-
-On the TODO list:
-- Full wifi support.
- Internal filesystem using the flash.
-- ...
+- WebREPL over WiFi from a browser (clients at https://github.com/micropython/webrepl).
Work-in-progress documentation is available at
http://docs.micropython.org/en/latest/esp8266/ .
@@ -45,6 +42,7 @@ dependencies.
Then, to build MicroPython for the ESP8266, just run:
```bash
$ cd esp8266
+$ make axtls
$ make
```
This will produce binary images in the `build/` subdirectory. If you install
@@ -52,7 +50,7 @@ MicroPython to your module for the first time, or after installing any other
firmware, you should erase flash completely:
```
-esptool.py --port /dev//ttyXXX erase_flash
+esptool.py --port /dev/ttyXXX erase_flash
```
Erase flash also as a troubleshooting measure, if a module doesn't behave as
diff --git a/esp8266/axtls_helpers.c b/esp8266/axtls_helpers.c
new file mode 100644
index 0000000000..097d9ed4c3
--- /dev/null
+++ b/esp8266/axtls_helpers.c
@@ -0,0 +1,66 @@
+/*
+ * This file is part of the MicroPython project, http://micropython.org/
+ *
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2016 Paul Sokolovsky
+ *
+ * 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 <stdint.h>
+#include <stdio.h>
+#include "py/mphal.h"
+#include "py/gc.h"
+
+// Functions for axTLS
+
+void *malloc(size_t size) {
+ return gc_alloc(size, false);
+}
+void free(void *ptr) {
+ gc_free(ptr);
+}
+void *calloc(size_t nmemb, size_t size) {
+ return m_malloc0(nmemb * size);
+}
+void *realloc(void *ptr, size_t size) {
+ return gc_realloc(ptr, size, true);
+}
+void abort_(void) {
+ printf("Aborted\n");
+}
+
+#define PLATFORM_HTONL(_n) ((uint32_t)( (((_n) & 0xff) << 24) | (((_n) & 0xff00) << 8) | (((_n) >> 8) & 0xff00) | (((_n) >> 24) & 0xff) ))
+#undef htonl
+#undef ntohl
+uint32_t ntohl(uint32_t netlong) {
+ return PLATFORM_HTONL(netlong);
+}
+uint32_t htonl(uint32_t netlong) {
+ return PLATFORM_HTONL(netlong);
+}
+
+time_t time(time_t *t) {
+ return mp_hal_ticks_ms() / 1000;
+}
+
+time_t mktime(void *tm) {
+ return 0;
+}
diff --git a/esp8266/eagle.rom.addr.v6.ld b/esp8266/eagle.rom.addr.v6.ld
index 80e03922bb..30e238f5a5 100644
--- a/esp8266/eagle.rom.addr.v6.ld
+++ b/esp8266/eagle.rom.addr.v6.ld
@@ -50,8 +50,8 @@ PROVIDE ( _UserExceptionVector = 0x40000050 );
PROVIDE ( __adddf3 = 0x4000c538 );
PROVIDE ( __addsf3 = 0x4000c180 );
PROVIDE ( __divdf3 = 0x4000cb94 );
-PROVIDE ( __divdi3 = 0x4000ce60 );
-PROVIDE ( __divsi3 = 0x4000dc88 );
+__divdi3 = 0x4000ce60;
+__divsi3 = 0x4000dc88;
PROVIDE ( __extendsfdf2 = 0x4000cdfc );
PROVIDE ( __fixdfsi = 0x4000ccb8 );
PROVIDE ( __fixunsdfsi = 0x4000cd00 );
@@ -61,16 +61,16 @@ PROVIDE ( __floatsisf = 0x4000e2ac );
PROVIDE ( __floatunsidf = 0x4000e2e8 );
PROVIDE ( __floatunsisf = 0x4000e2a4 );
PROVIDE ( __muldf3 = 0x4000c8f0 );
-PROVIDE ( __muldi3 = 0x40000650 );
+__muldi3 = 0x40000650;
PROVIDE ( __mulsf3 = 0x4000c3dc );
PROVIDE ( __subdf3 = 0x4000c688 );
PROVIDE ( __subsf3 = 0x4000c268 );
PROVIDE ( __truncdfsf2 = 0x4000cd5c );
-PROVIDE ( __udivdi3 = 0x4000d310 );
-PROVIDE ( __udivsi3 = 0x4000e21c );
-PROVIDE ( __umoddi3 = 0x4000d770 );
-PROVIDE ( __umodsi3 = 0x4000e268 );
-PROVIDE ( __umulsidi3 = 0x4000dcf0 );
+__udivdi3 = 0x4000d310;
+__udivsi3 = 0x4000e21c;
+__umoddi3 = 0x4000d770;
+__umodsi3 = 0x4000e268;
+__umulsidi3 = 0x4000dcf0;
PROVIDE ( _rom_store = 0x4000e388 );
PROVIDE ( _rom_store_table = 0x4000e328 );
PROVIDE ( _start = 0x4000042c );
diff --git a/esp8266/esp8266.ld b/esp8266/esp8266.ld
index 2c38e1c82d..79bdf87f71 100644
--- a/esp8266/esp8266.ld
+++ b/esp8266/esp8266.ld
@@ -120,6 +120,7 @@ SECTIONS
*extmod/*.o*(.literal* .text*)
*lib/fatfs/*.o*(.literal*, .text*)
+ */libaxtls.a:(.literal*, .text*)
*lib/libm/*.o*(.literal*, .text*)
*lib/mp-readline/*.o(.literal*, .text*)
*lib/netutils/*.o*(.literal*, .text*)
@@ -146,6 +147,7 @@ SECTIONS
*modutime.o(.literal* .text*)
*modlwip.o(.literal* .text*)
*modsocket.o(.literal* .text*)
+ *modonewire.o(.literal* .text*)
/* we put as much rodata as possible in this section */
/* note that only rodata accessed as a machine word is allowed here */
diff --git a/esp8266/esp_mphal.c b/esp8266/esp_mphal.c
index 2f813ca22f..25f1a9322f 100644
--- a/esp8266/esp_mphal.c
+++ b/esp8266/esp_mphal.c
@@ -51,12 +51,6 @@ void mp_hal_init(void) {
uart_init(UART_BIT_RATE_115200, UART_BIT_RATE_115200);
}
-void mp_hal_feed_watchdog(void) {
- //ets_wdt_disable(); // it's a pain while developing
- //WRITE_PERI_REG(0x60000914, 0x73);
- //wdt_feed(); // might also work
-}
-
void mp_hal_delay_us(uint32_t us) {
uint32_t start = system_get_time();
while (system_get_time() - start < us) {
@@ -71,7 +65,6 @@ int mp_hal_stdin_rx_chr(void) {
return c;
}
mp_hal_delay_us(1);
- mp_hal_feed_watchdog();
}
}
@@ -178,25 +171,27 @@ static int call_dupterm_read(void) {
mp_buffer_info_t bufinfo;
mp_get_buffer_raise(res, &bufinfo, MP_BUFFER_READ);
if (bufinfo.len == 0) {
- mp_printf(&mp_plat_print, "dupterm: EOF received, deactivating\n");
MP_STATE_PORT(term_obj) = NULL;
+ mp_printf(&mp_plat_print, "dupterm: EOF received, deactivating\n");
return -1;
}
nlr_pop();
return *(byte*)bufinfo.buf;
} else {
- // Temporarily disable dupterm to avoid infinite recursion
- mp_obj_t save_term = MP_STATE_PORT(term_obj);
MP_STATE_PORT(term_obj) = NULL;
- mp_printf(&mp_plat_print, "dupterm: ");
+ mp_printf(&mp_plat_print, "dupterm: Exception in read() method, deactivating: ");
mp_obj_print_exception(&mp_plat_print, nlr.ret_val);
- MP_STATE_PORT(term_obj) = save_term;
}
return -1;
}
STATIC void dupterm_task_handler(os_event_t *evt) {
+ static byte lock;
+ if (lock) {
+ return;
+ }
+ lock = 1;
while (1) {
int c = call_dupterm_read();
if (c < 0) {
@@ -205,6 +200,7 @@ STATIC void dupterm_task_handler(os_event_t *evt) {
ringbuf_put(&input_buf, c);
}
mp_hal_signal_input();
+ lock = 0;
}
STATIC os_event_t dupterm_evt_queue[4];
@@ -216,3 +212,47 @@ void dupterm_task_init() {
void mp_hal_signal_dupterm_input(void) {
system_os_post(DUPTERM_TASK_ID, 0, 0);
}
+
+void mp_hal_pin_config_od(mp_hal_pin_obj_t pin_id) {
+ const pyb_pin_obj_t *pin = &pyb_pin_obj[pin_id];
+
+ if (pin->phys_port == 16) {
+ // configure GPIO16 as input with output register holding 0
+ WRITE_PERI_REG(PAD_XPD_DCDC_CONF, (READ_PERI_REG(PAD_XPD_DCDC_CONF) & 0xffffffbc) | 1);
+ WRITE_PERI_REG(RTC_GPIO_CONF, READ_PERI_REG(RTC_GPIO_CONF) & ~1);
+ WRITE_PERI_REG(RTC_GPIO_ENABLE, (READ_PERI_REG(RTC_GPIO_ENABLE) & ~1)); // input
+ WRITE_PERI_REG(RTC_GPIO_OUT, (READ_PERI_REG(RTC_GPIO_OUT) & ~1)); // out=0
+ return;
+ }
+
+ ETS_GPIO_INTR_DISABLE();
+ PIN_FUNC_SELECT(pin->periph, pin->func);
+ GPIO_REG_WRITE(GPIO_PIN_ADDR(GPIO_ID_PIN(pin->phys_port)),
+ GPIO_REG_READ(GPIO_PIN_ADDR(GPIO_ID_PIN(pin->phys_port)))
+ | GPIO_PIN_PAD_DRIVER_SET(GPIO_PAD_DRIVER_ENABLE)); // open drain
+ GPIO_REG_WRITE(GPIO_ENABLE_ADDRESS,
+ GPIO_REG_READ(GPIO_ENABLE_ADDRESS) | (1 << pin->phys_port));
+ ETS_GPIO_INTR_ENABLE();
+}
+
+// Get pointer to esf_buf bookkeeping structure
+void *ets_get_esf_buf_ctlblk(void) {
+ // Get literal ptr before start of esf_rx_buf_alloc func
+ extern void *esf_rx_buf_alloc();
+ return ((void**)esf_rx_buf_alloc)[-1];
+}
+
+// Get number of esf_buf free buffers of given type, as encoded by index
+// idx 0 corresponds to buf types 1, 2; 1 - 4; 2 - 5; 3 - 7; 4 - 8
+// Only following buf types appear to be used:
+// 1 - tx buffer, 5 - management frame tx buffer; 8 - rx buffer
+int ets_esf_free_bufs(int idx) {
+ uint32_t *p = ets_get_esf_buf_ctlblk();
+ uint32_t *b = (uint32_t*)p[idx];
+ int cnt = 0;
+ while (b) {
+ b = (uint32_t*)b[0x20 / 4];
+ cnt++;
+ }
+ return cnt;
+}
diff --git a/esp8266/esp_mphal.h b/esp8266/esp_mphal.h
index 6713e42551..13b1c8fdf0 100644
--- a/esp8266/esp_mphal.h
+++ b/esp8266/esp_mphal.h
@@ -41,7 +41,6 @@ void mp_hal_signal_dupterm_input(void);
void mp_hal_init(void);
void mp_hal_rtc_init(void);
-void mp_hal_feed_watchdog(void);
uint32_t mp_hal_ticks_us(void);
void mp_hal_delay_us(uint32_t);
@@ -56,4 +55,29 @@ void dupterm_task_init();
void ets_event_poll(void);
#define ETS_POLL_WHILE(cond) { while (cond) ets_event_poll(); }
+// needed for machine.I2C
+#include "osapi.h"
+#define mp_hal_delay_us_fast(us) os_delay_us(us)
+
+// C-level pin HAL
+#include "etshal.h"
+#include "gpio.h"
+#include "esp8266/modpyb.h"
+#define mp_hal_pin_obj_t uint32_t
+#define mp_hal_get_pin_obj(o) mp_obj_get_pin(o)
+void mp_hal_pin_config_od(mp_hal_pin_obj_t pin);
+#define mp_hal_pin_low(p) do { \
+ if ((p) == 16) { WRITE_PERI_REG(RTC_GPIO_ENABLE, (READ_PERI_REG(RTC_GPIO_ENABLE) & ~1) | 1); } \
+ else { gpio_output_set(0, 1 << (p), 1 << (p), 0); } \
+ } while (0)
+#define mp_hal_pin_od_high(p) do { \
+ if ((p) == 16) { WRITE_PERI_REG(RTC_GPIO_ENABLE, (READ_PERI_REG(RTC_GPIO_ENABLE) & ~1)); } \
+ else { gpio_output_set(1 << (p), 0, 1 << (p), 0); } \
+ } while (0)
+#define mp_hal_pin_read(p) pin_get(p)
+#define mp_hal_pin_write(p, v) pin_set((p), (v))
+
+void *ets_get_esf_buf_ctlblk(void);
+int ets_esf_free_bufs(int idx);
+
#endif // _INCLUDED_MPHAL_H_
diff --git a/esp8266/esponewire.c b/esp8266/esponewire.c
new file mode 100644
index 0000000000..797ec0bd22
--- /dev/null
+++ b/esp8266/esponewire.c
@@ -0,0 +1,99 @@
+/*
+ * This file is part of the MicroPython project, http://micropython.org/
+ *
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2015-2016 Damien P. George
+ *
+ * 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 <stdint.h>
+
+#include "etshal.h"
+#include "user_interface.h"
+#include "modpyb.h"
+#include "esponewire.h"
+
+#define TIMING_RESET1 (0)
+#define TIMING_RESET2 (1)
+#define TIMING_RESET3 (2)
+#define TIMING_READ1 (3)
+#define TIMING_READ2 (4)
+#define TIMING_READ3 (5)
+#define TIMING_WRITE1 (6)
+#define TIMING_WRITE2 (7)
+#define TIMING_WRITE3 (8)
+
+uint16_t esp_onewire_timings[9] = {480, 40, 420, 5, 5, 40, 10, 50, 10};
+
+static uint32_t disable_irq(void) {
+ ets_intr_lock();
+ return 0;
+}
+
+static void enable_irq(uint32_t i) {
+ ets_intr_unlock();
+}
+
+static void mp_hal_delay_us_no_irq(uint32_t us) {
+ uint32_t start = system_get_time();
+ while (system_get_time() - start < us) {
+ }
+}
+
+#define DELAY_US mp_hal_delay_us_no_irq
+
+int esp_onewire_reset(uint pin) {
+ pin_set(pin, 0);
+ DELAY_US(esp_onewire_timings[TIMING_RESET1]);
+ uint32_t i = disable_irq();
+ pin_set(pin, 1);
+ DELAY_US(esp_onewire_timings[TIMING_RESET2]);
+ int status = !pin_get(pin);
+ enable_irq(i);
+ DELAY_US(esp_onewire_timings[TIMING_RESET3]);
+ return status;
+}
+
+int esp_onewire_readbit(uint pin) {
+ pin_set(pin, 1);
+ uint32_t i = disable_irq();
+ pin_set(pin, 0);
+ DELAY_US(esp_onewire_timings[TIMING_READ1]);
+ pin_set(pin, 1);
+ DELAY_US(esp_onewire_timings[TIMING_READ2]);
+ int value = pin_get(pin);
+ enable_irq(i);
+ DELAY_US(esp_onewire_timings[TIMING_READ3]);
+ return value;
+}
+
+void esp_onewire_writebit(uint pin, int value) {
+ uint32_t i = disable_irq();
+ pin_set(pin, 0);
+ DELAY_US(esp_onewire_timings[TIMING_WRITE1]);
+ if (value) {
+ pin_set(pin, 1);
+ }
+ DELAY_US(esp_onewire_timings[TIMING_WRITE2]);
+ pin_set(pin, 1);
+ DELAY_US(esp_onewire_timings[TIMING_WRITE3]);
+ enable_irq(i);
+}
diff --git a/esp8266/utils.c b/esp8266/esponewire.h
index e91ebe318d..da0a1d3880 100644
--- a/esp8266/utils.c
+++ b/esp8266/esponewire.h
@@ -1,10 +1,9 @@
/*
- * This file is part of the Micro Python project, http://micropython.org/
+ * This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
- * Copyright (c) 2015 Josef Gajdusek
- * Copyright (c) 2015 Paul Sokolovsky
+ * Copyright (c) 2016 Damien P. George
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@@ -25,26 +24,13 @@
* THE SOFTWARE.
*/
-#include "py/runtime.h"
-#include "py/obj.h"
-#include "py/nlr.h"
+#ifndef __MICROPY_INCLUDED_ESP8266_ESPONEWIRE_H__
+#define __MICROPY_INCLUDED_ESP8266_ESPONEWIRE_H__
-mp_obj_t call_function_1_protected(mp_obj_t fun, mp_obj_t arg) {
- nlr_buf_t nlr;
- if (nlr_push(&nlr) == 0) {
- return mp_call_function_1(fun, arg);
- } else {
- mp_obj_print_exception(&mp_plat_print, (mp_obj_t)nlr.ret_val);
- return (mp_obj_t)nlr.ret_val;
- }
-}
+extern uint16_t esp_onewire_timings[9];
-mp_obj_t call_function_2_protected(mp_obj_t fun, mp_obj_t arg1, mp_obj_t arg2) {
- nlr_buf_t nlr;
- if (nlr_push(&nlr) == 0) {
- return mp_call_function_2(fun, arg1, arg2);
- } else {
- mp_obj_print_exception(&mp_plat_print, (mp_obj_t)nlr.ret_val);
- return (mp_obj_t)nlr.ret_val;
- }
-}
+int esp_onewire_reset(uint pin);
+int esp_onewire_readbit(uint pin);
+void esp_onewire_writebit(uint pin, int value);
+
+#endif // __MICROPY_INCLUDED_ESP8266_ESPONEWIRE_H__
diff --git a/esp8266/etshal.h b/esp8266/etshal.h
index d8a57e8c75..0185a9e22c 100644
--- a/esp8266/etshal.h
+++ b/esp8266/etshal.h
@@ -20,4 +20,8 @@ void ets_timer_arm_new(os_timer_t *tim, uint32_t millis, bool repeat, bool is_mi
void ets_timer_setfn(os_timer_t *tim, ETSTimerFunc callback, void *cb_data);
void ets_timer_disarm(os_timer_t *tim);
+// These prototypes are for recent SDKs with "malloc tracking"
+void *pvPortMalloc(unsigned sz, const char *fname, int line);
+void vPortFree(void *p, const char *fname, int line);
+
#endif // _INCLUDED_ETSHAL_H_
diff --git a/esp8266/help.c b/esp8266/help.c
new file mode 100644
index 0000000000..3a4d6e83a2
--- /dev/null
+++ b/esp8266/help.c
@@ -0,0 +1,70 @@
+/*
+ * This file is part of the MicroPython project, http://micropython.org/
+ *
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2013-2016 Damien P. George
+ *
+ * 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 <stdio.h>
+
+#include "lib/utils/pyhelp.h"
+
+STATIC const char *help_text =
+"Welcome to MicroPython!\n"
+"\n"
+"For online docs please visit http://docs.micropython.org/en/latest/esp8266/ .\n"
+"For diagnostic information to include in bug reports execute 'import port_diag'.\n"
+"\n"
+"Basic WiFi configuration:\n"
+"\n"
+"import network\n"
+"sta_if = network.WLAN(network.STA_IF)\n"
+"sta_if.scan() # Scan for available access points\n"
+"sta_if.connect(\"<AP_name>\", \"<password>\") # Connect to an AP\n"
+"sta_if.isconnected() # Check for successful connection\n"
+"# Change name/password of ESP8266's AP:\n"
+"ap_if = network.WLAN(network.AP_IF)\n"
+"ap_if.config(essid=\"<AP_NAME>\", authmode=network.AUTH_WPA_WPA2_PSK, password=\"<password>\")\n"
+"\n"
+"Control commands:\n"
+" CTRL-A -- on a blank line, enter raw REPL mode\n"
+" CTRL-B -- on a blank line, enter normal REPL mode\n"
+" CTRL-C -- interrupt a running program\n"
+" CTRL-D -- on a blank line, do a soft reset of the board\n"
+" CTRL-E -- on a blank line, enter paste mode\n"
+"\n"
+"For further help on a specific object, type help(obj)\n"
+;
+
+STATIC mp_obj_t builtin_help(uint n_args, const mp_obj_t *args) {
+ if (n_args == 0) {
+ // print a general help message
+ printf("%s", help_text);
+
+ } else {
+ // try to print something sensible about the given object
+ pyhelp_print_obj(args[0]);
+ }
+
+ return mp_const_none;
+}
+MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(mp_builtin_help_obj, 0, 1, builtin_help);
diff --git a/esp8266/utils.h b/esp8266/intr.c
index ceef9720e8..62da4a721a 100644
--- a/esp8266/utils.h
+++ b/esp8266/intr.c
@@ -1,10 +1,9 @@
/*
- * This file is part of the Micro Python project, http://micropython.org/
+ * This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
- * Copyright (c) 2015 Josef Gajdusek
- * Copyright (c) 2015 Paul Sokolovsky
+ * Copyright (c) 2016 Damien P. George
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@@ -25,5 +24,14 @@
* THE SOFTWARE.
*/
-mp_obj_t call_function_1_protected(mp_obj_t fun, mp_obj_t arg);
-mp_obj_t call_function_2_protected(mp_obj_t fun, mp_obj_t arg1, mp_obj_t arg2);
+#include "etshal.h"
+#include "ets_alt_task.h"
+
+#include "modpyb.h"
+
+// this is in a separate file so it can go in iRAM
+void pin_intr_handler_iram(void *arg) {
+ uint32_t status = GPIO_REG_READ(GPIO_STATUS_ADDRESS);
+ GPIO_REG_WRITE(GPIO_STATUS_W1TC_ADDRESS, status);
+ pin_intr_handler(status);
+}
diff --git a/esp8266/main.c b/esp8266/main.c
index 08085299ba..45ee85ac88 100644
--- a/esp8266/main.c
+++ b/esp8266/main.c
@@ -47,12 +47,16 @@ STATIC void mp_reset(void) {
gc_init(heap, heap + sizeof(heap));
mp_init();
mp_obj_list_init(mp_sys_path, 0);
+ mp_obj_list_append(mp_sys_path, MP_OBJ_NEW_QSTR(MP_QSTR_)); // current dir (or base dir of the script)
+ mp_obj_list_append(mp_sys_path, MP_OBJ_NEW_QSTR(MP_QSTR__slash_));
+ mp_obj_list_append(mp_sys_path, MP_OBJ_NEW_QSTR(MP_QSTR__slash_lib));
mp_obj_list_init(mp_sys_argv, 0);
#if MICROPY_VFS_FAT
memset(MP_STATE_PORT(fs_user_mount), 0, sizeof(MP_STATE_PORT(fs_user_mount)));
#endif
MP_STATE_PORT(mp_kbd_exception) = mp_obj_new_exception(&mp_type_KeyboardInterrupt);
MP_STATE_PORT(term_obj) = MP_OBJ_NULL;
+ pin_init0();
#if MICROPY_MODULE_FROZEN
pyexec_frozen_module("_boot");
pyexec_file("boot.py");
diff --git a/esp8266/modesp.c b/esp8266/modesp.c
index 83d0c4a11f..44401d3a61 100644
--- a/esp8266/modesp.c
+++ b/esp8266/modesp.c
@@ -33,6 +33,7 @@
#include "py/obj.h"
#include "py/gc.h"
#include "py/runtime.h"
+#include "py/mphal.h"
#include "netutils.h"
#include "queue.h"
#include "ets_sys.h"
@@ -40,7 +41,7 @@
#include "user_interface.h"
#include "espconn.h"
#include "spi_flash.h"
-#include "utils.h"
+#include "mem.h"
#include "espneopixel.h"
#include "modpyb.h"
@@ -537,10 +538,11 @@ STATIC mp_obj_t esp_sleep_type(mp_uint_t n_args, const mp_obj_t *args) {
STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(esp_sleep_type_obj, 0, 1, esp_sleep_type);
STATIC mp_obj_t esp_deepsleep(mp_uint_t n_args, const mp_obj_t *args) {
+ system_deep_sleep_set_option(n_args > 1 ? mp_obj_get_int(args[1]) : 0);
system_deep_sleep(n_args > 0 ? mp_obj_get_int(args[0]) : 0);
return mp_const_none;
}
-STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(esp_deepsleep_obj, 0, 1, esp_deepsleep);
+STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(esp_deepsleep_obj, 0, 2, esp_deepsleep);
STATIC mp_obj_t esp_flash_id() {
return mp_obj_new_int(spi_flash_get_id());
@@ -608,6 +610,23 @@ STATIC mp_obj_t esp_flash_erase(mp_obj_t sector_in) {
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(esp_flash_erase_obj, esp_flash_erase);
+STATIC mp_obj_t esp_flash_size(void) {
+ extern char flashchip;
+ // For SDK 1.5.2, either address has shifted and not mirrored in
+ // eagle.rom.addr.v6.ld, or extra initial member was added.
+ SpiFlashChip *flash = (SpiFlashChip*)(&flashchip + 4);
+ #if 0
+ printf("deviceId: %x\n", flash->deviceId);
+ printf("chip_size: %u\n", flash->chip_size);
+ printf("block_size: %u\n", flash->block_size);
+ printf("sector_size: %u\n", flash->sector_size);
+ printf("page_size: %u\n", flash->page_size);
+ printf("status_mask: %u\n", flash->status_mask);
+ #endif
+ return mp_obj_new_int_from_uint(flash->chip_size);
+}
+STATIC MP_DEFINE_CONST_FUN_OBJ_0(esp_flash_size_obj, esp_flash_size);
+
STATIC mp_obj_t esp_neopixel_write_(mp_obj_t pin, mp_obj_t buf, mp_obj_t is800k) {
mp_buffer_info_t bufinfo;
mp_get_buffer_raise(buf, &bufinfo, MP_BUFFER_READ);
@@ -628,6 +647,22 @@ STATIC mp_obj_t esp_meminfo() {
}
STATIC MP_DEFINE_CONST_FUN_OBJ_0(esp_meminfo_obj, esp_meminfo);
+STATIC mp_obj_t esp_malloc(mp_obj_t size_in) {
+ return MP_OBJ_NEW_SMALL_INT((mp_uint_t)os_malloc(mp_obj_get_int(size_in)));
+}
+STATIC MP_DEFINE_CONST_FUN_OBJ_1(esp_malloc_obj, esp_malloc);
+
+STATIC mp_obj_t esp_free(mp_obj_t addr_in) {
+ os_free((void*)mp_obj_get_int(addr_in));
+ return mp_const_none;
+}
+STATIC MP_DEFINE_CONST_FUN_OBJ_1(esp_free_obj, esp_free);
+
+STATIC mp_obj_t esp_esf_free_bufs(mp_obj_t idx_in) {
+ return MP_OBJ_NEW_SMALL_INT(ets_esf_free_bufs(mp_obj_get_int(idx_in)));
+}
+STATIC MP_DEFINE_CONST_FUN_OBJ_1(esp_esf_free_bufs_obj, esp_esf_free_bufs);
+
STATIC const mp_map_elem_t esp_module_globals_table[] = {
{ MP_OBJ_NEW_QSTR(MP_QSTR___name__), MP_OBJ_NEW_QSTR(MP_QSTR_esp) },
@@ -638,6 +673,7 @@ STATIC const mp_map_elem_t esp_module_globals_table[] = {
{ MP_OBJ_NEW_QSTR(MP_QSTR_flash_read), (mp_obj_t)&esp_flash_read_obj },
{ MP_OBJ_NEW_QSTR(MP_QSTR_flash_write), (mp_obj_t)&esp_flash_write_obj },
{ MP_OBJ_NEW_QSTR(MP_QSTR_flash_erase), (mp_obj_t)&esp_flash_erase_obj },
+ { MP_OBJ_NEW_QSTR(MP_QSTR_flash_size), (mp_obj_t)&esp_flash_size_obj },
#if MODESP_ESPCONN
{ MP_OBJ_NEW_QSTR(MP_QSTR_socket), (mp_obj_t)&esp_socket_type },
{ MP_OBJ_NEW_QSTR(MP_QSTR_getaddrinfo), (mp_obj_t)&esp_getaddrinfo_obj },
@@ -645,6 +681,10 @@ STATIC const mp_map_elem_t esp_module_globals_table[] = {
{ MP_OBJ_NEW_QSTR(MP_QSTR_neopixel_write), (mp_obj_t)&esp_neopixel_write_obj },
{ MP_OBJ_NEW_QSTR(MP_QSTR_freemem), (mp_obj_t)&esp_freemem_obj },
{ MP_OBJ_NEW_QSTR(MP_QSTR_meminfo), (mp_obj_t)&esp_meminfo_obj },
+ { MP_OBJ_NEW_QSTR(MP_QSTR_info), (mp_obj_t)&pyb_info_obj }, // TODO delete/rename/move elsewhere
+ { MP_OBJ_NEW_QSTR(MP_QSTR_malloc), (mp_obj_t)&esp_malloc_obj },
+ { MP_OBJ_NEW_QSTR(MP_QSTR_free), (mp_obj_t)&esp_free_obj },
+ { MP_OBJ_NEW_QSTR(MP_QSTR_esf_free_bufs), (mp_obj_t)&esp_esf_free_bufs_obj },
#if MODESP_INCLUDE_CONSTANTS
{ MP_OBJ_NEW_QSTR(MP_QSTR_SLEEP_NONE),
diff --git a/esp8266/modmachine.c b/esp8266/modmachine.c
index 96f9845dc1..c3c9494ac8 100644
--- a/esp8266/modmachine.c
+++ b/esp8266/modmachine.c
@@ -30,16 +30,22 @@
#include "py/obj.h"
#include "py/runtime.h"
#include "extmod/machine_mem.h"
-#include "utils.h"
+#include "extmod/machine_i2c.h"
#include "modpyb.h"
+#include "modpybrtc.h"
#include "os_type.h"
#include "osapi.h"
#include "etshal.h"
+#include "ets_alt_task.h"
#include "user_interface.h"
#if MICROPY_PY_MACHINE
+//#define MACHINE_WAKE_IDLE (0x01)
+//#define MACHINE_WAKE_SLEEP (0x02)
+#define MACHINE_WAKE_DEEPSLEEP (0x04)
+
STATIC mp_obj_t machine_freq(mp_uint_t n_args, const mp_obj_t *args) {
if (n_args == 0) {
// get
@@ -63,12 +69,51 @@ STATIC mp_obj_t machine_reset(void) {
}
STATIC MP_DEFINE_CONST_FUN_OBJ_0(machine_reset_obj, machine_reset);
+STATIC mp_obj_t machine_reset_cause(void) {
+ return MP_OBJ_NEW_SMALL_INT(system_get_rst_info()->reason);
+}
+STATIC MP_DEFINE_CONST_FUN_OBJ_0(machine_reset_cause_obj, machine_reset_cause);
+
STATIC mp_obj_t machine_unique_id(void) {
uint32_t id = system_get_chip_id();
return mp_obj_new_bytes((byte*)&id, sizeof(id));
}
STATIC MP_DEFINE_CONST_FUN_OBJ_0(machine_unique_id_obj, machine_unique_id);
+STATIC mp_obj_t machine_deepsleep(void) {
+ // default to sleep forever
+ uint32_t sleep_us = 0;
+
+ // see if RTC.ALARM0 should wake the device
+ if (pyb_rtc_alarm0_wake & MACHINE_WAKE_DEEPSLEEP) {
+ uint64_t t = pyb_rtc_get_us_since_2000();
+ if (pyb_rtc_alarm0_expiry <= t) {
+ sleep_us = 1; // alarm already expired so wake immediately
+ } else {
+ uint64_t delta = pyb_rtc_alarm0_expiry - t;
+ if (delta <= 0xffffffff) {
+ // sleep for the desired time
+ sleep_us = delta;
+ } else {
+ // overflow, just set to maximum sleep time
+ sleep_us = 0xffffffff;
+ }
+ }
+ }
+
+ // put the device in a deep-sleep state
+ system_deep_sleep_set_option(0); // default power down mode; TODO check this
+ system_deep_sleep(sleep_us);
+
+ for (;;) {
+ // we must not return
+ ets_loop_iter();
+ }
+
+ return mp_const_none;
+}
+STATIC MP_DEFINE_CONST_FUN_OBJ_0(machine_deepsleep_obj, machine_deepsleep);
+
typedef struct _esp_timer_obj_t {
mp_obj_base_t base;
os_timer_t timer;
@@ -91,7 +136,7 @@ STATIC mp_obj_t esp_timer_make_new(const mp_obj_type_t *type, mp_uint_t n_args,
STATIC void esp_timer_cb(void *arg) {
esp_timer_obj_t *self = arg;
- call_function_1_protected(self->callback, self);
+ mp_call_function_1_protected(self->callback, self);
}
STATIC mp_obj_t esp_timer_init_helper(esp_timer_obj_t *self, mp_uint_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
@@ -152,15 +197,26 @@ STATIC const mp_rom_map_elem_t machine_module_globals_table[] = {
{ MP_ROM_QSTR(MP_QSTR_freq), MP_ROM_PTR(&machine_freq_obj) },
{ MP_ROM_QSTR(MP_QSTR_reset), MP_ROM_PTR(&machine_reset_obj) },
+ { MP_ROM_QSTR(MP_QSTR_reset_cause), MP_ROM_PTR(&machine_reset_cause_obj) },
{ MP_ROM_QSTR(MP_QSTR_unique_id), MP_ROM_PTR(&machine_unique_id_obj) },
+ { MP_ROM_QSTR(MP_QSTR_deepsleep), MP_ROM_PTR(&machine_deepsleep_obj) },
+ { MP_ROM_QSTR(MP_QSTR_RTC), MP_ROM_PTR(&pyb_rtc_type) },
{ MP_ROM_QSTR(MP_QSTR_Timer), MP_ROM_PTR(&esp_timer_type) },
{ MP_ROM_QSTR(MP_QSTR_Pin), MP_ROM_PTR(&pyb_pin_type) },
{ MP_ROM_QSTR(MP_QSTR_PWM), MP_ROM_PTR(&pyb_pwm_type) },
{ MP_ROM_QSTR(MP_QSTR_ADC), MP_ROM_PTR(&pyb_adc_type) },
{ MP_ROM_QSTR(MP_QSTR_UART), MP_ROM_PTR(&pyb_uart_type) },
- { MP_ROM_QSTR(MP_QSTR_I2C), MP_ROM_PTR(&pyb_i2c_type) },
+ { MP_ROM_QSTR(MP_QSTR_I2C), MP_ROM_PTR(&machine_i2c_type) },
{ MP_ROM_QSTR(MP_QSTR_SPI), MP_ROM_PTR(&pyb_spi_type) },
+
+ // wake abilities
+ { MP_ROM_QSTR(MP_QSTR_DEEPSLEEP), MP_ROM_INT(MACHINE_WAKE_DEEPSLEEP) },
+
+ // reset causes
+ { MP_ROM_QSTR(MP_QSTR_PWR_ON_RESET), MP_ROM_INT(REASON_EXT_SYS_RST) },
+ { MP_ROM_QSTR(MP_QSTR_HARD_RESET), MP_ROM_INT(REASON_EXT_SYS_RST) },
+ { MP_ROM_QSTR(MP_QSTR_DEEPSLEEP_RESET), MP_ROM_INT(REASON_DEEP_SLEEP_AWAKE) },
};
STATIC MP_DEFINE_CONST_DICT(machine_module_globals, machine_module_globals_table);
diff --git a/esp8266/modnetwork.c b/esp8266/modnetwork.c
index 0aaeb55657..5e9273158c 100644
--- a/esp8266/modnetwork.c
+++ b/esp8266/modnetwork.c
@@ -39,6 +39,7 @@
#include "espconn.h"
#include "spi_flash.h"
#include "ets_alt_task.h"
+#include "lwip/dns.h"
#define MODNETWORK_INCLUDE_CONSTANTS (1)
@@ -189,40 +190,58 @@ STATIC mp_obj_t esp_isconnected(mp_obj_t self_in) {
STATIC MP_DEFINE_CONST_FUN_OBJ_1(esp_isconnected_obj, esp_isconnected);
-STATIC mp_obj_t esp_mac(mp_uint_t n_args, const mp_obj_t *args) {
+STATIC mp_obj_t esp_ifconfig(size_t n_args, const mp_obj_t *args) {
wlan_if_obj_t *self = MP_OBJ_TO_PTR(args[0]);
- uint8_t mac[6];
- if (n_args == 1) {
- wifi_get_macaddr(self->if_id, mac);
- return mp_obj_new_bytes(mac, sizeof(mac));
- } else {
- mp_buffer_info_t bufinfo;
- mp_get_buffer_raise(args[1], &bufinfo, MP_BUFFER_READ);
-
- if (bufinfo.len != 6) {
- nlr_raise(mp_obj_new_exception_msg(&mp_type_ValueError,
- "invalid buffer length"));
- }
-
- wifi_set_macaddr(self->if_id, bufinfo.buf);
- return mp_const_none;
- }
-}
-STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(esp_mac_obj, 1, 2, esp_mac);
-
-STATIC mp_obj_t esp_ifconfig(mp_obj_t self_in) {
- wlan_if_obj_t *self = MP_OBJ_TO_PTR(self_in);
struct ip_info info;
+ ip_addr_t dns_addr;
wifi_get_ip_info(self->if_id, &info);
- mp_obj_t ifconfig[4] = {
+ if (n_args == 1) {
+ // get
+ dns_addr = dns_getserver(0);
+ mp_obj_t tuple[4] = {
netutils_format_ipv4_addr((uint8_t*)&info.ip, NETUTILS_BIG),
netutils_format_ipv4_addr((uint8_t*)&info.netmask, NETUTILS_BIG),
netutils_format_ipv4_addr((uint8_t*)&info.gw, NETUTILS_BIG),
- MP_OBJ_NEW_QSTR(MP_QSTR_), // no DNS server
- };
- return mp_obj_new_tuple(4, ifconfig);
+ netutils_format_ipv4_addr((uint8_t*)&dns_addr, NETUTILS_BIG),
+ };
+ return mp_obj_new_tuple(4, tuple);
+ } else {
+ // set
+ mp_obj_t *items;
+ bool restart_dhcp_server = false;
+ mp_obj_get_array_fixed_n(args[1], 4, &items);
+ netutils_parse_ipv4_addr(items[0], (void*)&info.ip, NETUTILS_BIG);
+ if (mp_obj_is_integer(items[1])) {
+ // allow numeric netmask, i.e.:
+ // 24 -> 255.255.255.0
+ // 16 -> 255.255.0.0
+ // etc...
+ uint32_t* m = (uint32_t*)&info.netmask;
+ *m = htonl(0xffffffff << (32 - mp_obj_get_int(items[1])));
+ } else {
+ netutils_parse_ipv4_addr(items[1], (void*)&info.netmask, NETUTILS_BIG);
+ }
+ netutils_parse_ipv4_addr(items[2], (void*)&info.gw, NETUTILS_BIG);
+ netutils_parse_ipv4_addr(items[3], (void*)&dns_addr, NETUTILS_BIG);
+ // To set a static IP we have to disable DHCP first
+ if (self->if_id == STATION_IF) {
+ wifi_station_dhcpc_stop();
+ } else {
+ restart_dhcp_server = wifi_softap_dhcps_status();
+ wifi_softap_dhcps_stop();
+ }
+ if (!wifi_set_ip_info(self->if_id, &info)) {
+ nlr_raise(mp_obj_new_exception_msg(&mp_type_OSError,
+ "wifi_set_ip_info() failed"));
+ }
+ dns_setserver(0, &dns_addr);
+ if (restart_dhcp_server) {
+ wifi_softap_dhcps_start();
+ }
+ return mp_const_none;
+ }
}
-STATIC MP_DEFINE_CONST_FUN_OBJ_1(esp_ifconfig_obj, esp_ifconfig);
+STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(esp_ifconfig_obj, 1, 2, esp_ifconfig);
STATIC mp_obj_t esp_config(size_t n_args, const mp_obj_t *args, mp_map_t *kwargs) {
if (n_args != 1 && kwargs->used != 0) {
@@ -242,13 +261,26 @@ STATIC mp_obj_t esp_config(size_t n_args, const mp_obj_t *args, mp_map_t *kwargs
error_check(wifi_softap_get_config(&cfg.ap), "can't get AP config");
}
+ int req_if = -1;
+
if (kwargs->used != 0) {
for (mp_uint_t i = 0; i < kwargs->alloc; i++) {
if (MP_MAP_SLOT_IS_FILLED(kwargs, i)) {
#define QS(x) (uintptr_t)MP_OBJ_NEW_QSTR(x)
switch ((uintptr_t)kwargs->table[i].key) {
+ case QS(MP_QSTR_mac): {
+ mp_buffer_info_t bufinfo;
+ mp_get_buffer_raise(args[1], &bufinfo, MP_BUFFER_READ);
+ if (bufinfo.len != 6) {
+ nlr_raise(mp_obj_new_exception_msg(&mp_type_ValueError,
+ "invalid buffer length"));
+ }
+ wifi_set_macaddr(self->if_id, bufinfo.buf);
+ break;
+ }
case QS(MP_QSTR_essid): {
+ req_if = SOFTAP_IF;
mp_uint_t len;
const char *s = mp_obj_str_get_data(kwargs->table[i].value, &len);
len = MIN(len, sizeof(cfg.ap.ssid));
@@ -256,6 +288,30 @@ STATIC mp_obj_t esp_config(size_t n_args, const mp_obj_t *args, mp_map_t *kwargs
cfg.ap.ssid_len = len;
break;
}
+ case QS(MP_QSTR_hidden): {
+ req_if = SOFTAP_IF;
+ cfg.ap.ssid_hidden = mp_obj_is_true(kwargs->table[i].value);
+ break;
+ }
+ case QS(MP_QSTR_authmode): {
+ req_if = SOFTAP_IF;
+ cfg.ap.authmode = mp_obj_get_int(kwargs->table[i].value);
+ break;
+ }
+ case QS(MP_QSTR_password): {
+ req_if = SOFTAP_IF;
+ mp_uint_t len;
+ const char *s = mp_obj_str_get_data(kwargs->table[i].value, &len);
+ len = MIN(len, sizeof(cfg.ap.password) - 1);
+ memcpy(cfg.ap.password, s, len);
+ cfg.ap.password[len] = 0;
+ break;
+ }
+ case QS(MP_QSTR_channel): {
+ req_if = SOFTAP_IF;
+ cfg.ap.channel = mp_obj_get_int(kwargs->table[i].value);
+ break;
+ }
default:
goto unknown;
}
@@ -263,6 +319,11 @@ STATIC mp_obj_t esp_config(size_t n_args, const mp_obj_t *args, mp_map_t *kwargs
}
}
+ // We post-check interface requirements to save on code size
+ if (req_if >= 0) {
+ require_if(args[0], req_if);
+ }
+
if (self->if_id == STATION_IF) {
error_check(wifi_station_set_config(&cfg.sta), "can't set STA config");
} else {
@@ -279,13 +340,43 @@ STATIC mp_obj_t esp_config(size_t n_args, const mp_obj_t *args, mp_map_t *kwargs
"can query only one param"));
}
+ mp_obj_t val;
+
#define QS(x) (uintptr_t)MP_OBJ_NEW_QSTR(x)
switch ((uintptr_t)args[1]) {
+ case QS(MP_QSTR_mac): {
+ uint8_t mac[6];
+ wifi_get_macaddr(self->if_id, mac);
+ return mp_obj_new_bytes(mac, sizeof(mac));
+ }
case QS(MP_QSTR_essid):
- return mp_obj_new_str((char*)cfg.ap.ssid, cfg.ap.ssid_len, false);
+ req_if = SOFTAP_IF;
+ val = mp_obj_new_str((char*)cfg.ap.ssid, cfg.ap.ssid_len, false);
+ break;
+ case QS(MP_QSTR_hidden):
+ req_if = SOFTAP_IF;
+ val = mp_obj_new_bool(cfg.ap.ssid_hidden);
+ break;
+ case QS(MP_QSTR_authmode):
+ req_if = SOFTAP_IF;
+ val = MP_OBJ_NEW_SMALL_INT(cfg.ap.authmode);
+ break;
+ case QS(MP_QSTR_channel):
+ req_if = SOFTAP_IF;
+ val = MP_OBJ_NEW_SMALL_INT(cfg.ap.channel);
+ break;
+ default:
+ goto unknown;
}
#undef QS
+ // We post-check interface requirements to save on code size
+ if (req_if >= 0) {
+ require_if(args[0], req_if);
+ }
+
+ return val;
+
unknown:
nlr_raise(mp_obj_new_exception_msg(&mp_type_ValueError,
"unknown config param"));
@@ -299,7 +390,6 @@ STATIC const mp_map_elem_t wlan_if_locals_dict_table[] = {
{ MP_OBJ_NEW_QSTR(MP_QSTR_status), (mp_obj_t)&esp_status_obj },
{ MP_OBJ_NEW_QSTR(MP_QSTR_scan), (mp_obj_t)&esp_scan_obj },
{ MP_OBJ_NEW_QSTR(MP_QSTR_isconnected), (mp_obj_t)&esp_isconnected_obj },
- { MP_OBJ_NEW_QSTR(MP_QSTR_mac), (mp_obj_t)&esp_mac_obj },
{ MP_OBJ_NEW_QSTR(MP_QSTR_config), (mp_obj_t)&esp_config_obj },
{ MP_OBJ_NEW_QSTR(MP_QSTR_ifconfig), (mp_obj_t)&esp_ifconfig_obj },
};
@@ -312,16 +402,6 @@ const mp_obj_type_t wlan_if_type = {
.locals_dict = (mp_obj_t)&wlan_if_locals_dict,
};
-STATIC mp_obj_t esp_wifi_mode(mp_uint_t n_args, const mp_obj_t *args) {
- if (n_args == 0) {
- return mp_obj_new_int(wifi_get_opmode());
- } else {
- wifi_set_opmode(mp_obj_get_int(args[0]));
- return mp_const_none;
- }
-}
-STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(esp_wifi_mode_obj, 0, 1, esp_wifi_mode);
-
STATIC mp_obj_t esp_phy_mode(mp_uint_t n_args, const mp_obj_t *args) {
if (n_args == 0) {
return mp_obj_new_int(wifi_get_phy_mode());
@@ -335,7 +415,6 @@ STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(esp_phy_mode_obj, 0, 1, esp_phy_mode)
STATIC const mp_map_elem_t mp_module_network_globals_table[] = {
{ MP_OBJ_NEW_QSTR(MP_QSTR___name__), MP_OBJ_NEW_QSTR(MP_QSTR_network) },
{ MP_OBJ_NEW_QSTR(MP_QSTR_WLAN), (mp_obj_t)&get_wlan_obj },
- { MP_OBJ_NEW_QSTR(MP_QSTR_wifi_mode), (mp_obj_t)&esp_wifi_mode_obj },
{ MP_OBJ_NEW_QSTR(MP_QSTR_phy_mode), (mp_obj_t)&esp_phy_mode_obj },
#if MODNETWORK_INCLUDE_CONSTANTS
@@ -363,6 +442,17 @@ STATIC const mp_map_elem_t mp_module_network_globals_table[] = {
MP_OBJ_NEW_SMALL_INT(PHY_MODE_11G) },
{ MP_OBJ_NEW_QSTR(MP_QSTR_MODE_11N),
MP_OBJ_NEW_SMALL_INT(PHY_MODE_11N) },
+
+ { MP_OBJ_NEW_QSTR(MP_QSTR_AUTH_OPEN),
+ MP_OBJ_NEW_SMALL_INT(AUTH_OPEN) },
+ { MP_OBJ_NEW_QSTR(MP_QSTR_AUTH_WEP),
+ MP_OBJ_NEW_SMALL_INT(AUTH_WEP) },
+ { MP_OBJ_NEW_QSTR(MP_QSTR_AUTH_WPA_PSK),
+ MP_OBJ_NEW_SMALL_INT(AUTH_WPA_PSK) },
+ { MP_OBJ_NEW_QSTR(MP_QSTR_AUTH_WPA2_PSK),
+ MP_OBJ_NEW_SMALL_INT(AUTH_WPA2_PSK) },
+ { MP_OBJ_NEW_QSTR(MP_QSTR_AUTH_WPA_WPA2_PSK),
+ MP_OBJ_NEW_SMALL_INT(AUTH_WPA_WPA2_PSK) },
#endif
};
diff --git a/esp8266/modonewire.c b/esp8266/modonewire.c
index 267da281ed..0fcf1ab6a6 100644
--- a/esp8266/modonewire.c
+++ b/esp8266/modonewire.c
@@ -27,80 +27,28 @@
#include <stdio.h>
#include <stdint.h>
-#include "etshal.h"
-#include "user_interface.h"
#include "py/obj.h"
#include "py/mphal.h"
#include "modpyb.h"
-
-STATIC uint32_t disable_irq(void) {
- ets_intr_lock();
- return 0;
-}
-
-STATIC void enable_irq(uint32_t i) {
- ets_intr_unlock();
-}
-
-STATIC void mp_hal_delay_us_no_irq(uint32_t us) {
- uint32_t start = system_get_time();
- while (system_get_time() - start < us) {
- }
-}
-
-#define DELAY_US mp_hal_delay_us_no_irq
-
-#define TIMING_RESET1 (0)
-#define TIMING_RESET2 (1)
-#define TIMING_RESET3 (2)
-#define TIMING_READ1 (3)
-#define TIMING_READ2 (4)
-#define TIMING_READ3 (5)
-#define TIMING_WRITE1 (6)
-#define TIMING_WRITE2 (7)
-#define TIMING_WRITE3 (8)
-
-static int timings[] = {480, 40, 420, 5, 5, 40, 10, 50, 10};
+#include "esponewire.h"
STATIC mp_obj_t onewire_timings(mp_obj_t timings_in) {
mp_obj_t *items;
mp_obj_get_array_fixed_n(timings_in, 9, &items);
for (int i = 0; i < 9; ++i) {
- timings[i] = mp_obj_get_int(items[i]);
+ esp_onewire_timings[i] = mp_obj_get_int(items[i]);
}
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(onewire_timings_obj, onewire_timings);
STATIC mp_obj_t onewire_reset(mp_obj_t pin_in) {
- uint pin = mp_obj_get_pin(pin_in);
- pin_set(pin, 0);
- DELAY_US(timings[TIMING_RESET1]);
- uint32_t i = disable_irq();
- pin_set(pin, 1);
- DELAY_US(timings[TIMING_RESET2]);
- int status = !pin_get(pin);
- enable_irq(i);
- DELAY_US(timings[TIMING_RESET3]);
- return mp_obj_new_bool(status);
+ return mp_obj_new_bool(esp_onewire_reset(mp_obj_get_pin(pin_in)));
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(onewire_reset_obj, onewire_reset);
-STATIC int _onewire_readbit(uint pin) {
- pin_set(pin, 1);
- uint32_t i = disable_irq();
- pin_set(pin, 0);
- DELAY_US(timings[TIMING_READ1]);
- pin_set(pin, 1);
- DELAY_US(timings[TIMING_READ2]);
- int value = pin_get(pin);
- enable_irq(i);
- DELAY_US(timings[TIMING_READ3]);
- return value;
-}
-
STATIC mp_obj_t onewire_readbit(mp_obj_t pin_in) {
- return MP_OBJ_NEW_SMALL_INT(_onewire_readbit(mp_obj_get_pin(pin_in)));
+ return MP_OBJ_NEW_SMALL_INT(esp_onewire_readbit(mp_obj_get_pin(pin_in)));
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(onewire_readbit_obj, onewire_readbit);
@@ -108,25 +56,14 @@ STATIC mp_obj_t onewire_readbyte(mp_obj_t pin_in) {
uint pin = mp_obj_get_pin(pin_in);
uint8_t value = 0;
for (int i = 0; i < 8; ++i) {
- value |= _onewire_readbit(pin) << i;
+ value |= esp_onewire_readbit(pin) << i;
}
return MP_OBJ_NEW_SMALL_INT(value);
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(onewire_readbyte_obj, onewire_readbyte);
-STATIC void _onewire_writebit(uint pin, int value) {
- uint32_t i = disable_irq();
- pin_set(pin, 0);
- DELAY_US(timings[TIMING_WRITE1]);
- pin_set(pin, value);
- DELAY_US(timings[TIMING_WRITE2]);
- pin_set(pin, 1);
- DELAY_US(timings[TIMING_WRITE3]);
- enable_irq(i);
-}
-
STATIC mp_obj_t onewire_writebit(mp_obj_t pin_in, mp_obj_t value_in) {
- _onewire_writebit(mp_obj_get_pin(pin_in), mp_obj_get_int(value_in));
+ esp_onewire_writebit(mp_obj_get_pin(pin_in), mp_obj_get_int(value_in));
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_2(onewire_writebit_obj, onewire_writebit);
@@ -135,7 +72,7 @@ STATIC mp_obj_t onewire_writebyte(mp_obj_t pin_in, mp_obj_t value_in) {
uint pin = mp_obj_get_pin(pin_in);
int value = mp_obj_get_int(value_in);
for (int i = 0; i < 8; ++i) {
- _onewire_writebit(pin, value & 1);
+ esp_onewire_writebit(pin, value & 1);
value >>= 1;
}
return mp_const_none;
diff --git a/esp8266/modpyb.c b/esp8266/modpyb.c
index 504ec382c4..ba53e71b37 100644
--- a/esp8266/modpyb.c
+++ b/esp8266/modpyb.c
@@ -26,14 +26,15 @@
#include <stdio.h>
-#include "py/nlr.h"
-#include "py/obj.h"
#include "py/gc.h"
-#include "py/mphal.h"
#include "gccollect.h"
-#include "user_interface.h"
#include "modpyb.h"
+// The pyb module no longer exists since all functionality now appears
+// elsewhere, in more standard places (eg time, machine modules). The
+// only remaining function is pyb.info() which has been moved to the
+// esp module, pending deletion/renaming/moving elsewher.
+
STATIC mp_obj_t pyb_info(mp_uint_t n_args, const mp_obj_t *args) {
// print info about memory
{
@@ -75,78 +76,4 @@ STATIC mp_obj_t pyb_info(mp_uint_t n_args, const mp_obj_t *args) {
return mp_const_none;
}
-STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(pyb_info_obj, 0, 1, pyb_info);
-
-STATIC mp_obj_t pyb_sync(void) {
- //storage_flush();
- return mp_const_none;
-}
-STATIC MP_DEFINE_CONST_FUN_OBJ_0(pyb_sync_obj, pyb_sync);
-
-STATIC mp_obj_t pyb_millis(void) {
- return MP_OBJ_NEW_SMALL_INT(mp_hal_ticks_ms());
-}
-STATIC MP_DEFINE_CONST_FUN_OBJ_0(pyb_millis_obj, pyb_millis);
-
-STATIC mp_obj_t pyb_elapsed_millis(mp_obj_t start) {
- uint32_t startMillis = mp_obj_get_int(start);
- uint32_t currMillis = mp_hal_ticks_ms();
- return MP_OBJ_NEW_SMALL_INT((currMillis - startMillis) & 0x3fffffff);
-}
-STATIC MP_DEFINE_CONST_FUN_OBJ_1(pyb_elapsed_millis_obj, pyb_elapsed_millis);
-
-STATIC mp_obj_t pyb_micros(void) {
- return MP_OBJ_NEW_SMALL_INT(system_get_time());
-}
-STATIC MP_DEFINE_CONST_FUN_OBJ_0(pyb_micros_obj, pyb_micros);
-
-STATIC mp_obj_t pyb_elapsed_micros(mp_obj_t start) {
- uint32_t startMicros = mp_obj_get_int(start);
- uint32_t currMicros = system_get_time();
- return MP_OBJ_NEW_SMALL_INT((currMicros - startMicros) & 0x3fffffff);
-}
-STATIC MP_DEFINE_CONST_FUN_OBJ_1(pyb_elapsed_micros_obj, pyb_elapsed_micros);
-
-STATIC mp_obj_t pyb_delay(mp_obj_t ms_in) {
- mp_int_t ms = mp_obj_get_int(ms_in);
- if (ms >= 0) {
- mp_hal_delay_ms(ms);
- }
- return mp_const_none;
-}
-STATIC MP_DEFINE_CONST_FUN_OBJ_1(pyb_delay_obj, pyb_delay);
-
-STATIC mp_obj_t pyb_udelay(mp_obj_t usec_in) {
- mp_int_t usec = mp_obj_get_int(usec_in);
- if (usec >= 0) {
- mp_hal_delay_us(usec);
- }
- return mp_const_none;
-}
-STATIC MP_DEFINE_CONST_FUN_OBJ_1(pyb_udelay_obj, pyb_udelay);
-
-STATIC const mp_map_elem_t pyb_module_globals_table[] = {
- { MP_OBJ_NEW_QSTR(MP_QSTR___name__), MP_OBJ_NEW_QSTR(MP_QSTR_pyb) },
-
- { MP_OBJ_NEW_QSTR(MP_QSTR_info), (mp_obj_t)&pyb_info_obj },
-
- { MP_OBJ_NEW_QSTR(MP_QSTR_millis), (mp_obj_t)&pyb_millis_obj },
- { MP_OBJ_NEW_QSTR(MP_QSTR_elapsed_millis), (mp_obj_t)&pyb_elapsed_millis_obj },
- { MP_OBJ_NEW_QSTR(MP_QSTR_micros), (mp_obj_t)&pyb_micros_obj },
- { MP_OBJ_NEW_QSTR(MP_QSTR_elapsed_micros), (mp_obj_t)&pyb_elapsed_micros_obj },
- { MP_OBJ_NEW_QSTR(MP_QSTR_delay), (mp_obj_t)&pyb_delay_obj },
- { MP_OBJ_NEW_QSTR(MP_QSTR_udelay), (mp_obj_t)&pyb_udelay_obj },
- { MP_OBJ_NEW_QSTR(MP_QSTR_sync), (mp_obj_t)&pyb_sync_obj },
-
- { MP_OBJ_NEW_QSTR(MP_QSTR_Pin), (mp_obj_t)&pyb_pin_type },
- { MP_OBJ_NEW_QSTR(MP_QSTR_ADC), (mp_obj_t)&pyb_adc_type },
- { MP_OBJ_NEW_QSTR(MP_QSTR_RTC), (mp_obj_t)&pyb_rtc_type },
-};
-
-STATIC MP_DEFINE_CONST_DICT(pyb_module_globals, pyb_module_globals_table);
-
-const mp_obj_module_t pyb_module = {
- .base = { &mp_type_module },
- .name = MP_QSTR_pyb,
- .globals = (mp_obj_dict_t*)&pyb_module_globals,
-};
+MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(pyb_info_obj, 0, 1, pyb_info);
diff --git a/esp8266/modpyb.h b/esp8266/modpyb.h
index 3ac9f2f15f..dc399ad819 100644
--- a/esp8266/modpyb.h
+++ b/esp8266/modpyb.h
@@ -1,3 +1,8 @@
+#ifndef __MICROPY_INCLUDED_ESP8266_MODPYB_H__
+#define __MICROPY_INCLUDED_ESP8266_MODPYB_H__
+
+#include "py/obj.h"
+
extern const mp_obj_type_t pyb_pin_type;
extern const mp_obj_type_t pyb_pwm_type;
extern const mp_obj_type_t pyb_adc_type;
@@ -6,15 +11,24 @@ extern const mp_obj_type_t pyb_uart_type;
extern const mp_obj_type_t pyb_i2c_type;
extern const mp_obj_type_t pyb_spi_type;
+MP_DECLARE_CONST_FUN_OBJ(pyb_info_obj);
+
typedef struct _pyb_pin_obj_t {
mp_obj_base_t base;
- uint16_t pin_id;
uint16_t phys_port;
- uint32_t periph;
uint16_t func;
+ uint32_t periph;
} pyb_pin_obj_t;
+const pyb_pin_obj_t pyb_pin_obj[16 + 1];
+
+void pin_init0(void);
+void pin_intr_handler_iram(void *arg);
+void pin_intr_handler(uint32_t);
+
uint mp_obj_get_pin(mp_obj_t pin_in);
pyb_pin_obj_t *mp_obj_get_pin_obj(mp_obj_t pin_in);
int pin_get(uint pin);
void pin_set(uint pin, int value);
+
+#endif // __MICROPY_INCLUDED_ESP8266_MODPYB_H__
diff --git a/esp8266/modpybi2c.c b/esp8266/modpybi2c.c
deleted file mode 100644
index 0216abeb99..0000000000
--- a/esp8266/modpybi2c.c
+++ /dev/null
@@ -1,323 +0,0 @@
-/*
- * This file is part of the MicroPython project, http://micropython.org/
- *
- * The MIT License (MIT)
- *
- * Copyright (c) 2016 Damien P. George
- *
- * 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 <stdio.h>
-#include <stdint.h>
-#include <string.h>
-
-#include "ets_sys.h"
-#include "etshal.h"
-#include "osapi.h"
-#include "gpio.h"
-
-#include "py/runtime.h"
-#include "modpyb.h"
-
-typedef struct _pyb_i2c_obj_t {
- mp_obj_base_t base;
- pyb_pin_obj_t *scl;
- pyb_pin_obj_t *sda;
-} pyb_i2c_obj_t;
-
-// these set the frequency of SCL
-#define mphal_i2c_wait_a() os_delay_us(2)
-#define mphal_i2c_wait_b() os_delay_us(1)
-
-STATIC void mphal_i2c_set_sda(pyb_i2c_obj_t *self, uint8_t sda) {
- uint32_t port = self->sda->phys_port;
- sda &= 0x01;
- gpio_output_set(sda << port, (1 - sda) << port, 1 << port, 0);
-}
-
-STATIC void mphal_i2c_set_scl(pyb_i2c_obj_t *self, uint8_t scl) {
- uint32_t port = self->scl->phys_port;
- scl &= 0x01;
- gpio_output_set(scl << port, (1 - scl) << port, 1 << port, 0);
-}
-
-STATIC int mphal_i2c_get_sda(pyb_i2c_obj_t *self) {
- return GPIO_INPUT_GET(GPIO_ID_PIN(self->sda->phys_port));
-}
-
-STATIC void mphal_i2c_start(pyb_i2c_obj_t *self) {
- mphal_i2c_set_sda(self, 1);
- mphal_i2c_wait_a();
- mphal_i2c_set_scl(self, 1);
- mphal_i2c_wait_a();
- mphal_i2c_set_sda(self, 0);
- mphal_i2c_wait_a();
-}
-
-STATIC void mphal_i2c_stop(pyb_i2c_obj_t *self) {
- mphal_i2c_wait_a();
- mphal_i2c_set_sda(self, 0);
- mphal_i2c_wait_a();
- mphal_i2c_set_scl(self, 1);
- mphal_i2c_wait_a();
- mphal_i2c_set_sda(self, 1);
- mphal_i2c_wait_a();
-}
-
-STATIC void mphal_i2c_init(pyb_i2c_obj_t *self, uint32_t freq) {
- pyb_pin_obj_t *scl = self->scl;
- pyb_pin_obj_t *sda = self->sda;
-
- ETS_GPIO_INTR_DISABLE();
- //ETS_INTR_LOCK();
-
- PIN_FUNC_SELECT(sda->periph, sda->func);
- PIN_FUNC_SELECT(scl->periph, scl->func);
-
- GPIO_REG_WRITE(GPIO_PIN_ADDR(GPIO_ID_PIN(sda->phys_port)),
- GPIO_REG_READ(GPIO_PIN_ADDR(GPIO_ID_PIN(sda->phys_port)))
- | GPIO_PIN_PAD_DRIVER_SET(GPIO_PAD_DRIVER_ENABLE)); // open drain
- GPIO_REG_WRITE(GPIO_ENABLE_ADDRESS,
- GPIO_REG_READ(GPIO_ENABLE_ADDRESS) | (1 << sda->phys_port));
- GPIO_REG_WRITE(GPIO_PIN_ADDR(GPIO_ID_PIN(scl->phys_port)),
- GPIO_REG_READ(GPIO_PIN_ADDR(GPIO_ID_PIN(scl->phys_port)))
- | GPIO_PIN_PAD_DRIVER_SET(GPIO_PAD_DRIVER_ENABLE)); // open drain
- GPIO_REG_WRITE(GPIO_ENABLE_ADDRESS,
- GPIO_REG_READ(GPIO_ENABLE_ADDRESS) | (1 << scl->phys_port));
-
- mphal_i2c_set_scl(self, 1);
- mphal_i2c_set_sda(self, 1);
-
- ETS_GPIO_INTR_ENABLE();
- //ETS_INTR_UNLOCK();
-
- mphal_i2c_set_scl(self, 0);
- mphal_i2c_wait_a();
-
- // when SCL = 0, toggle SDA to clear up
- mphal_i2c_set_sda(self, 0);
- mphal_i2c_wait_a();
- mphal_i2c_set_sda(self, 1);
- mphal_i2c_wait_a();
-
- // set data_cnt to max value
- for (uint8_t i = 0; i < 28; i++) {
- mphal_i2c_set_scl(self, 0);
- mphal_i2c_wait_a();
- mphal_i2c_set_scl(self, 1);
- mphal_i2c_wait_a();
- }
-
- // reset all
- mphal_i2c_stop(self);
-}
-
-STATIC int mphal_i2c_write_byte(pyb_i2c_obj_t *self, uint8_t val) {
- uint8_t dat;
- sint8 i;
-
- mphal_i2c_wait_a();
-
- mphal_i2c_set_scl(self, 0);
- mphal_i2c_wait_a();
-
- for (i = 7; i >= 0; i--) {
- dat = val >> i;
- mphal_i2c_set_sda(self, dat);
- mphal_i2c_wait_a();
- mphal_i2c_set_scl(self, 1);
- mphal_i2c_wait_a();
-
- if (i == 0) {
- mphal_i2c_wait_b();
- }
-
- mphal_i2c_set_scl(self, 0);
- mphal_i2c_wait_a();
- }
-
- mphal_i2c_set_sda(self, 1);
- mphal_i2c_wait_a();
- mphal_i2c_set_scl(self, 1);
- mphal_i2c_wait_a();
-
- int ret = mphal_i2c_get_sda(self);
- mphal_i2c_wait_a();
- mphal_i2c_set_scl(self, 0);
- mphal_i2c_wait_a();
-
- return !ret;
-}
-
-STATIC void mphal_i2c_write(pyb_i2c_obj_t *self, uint8_t addr, uint8_t *data, size_t len, bool stop) {
- mphal_i2c_start(self);
- if (!mphal_i2c_write_byte(self, addr << 1)) {
- goto er;
- }
- while (len--) {
- if (!mphal_i2c_write_byte(self, *data++)) {
- goto er;
- }
- }
- if (stop) {
- mphal_i2c_stop(self);
- }
- return;
-
-er:
- mphal_i2c_stop(self);
- nlr_raise(mp_obj_new_exception_msg(&mp_type_OSError, "I2C bus error"));
-}
-
-STATIC int mphal_i2c_read_byte(pyb_i2c_obj_t *self, uint8_t *val) {
- mphal_i2c_wait_a();
- mphal_i2c_set_scl(self, 0);
- mphal_i2c_wait_a();
-
- uint8_t dat = 0;
- for (int i = 7; i >= 0; i--) {
- mphal_i2c_set_scl(self, 1);
- mphal_i2c_wait_a();
- dat = (dat << 1) | mphal_i2c_get_sda(self);
- mphal_i2c_wait_a();
- mphal_i2c_set_scl(self, 0);
- mphal_i2c_wait_a();
- }
- *val = dat;
-
- mphal_i2c_wait_a();
- mphal_i2c_set_scl(self, 1);
- mphal_i2c_wait_a();
- mphal_i2c_wait_b();
- mphal_i2c_set_scl(self, 0);
- mphal_i2c_wait_a();
-
- return 1; // success
-}
-
-STATIC void mphal_i2c_read(pyb_i2c_obj_t *self, uint8_t addr, uint8_t *data, size_t len, bool stop) {
- mphal_i2c_start(self);
- if (!mphal_i2c_write_byte(self, (addr << 1) | 1)) {
- goto er;
- }
- while (len--) {
- if (!mphal_i2c_read_byte(self, data++)) {
- goto er;
- }
- }
- if (stop) {
- mphal_i2c_stop(self);
- }
- return;
-
-er:
- mphal_i2c_stop(self);
- nlr_raise(mp_obj_new_exception_msg(&mp_type_OSError, "I2C bus error"));
-}
-
-/******************************************************************************/
-// MicroPython bindings for I2C
-
-STATIC void pyb_i2c_obj_init_helper(pyb_i2c_obj_t *self, mp_uint_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
- enum { ARG_scl, ARG_sda, ARG_freq };
- static const mp_arg_t allowed_args[] = {
- { MP_QSTR_scl, MP_ARG_REQUIRED | MP_ARG_OBJ },
- { MP_QSTR_sda, MP_ARG_REQUIRED | MP_ARG_OBJ },
- { MP_QSTR_freq, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 400000} },
- };
- mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
- mp_arg_parse_all(n_args, pos_args, kw_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
- self->scl = mp_obj_get_pin_obj(args[ARG_scl].u_obj);
- self->sda = mp_obj_get_pin_obj(args[ARG_sda].u_obj);
- mphal_i2c_init(self, args[ARG_freq].u_int);
-}
-
-STATIC mp_obj_t pyb_i2c_make_new(const mp_obj_type_t *type, size_t n_args, size_t n_kw, const mp_obj_t *args) {
- mp_arg_check_num(n_args, n_kw, 0, MP_OBJ_FUN_ARGS_MAX, true);
- pyb_i2c_obj_t *self = m_new_obj(pyb_i2c_obj_t);
- self->base.type = &pyb_i2c_type;
- mp_map_t kw_args;
- mp_map_init_fixed_table(&kw_args, n_kw, args + n_args);
- pyb_i2c_obj_init_helper(self, n_args, args, &kw_args);
- return (mp_obj_t)self;
-}
-
-STATIC mp_obj_t pyb_i2c_obj_init(mp_uint_t n_args, const mp_obj_t *args, mp_map_t *kw_args) {
- pyb_i2c_obj_init_helper(args[0], n_args - 1, args + 1, kw_args);
- return mp_const_none;
-}
-MP_DEFINE_CONST_FUN_OBJ_KW(pyb_i2c_init_obj, 1, pyb_i2c_obj_init);
-
-STATIC mp_obj_t pyb_i2c_readfrom(size_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
- enum { ARG_addr, ARG_n, ARG_stop };
- static const mp_arg_t allowed_args[] = {
- { MP_QSTR_addr, MP_ARG_REQUIRED | MP_ARG_INT, {.u_int = 0} },
- { MP_QSTR_n, MP_ARG_REQUIRED | MP_ARG_INT, {.u_int = 0} },
- { MP_QSTR_stop, MP_ARG_KW_ONLY | MP_ARG_BOOL, {.u_bool = true} },
- };
- pyb_i2c_obj_t *self = pos_args[0];
- mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
- mp_arg_parse_all(n_args - 1, pos_args + 1, kw_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
-
- // do the I2C transfer
- vstr_t vstr;
- vstr_init_len(&vstr, args[ARG_n].u_int);
- mphal_i2c_read(self, args[ARG_addr].u_int, (uint8_t*)vstr.buf, vstr.len, args[ARG_stop].u_bool);
-
- return mp_obj_new_str_from_vstr(&mp_type_bytes, &vstr);
-}
-MP_DEFINE_CONST_FUN_OBJ_KW(pyb_i2c_readfrom_obj, 1, pyb_i2c_readfrom);
-
-STATIC mp_obj_t pyb_i2c_writeto(mp_uint_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
- enum { ARG_addr, ARG_buf, ARG_stop };
- static const mp_arg_t allowed_args[] = {
- { MP_QSTR_addr, MP_ARG_REQUIRED | MP_ARG_INT, {.u_int = 0} },
- { MP_QSTR_buf, MP_ARG_REQUIRED | MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL} },
- { MP_QSTR_stop, MP_ARG_KW_ONLY | MP_ARG_BOOL, {.u_bool = true} },
- };
- pyb_i2c_obj_t *self = pos_args[0];
- mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
- mp_arg_parse_all(n_args - 1, pos_args + 1, kw_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
-
- // get the buffer to write from
- mp_buffer_info_t bufinfo;
- mp_get_buffer_raise(args[ARG_buf].u_obj, &bufinfo, MP_BUFFER_READ);
-
- // do the I2C transfer
- mphal_i2c_write(self, args[ARG_addr].u_int, bufinfo.buf, bufinfo.len, args[ARG_stop].u_bool);
-
- return mp_const_none;
-}
-STATIC MP_DEFINE_CONST_FUN_OBJ_KW(pyb_i2c_writeto_obj, 1, pyb_i2c_writeto);
-
-STATIC const mp_rom_map_elem_t pyb_i2c_locals_dict_table[] = {
- { MP_ROM_QSTR(MP_QSTR_init), MP_ROM_PTR(&pyb_i2c_init_obj) },
- { MP_ROM_QSTR(MP_QSTR_readfrom), MP_ROM_PTR(&pyb_i2c_readfrom_obj) },
- { MP_ROM_QSTR(MP_QSTR_writeto), MP_ROM_PTR(&pyb_i2c_writeto_obj) },
-};
-
-STATIC MP_DEFINE_CONST_DICT(pyb_i2c_locals_dict, pyb_i2c_locals_dict_table);
-
-const mp_obj_type_t pyb_i2c_type = {
- { &mp_type_type },
- .name = MP_QSTR_I2C,
- .make_new = pyb_i2c_make_new,
- .locals_dict = (mp_obj_dict_t*)&pyb_i2c_locals_dict,
-};
diff --git a/esp8266/modpybpin.c b/esp8266/modpybpin.c
index 63ba410849..6b9e20268b 100644
--- a/esp8266/modpybpin.c
+++ b/esp8266/modpybpin.c
@@ -28,14 +28,23 @@
#include <stdint.h>
#include <string.h>
+#include "etshal.h"
#include "c_types.h"
#include "user_interface.h"
#include "gpio.h"
#include "py/nlr.h"
#include "py/runtime.h"
+#include "py/gc.h"
#include "modpyb.h"
+#define GET_TRIGGER(phys_port) \
+ GPIO_PIN_INT_TYPE_GET(GPIO_REG_READ(GPIO_PIN_ADDR(phys_port)))
+#define SET_TRIGGER(phys_port, trig) \
+ (GPIO_REG_WRITE(GPIO_PIN_ADDR(phys_port), \
+ (GPIO_REG_READ(GPIO_PIN_ADDR(phys_port)) & ~GPIO_PIN_INT_TYPE_MASK) \
+ | GPIO_PIN_INT_TYPE_SET(trig))) \
+
#define GPIO_MODE_INPUT (0)
#define GPIO_MODE_OUTPUT (1)
#define GPIO_MODE_OPEN_DRAIN (2) // synthesised
@@ -44,26 +53,64 @@
// Removed in SDK 1.1.0
//#define GPIO_PULL_DOWN (2)
-STATIC const pyb_pin_obj_t pyb_pin_obj[] = {
- {{&pyb_pin_type}, 0, 0, PERIPHS_IO_MUX_GPIO0_U, FUNC_GPIO0},
- {{&pyb_pin_type}, 1, 1, PERIPHS_IO_MUX_U0TXD_U, FUNC_GPIO1},
- {{&pyb_pin_type}, 2, 2, PERIPHS_IO_MUX_GPIO2_U, FUNC_GPIO2},
- {{&pyb_pin_type}, 3, 3, PERIPHS_IO_MUX_U0RXD_U, FUNC_GPIO3},
- {{&pyb_pin_type}, 4, 4, PERIPHS_IO_MUX_GPIO4_U, FUNC_GPIO4},
- {{&pyb_pin_type}, 5, 5, PERIPHS_IO_MUX_GPIO5_U, FUNC_GPIO5},
- {{&pyb_pin_type}, 9, 9, PERIPHS_IO_MUX_SD_DATA2_U, FUNC_GPIO9},
- {{&pyb_pin_type}, 10, 10, PERIPHS_IO_MUX_SD_DATA3_U, FUNC_GPIO10},
- {{&pyb_pin_type}, 12, 12, PERIPHS_IO_MUX_MTDI_U, FUNC_GPIO12},
- {{&pyb_pin_type}, 13, 13, PERIPHS_IO_MUX_MTCK_U, FUNC_GPIO13},
- {{&pyb_pin_type}, 14, 14, PERIPHS_IO_MUX_MTMS_U, FUNC_GPIO14},
- {{&pyb_pin_type}, 15, 15, PERIPHS_IO_MUX_MTDO_U, FUNC_GPIO15},
+typedef struct _pin_irq_obj_t {
+ mp_obj_base_t base;
+ uint16_t phys_port;
+} pin_irq_obj_t;
+
+const pyb_pin_obj_t pyb_pin_obj[16 + 1] = {
+ {{&pyb_pin_type}, 0, FUNC_GPIO0, PERIPHS_IO_MUX_GPIO0_U},
+ {{&pyb_pin_type}, 1, FUNC_GPIO1, PERIPHS_IO_MUX_U0TXD_U},
+ {{&pyb_pin_type}, 2, FUNC_GPIO2, PERIPHS_IO_MUX_GPIO2_U},
+ {{&pyb_pin_type}, 3, FUNC_GPIO3, PERIPHS_IO_MUX_U0RXD_U},
+ {{&pyb_pin_type}, 4, FUNC_GPIO4, PERIPHS_IO_MUX_GPIO4_U},
+ {{&pyb_pin_type}, 5, FUNC_GPIO5, PERIPHS_IO_MUX_GPIO5_U},
+ {{NULL}, 0, 0, 0},
+ {{NULL}, 0, 0, 0},
+ {{NULL}, 0, 0, 0},
+ {{&pyb_pin_type}, 9, FUNC_GPIO9, PERIPHS_IO_MUX_SD_DATA2_U},
+ {{&pyb_pin_type}, 10, FUNC_GPIO10, PERIPHS_IO_MUX_SD_DATA3_U},
+ {{NULL}, 0, 0, 0},
+ {{&pyb_pin_type}, 12, FUNC_GPIO12, PERIPHS_IO_MUX_MTDI_U},
+ {{&pyb_pin_type}, 13, FUNC_GPIO13, PERIPHS_IO_MUX_MTCK_U},
+ {{&pyb_pin_type}, 14, FUNC_GPIO14, PERIPHS_IO_MUX_MTMS_U},
+ {{&pyb_pin_type}, 15, FUNC_GPIO15, PERIPHS_IO_MUX_MTDO_U},
// GPIO16 is special, belongs to different register set, and
// otherwise handled specially.
- {{&pyb_pin_type}, 16, 16, -1, -1},
+ {{&pyb_pin_type}, 16, -1, -1},
};
STATIC uint8_t pin_mode[16 + 1];
+// forward declaration
+STATIC const pin_irq_obj_t pin_irq_obj[16];
+
+void pin_init0(void) {
+ ETS_GPIO_INTR_DISABLE();
+ ETS_GPIO_INTR_ATTACH(pin_intr_handler_iram, NULL);
+ // disable all interrupts
+ memset(&MP_STATE_PORT(pin_irq_handler)[0], 0, 16 * sizeof(mp_obj_t));
+ for (int p = 0; p < 16; ++p) {
+ GPIO_REG_WRITE(GPIO_STATUS_W1TC_ADDRESS, 1 << p);
+ SET_TRIGGER(p, 0);
+ }
+ ETS_GPIO_INTR_ENABLE();
+}
+
+void pin_intr_handler(uint32_t status) {
+ gc_lock();
+ status &= 0xffff;
+ for (int p = 0; status; ++p, status >>= 1) {
+ if (status & 1) {
+ mp_obj_t handler = MP_STATE_PORT(pin_irq_handler)[p];
+ if (handler != MP_OBJ_NULL) {
+ mp_call_function_1_protected(handler, MP_OBJ_FROM_PTR(&pyb_pin_obj[p]));
+ }
+ }
+ }
+ gc_unlock();
+}
+
pyb_pin_obj_t *mp_obj_get_pin_obj(mp_obj_t pin_in) {
if (mp_obj_get_type(pin_in) != &pyb_pin_type) {
nlr_raise(mp_obj_new_exception_msg(&mp_type_ValueError, "expecting a pin"));
@@ -130,36 +177,37 @@ STATIC void pyb_pin_print(const mp_print_t *print, mp_obj_t self_in, mp_print_ki
pyb_pin_obj_t *self = self_in;
// pin name
- mp_printf(print, "Pin(%u)", self->pin_id);
+ mp_printf(print, "Pin(%u)", self->phys_port);
}
-// pin.init(mode, pull=Pin.PULL_NONE, af=-1)
+// pin.init(mode, pull=None, *, value)
STATIC mp_obj_t pyb_pin_obj_init_helper(pyb_pin_obj_t *self, mp_uint_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
+ enum { ARG_mode, ARG_pull, ARG_value };
static const mp_arg_t allowed_args[] = {
{ MP_QSTR_mode, MP_ARG_REQUIRED | MP_ARG_INT },
- { MP_QSTR_pull, MP_ARG_INT, {.u_int = GPIO_PULL_NONE}},
+ { MP_QSTR_pull, MP_ARG_OBJ, {.u_obj = mp_const_none}},
{ MP_QSTR_value, MP_ARG_KW_ONLY | MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL}},
};
// parse args
- struct {
- mp_arg_val_t mode, pull, value;
- } args;
- mp_arg_parse_all(n_args, pos_args, kw_args,
- MP_ARRAY_SIZE(allowed_args), allowed_args, (mp_arg_val_t*)&args);
+ mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
+ mp_arg_parse_all(n_args, pos_args, kw_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
// get io mode
- uint mode = args.mode.u_int;
+ uint mode = args[ARG_mode].u_int;
// get pull mode
- uint pull = args.pull.u_int;
+ uint pull = GPIO_PULL_NONE;
+ if (args[ARG_pull].u_obj != mp_const_none) {
+ pull = mp_obj_get_int(args[ARG_pull].u_obj);
+ }
// get initial value
int value;
- if (args.value.u_obj == MP_OBJ_NULL) {
+ if (args[ARG_value].u_obj == MP_OBJ_NULL) {
value = -1;
} else {
- value = mp_obj_is_true(args.value.u_obj);
+ value = mp_obj_is_true(args[ARG_value].u_obj);
}
// save the mode
@@ -198,16 +246,13 @@ STATIC mp_obj_t pyb_pin_obj_init_helper(pyb_pin_obj_t *self, mp_uint_t n_args, c
STATIC mp_obj_t pyb_pin_make_new(const mp_obj_type_t *type, mp_uint_t n_args, mp_uint_t n_kw, const mp_obj_t *args) {
mp_arg_check_num(n_args, n_kw, 1, MP_OBJ_FUN_ARGS_MAX, true);
- // Run an argument through the mapper and return the result.
+ // get the wanted pin object
int wanted_pin = mp_obj_get_int(args[0]);
pyb_pin_obj_t *pin = NULL;
- for (int i = 0; i < MP_ARRAY_SIZE(pyb_pin_obj); i++) {
- if (pyb_pin_obj[i].pin_id == wanted_pin) {
- pin = (pyb_pin_obj_t*)&pyb_pin_obj[i];
- break;
- }
+ if (0 <= wanted_pin && wanted_pin < MP_ARRAY_SIZE(pyb_pin_obj)) {
+ pin = (pyb_pin_obj_t*)&pyb_pin_obj[wanted_pin];
}
- if (pin == NULL) {
+ if (pin == NULL || pin->base.type == NULL) {
nlr_raise(mp_obj_new_exception_msg(&mp_type_ValueError, "invalid pin"));
}
@@ -263,20 +308,57 @@ STATIC mp_obj_t pyb_pin_high(mp_obj_t self_in) {
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(pyb_pin_high_obj, pyb_pin_high);
+// pin.irq(*, trigger, handler=None)
+STATIC mp_obj_t pyb_pin_irq(size_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
+ enum { ARG_trigger, ARG_handler };
+ static const mp_arg_t allowed_args[] = {
+ { MP_QSTR_trigger, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 0} },
+ { MP_QSTR_handler, MP_ARG_KW_ONLY | MP_ARG_OBJ, {.u_obj = mp_const_none} },
+ };
+ pyb_pin_obj_t *self = MP_OBJ_TO_PTR(pos_args[0]);
+ mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
+ mp_arg_parse_all(n_args - 1, pos_args + 1, kw_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
+
+ if (self->phys_port >= 16) {
+ nlr_raise(mp_obj_new_exception_msg(&mp_type_OSError, "pin does not have IRQ capabilities"));
+ }
+
+ if (args[ARG_trigger].u_int != 0) {
+ // configure irq
+ mp_obj_t handler = args[ARG_handler].u_obj;
+ if (handler == mp_const_none) {
+ handler = MP_OBJ_NULL;
+ }
+ ETS_GPIO_INTR_DISABLE();
+ MP_STATE_PORT(pin_irq_handler)[self->phys_port] = handler;
+ SET_TRIGGER(self->phys_port, args[ARG_trigger].u_int);
+ GPIO_REG_WRITE(GPIO_STATUS_W1TC_ADDRESS, 1 << self->phys_port);
+ ETS_GPIO_INTR_ENABLE();
+ }
+
+ // return the irq object
+ return MP_OBJ_FROM_PTR(&pin_irq_obj[self->phys_port]);
+}
+STATIC MP_DEFINE_CONST_FUN_OBJ_KW(pyb_pin_irq_obj, 1, pyb_pin_irq);
+
STATIC const mp_map_elem_t pyb_pin_locals_dict_table[] = {
// instance methods
{ MP_OBJ_NEW_QSTR(MP_QSTR_init), (mp_obj_t)&pyb_pin_init_obj },
{ MP_OBJ_NEW_QSTR(MP_QSTR_value), (mp_obj_t)&pyb_pin_value_obj },
{ MP_OBJ_NEW_QSTR(MP_QSTR_low), (mp_obj_t)&pyb_pin_low_obj },
{ MP_OBJ_NEW_QSTR(MP_QSTR_high), (mp_obj_t)&pyb_pin_high_obj },
+ { MP_OBJ_NEW_QSTR(MP_QSTR_irq), (mp_obj_t)&pyb_pin_irq_obj },
// class constants
{ MP_OBJ_NEW_QSTR(MP_QSTR_IN), MP_OBJ_NEW_SMALL_INT(GPIO_MODE_INPUT) },
{ MP_OBJ_NEW_QSTR(MP_QSTR_OUT), MP_OBJ_NEW_SMALL_INT(GPIO_MODE_OUTPUT) },
{ MP_OBJ_NEW_QSTR(MP_QSTR_OPEN_DRAIN), MP_OBJ_NEW_SMALL_INT(GPIO_MODE_OPEN_DRAIN) },
- { MP_OBJ_NEW_QSTR(MP_QSTR_PULL_NONE), MP_OBJ_NEW_SMALL_INT(GPIO_PULL_NONE) },
{ MP_OBJ_NEW_QSTR(MP_QSTR_PULL_UP), MP_OBJ_NEW_SMALL_INT(GPIO_PULL_UP) },
//{ MP_OBJ_NEW_QSTR(MP_QSTR_PULL_DOWN), MP_OBJ_NEW_SMALL_INT(GPIO_PULL_DOWN) },
+
+ // IRG triggers, can be or'd together
+ { MP_OBJ_NEW_QSTR(MP_QSTR_IRQ_RISING), MP_OBJ_NEW_SMALL_INT(GPIO_PIN_INTR_POSEDGE) },
+ { MP_OBJ_NEW_QSTR(MP_QSTR_IRQ_FALLING), MP_OBJ_NEW_SMALL_INT(GPIO_PIN_INTR_NEGEDGE) },
};
STATIC MP_DEFINE_CONST_DICT(pyb_pin_locals_dict, pyb_pin_locals_dict_table);
@@ -289,3 +371,59 @@ const mp_obj_type_t pyb_pin_type = {
.call = pyb_pin_call,
.locals_dict = (mp_obj_t)&pyb_pin_locals_dict,
};
+
+/******************************************************************************/
+// Pin IRQ object
+
+STATIC const mp_obj_type_t pin_irq_type;
+
+STATIC const pin_irq_obj_t pin_irq_obj[16] = {
+ {{&pin_irq_type}, 0},
+ {{&pin_irq_type}, 1},
+ {{&pin_irq_type}, 2},
+ {{&pin_irq_type}, 3},
+ {{&pin_irq_type}, 4},
+ {{&pin_irq_type}, 5},
+ {{&pin_irq_type}, 6},
+ {{&pin_irq_type}, 7},
+ {{&pin_irq_type}, 8},
+ {{&pin_irq_type}, 9},
+ {{&pin_irq_type}, 10},
+ {{&pin_irq_type}, 11},
+ {{&pin_irq_type}, 12},
+ {{&pin_irq_type}, 13},
+ {{&pin_irq_type}, 14},
+ {{&pin_irq_type}, 15},
+};
+
+STATIC mp_obj_t pin_irq_call(mp_obj_t self_in, size_t n_args, size_t n_kw, const mp_obj_t *args) {
+ pin_irq_obj_t *self = self_in;
+ mp_arg_check_num(n_args, n_kw, 0, 0, false);
+ pin_intr_handler(1 << self->phys_port);
+ return mp_const_none;
+}
+
+STATIC mp_obj_t pin_irq_trigger(size_t n_args, const mp_obj_t *args) {
+ pin_irq_obj_t *self = args[0];
+ uint32_t orig_trig = GET_TRIGGER(self->phys_port);
+ if (n_args == 2) {
+ // set trigger
+ SET_TRIGGER(self->phys_port, mp_obj_get_int(args[1]));
+ }
+ // return original trigger value
+ return MP_OBJ_NEW_SMALL_INT(orig_trig);
+}
+STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(pin_irq_trigger_obj, 1, 2, pin_irq_trigger);
+
+STATIC const mp_rom_map_elem_t pin_irq_locals_dict_table[] = {
+ { MP_ROM_QSTR(MP_QSTR_trigger), MP_ROM_PTR(&pin_irq_trigger_obj) },
+};
+
+STATIC MP_DEFINE_CONST_DICT(pin_irq_locals_dict, pin_irq_locals_dict_table);
+
+STATIC const mp_obj_type_t pin_irq_type = {
+ { &mp_type_type },
+ .name = MP_QSTR_IRQ,
+ .call = pin_irq_call,
+ .locals_dict = (mp_obj_dict_t*)&pin_irq_locals_dict,
+};
diff --git a/esp8266/modpybpwm.c b/esp8266/modpybpwm.c
index ccd5f56b25..871e4c3dd7 100644
--- a/esp8266/modpybpwm.c
+++ b/esp8266/modpybpwm.c
@@ -47,7 +47,7 @@ STATIC bool pwm_inited = false;
STATIC void pyb_pwm_print(const mp_print_t *print, mp_obj_t self_in, mp_print_kind_t kind) {
pyb_pwm_obj_t *self = MP_OBJ_TO_PTR(self_in);
- mp_printf(print, "PWM(%u", self->pin->pin_id);
+ mp_printf(print, "PWM(%u", self->pin->phys_port);
if (self->active) {
mp_printf(print, ", freq=%u, duty=%u",
pwm_get_freq(self->channel), pwm_get_duty(self->channel));
diff --git a/esp8266/modpybrtc.c b/esp8266/modpybrtc.c
index 594c34b157..e62dc88175 100644
--- a/esp8266/modpybrtc.c
+++ b/esp8266/modpybrtc.c
@@ -49,6 +49,10 @@ typedef struct _pyb_rtc_obj_t {
// singleton RTC object
STATIC const pyb_rtc_obj_t pyb_rtc_obj = {{&pyb_rtc_type}};
+// ALARM0 state
+uint32_t pyb_rtc_alarm0_wake; // see MACHINE_WAKE_xxx constants
+uint64_t pyb_rtc_alarm0_expiry; // in microseconds
+
void mp_hal_rtc_init(void) {
uint32_t magic;
@@ -61,6 +65,10 @@ void mp_hal_rtc_init(void) {
system_rtc_mem_write(MEM_CAL_ADDR, &cal, sizeof(cal));
system_rtc_mem_write(MEM_DELTA_ADDR, &delta, sizeof(delta));
}
+
+ // reset ALARM0 state
+ pyb_rtc_alarm0_wake = 0;
+ pyb_rtc_alarm0_expiry = 0;
}
STATIC mp_obj_t pyb_rtc_make_new(const mp_obj_type_t *type, mp_uint_t n_args, mp_uint_t n_kw, const mp_obj_t *args) {
@@ -177,9 +185,49 @@ STATIC mp_obj_t pyb_rtc_memory(mp_uint_t n_args, const mp_obj_t *args) {
}
STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(pyb_rtc_memory_obj, 1, 2, pyb_rtc_memory);
+STATIC mp_obj_t pyb_rtc_alarm(mp_obj_t self_in, mp_obj_t alarm_id, mp_obj_t time_in) {
+ (void)self_in; // unused
+
+ // check we want alarm0
+ if (mp_obj_get_int(alarm_id) != 0) {
+ nlr_raise(mp_obj_new_exception_msg(&mp_type_ValueError, "invalid alarm"));
+ }
+
+ // set expiry time (in microseconds)
+ pyb_rtc_alarm0_expiry = pyb_rtc_get_us_since_2000() + mp_obj_get_int(time_in) * 1000;
+
+ return mp_const_none;
+
+}
+STATIC MP_DEFINE_CONST_FUN_OBJ_3(pyb_rtc_alarm_obj, pyb_rtc_alarm);
+
+STATIC mp_obj_t pyb_rtc_irq(size_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
+ enum { ARG_trigger, ARG_wake };
+ static const mp_arg_t allowed_args[] = {
+ { MP_QSTR_trigger, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 0} },
+ { MP_QSTR_wake, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 0} },
+ };
+ mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
+ mp_arg_parse_all(n_args - 1, pos_args + 1, kw_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
+
+ // check we want alarm0
+ if (args[ARG_trigger].u_int != 0) {
+ nlr_raise(mp_obj_new_exception_msg(&mp_type_ValueError, "invalid alarm"));
+ }
+
+ // set the wake value
+ pyb_rtc_alarm0_wake = args[ARG_wake].u_int;
+
+ return mp_const_none;
+}
+STATIC MP_DEFINE_CONST_FUN_OBJ_KW(pyb_rtc_irq_obj, 1, pyb_rtc_irq);
+
STATIC const mp_map_elem_t pyb_rtc_locals_dict_table[] = {
{ MP_OBJ_NEW_QSTR(MP_QSTR_datetime), (mp_obj_t)&pyb_rtc_datetime_obj },
{ MP_OBJ_NEW_QSTR(MP_QSTR_memory), (mp_obj_t)&pyb_rtc_memory_obj },
+ { MP_OBJ_NEW_QSTR(MP_QSTR_alarm), (mp_obj_t)&pyb_rtc_alarm_obj },
+ { MP_OBJ_NEW_QSTR(MP_QSTR_irq), (mp_obj_t)&pyb_rtc_irq_obj },
+ { MP_OBJ_NEW_QSTR(MP_QSTR_ALARM0), MP_OBJ_NEW_SMALL_INT(0) },
};
STATIC MP_DEFINE_CONST_DICT(pyb_rtc_locals_dict, pyb_rtc_locals_dict_table);
diff --git a/esp8266/modpybrtc.h b/esp8266/modpybrtc.h
index 2a982d38fa..b4ca780712 100644
--- a/esp8266/modpybrtc.h
+++ b/esp8266/modpybrtc.h
@@ -24,6 +24,9 @@
* THE SOFTWARE.
*/
+extern uint32_t pyb_rtc_alarm0_wake;
+extern uint64_t pyb_rtc_alarm0_expiry;
+
void pyb_rtc_set_us_since_2000(uint64_t nowus);
uint64_t pyb_rtc_get_us_since_2000();
diff --git a/esp8266/modpybspi.c b/esp8266/modpybspi.c
index 70933e04dc..1131e8ef6b 100644
--- a/esp8266/modpybspi.c
+++ b/esp8266/modpybspi.c
@@ -35,16 +35,16 @@
#include "py/runtime.h"
#include "py/stream.h"
-#include "modpyb.h"
+#include "py/mphal.h"
typedef struct _pyb_spi_obj_t {
mp_obj_base_t base;
uint32_t baudrate;
uint8_t polarity;
uint8_t phase;
- pyb_pin_obj_t *sck;
- pyb_pin_obj_t *mosi;
- pyb_pin_obj_t *miso;
+ mp_hal_pin_obj_t sck;
+ mp_hal_pin_obj_t mosi;
+ mp_hal_pin_obj_t miso;
} pyb_spi_obj_t;
STATIC void mp_hal_spi_transfer(pyb_spi_obj_t *self, size_t src_len, const uint8_t *src_buf, size_t dest_len, uint8_t *dest_buf) {
@@ -59,20 +59,20 @@ STATIC void mp_hal_spi_transfer(pyb_spi_obj_t *self, size_t src_len, const uint8
}
uint8_t data_in = 0;
for (int j = 0; j < 8; ++j, data_out <<= 1) {
- pin_set(self->mosi->phys_port, (data_out >> 7) & 1);
+ mp_hal_pin_write(self->mosi, (data_out >> 7) & 1);
if (self->phase == 0) {
ets_delay_us(delay_half);
- pin_set(self->sck->phys_port, 1 - self->polarity);
+ mp_hal_pin_write(self->sck, 1 - self->polarity);
} else {
- pin_set(self->sck->phys_port, 1 - self->polarity);
+ mp_hal_pin_write(self->sck, 1 - self->polarity);
ets_delay_us(delay_half);
}
- data_in = (data_in << 1) | pin_get(self->miso->phys_port);
+ data_in = (data_in << 1) | mp_hal_pin_read(self->miso);
if (self->phase == 0) {
ets_delay_us(delay_half);
- pin_set(self->sck->phys_port, self->polarity);
+ mp_hal_pin_write(self->sck, self->polarity);
} else {
- pin_set(self->sck->phys_port, self->polarity);
+ mp_hal_pin_write(self->sck, self->polarity);
ets_delay_us(delay_half);
}
}
@@ -90,7 +90,7 @@ STATIC void mp_hal_spi_transfer(pyb_spi_obj_t *self, size_t src_len, const uint8
STATIC void pyb_spi_print(const mp_print_t *print, mp_obj_t self_in, mp_print_kind_t kind) {
pyb_spi_obj_t *self = MP_OBJ_TO_PTR(self_in);
mp_printf(print, "SPI(baudrate=%u, polarity=%u, phase=%u, sck=%u, mosi=%u, miso=%u)",
- self->baudrate, self->polarity, self->phase, self->sck->phys_port, self->mosi->phys_port, self->miso->phys_port);
+ self->baudrate, self->polarity, self->phase, self->sck, self->mosi, self->miso);
}
STATIC void pyb_spi_init_helper(pyb_spi_obj_t *self, size_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
@@ -116,13 +116,13 @@ STATIC void pyb_spi_init_helper(pyb_spi_obj_t *self, size_t n_args, const mp_obj
self->phase = args[ARG_phase].u_int;
}
if (args[ARG_sck].u_obj != MP_OBJ_NULL) {
- self->sck = mp_obj_get_pin_obj(args[ARG_sck].u_obj);
+ self->sck = mp_hal_get_pin_obj(args[ARG_sck].u_obj);
}
if (args[ARG_mosi].u_obj != MP_OBJ_NULL) {
- self->mosi = mp_obj_get_pin_obj(args[ARG_mosi].u_obj);
+ self->mosi = mp_hal_get_pin_obj(args[ARG_mosi].u_obj);
}
if (args[ARG_miso].u_obj != MP_OBJ_NULL) {
- self->miso = mp_obj_get_pin_obj(args[ARG_miso].u_obj);
+ self->miso = mp_hal_get_pin_obj(args[ARG_miso].u_obj);
}
}
@@ -134,9 +134,9 @@ STATIC mp_obj_t pyb_spi_make_new(const mp_obj_type_t *type, size_t n_args, size_
self->baudrate = 500000;
self->polarity = 0;
self->phase = 0;
- self->sck = NULL;
- self->mosi = NULL;
- self->miso = NULL;
+ self->sck = 14;
+ self->mosi = 13;
+ self->miso = 12;
mp_map_t kw_args;
mp_map_init_fixed_table(&kw_args, n_kw, args + n_args);
pyb_spi_init_helper(self, n_args, args, &kw_args);
diff --git a/esp8266/modpybuart.c b/esp8266/modpybuart.c
index 4c06f80907..eefb38d998 100644
--- a/esp8266/modpybuart.c
+++ b/esp8266/modpybuart.c
@@ -36,9 +36,14 @@
#include "py/stream.h"
#include "modpyb.h"
+// baudrate is currently fixed to this value
+#define UART_BAUDRATE (115200)
+
typedef struct _pyb_uart_obj_t {
mp_obj_base_t base;
uint8_t uart_id;
+ uint16_t timeout; // timeout waiting for first char (in ms)
+ uint16_t timeout_char; // timeout waiting between chars (in ms)
} pyb_uart_obj_t;
/******************************************************************************/
@@ -46,24 +51,35 @@ typedef struct _pyb_uart_obj_t {
STATIC void pyb_uart_print(const mp_print_t *print, mp_obj_t self_in, mp_print_kind_t kind) {
pyb_uart_obj_t *self = MP_OBJ_TO_PTR(self_in);
- mp_printf(print, "UART(%u)", self->uart_id);
+ mp_printf(print, "UART(%u, baudrate=%u, timeout=%u, timeout_char=%u)",
+ self->uart_id, UART_BAUDRATE, self->timeout, self->timeout_char);
}
STATIC void pyb_uart_init_helper(pyb_uart_obj_t *self, size_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
- /*
- enum { ARG_baudrate, ARG_bits, ARG_parity, ARG_stop };
+ enum { ARG_timeout, ARG_timeout_char };
static const mp_arg_t allowed_args[] = {
- { MP_QSTR_baudrate, MP_ARG_REQUIRED | MP_ARG_INT, {.u_int = 9600} },
- { MP_QSTR_bits, MP_ARG_INT, {.u_int = 8} },
- { MP_QSTR_parity, MP_ARG_OBJ, {.u_obj = mp_const_none} },
- { MP_QSTR_stop, MP_ARG_INT, {.u_int = 1} },
- { MP_QSTR_tx, MP_ARG_KW_ONLY | MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL} },
- { MP_QSTR_rx, MP_ARG_KW_ONLY | MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL} },
+ //{ MP_QSTR_baudrate, MP_ARG_REQUIRED | MP_ARG_INT, {.u_int = 9600} },
+ //{ MP_QSTR_bits, MP_ARG_INT, {.u_int = 8} },
+ //{ MP_QSTR_parity, MP_ARG_OBJ, {.u_obj = mp_const_none} },
+ //{ MP_QSTR_stop, MP_ARG_INT, {.u_int = 1} },
+ //{ MP_QSTR_tx, MP_ARG_KW_ONLY | MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL} },
+ //{ MP_QSTR_rx, MP_ARG_KW_ONLY | MP_ARG_OBJ, {.u_obj = MP_OBJ_NULL} },
+ { MP_QSTR_timeout, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 0} },
+ { MP_QSTR_timeout_char, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 0} },
};
mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
mp_arg_parse_all(n_args, pos_args, kw_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
- */
- // not implemented
+
+ // set timeout
+ self->timeout = args[ARG_timeout].u_int;
+
+ // set timeout_char
+ // make sure it is at least as long as a whole character (13 bits to be safe)
+ self->timeout_char = args[ARG_timeout_char].u_int;
+ uint32_t min_timeout_char = 13000 / UART_BAUDRATE + 1;
+ if (self->timeout_char < min_timeout_char) {
+ self->timeout_char = min_timeout_char;
+ }
}
STATIC mp_obj_t pyb_uart_make_new(const mp_obj_type_t *type, size_t n_args, size_t n_kw, const mp_obj_t *args) {
@@ -80,12 +96,10 @@ STATIC mp_obj_t pyb_uart_make_new(const mp_obj_type_t *type, size_t n_args, size
self->base.type = &pyb_uart_type;
self->uart_id = uart_id;
- if (n_args > 1 || n_kw > 0) {
- // init the peripheral
- mp_map_t kw_args;
- mp_map_init_fixed_table(&kw_args, n_kw, args + n_args);
- pyb_uart_init_helper(self, n_args - 1, args + 1, &kw_args);
- }
+ // init the peripheral
+ mp_map_t kw_args;
+ mp_map_init_fixed_table(&kw_args, n_kw, args + n_args);
+ pyb_uart_init_helper(self, n_args - 1, args + 1, &kw_args);
return MP_OBJ_FROM_PTR(self);
}
@@ -109,7 +123,32 @@ STATIC const mp_rom_map_elem_t pyb_uart_locals_dict_table[] = {
STATIC MP_DEFINE_CONST_DICT(pyb_uart_locals_dict, pyb_uart_locals_dict_table);
STATIC mp_uint_t pyb_uart_read(mp_obj_t self_in, void *buf_in, mp_uint_t size, int *errcode) {
- mp_not_implemented("reading from UART");
+ pyb_uart_obj_t *self = MP_OBJ_TO_PTR(self_in);
+
+ if (self->uart_id == 1) {
+ nlr_raise(mp_obj_new_exception_msg_varg(&mp_type_OSError, "UART(1) can't read"));
+ }
+
+ // make sure we want at least 1 char
+ if (size == 0) {
+ return 0;
+ }
+
+ // wait for first char to become available
+ if (!uart_rx_wait(self->timeout * 1000)) {
+ *errcode = EAGAIN;
+ return MP_STREAM_ERROR;
+ }
+
+ // read the data
+ uint8_t *buf = buf_in;
+ for (;;) {
+ *buf++ = uart_rx_char();
+ if (--size == 0 || !uart_rx_wait(self->timeout_char * 1000)) {
+ // return number of bytes read
+ return buf - (uint8_t*)buf_in;
+ }
+ }
}
STATIC mp_uint_t pyb_uart_write(mp_obj_t self_in, const void *buf_in, mp_uint_t size, int *errcode) {
diff --git a/esp8266/moduos.c b/esp8266/moduos.c
index 8b9c177db0..d75062eaf7 100644
--- a/esp8266/moduos.c
+++ b/esp8266/moduos.c
@@ -35,7 +35,7 @@
#include "py/runtime.h"
#include "extmod/misc.h"
#include "genhdr/mpversion.h"
-#include "etshal.h"
+#include "esp_mphal.h"
#include "user_interface.h"
extern const mp_obj_type_t mp_fat_vfs_type;
@@ -88,6 +88,11 @@ STATIC mp_obj_t os_listdir(mp_uint_t n_args, const mp_obj_t *args) {
}
STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(os_listdir_obj, 0, 1, os_listdir);
+STATIC mp_obj_t os_mkdir(mp_obj_t path_in) {
+ return vfs_proxy_call(MP_QSTR_mkdir, 1, &path_in);
+}
+STATIC MP_DEFINE_CONST_FUN_OBJ_1(os_mkdir_obj, os_mkdir);
+
STATIC mp_obj_t os_remove(mp_obj_t path_in) {
return vfs_proxy_call(MP_QSTR_remove, 1, &path_in);
}
@@ -105,16 +110,25 @@ STATIC mp_obj_t os_urandom(mp_obj_t num) {
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(os_urandom_obj, os_urandom);
+STATIC mp_obj_t os_dupterm_notify(mp_obj_t obj_in) {
+ (void)obj_in;
+ mp_hal_signal_dupterm_input();
+ return mp_const_none;
+}
+STATIC MP_DEFINE_CONST_FUN_OBJ_1(os_dupterm_notify_obj, os_dupterm_notify);
+
STATIC const mp_rom_map_elem_t os_module_globals_table[] = {
{ MP_ROM_QSTR(MP_QSTR___name__), MP_ROM_QSTR(MP_QSTR_uos) },
{ MP_ROM_QSTR(MP_QSTR_uname), MP_ROM_PTR(&os_uname_obj) },
{ MP_ROM_QSTR(MP_QSTR_urandom), MP_ROM_PTR(&os_urandom_obj) },
#if MICROPY_PY_OS_DUPTERM
{ MP_ROM_QSTR(MP_QSTR_dupterm), MP_ROM_PTR(&mp_uos_dupterm_obj) },
+ { MP_ROM_QSTR(MP_QSTR_dupterm_notify), MP_ROM_PTR(&os_dupterm_notify_obj) },
#endif
#if MICROPY_VFS_FAT
{ MP_ROM_QSTR(MP_QSTR_VfsFat), MP_ROM_PTR(&mp_fat_vfs_type) },
{ MP_ROM_QSTR(MP_QSTR_listdir), MP_ROM_PTR(&os_listdir_obj) },
+ { MP_ROM_QSTR(MP_QSTR_mkdir), MP_ROM_PTR(&os_mkdir_obj) },
{ MP_ROM_QSTR(MP_QSTR_remove), MP_ROM_PTR(&os_remove_obj) },
#endif
};
diff --git a/esp8266/mpconfigport.h b/esp8266/mpconfigport.h
index 9319db4b38..e2c7f57e22 100644
--- a/esp8266/mpconfigport.h
+++ b/esp8266/mpconfigport.h
@@ -9,6 +9,7 @@
#define MICROPY_EMIT_INLINE_THUMB (0)
#define MICROPY_MEM_STATS (0)
#define MICROPY_DEBUG_PRINTERS (1)
+#define MICROPY_DEBUG_PRINTER_DEST mp_debug_print
#define MICROPY_ENABLE_GC (1)
#define MICROPY_STACK_CHECK (1)
#define MICROPY_REPL_EVENT_DRIVEN (0)
@@ -50,6 +51,11 @@
#define MICROPY_PY_UZLIB (1)
#define MICROPY_PY_LWIP (1)
#define MICROPY_PY_MACHINE (1)
+#define MICROPY_PY_MACHINE_I2C (1)
+#define MICROPY_PY_WEBSOCKET (1)
+#define MICROPY_PY_WEBREPL (1)
+#define MICROPY_PY_WEBREPL_DELAY (20)
+#define MICROPY_PY_FRAMEBUF (1)
#define MICROPY_PY_MICROPYTHON_MEM_INFO (1)
#define MICROPY_PY_OS_DUPTERM (1)
#define MICROPY_CPYTHON_COMPAT (1)
@@ -57,7 +63,7 @@
#define MICROPY_FLOAT_IMPL (MICROPY_FLOAT_IMPL_FLOAT)
#define MICROPY_ERROR_REPORTING (MICROPY_ERROR_REPORTING_NORMAL)
#define MICROPY_STREAMS_NON_BLOCK (1)
-#define MICROPY_MODULE_FROZEN (1)
+#define MICROPY_MODULE_FROZEN_STR (1)
#define MICROPY_MODULE_FROZEN_LEXER mp_lexer_new_from_str32
#define MICROPY_FATFS_ENABLE_LFN (1)
@@ -100,12 +106,12 @@ typedef uint32_t sys_prot_t; // for modlwip
#define MP_PLAT_PRINT_STRN(str, len) mp_hal_stdout_tx_strn_cooked(str, len)
// extra built in names to add to the global namespace
-extern const struct _mp_obj_fun_builtin_t mp_builtin_open_obj;
#define MICROPY_PORT_BUILTINS \
+ { MP_OBJ_NEW_QSTR(MP_QSTR_help), (mp_obj_t)&mp_builtin_help_obj }, \
+ { MP_OBJ_NEW_QSTR(MP_QSTR_input), (mp_obj_t)&mp_builtin_input_obj }, \
{ MP_OBJ_NEW_QSTR(MP_QSTR_open), (mp_obj_t)&mp_builtin_open_obj },
// extra built in modules to add to the list of known ones
-extern const struct _mp_obj_module_t pyb_module;
extern const struct _mp_obj_module_t esp_module;
extern const struct _mp_obj_module_t network_module;
extern const struct _mp_obj_module_t utime_module;
@@ -115,7 +121,6 @@ extern const struct _mp_obj_module_t mp_module_machine;
extern const struct _mp_obj_module_t onewire_module;
#define MICROPY_PORT_BUILTIN_MODULES \
- { MP_OBJ_NEW_QSTR(MP_QSTR_pyb), (mp_obj_t)&pyb_module }, \
{ MP_OBJ_NEW_QSTR(MP_QSTR_esp), (mp_obj_t)&esp_module }, \
{ MP_OBJ_NEW_QSTR(MP_QSTR_lwip), (mp_obj_t)&mp_module_lwip }, \
{ MP_OBJ_NEW_QSTR(MP_QSTR_socket), (mp_obj_t)&mp_module_lwip }, \
@@ -137,6 +142,7 @@ extern const struct _mp_obj_module_t onewire_module;
const char *readline_hist[8]; \
vstr_t *repl_line; \
mp_obj_t mp_kbd_exception; \
+ mp_obj_t pin_irq_handler[16]; \
// We need to provide a declaration/definition of alloca()
#include <alloca.h>
@@ -146,6 +152,6 @@ extern const struct _mp_obj_module_t onewire_module;
#define MICROPY_MPHALPORT_H "esp_mphal.h"
#define MICROPY_HW_BOARD_NAME "ESP module"
#define MICROPY_HW_MCU_NAME "ESP8266"
-#define MICROPY_PY_SYS_PLATFORM "ESP8266"
+#define MICROPY_PY_SYS_PLATFORM "esp8266"
#define _assert(expr) ((expr) ? (void)0 : __assert_func(__FILE__, __LINE__, __func__, #expr))
diff --git a/esp8266/qstrdefsport.h b/esp8266/qstrdefsport.h
index 1819395fa4..7610eb33da 100644
--- a/esp8266/qstrdefsport.h
+++ b/esp8266/qstrdefsport.h
@@ -24,198 +24,8 @@
* THE SOFTWARE.
*/
-// qstrs specific to this port
+// qstrs specific to this port, only needed if they aren't auto-generated
-Q(help)
-
-// pyb module
-Q(pyb)
-Q(info)
-Q(freq)
-Q(millis)
-Q(elapsed_millis)
-Q(micros)
-Q(elapsed_micros)
-Q(delay)
-Q(udelay)
-Q(sync)
-Q(unique_id)
-
-// uos module
-Q(uos)
-Q(os)
-Q(uname)
-Q(sysname)
-Q(nodename)
-Q(release)
-Q(version)
-Q(machine)
-
-Q(esp)
-Q(socket)
-Q(usocket)
-Q(connect)
-Q(disconnect)
-Q(wifi_mode)
-Q(phy_mode)
-Q(osdebug)
-Q(sleep_type)
-Q(deepsleep)
-Q(adc)
-Q(vdd33)
-Q(chip_id)
-Q(flash_id)
-Q(flash_read)
-Q(flash_write)
-Q(flash_erase)
-Q(sdk_version)
-Q(freemem)
-Q(meminfo)
-Q(getaddrinfo)
-Q(send)
-Q(sendto)
-Q(recv)
-Q(recvfrom)
-Q(listen)
-Q(accept)
-Q(bind)
-Q(settimeout)
-Q(setblocking)
-Q(setsockopt)
-Q(close)
-Q(protocol)
-Q(getpeername)
-Q(onconnect)
-Q(onrecv)
-Q(onsent)
-Q(ondisconnect)
-Q(neopixel_write)
-Q(MODE_11B)
-Q(MODE_11G)
-Q(MODE_11N)
-Q(SLEEP_NONE)
-Q(SLEEP_LIGHT)
-Q(SLEEP_MODEM)
-Q(STA_MODE)
-Q(AP_MODE)
-Q(STA_AP_MODE)
-
-// network module
-Q(network)
-Q(WLAN)
-Q(active)
-Q(scan)
-Q(status)
-Q(isconnected)
-Q(mac)
-Q(config)
-Q(ifconfig)
-Q(STA_IF)
-Q(AP_IF)
-Q(STAT_IDLE)
-Q(STAT_CONNECTING)
-Q(STAT_WRONG_PASSWORD)
-Q(STAT_NO_AP_FOUND)
-Q(STAT_CONNECT_FAIL)
-Q(STAT_GOT_IP)
-// config keys
-Q(essid)
-
-// Pin class
-Q(Pin)
-Q(init)
-Q(mode)
-Q(pull)
-Q(value)
-Q(low)
-Q(high)
-Q(IN)
-Q(OUT)
-Q(OPEN_DRAIN)
-Q(PULL_NONE)
-Q(PULL_UP)
-Q(PULL_DOWN)
-
-// PWM class
-Q(PWM)
-Q(init)
-Q(deinit)
-Q(freq)
-Q(duty)
-
-// RTC
-Q(RTC)
-Q(datetime)
-Q(memory)
-
-// ADC
-Q(ADC)
-Q(read)
-
-// UART
-Q(UART)
-Q(init)
-
-// I2C
-Q(I2C)
-Q(init)
-Q(scl)
-Q(sda)
-Q(freq)
-Q(readfrom)
-Q(writeto)
-Q(stop)
-Q(buf)
-Q(addr)
-Q(n)
-
-// SPI
-Q(SPI)
-Q(init)
-Q(baudrate)
-Q(phase)
-Q(polarity)
-Q(sck)
-Q(mosi)
-Q(miso)
-Q(read)
-Q(readinto)
-Q(write)
-Q(write_readinto)
-
-// utime
-Q(utime)
-Q(localtime)
-Q(mktime)
-Q(sleep)
-Q(sleep_ms)
-Q(sleep_us)
-Q(ticks_ms)
-Q(ticks_us)
-Q(ticks_cpu)
-Q(ticks_diff)
-Q(time)
-
-// machine
-Q(reset)
-Q(Timer)
-Q(callback)
-Q(deinit)
-Q(init)
-Q(mode)
-Q(period)
-Q(ONE_SHOT)
-Q(PERIODIC)
-
-// onewire
-Q(_onewire)
-Q(onewire)
-Q(timings)
-Q(reset)
-Q(readbit)
-Q(readbyte)
-Q(writebit)
-Q(writebyte)
-Q(crc8)
-
-Q(json)
+// Entries for sys.path
+Q(/)
+Q(/lib)
diff --git a/esp8266/scripts/_boot.py b/esp8266/scripts/_boot.py
new file mode 100644
index 0000000000..c950de6758
--- /dev/null
+++ b/esp8266/scripts/_boot.py
@@ -0,0 +1,9 @@
+import uos
+from flashbdev import bdev
+
+try:
+ if bdev:
+ vfs = uos.VfsFat(bdev, "")
+except OSError:
+ import inisetup
+ vfs = inisetup.setup()
diff --git a/esp8266/scripts/flashbdev.py b/esp8266/scripts/flashbdev.py
new file mode 100644
index 0000000000..07ed966020
--- /dev/null
+++ b/esp8266/scripts/flashbdev.py
@@ -0,0 +1,68 @@
+import esp
+
+class FlashBdev:
+
+ SEC_SIZE = 4096
+ START_SEC = 0x89000 // SEC_SIZE
+ NUM_BLK = 0x73
+
+ def __init__(self, blocks=NUM_BLK):
+ self.blocks = blocks
+
+ def readblocks(self, n, buf):
+ #print("readblocks(%s, %x(%d))" % (n, id(buf), len(buf)))
+ esp.flash_read((n + self.START_SEC) * self.SEC_SIZE, buf)
+
+ def writeblocks(self, n, buf):
+ #print("writeblocks(%s, %x(%d))" % (n, id(buf), len(buf)))
+ #assert len(buf) <= self.SEC_SIZE, len(buf)
+ esp.flash_erase(n + self.START_SEC)
+ esp.flash_write((n + self.START_SEC) * self.SEC_SIZE, buf)
+
+ def ioctl(self, op, arg):
+ #print("ioctl(%d, %r)" % (op, arg))
+ if op == 4: # BP_IOCTL_SEC_COUNT
+ return self.blocks
+ if op == 5: # BP_IOCTL_SEC_SIZE
+ return self.SEC_SIZE
+
+def set_bl_flash_size(real_size):
+ if real_size == 256*1024:
+ code = 1
+ elif real_size == 512*1024:
+ code = 0
+ elif real_size == 1024*1024:
+ code = 2
+ elif real_size == 2048*1024:
+ code = 3
+ elif real_size == 4096*1024:
+ code = 4
+ else:
+ code = 2
+ buf = bytearray(4096)
+ esp.flash_read(0, buf)
+ buf[3] = (buf[3] & 0xf) | (code << 4)
+ esp.flash_erase(0)
+ esp.flash_write(0, buf)
+
+# If bootloader size ID doesn't correspond to real Flash size,
+# fix bootloader value and reboot.
+size = esp.flash_id() >> 16
+# Check that it looks like realistic power of 2 for flash sizes
+# commonly used with esp8266
+if 22 >= size >= 18:
+ size = 1 << size
+ if size != esp.flash_size():
+ import machine
+ import time
+ print("Bootloader Flash size appear to have been set incorrectly, trying to fix")
+ set_bl_flash_size(size)
+ machine.reset()
+ while 1: time.sleep(1)
+
+size = esp.flash_size()
+if size < 1024*1024:
+ bdev = None
+else:
+ # 16K at the flash end is reserved for SDK params storage
+ bdev = FlashBdev((size - 16384) // FlashBdev.SEC_SIZE - FlashBdev.START_SEC)
diff --git a/esp8266/scripts/inisetup.py b/esp8266/scripts/inisetup.py
new file mode 100644
index 0000000000..93a05bd8a7
--- /dev/null
+++ b/esp8266/scripts/inisetup.py
@@ -0,0 +1,46 @@
+import uos
+import network
+from flashbdev import bdev
+
+def wifi():
+ import ubinascii
+ ap_if = network.WLAN(network.AP_IF)
+ essid = b"MicroPython-%s" % ubinascii.hexlify(ap_if.config("mac")[-3:])
+ ap_if.config(essid=essid, authmode=network.AUTH_WPA_WPA2_PSK, password=b"micropythoN")
+
+def check_bootsec():
+ buf = bytearray(bdev.SEC_SIZE)
+ bdev.readblocks(0, buf)
+ empty = True
+ for b in buf:
+ if b != 0xff:
+ empty = False
+ break
+ if empty:
+ return True
+ fs_corrupted()
+
+def fs_corrupted():
+ import time
+ while 1:
+ print("""\
+FAT filesystem appears to be corrupted. If you had important data there, you
+may want to make a flash snapshot to try to recover it. Otherwise, perform
+factory reprogramming of MicroPython firmware (completely erase flash, followed
+by firmware programming).
+""")
+ time.sleep(3)
+
+def setup():
+ check_bootsec()
+ print("Performing initial setup")
+ wifi()
+ uos.VfsFat.mkfs(bdev)
+ vfs = uos.VfsFat(bdev, "")
+ with open("/boot.py", "w") as f:
+ f.write("""\
+# This file is executed on every boot (including wake-boot from deepsleep)
+import webrepl
+webrepl.start()
+""")
+ return vfs
diff --git a/esp8266/scripts/main.py b/esp8266/scripts/main.py
deleted file mode 100644
index 83bc52a321..0000000000
--- a/esp8266/scripts/main.py
+++ /dev/null
@@ -1 +0,0 @@
-# This script is run on boot
diff --git a/esp8266/scripts/neopixel.py b/esp8266/scripts/neopixel.py
new file mode 100644
index 0000000000..4818c74a3b
--- /dev/null
+++ b/esp8266/scripts/neopixel.py
@@ -0,0 +1,24 @@
+# NeoPixel driver for MicroPython on ESP8266
+# MIT license; Copyright (c) 2016 Damien P. George
+
+from esp import neopixel_write
+
+class NeoPixel:
+ def __init__(self, pin, n):
+ self.pin = pin
+ self.n = n
+ self.buf = bytearray(n * 3)
+ self.pin.init(pin.OUT, pin.PULL_NONE)
+
+ def __setitem__(self, index, val):
+ r, g, b = val
+ self.buf[index * 3] = g
+ self.buf[index * 3 + 1] = r
+ self.buf[index * 3 + 2] = b
+
+ def __getitem__(self, index):
+ i = index * 3
+ return self.buf[i + 1], self.buf[i], self.buf[i + 2]
+
+ def write(self):
+ neopixel_write(self.pin, self.buf, True)
diff --git a/esp8266/scripts/ntptime.py b/esp8266/scripts/ntptime.py
new file mode 100644
index 0000000000..650cc2e85b
--- /dev/null
+++ b/esp8266/scripts/ntptime.py
@@ -0,0 +1,34 @@
+try:
+ import usocket as socket
+except:
+ import socket
+try:
+ import ustruct as struct
+except:
+ import struct
+
+# (date(2000, 1, 1) - date(1900, 1, 1)).days * 24*60*60
+NTP_DELTA = 3155673600
+
+def time():
+ NTP_QUERY = bytearray(48)
+ NTP_QUERY[0] = 0x1b
+ addr = socket.getaddrinfo('pool.ntp.org', 123)[0][-1]
+ s = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
+ s.settimeout(1)
+ res = s.sendto(NTP_QUERY, addr)
+ msg = s.recv(48)
+ s.close()
+ val = struct.unpack("!I", msg[40:44])[0]
+ return val - NTP_DELTA
+
+# There's currently no timezone support in MicroPython, so
+# utime.localtime() will return UTC time (as if it was .gmtime())
+def settime():
+ t = time()
+ import machine
+ import utime
+ tm = utime.localtime(t)
+ tm = tm[0:3] + (0,) + tm[3:6] + (0,)
+ machine.RTC().datetime(tm)
+ print(utime.localtime())
diff --git a/esp8266/tests/onewire.py b/esp8266/scripts/onewire.py
index 15fec1e55c..4980d0af5c 100644
--- a/esp8266/tests/onewire.py
+++ b/esp8266/scripts/onewire.py
@@ -1,12 +1,15 @@
-import time
-import pyb
+# 1-Wire driver for MicroPython on ESP8266
+# MIT license; Copyright (c) 2016 Damien P. George
+
import _onewire as _ow
+class OneWireError(Exception):
+ pass
+
class OneWire:
- CMD_SEARCHROM = const(0xf0)
- CMD_READROM = const(0x33)
- CMD_MATCHROM = const(0x55)
- CMD_SKIPROM = const(0xcc)
+ SEARCH_ROM = const(0xf0)
+ MATCH_ROM = const(0x55)
+ SKIP_ROM = const(0xcc)
def __init__(self, pin):
self.pin = pin
@@ -15,32 +18,32 @@ class OneWire:
def reset(self):
return _ow.reset(self.pin)
- def read_bit(self):
+ def readbit(self):
return _ow.readbit(self.pin)
- def read_byte(self):
+ def readbyte(self):
return _ow.readbyte(self.pin)
- def read_bytes(self, count):
+ def read(self, count):
buf = bytearray(count)
for i in range(count):
buf[i] = _ow.readbyte(self.pin)
return buf
- def write_bit(self, value):
+ def writebit(self, value):
return _ow.writebit(self.pin, value)
- def write_byte(self, value):
+ def writebyte(self, value):
return _ow.writebyte(self.pin, value)
- def write_bytes(self, buf):
+ def write(self, buf):
for b in buf:
_ow.writebyte(self.pin, b)
def select_rom(self, rom):
self.reset()
- self.write_byte(CMD_MATCHROM)
- self.write_bytes(rom)
+ self.writebyte(MATCH_ROM)
+ self.write(rom)
def scan(self):
devices = []
@@ -57,7 +60,7 @@ class OneWire:
def _search_rom(self, l_rom, diff):
if not self.reset():
return None, 0
- self.write_byte(CMD_SEARCHROM)
+ self.writebyte(SEARCH_ROM)
if not l_rom:
l_rom = bytearray(8)
rom = bytearray(8)
@@ -66,8 +69,8 @@ class OneWire:
for byte in range(8):
r_b = 0
for bit in range(8):
- b = self.read_bit()
- if self.read_bit():
+ b = self.readbit()
+ if self.readbit():
if b: # there are no devices or there is an error on the bus
return None, 0
else:
@@ -75,7 +78,7 @@ class OneWire:
if diff > i or ((l_rom[byte] & (1 << bit)) and diff != i):
b = 1
next_diff = i
- self.write_bit(b)
+ self.writebit(b)
if b:
r_b |= 1 << bit
i -= 1
@@ -86,62 +89,39 @@ class OneWire:
return _ow.crc8(data)
class DS18B20:
- THERM_CMD_CONVERTTEMP = const(0x44)
- THERM_CMD_RSCRATCHPAD = const(0xbe)
+ CONVERT = const(0x44)
+ RD_SCRATCH = const(0xbe)
+ WR_SCRATCH = const(0x4e)
def __init__(self, onewire):
self.ow = onewire
- self.roms = []
def scan(self):
- self.roms = []
- for rom in self.ow.scan():
- if rom[0] == 0x28:
- self.roms += [rom]
- return self.roms
+ return [rom for rom in self.ow.scan() if rom[0] == 0x28]
- def start_measure(self):
+ def convert_temp(self):
if not self.ow.reset():
- return False
- self.ow.write_byte(CMD_SKIPROM)
- self.ow.write_byte(THERM_CMD_CONVERTTEMP)
- return True
+ raise OneWireError
+ self.ow.writebyte(SKIP_ROM)
+ self.ow.writebyte(CONVERT)
- def get_temp(self, rom):
+ def read_scratch(self, rom):
if not self.ow.reset():
- return None
+ raise OneWireError
+ self.ow.select_rom(rom)
+ self.ow.writebyte(RD_SCRATCH)
+ buf = self.ow.read(9)
+ if self.ow.crc8(buf):
+ raise OneWireError
+ return buf
+ def write_scratch(self, rom, buf):
+ if not self.ow.reset():
+ raise OneWireError
self.ow.select_rom(rom)
- self.ow.write_byte(THERM_CMD_RSCRATCHPAD)
+ self.ow.writebyte(WR_SCRATCH)
+ self.ow.write(buf)
- buf = self.ow.read_bytes(9)
- if self.ow.crc8(buf):
- return None
-
- return self._convert_temp(buf)
-
- def _convert_temp(self, data):
- temp_lsb = data[0]
- temp_msb = data[1]
- return (temp_msb << 8 | temp_lsb) / 16
-
-# connect 1-wire temp sensors to GPIO12 for this test
-def test():
- dat = pyb.Pin(12)
- ow = OneWire(dat)
-
- ds = DS18B20(ow)
- roms = ow.scan()
- print('found devices:', roms)
-
- for i in range(4):
- print('temperatures:', end=' ')
- ds.start_measure()
- time.sleep_ms(750)
- for rom in roms:
- print(ds.get_temp(rom), end=' ')
- print()
-
-#pyb.freq(80000000)
-#pyb.freq(160000000)
-test()
+ def read_temp(self, rom):
+ buf = self.read_scratch(rom)
+ return (buf[1] << 8 | buf[0]) / 16
diff --git a/esp8266/scripts/port_diag.py b/esp8266/scripts/port_diag.py
new file mode 100644
index 0000000000..fd7ee52d14
--- /dev/null
+++ b/esp8266/scripts/port_diag.py
@@ -0,0 +1,19 @@
+import esp
+import uctypes
+
+
+def main():
+
+ ROM = uctypes.bytearray_at(0x40200000, 16)
+ fid = esp.flash_id()
+
+ print("Flash ID: %x (Vendor: %x Device: %x)" % (fid, fid & 0xff, fid & 0xff00 | fid >> 16))
+
+ print("Flash bootloader data:")
+ SZ_MAP = {0: "512KB", 1: "256KB", 2: "1MB", 3: "2MB", 4: "4MB"}
+ FREQ_MAP = {0: "40MHZ", 1: "26MHZ", 2: "20MHz", 0xf: "80MHz"}
+ print("Byte @2: %02x" % ROM[2])
+ print("Byte @3: %02x (Flash size: %s Flash freq: %s)" % (ROM[3], SZ_MAP.get(ROM[3] >> 4, "?"), FREQ_MAP.get(ROM[3] & 0xf)))
+
+
+main()
diff --git a/esp8266/scripts/webrepl.py b/esp8266/scripts/webrepl.py
new file mode 100644
index 0000000000..1a2c82277e
--- /dev/null
+++ b/esp8266/scripts/webrepl.py
@@ -0,0 +1,62 @@
+# This module should be imported from REPL, not run from command line.
+import socket
+import uos
+import network
+import websocket
+import websocket_helper
+import _webrepl
+
+listen_s = None
+client_s = None
+
+def setup_conn(port, accept_handler):
+ global listen_s, client_s
+ listen_s = socket.socket()
+ listen_s.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
+
+ ai = socket.getaddrinfo("0.0.0.0", port)
+ addr = ai[0][4]
+
+ listen_s.bind(addr)
+ listen_s.listen(1)
+ listen_s.setsockopt(socket.SOL_SOCKET, 20, accept_handler)
+ for i in (network.AP_IF, network.STA_IF):
+ iface = network.WLAN(i)
+ if iface.active():
+ print("WebREPL daemon started on ws://%s:%d" % (iface.ifconfig()[0], port))
+
+
+def accept_conn(listen_sock):
+ global client_s
+ cl, remote_addr = listen_sock.accept()
+ print("\nWebREPL connection from:", remote_addr)
+ client_s = cl
+ websocket_helper.server_handshake(cl)
+ ws = websocket.websocket(cl, True)
+ ws = _webrepl._webrepl(ws)
+ cl.setblocking(False)
+ # notify REPL on socket incoming data
+ cl.setsockopt(socket.SOL_SOCKET, 20, uos.dupterm_notify)
+ uos.dupterm(ws)
+
+
+def stop():
+ global listen_s, client_s
+ uos.dupterm(None)
+ if client_s:
+ client_s.close()
+ if listen_s:
+ listen_s.close()
+
+
+def start(port=8266):
+ stop()
+ try:
+ import port_config
+ _webrepl.password(port_config.WEBREPL_PASS)
+ setup_conn(port, accept_conn)
+ print("Started webrepl in normal mode")
+ except:
+ import webrepl_setup
+ setup_conn(port, webrepl_setup.handle_conn)
+ print("Started webrepl in setup mode")
diff --git a/esp8266/scripts/webrepl_setup.py b/esp8266/scripts/webrepl_setup.py
new file mode 100644
index 0000000000..7c4068750c
--- /dev/null
+++ b/esp8266/scripts/webrepl_setup.py
@@ -0,0 +1,80 @@
+import sys
+import socket
+import time
+
+from websocket import *
+import websocket_helper
+
+
+def setup_server():
+ s = socket.socket()
+ s.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
+
+ ai = socket.getaddrinfo("0.0.0.0", 8266)
+ addr = ai[0][4]
+
+ s.bind(addr)
+ s.listen(1)
+ return s
+
+def getpass(stream, prompt):
+ stream.write(prompt)
+ passwd = b""
+ while 1:
+ c = stream.read(1)
+ if c in (b"\r", b"\n"):
+ stream.write("\r\n")
+ return passwd
+ passwd += c
+# stream.write("*")
+
+def handle_conn(listen_sock):
+ cl, remote_addr = listen_sock.accept()
+
+ print("""
+
+First-time WebREPL connection has been received. WebREPL initial setup
+will now start over this connection. During setup, UART REPL will be
+non-responsive. After setup finishes, the board will be rebooted. In
+case of error during setup, current session will continue.
+
+If you receive this message unexpectedly, it may mean that your WebREPL
+connection is being hacked (power off board if unsure).
+""")
+
+ websocket_helper.server_handshake(cl)
+ ws = websocket(cl)
+
+ ws.write("""\
+Welcome to MicroPython WebREPL!\r
+\r
+This is the first time you connect to WebREPL, so please set a password\r
+to use for the following WebREPL sessions. Once you enter the password\r
+twice, your board will reboot with WebREPL running in active mode. On\r
+some boards, you may need to press reset button or reconnect power.\r
+\r
+""")
+
+ while 1:
+ passwd1 = getpass(ws, "New password: ")
+ if len(passwd1) < 4:
+ ws.write("Password too short\r\n")
+ continue
+ passwd2 = getpass(ws, "Confirm password: ")
+ if passwd1 == passwd2:
+ break
+ ws.write("Passwords do not match\r\n")
+
+ with open("port_config.py", "w") as f:
+ f.write("WEBREPL_PASS = %r\n" % passwd1.decode("ascii"))
+
+ ws.write("Password successfully set, restarting...\r\n")
+ cl.close()
+ time.sleep(2)
+ import machine
+ machine.reset()
+
+
+def test():
+ s = setup_server()
+ handle_conn(s)
diff --git a/esp8266/scripts/websocket_helper.py b/esp8266/scripts/websocket_helper.py
new file mode 100644
index 0000000000..22ac28592d
--- /dev/null
+++ b/esp8266/scripts/websocket_helper.py
@@ -0,0 +1,75 @@
+import sys
+try:
+ import ubinascii as binascii
+except:
+ import binascii
+try:
+ import uhashlib as hashlib
+except:
+ import hashlib
+
+DEBUG = 0
+
+def server_handshake(sock):
+ clr = sock.makefile("rwb", 0)
+ l = clr.readline()
+ #sys.stdout.write(repr(l))
+
+ webkey = None
+
+ while 1:
+ l = clr.readline()
+ if not l:
+ raise OSError("EOF in headers")
+ if l == b"\r\n":
+ break
+ # sys.stdout.write(l)
+ h, v = [x.strip() for x in l.split(b":", 1)]
+ if DEBUG:
+ print((h, v))
+ if h == b'Sec-WebSocket-Key':
+ webkey = v
+
+ if not webkey:
+ raise OSError("Not a websocket request")
+
+ if DEBUG:
+ print("Sec-WebSocket-Key:", webkey, len(webkey))
+
+ respkey = webkey + b"258EAFA5-E914-47DA-95CA-C5AB0DC85B11"
+ respkey = hashlib.sha1(respkey).digest()
+ respkey = binascii.b2a_base64(respkey)[:-1]
+
+ resp = b"""\
+HTTP/1.1 101 Switching Protocols\r
+Upgrade: websocket\r
+Connection: Upgrade\r
+Sec-WebSocket-Accept: %s\r
+\r
+""" % respkey
+
+ if DEBUG:
+ print(resp)
+ sock.send(resp)
+
+
+# Very simplified client handshake, works for MicroPython's
+# websocket server implementation, but probably not for other
+# servers.
+def client_handshake(sock):
+ cl = sock.makefile("rwb", 0)
+ cl.write(b"""\
+GET / HTTP/1.1\r
+Host: echo.websocket.org\r
+Connection: Upgrade\r
+Upgrade: websocket\r
+Sec-WebSocket-Key: foo\r
+\r
+""")
+ l = cl.readline()
+# print(l)
+ while 1:
+ l = cl.readline()
+ if l == b"\r\n":
+ break
+# sys.stdout.write(l)
diff --git a/esp8266/tests/neopixel.py b/esp8266/tests/neopixel.py
deleted file mode 100644
index 7717bb496b..0000000000
--- a/esp8266/tests/neopixel.py
+++ /dev/null
@@ -1,64 +0,0 @@
-import time
-import machine
-from esp import neopixel_write
-
-class NeoPixel:
- def __init__(self, pin, n):
- self.pin = pin
- self.n = n
- self.buf = bytearray(n * 3)
-
- def __setitem__(self, index, val):
- r, g, b = val
- self.buf[index * 3] = g
- self.buf[index * 3 + 1] = r
- self.buf[index * 3 + 2] = b
-
- def __getitem__(self, index):
- i = index * 3
- return self.buf[i], self.buf[i + 1], self.buf[i + 2]
-
- def write(self):
- neopixel_write(self.pin, self.buf, True)
-
-def test():
- # put a neopixel strip on GPIO4
- p = machine.Pin(4, machine.Pin.OUT)
- np = NeoPixel(p, 8)
- n = np.n
-
- # cycle
- for i in range(4 * n):
- for j in range(n):
- np[j] = (0, 0, 0)
- np[i % n] = (255, 255, 255)
- np.write()
- time.sleep_ms(25)
-
- # bounce
- for i in range(4 * n):
- for j in range(n):
- np[j] = (0, 0, 128)
- if (i // n) % 2 == 0:
- np[i % n] = (0, 0, 0)
- else:
- np[n - 1 - (i % n)] = (0, 0, 0)
- np.write()
- time.sleep_ms(60)
-
- # fade in/out
- for i in range(0, 4 * 256, 8):
- for j in range(n):
- if (i // 256) % 2 == 0:
- val = i & 0xff
- else:
- val = 255 - (i & 0xff)
- np[j] = (val, 0, 0)
- np.write()
-
- # clear
- for i in range(n):
- np[i] = (0, 0, 0)
- np.write()
-
-test()
diff --git a/esp8266/uart.c b/esp8266/uart.c
index f371935399..573f0cb072 100644
--- a/esp8266/uart.c
+++ b/esp8266/uart.c
@@ -27,14 +27,6 @@ extern UartDevice UartDev;
// the uart to which OS messages go; -1 to disable
static int uart_os = UART_OS;
-/* unused
-// circular buffer for RX buffering
-#define RX_BUF_SIZE (256)
-static uint16_t rx_buf_in;
-static uint16_t rx_buf_out;
-static uint8_t rx_buf[RX_BUF_SIZE];
-*/
-
#if MICROPY_REPL_EVENT_DRIVEN
static os_event_t uart_evt_queue[16];
#endif
@@ -94,12 +86,6 @@ static void ICACHE_FLASH_ATTR uart_config(uint8 uart_no) {
WRITE_PERI_REG(UART_INT_CLR(uart_no), 0xffff);
// enable rx_interrupt
SET_PERI_REG_MASK(UART_INT_ENA(uart_no), UART_RXFIFO_FULL_INT_ENA);
-
- /* unused
- // init RX buffer
- rx_buf_in = 0;
- rx_buf_out = 0;
- */
}
/******************************************************************************
@@ -179,7 +165,6 @@ static void uart0_rx_intr_handler(void *para) {
goto read_chars;
} else if (UART_RXFIFO_TOUT_INT_ST == (READ_PERI_REG(UART_INT_ST(uart_no)) & UART_RXFIFO_TOUT_INT_ST)) {
read_chars:
-#if 1 //MICROPY_REPL_EVENT_DRIVEN is not available here
ETS_UART_INTR_DISABLE();
while (READ_PERI_REG(UART_STATUS(uart_no)) & (UART_RXFIFO_CNT << UART_RXFIFO_CNT_S)) {
@@ -196,31 +181,28 @@ static void uart0_rx_intr_handler(void *para) {
// Clear pending FIFO interrupts
WRITE_PERI_REG(UART_INT_CLR(UART_REPL), UART_RXFIFO_TOUT_INT_CLR | UART_RXFIFO_FULL_INT_ST);
ETS_UART_INTR_ENABLE();
+ }
+}
-#else
- while (READ_PERI_REG(UART_STATUS(uart_no)) & (UART_RXFIFO_CNT << UART_RXFIFO_CNT_S)) {
- uint8 RcvChar = READ_PERI_REG(UART_FIFO(uart_no)) & 0xff;
- uint16_t rx_buf_in_next = (rx_buf_in + 1) % RX_BUF_SIZE;
- if (rx_buf_in_next != rx_buf_out) {
- rx_buf[rx_buf_in] = RcvChar;
- rx_buf_in = rx_buf_in_next;
- }
+// Waits at most timeout microseconds for at least 1 char to become ready for reading.
+// Returns true if something available, false if not.
+bool uart_rx_wait(uint32_t timeout_us) {
+ uint32_t start = system_get_time();
+ for (;;) {
+ if (input_buf.iget != input_buf.iput) {
+ return true; // have at least 1 char ready for reading
}
-#endif
+ if (system_get_time() - start >= timeout_us) {
+ return false; // timeout
+ }
+ ets_event_poll();
}
}
-/* unused
-int uart0_rx(void) {
- if (rx_buf_out != rx_buf_in) {
- int chr = rx_buf[rx_buf_out];
- rx_buf_out = (rx_buf_out + 1) % RX_BUF_SIZE;
- return chr;
- } else {
- return -1;
- }
+// Returns char from the input buffer, else -1 if buffer is empty.
+int uart_rx_char(void) {
+ return ringbuf_get(&input_buf);
}
-*/
int uart_rx_one_char(uint8 uart_no) {
if (READ_PERI_REG(UART_STATUS(uart_no)) & (UART_RXFIFO_CNT << UART_RXFIFO_CNT_S)) {
diff --git a/esp8266/uart.h b/esp8266/uart.h
index 2f762db5a2..8e09beea58 100644
--- a/esp8266/uart.h
+++ b/esp8266/uart.h
@@ -91,6 +91,8 @@ typedef struct {
void uart_init(UartBautRate uart0_br, UartBautRate uart1_br);
int uart0_rx(void);
+bool uart_rx_wait(uint32_t timeout_us);
+int uart_rx_char(void);
void uart_tx_one_char(uint8 uart, uint8 TxChar);
void uart_flush(uint8 uart);
void uart_os_config(int uart);