summaryrefslogtreecommitdiffstatshomepage
path: root/esp8266
diff options
context:
space:
mode:
authorDamien George <damien.p.george@gmail.com>2017-08-14 12:21:43 +1000
committerDamien George <damien.p.george@gmail.com>2017-08-14 12:21:43 +1000
commit1db008349cc970fd83b85574492badbf0460ad51 (patch)
tree76ca40810fd44eec799ff01e3c3a753c494bae9e /esp8266
parentbb254ba0ea89ce60dd6deab94991b2651c00dff3 (diff)
parent3611dcc260cef08eaa497cea4e3ca17977848b6c (diff)
downloadmicropython-1db008349cc970fd83b85574492badbf0460ad51.tar.gz
micropython-1db008349cc970fd83b85574492badbf0460ad51.zip
Merge tag 'v1.8.4' into parse-bytecode
Support for stream decompression in uzlib, and more ESP8266 features This release includes some bug fixes, code clean-up, updates to the docs, more tests, and various feature additions. The uzlib module now supports efficient stream decompression in the form of the uzlib.DecompIO class. Freezing of bytecode now supports floats for the ESP8266 port, as well as complex numbers for all ports. The stmhal port has ADC working on L4 microcontrollers, fixed initialisation for DAC, and addition of the machine.WDT class and machine.reset_cause function. For the ESP8266 port Pin(16) now works as an input pin and the hardware SPI peripheral is exposed as machine.SPI(1). The os.umount function is implemented and the port supports mounting of externally connected SD cards. The machine.WDT class is added, wlan.scan() is fixed to return all access points, and there is support for DS18S20 devices. py core: - runtime: factor out exception raising helpers - runtime: define mp_check_self(pred) helper macro - objdict: get rid of asserts (remove/replace with mp_check_self()) - get rid of assert() in method argument checking functions - objtuple: in tuple_cmp_helper, use mp_check_self instead of raising - objstr: use mp_raise_{Type,Value}Error instead of mp_raise_msg - obj.h: for obj reprs A,B,C use void* explicitly for mp_obj_t typedef - mpconfigport.h: remove typedef of machine_ptr_t, it's no longer needed - sequence: allow to use bignums as indices in slice objects - stream.c: use mp_obj_get_type in mp_get_stream_raise - gc: add MICROPY_GC_CONSERVATIVE_CLEAR option to always zero memory - compile: don't compile assert statements when optimisations enabled - modstruct: use more compact mp_raise_ValueError function - emitglue: use more compact mp_raise_ValueError function - rename struct mp_code_state to mp_code_state_t - mkrules.mk: allow to override name of libmicropython.a - mpprint: fail an assertion with unsupported format specifiers - makeqstrdata.py: compute the qstr hash from bytes, not characters - if str/bytes hash is 0 then explicitly compute it - emitglue.c: provide mp_raw_code_load_file for any unix architecture - add MICROPY_USE_INTERNAL_PRINTF option, defaults to enabled extmod: - modwebrepl: set_password(): raise exception for too long password - uzlib/: update uzlib to v2.0: new API supporting stream decompression - moduzlib: refactor to new stream-compatible uzlib 2.0 API - uzlib/: update uzlib to v2.0.1: fixes for pedantic compiler warnings - uzlib/: update uzlib to v2.0.2: consistently use stdint types - modbtree: do CHECK_ERROR after __bt_seq() - modubinascii: implement binascii.crc32 - modubinascii: make crc32() support configurable - modframebuf: fix pixel accessor to return a 1-bit result - add machine_spi with generic SPI C-protocol and helper methods - modframebuf: fix fill and scroll when height not divisible by 8 - moduzlib: implement zlib stream decompressor class, DecompIO - moduzlib: use mperrno.h for error constants - modframebuf: include font from stmhal directory explicitly - moduzlib: support wbits arg to DecompIO - framebuf: add the xstep!=0 case to scroll() method lib: - utils/stdout_helpers: fix function signature to match py/mphal.h - berkeley-db-1.xx: update to upstream, fixes MacOSX build - utils/pyexec: qstr_pool_info() requires size_t* parameters drivers: - sdcard: port the SDCard driver to new machine API, with backwards compatibility for pyboard tools: - mpy-tool.py: support freezing float literals with obj-repr C - mpy-tool.py: store qstr config values in global config object - mpy-tool.py: compute the hash value for str/bytes objects - mpy-tool.py: support freezing of complex numbers tests: - rename zlibd_decompress.py -> uzlib_decompress.py - basics: add more tuple tests to improve coverage testing - basics: add more list tests to improve coverage testing - misc/non_compliant: add tests to improve coverage testing - basics: add test for break from within try within a for-loop - basics: add a test file for overriding special methods - basics/special_methods: enable tests for extra special methods - uzlib_decompress: actually test raw DEFLATE stream - run-tests: disable thread/thread_lock4.py on Travis - run-tests: disable thread/stress_heap.py when running on Travis - cmdline: add test for -O option to check optimisation value - extmod/vfs_fat_ramdisk: add tests for VFS.umount() - run-tests: disable thread_gc1.py test on Travis - unix/extra_coverage: add test for str/bytes with invalid hash - extmod: add test for uzlib.DecompIO - extmod: add a test for framebuf module, tested by coverage build - extmod/uzlib_decompio: add zlib bitstream testcases - extmod/framebuf1: add tests for scrolling in the x-direction - run-tests: disable thread/stress_recurse.py test on Travis unix port: - mpconfigport.h: don't include stdio.h on MacOS - when find'ing frozen files don't use extra slash, do follow symlinks qemu-arm port: - enable MICROPY_PY_ALL_SPECIAL_METHODS stmhal port: - boards: update STM32L476 pin defs to include ADC channels - adc.c: get ADC working on STM32L4 MCUs - fix timer capture/compare interrupt handling for TIM1 and TIM8 - remove obsolete code for special handling of TIM3 irq settings - make ADC channel 16 available on L4 MCUs - update pin print to print new constants - modusocket: set self->nic to MP_OBJ_NULL after socket close - update boot.py files to use VCP instead of CDC - spi: factor out SPI transfer code to a single function - spi: support new machine SPI methods in legacy SPI object - add machine.WDT class - set STM32F7DISC CPU Frequency to 216 MHz - dac: fix DAC (re-)initialisation by resetting DMA - wdt: implement keyword args to WDT constructor - modmachine: implement machine.reset_cause() function, and consts - machine.POWER_ON is renamed to machine.PWRON_RESET - when find'ing frozen files don't use extra slash, do follow symlinks cc3200 port: - add machine.PWRON_RESET constant (machine.POWER_ON is now deprecated) teensy port: - fix execution of frozen boot.py and main.py esp8266 port: - fix reading of pin object for GPIO16; Pin(16) now works as an input - PULL_UP is not supported on Pin(16), so raise an exception in this case - enable support for all special methods - modpybhspi: add a HSPI module for hardware SPI support - modmachinespi: add a factory method for SoftSPI/HSPI - esp_mphal: no longer disable watchdog on startup - modpybrtc: use 64-bit arithmetic when computing alarm expiry - hspi: enable duplex operation of hardware SPI - modous: add os.umount method to unmount a filesystem - modmachinewdt: implement machine.WDT class - modules: split onewire.py into OneWire and DS18X20 driver - modules/onewire: change onewire.read() to onewire.readinto() - modules/ds18x20.py: add support for DS18S20 devices - modpybspi: use generic SPI helper methods to implement SPI - modpybhspi: simplify HSPI driver by using 1 function for xfers - modmachinewdt: add .deinit() method - modmachine: add WDT_RESET and SOFT_RESET constants - modmachine: don't expose internal SoftSPI and HSPI classes - modmachine: simplify SPI class implementation multiplexing - espneopixel: disable IRQs during eps.neopixel_write - modnetwork: fix wlan.scan() method so it returns all networks - modmachine: map PWR_ON_RESET to vendor's REASON_DEFAULT_RST - machine.PWR_ON_RESET is renamed to machine.PWRON_RESET - when find'ing frozen files don't use extra slash, do follow symlinks docs: - esp8266/tutorial/pins: fix typo in commands for pin input mode - esp8266/intro: add command to install esptool.py 1.0.1 via pip - library/machine.WDT: add note that WDT is only available on WiPy - esp8266/quickref: fix and update the SPI docs - esp8266: update quickref and tutorial for OneWire/DS18X20 driver - pyboard: update USB mouse tutorial to use VCP instead of CDC - pyboard: update USB mouse tutorial to use pyb.USB_HID() - library: add reference for pyb.usb_mode and pyb.USB_HID - pyboard/quickref: add links to pinouts for other pyboard variants - pyboard/quickref: add section on "delay and timing" for utime mod - esp8266/quickref: add internal links to docs for some modules - esp8266/quickref: update information on SPI classes - esp8266/quickref: further improvements for SPI subsections - library/machine.WDT: add that WDT is available on pyboard - reference/isr_rules.rst: two minor additions to docs for using ISR misc: - add *.pyc to .gitignore, because Python 2 doesn't use __pycache__ - build mpy-cross as part of the Travis process
Diffstat (limited to 'esp8266')
-rw-r--r--esp8266/Makefile6
-rw-r--r--esp8266/esp8266.ld3
-rw-r--r--esp8266/esp_mphal.c6
-rw-r--r--esp8266/espneopixel.c2
-rw-r--r--esp8266/etshal.h3
-rw-r--r--esp8266/hspi.c331
-rw-r--r--esp8266/hspi.h79
-rw-r--r--esp8266/hspi_register.h278
-rw-r--r--esp8266/modmachine.c9
-rw-r--r--esp8266/modmachinewdt.c85
-rw-r--r--esp8266/modnetwork.c7
-rw-r--r--esp8266/modpyb.h2
-rw-r--r--esp8266/modpybhspi.c224
-rw-r--r--esp8266/modpybpin.c8
-rw-r--r--esp8266/modpybrtc.c2
-rw-r--r--esp8266/modpybspi.c70
-rw-r--r--esp8266/modules/ds18x20.py46
-rw-r--r--esp8266/modules/onewire.py (renamed from esp8266/scripts/onewire.py)51
-rw-r--r--esp8266/moduos.c5
-rw-r--r--esp8266/mpconfigport.h4
20 files changed, 1103 insertions, 118 deletions
diff --git a/esp8266/Makefile b/esp8266/Makefile
index ea9c7eb871..433b41ecfd 100644
--- a/esp8266/Makefile
+++ b/esp8266/Makefile
@@ -78,7 +78,9 @@ SRC_C = \
modpybrtc.c \
modpybadc.c \
modpybuart.c \
+ modmachinewdt.c \
modpybspi.c \
+ modpybhspi.c \
modesp.c \
modnetwork.c \
modutime.c \
@@ -89,6 +91,7 @@ SRC_C = \
$(BUILD)/frozen.c \
fatfs_port.c \
axtls_helpers.c \
+ hspi.c \
$(SRC_MOD)
STM_SRC_C = $(addprefix stmhal/,\
@@ -125,7 +128,6 @@ LIB_SRC_C = $(addprefix lib/,\
timeutils/timeutils.c \
utils/pyexec.c \
utils/pyhelp.c \
- utils/printf.c \
fatfs/ff.c \
fatfs/option/ccsbcs.c \
)
@@ -137,7 +139,7 @@ DRIVERS_SRC_C = $(addprefix drivers/,\
SRC_S = \
gchelper.s \
-FROZEN_MPY_PY_FILES := $(shell find $(FROZEN_MPY_DIR)/ -type f -name '*.py')
+FROZEN_MPY_PY_FILES := $(shell find -L $(FROZEN_MPY_DIR) -type f -name '*.py')
FROZEN_MPY_MPY_FILES := $(addprefix $(BUILD)/,$(FROZEN_MPY_PY_FILES:.py=.mpy))
OBJ =
diff --git a/esp8266/esp8266.ld b/esp8266/esp8266.ld
index a55aff52e5..c726790d38 100644
--- a/esp8266/esp8266.ld
+++ b/esp8266/esp8266.ld
@@ -141,7 +141,10 @@ SECTIONS
*modpybadc.o(.literal*, .text*)
*modpybuart.o(.literal*, .text*)
*modpybi2c.o(.literal*, .text*)
+ *modmachinewdt.o(.literal*, .text*)
*modpybspi.o(.literal*, .text*)
+ *modpybhspi.o(.literal*, .text*)
+ *hspi.o(.literal*, .text*)
*modesp.o(.literal* .text*)
*modnetwork.o(.literal* .text*)
*moduos.o(.literal* .text*)
diff --git a/esp8266/esp_mphal.c b/esp8266/esp_mphal.c
index a2710af2e6..dc6944fd4c 100644
--- a/esp8266/esp_mphal.c
+++ b/esp8266/esp_mphal.c
@@ -36,17 +36,13 @@
#include "extmod/misc.h"
#include "lib/utils/pyexec.h"
-extern void ets_wdt_disable(void);
-extern void wdt_feed(void);
-extern void ets_delay_us();
-
STATIC byte input_buf_array[256];
ringbuf_t input_buf = {input_buf_array, sizeof(input_buf_array)};
void mp_hal_debug_tx_strn_cooked(void *env, const char *str, uint32_t len);
const mp_print_t mp_debug_print = {NULL, mp_hal_debug_tx_strn_cooked};
void mp_hal_init(void) {
- ets_wdt_disable(); // it's a pain while developing
+ //ets_wdt_disable(); // it's a pain while developing
mp_hal_rtc_init();
uart_init(UART_BIT_RATE_115200, UART_BIT_RATE_115200);
}
diff --git a/esp8266/espneopixel.c b/esp8266/espneopixel.c
index 0f12f4c820..e16c874f23 100644
--- a/esp8266/espneopixel.c
+++ b/esp8266/espneopixel.c
@@ -41,6 +41,7 @@ void /*ICACHE_RAM_ATTR*/ esp_neopixel_write(uint8_t pin, uint8_t *pixels, uint32
}
#endif
+ uint32_t irq_state = mp_hal_quiet_timing_enter();
for(t = time0;; t = time0) {
if(pix & mask) t = time1; // Bit high duration
while(((c = mp_hal_ticks_cpu()) - startTime) < period); // Wait for bit start
@@ -55,4 +56,5 @@ void /*ICACHE_RAM_ATTR*/ esp_neopixel_write(uint8_t pin, uint8_t *pixels, uint32
}
}
while((mp_hal_ticks_cpu() - startTime) < period); // Wait for last bit
+ mp_hal_quiet_timing_exit(irq_state);
}
diff --git a/esp8266/etshal.h b/esp8266/etshal.h
index dd61ddec93..e7326a43ba 100644
--- a/esp8266/etshal.h
+++ b/esp8266/etshal.h
@@ -20,6 +20,9 @@ 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);
+extern void ets_wdt_disable(void);
+extern void wdt_feed(void);
+
// Opaque structure
typedef char MD5_CTX[64];
diff --git a/esp8266/hspi.c b/esp8266/hspi.c
new file mode 100644
index 0000000000..436fb4f6f4
--- /dev/null
+++ b/esp8266/hspi.c
@@ -0,0 +1,331 @@
+/*
+* The MIT License (MIT)
+*
+* Copyright (c) 2015 David Ogilvy (MetalPhreak)
+* Modified 2016 by Radomir Dopieralski
+*
+* 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 "hspi.h"
+
+/*
+Wrapper to setup HSPI/SPI GPIO pins and default SPI clock
+ spi_no - SPI (0) or HSPI (1)
+Not used in Micropython.
+*/
+void spi_init(uint8_t spi_no) {
+ spi_init_gpio(spi_no, SPI_CLK_USE_DIV);
+ spi_clock(spi_no, SPI_CLK_PREDIV, SPI_CLK_CNTDIV);
+ spi_tx_byte_order(spi_no, SPI_BYTE_ORDER_HIGH_TO_LOW);
+ spi_rx_byte_order(spi_no, SPI_BYTE_ORDER_HIGH_TO_LOW);
+
+ SET_PERI_REG_MASK(SPI_USER(spi_no), SPI_CS_SETUP|SPI_CS_HOLD);
+ CLEAR_PERI_REG_MASK(SPI_USER(spi_no), SPI_FLASH_MODE);
+}
+
+
+/*
+Configures SPI mode parameters for clock edge and clock polarity.
+ spi_no - SPI (0) or HSPI (1)
+ spi_cpha - (0) Data is valid on clock leading edge
+ (1) Data is valid on clock trailing edge
+ spi_cpol - (0) Clock is low when inactive
+ (1) Clock is high when inactive
+For Micropython this version is different from original.
+*/
+void spi_mode(uint8_t spi_no, uint8_t spi_cpha, uint8_t spi_cpol) {
+ if (spi_cpol) {
+ SET_PERI_REG_MASK(SPI_PIN(HSPI), SPI_IDLE_EDGE);
+ } else {
+ CLEAR_PERI_REG_MASK(SPI_PIN(HSPI), SPI_IDLE_EDGE);
+ }
+ if (spi_cpha == spi_cpol) {
+ // Mode 3 - MOSI is set on falling edge of clock
+ // Mode 0 - MOSI is set on falling edge of clock
+ CLEAR_PERI_REG_MASK(SPI_USER(HSPI), SPI_CK_OUT_EDGE);
+ SET_PERI_REG_MASK(SPI_USER(HSPI), SPI_CK_I_EDGE);
+ } else {
+ // Mode 2 - MOSI is set on rising edge of clock
+ // Mode 1 - MOSI is set on rising edge of clock
+ SET_PERI_REG_MASK(SPI_USER(HSPI), SPI_CK_OUT_EDGE);
+ CLEAR_PERI_REG_MASK(SPI_USER(HSPI), SPI_CK_I_EDGE);
+ }
+}
+
+
+/*
+Initialise the GPIO pins for use as SPI pins.
+ spi_no - SPI (0) or HSPI (1)
+ sysclk_as_spiclk -
+ SPI_CLK_80MHZ_NODIV (1) if using 80MHz for SPI clock.
+ SPI_CLK_USE_DIV (0) if using divider for lower speed.
+*/
+void spi_init_gpio(uint8_t spi_no, uint8_t sysclk_as_spiclk) {
+ uint32_t clock_div_flag = 0;
+ if (sysclk_as_spiclk) {
+ clock_div_flag = 0x0001;
+ }
+ if (spi_no == SPI) {
+ // Set bit 8 if 80MHz sysclock required
+ WRITE_PERI_REG(PERIPHS_IO_MUX, 0x005 | (clock_div_flag<<8));
+ PIN_FUNC_SELECT(PERIPHS_IO_MUX_SD_CLK_U, 1);
+ PIN_FUNC_SELECT(PERIPHS_IO_MUX_SD_CMD_U, 1);
+ PIN_FUNC_SELECT(PERIPHS_IO_MUX_SD_DATA0_U, 1);
+ PIN_FUNC_SELECT(PERIPHS_IO_MUX_SD_DATA1_U, 1);
+ } else if (spi_no == HSPI) {
+ // Set bit 9 if 80MHz sysclock required
+ WRITE_PERI_REG(PERIPHS_IO_MUX, 0x105 | (clock_div_flag<<9));
+ // GPIO12 is HSPI MISO pin (Master Data In)
+ PIN_FUNC_SELECT(PERIPHS_IO_MUX_MTDI_U, 2);
+ // GPIO13 is HSPI MOSI pin (Master Data Out)
+ PIN_FUNC_SELECT(PERIPHS_IO_MUX_MTCK_U, 2);
+ // GPIO14 is HSPI CLK pin (Clock)
+ PIN_FUNC_SELECT(PERIPHS_IO_MUX_MTMS_U, 2);
+ // GPIO15 is HSPI CS pin (Chip Select / Slave Select)
+ // In Micropython, we are handling CS ourself in drivers.
+ // PIN_FUNC_SELECT(PERIPHS_IO_MUX_MTDO_U, 2);
+ }
+}
+
+
+/*
+Set up the control registers for the SPI clock
+ spi_no - SPI (0) or HSPI (1)
+ prediv - predivider value (actual division value)
+ cntdiv - postdivider value (actual division value)
+Set either divider to 0 to disable all division (80MHz sysclock)
+*/
+void spi_clock(uint8_t spi_no, uint16_t prediv, uint8_t cntdiv) {
+ if (prediv == 0 || cntdiv == 0) {
+ WRITE_PERI_REG(SPI_CLOCK(spi_no), SPI_CLK_EQU_SYSCLK);
+ } else {
+ WRITE_PERI_REG(SPI_CLOCK(spi_no),
+ (((prediv - 1) & SPI_CLKDIV_PRE) << SPI_CLKDIV_PRE_S) |
+ (((cntdiv - 1) & SPI_CLKCNT_N) << SPI_CLKCNT_N_S) |
+ (((cntdiv >> 1) & SPI_CLKCNT_H) << SPI_CLKCNT_H_S) |
+ ((0 & SPI_CLKCNT_L) << SPI_CLKCNT_L_S)
+ );
+ }
+}
+
+
+/*
+Setup the byte order for shifting data out of buffer
+ spi_no - SPI (0) or HSPI (1)
+ byte_order -
+ SPI_BYTE_ORDER_HIGH_TO_LOW (1)
+ Data is sent out starting with Bit31 and down to Bit0
+ SPI_BYTE_ORDER_LOW_TO_HIGH (0)
+ Data is sent out starting with the lowest BYTE, from MSB to LSB,
+ followed by the second lowest BYTE, from MSB to LSB, followed by
+ the second highest BYTE, from MSB to LSB, followed by the highest
+ BYTE, from MSB to LSB 0xABCDEFGH would be sent as 0xGHEFCDAB.
+*/
+void spi_tx_byte_order(uint8_t spi_no, uint8_t byte_order) {
+ if (byte_order) {
+ SET_PERI_REG_MASK(SPI_USER(spi_no), SPI_WR_BYTE_ORDER);
+ } else {
+ CLEAR_PERI_REG_MASK(SPI_USER(spi_no), SPI_WR_BYTE_ORDER);
+ }
+}
+
+
+/*
+Setup the byte order for shifting data into buffer
+ spi_no - SPI (0) or HSPI (1)
+ byte_order -
+ SPI_BYTE_ORDER_HIGH_TO_LOW (1)
+ Data is read in starting with Bit31 and down to Bit0
+ SPI_BYTE_ORDER_LOW_TO_HIGH (0)
+ Data is read in starting with the lowest BYTE, from MSB to LSB,
+ followed by the second lowest BYTE, from MSB to LSB, followed by
+ the second highest BYTE, from MSB to LSB, followed by the highest
+ BYTE, from MSB to LSB 0xABCDEFGH would be read as 0xGHEFCDAB
+*/
+void spi_rx_byte_order(uint8_t spi_no, uint8_t byte_order) {
+ if (byte_order) {
+ SET_PERI_REG_MASK(SPI_USER(spi_no), SPI_RD_BYTE_ORDER);
+ } else {
+ CLEAR_PERI_REG_MASK(SPI_USER(spi_no), SPI_RD_BYTE_ORDER);
+ }
+}
+
+
+/*
+SPI transaction function
+ spi_no - SPI (0) or HSPI (1)
+ cmd_bits - actual number of bits to transmit
+ cmd_data - command data
+ addr_bits - actual number of bits to transmit
+ addr_data - address data
+ dout_bits - actual number of bits to transmit
+ dout_data - output data
+ din_bits - actual number of bits to receive
+Returns: read data - uint32_t containing read in data only if RX was set
+ 0 - something went wrong (or actual read data was 0)
+ 1 - data sent ok (or actual read data is 1)
+Note: all data is assumed to be stored in the lower bits of the data variables
+(for anything <32 bits).
+*/
+uint32_t spi_transaction(uint8_t spi_no, uint8_t cmd_bits, uint16_t cmd_data,
+ uint32_t addr_bits, uint32_t addr_data,
+ uint32_t dout_bits, uint32_t dout_data,
+ uint32_t din_bits, uint32_t dummy_bits) {
+ while (spi_busy(spi_no)) {}; // Wait for SPI to be ready
+
+// Enable SPI Functions
+ // Disable MOSI, MISO, ADDR, COMMAND, DUMMY in case previously set.
+ CLEAR_PERI_REG_MASK(SPI_USER(spi_no), SPI_USR_MOSI | SPI_USR_MISO |
+ SPI_USR_COMMAND | SPI_USR_ADDR | SPI_USR_DUMMY);
+
+ // Enable functions based on number of bits. 0 bits = disabled.
+ // This is rather inefficient but allows for a very generic function.
+ // CMD ADDR and MOSI are set below to save on an extra if statement.
+ if (din_bits) {
+ if (dout_bits) {
+ SET_PERI_REG_MASK(SPI_USER(spi_no), SPI_DOUTDIN);
+ } else {
+ SET_PERI_REG_MASK(SPI_USER(spi_no), SPI_USR_MISO);
+ }
+ }
+ if (dummy_bits) {
+ SET_PERI_REG_MASK(SPI_USER(spi_no), SPI_USR_DUMMY);
+ }
+
+// Setup Bitlengths
+ WRITE_PERI_REG(SPI_USER1(spi_no),
+ // Number of bits in Address
+ ((addr_bits - 1) & SPI_USR_ADDR_BITLEN) << SPI_USR_ADDR_BITLEN_S |
+ // Number of bits to Send
+ ((dout_bits - 1) & SPI_USR_MOSI_BITLEN) << SPI_USR_MOSI_BITLEN_S |
+ // Number of bits to receive
+ ((din_bits - 1) & SPI_USR_MISO_BITLEN) << SPI_USR_MISO_BITLEN_S |
+ // Number of Dummy bits to insert
+ ((dummy_bits - 1) & SPI_USR_DUMMY_CYCLELEN) << SPI_USR_DUMMY_CYCLELEN_S);
+
+// Setup Command Data
+ if (cmd_bits) {
+ // Enable COMMAND function in SPI module
+ SET_PERI_REG_MASK(SPI_USER(spi_no), SPI_USR_COMMAND);
+ // Align command data to high bits
+ uint16_t command = cmd_data << (16-cmd_bits);
+ // Swap byte order
+ command = ((command>>8)&0xff) | ((command<<8)&0xff00);
+ WRITE_PERI_REG(SPI_USER2(spi_no), (
+ (((cmd_bits - 1) & SPI_USR_COMMAND_BITLEN) << SPI_USR_COMMAND_BITLEN_S) |
+ (command & SPI_USR_COMMAND_VALUE)
+ ));
+ }
+
+// Setup Address Data
+ if (addr_bits) {
+ // Enable ADDRess function in SPI module
+ SET_PERI_REG_MASK(SPI_USER(spi_no), SPI_USR_ADDR);
+ // Align address data to high bits
+ WRITE_PERI_REG(SPI_ADDR(spi_no), addr_data << (32 - addr_bits));
+ }
+
+// Setup DOUT data
+ if (dout_bits) {
+ // Enable MOSI function in SPI module
+ SET_PERI_REG_MASK(SPI_USER(spi_no), SPI_USR_MOSI);
+ // Copy data to W0
+ if (READ_PERI_REG(SPI_USER(spi_no))&SPI_WR_BYTE_ORDER) {
+ WRITE_PERI_REG(SPI_W0(spi_no), dout_data << (32 - dout_bits));
+ } else {
+ uint8_t dout_extra_bits = dout_bits%8;
+
+ if (dout_extra_bits) {
+ // If your data isn't a byte multiple (8/16/24/32 bits) and you
+ // don't have SPI_WR_BYTE_ORDER set, you need this to move the
+ // non-8bit remainder to the MSBs. Not sure if there's even a use
+ // case for this, but it's here if you need it... For example,
+ // 0xDA4 12 bits without SPI_WR_BYTE_ORDER would usually be output
+ // as if it were 0x0DA4, of which 0xA4, and then 0x0 would be
+ // shifted out (first 8 bits of low byte, then 4 MSB bits of high
+ // byte - ie reverse byte order).
+ // The code below shifts it out as 0xA4 followed by 0xD as you
+ // might require.
+ WRITE_PERI_REG(SPI_W0(spi_no), (
+ (0xFFFFFFFF << (dout_bits - dout_extra_bits) & dout_data)
+ << (8-dout_extra_bits) |
+ ((0xFFFFFFFF >> (32 - (dout_bits - dout_extra_bits)))
+ & dout_data)
+ ));
+ } else {
+ WRITE_PERI_REG(SPI_W0(spi_no), dout_data);
+ }
+ }
+}
+
+// Begin SPI Transaction
+ SET_PERI_REG_MASK(SPI_CMD(spi_no), SPI_USR);
+
+// Return DIN data
+ if (din_bits) {
+ while (spi_busy(spi_no)) {}; // Wait for SPI transaction to complete
+ if (READ_PERI_REG(SPI_USER(spi_no))&SPI_RD_BYTE_ORDER) {
+ // Assuming data in is written to MSB. TBC
+ return READ_PERI_REG(SPI_W0(spi_no)) >> (32 - din_bits);
+ } else {
+ // Read in the same way as DOUT is sent. Note existing contents of
+ // SPI_W0 remain unless overwritten!
+ return READ_PERI_REG(SPI_W0(spi_no));
+ }
+ return 0; // Something went wrong
+ }
+
+ // Transaction completed
+ return 1; // Success
+}
+
+
+/*
+Just do minimal work needed to send 8 bits.
+*/
+inline void spi_tx8fast(uint8_t spi_no, uint8_t dout_data) {
+ while (spi_busy(spi_no)) {}; // Wait for SPI to be ready
+
+// Enable SPI Functions
+ // Disable MOSI, MISO, ADDR, COMMAND, DUMMY in case previously set.
+ CLEAR_PERI_REG_MASK(SPI_USER(spi_no), SPI_USR_MOSI | SPI_USR_MISO |
+ SPI_USR_COMMAND | SPI_USR_ADDR | SPI_USR_DUMMY);
+
+// Setup Bitlengths
+ WRITE_PERI_REG(SPI_USER1(spi_no),
+ // Number of bits to Send
+ ((8 - 1) & SPI_USR_MOSI_BITLEN) << SPI_USR_MOSI_BITLEN_S |
+ // Number of bits to receive
+ ((8 - 1) & SPI_USR_MISO_BITLEN) << SPI_USR_MISO_BITLEN_S);
+
+
+// Setup DOUT data
+ // Enable MOSI function in SPI module
+ SET_PERI_REG_MASK(SPI_USER(spi_no), SPI_USR_MOSI);
+ // Copy data to W0
+ if (READ_PERI_REG(SPI_USER(spi_no)) & SPI_WR_BYTE_ORDER) {
+ WRITE_PERI_REG(SPI_W0(spi_no), dout_data << (32 - 8));
+ } else {
+ WRITE_PERI_REG(SPI_W0(spi_no), dout_data);
+ }
+
+// Begin SPI Transaction
+ SET_PERI_REG_MASK(SPI_CMD(spi_no), SPI_USR);
+}
diff --git a/esp8266/hspi.h b/esp8266/hspi.h
new file mode 100644
index 0000000000..c68366ef44
--- /dev/null
+++ b/esp8266/hspi.h
@@ -0,0 +1,79 @@
+/*
+* The MIT License (MIT)
+*
+* Copyright (c) 2015 David Ogilvy (MetalPhreak)
+* Modified 2016 by Radomir Dopieralski
+*
+* 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.
+*/
+
+#ifndef SPI_APP_H
+#define SPI_APP_H
+
+#include "hspi_register.h"
+#include "ets_sys.h"
+#include "osapi.h"
+#include "os_type.h"
+
+// Define SPI hardware modules
+#define SPI 0
+#define HSPI 1
+
+#define SPI_CLK_USE_DIV 0
+#define SPI_CLK_80MHZ_NODIV 1
+
+#define SPI_BYTE_ORDER_HIGH_TO_LOW 1
+#define SPI_BYTE_ORDER_LOW_TO_HIGH 0
+
+#ifndef CPU_CLK_FREQ //Should already be defined in eagle_soc.h
+#define CPU_CLK_FREQ (80 * 1000000)
+#endif
+
+// Define some default SPI clock settings
+#define SPI_CLK_PREDIV 10
+#define SPI_CLK_CNTDIV 2
+#define SPI_CLK_FREQ (CPU_CLK_FREQ / (SPI_CLK_PREDIV * SPI_CLK_CNTDIV))
+// 80 / 20 = 4 MHz
+
+void spi_init(uint8_t spi_no);
+void spi_mode(uint8_t spi_no, uint8_t spi_cpha,uint8_t spi_cpol);
+void spi_init_gpio(uint8_t spi_no, uint8_t sysclk_as_spiclk);
+void spi_clock(uint8_t spi_no, uint16_t prediv, uint8_t cntdiv);
+void spi_tx_byte_order(uint8_t spi_no, uint8_t byte_order);
+void spi_rx_byte_order(uint8_t spi_no, uint8_t byte_order);
+uint32_t spi_transaction(uint8_t spi_no, uint8_t cmd_bits, uint16_t cmd_data,
+ uint32_t addr_bits, uint32_t addr_data,
+ uint32_t dout_bits, uint32_t dout_data,
+ uint32_t din_bits, uint32_t dummy_bits);
+void spi_tx8fast(uint8_t spi_no, uint8_t dout_data);
+
+// Expansion Macros
+#define spi_busy(spi_no) READ_PERI_REG(SPI_CMD(spi_no))&SPI_USR
+
+#define spi_txd(spi_no, bits, data) spi_transaction(spi_no, 0, 0, 0, 0, bits, (uint32_t) data, 0, 0)
+#define spi_tx8(spi_no, data) spi_transaction(spi_no, 0, 0, 0, 0, 8, (uint32_t) data, 0, 0)
+#define spi_tx16(spi_no, data) spi_transaction(spi_no, 0, 0, 0, 0, 16, (uint32_t) data, 0, 0)
+#define spi_tx32(spi_no, data) spi_transaction(spi_no, 0, 0, 0, 0, 32, (uint32_t) data, 0, 0)
+
+#define spi_rxd(spi_no, bits) spi_transaction(spi_no, 0, 0, 0, 0, 0, 0, bits, 0)
+#define spi_rx8(spi_no) spi_transaction(spi_no, 0, 0, 0, 0, 0, 0, 8, 0)
+#define spi_rx16(spi_no) spi_transaction(spi_no, 0, 0, 0, 0, 0, 0, 16, 0)
+#define spi_rx32(spi_no) spi_transaction(spi_no, 0, 0, 0, 0, 0, 0, 32, 0)
+
+#endif
diff --git a/esp8266/hspi_register.h b/esp8266/hspi_register.h
new file mode 100644
index 0000000000..30a5ff5884
--- /dev/null
+++ b/esp8266/hspi_register.h
@@ -0,0 +1,278 @@
+/*
+ * Copyright (c) 2010 - 2011 Espressif System
+ * Modified by David Ogilvy (MetalPhreak)
+ * Based on original file included in SDK 1.0.0
+ *
+ * Missing defines from previous SDK versions have
+ * been added and are noted with comments. The
+ * names of these defines are likely to change.
+ */
+
+#ifndef SPI_REGISTER_H_INCLUDED
+#define SPI_REGISTER_H_INCLUDED
+
+#define REG_SPI_BASE(i) (0x60000200-i*0x100)
+
+#define SPI_CMD(i) (REG_SPI_BASE(i) + 0x0)
+#define SPI_FLASH_READ (BIT(31)) //From previous SDK
+#define SPI_FLASH_WREN (BIT(30)) //From previous SDK
+#define SPI_FLASH_WRDI (BIT(29)) //From previous SDK
+#define SPI_FLASH_RDID (BIT(28)) //From previous SDK
+#define SPI_FLASH_RDSR (BIT(27)) //From previous SDK
+#define SPI_FLASH_WRSR (BIT(26)) //From previous SDK
+#define SPI_FLASH_PP (BIT(25)) //From previous SDK
+#define SPI_FLASH_SE (BIT(24)) //From previous SDK
+#define SPI_FLASH_BE (BIT(23)) //From previous SDK
+#define SPI_FLASH_CE (BIT(22)) //From previous SDK
+#define SPI_FLASH_DP (BIT(21)) //From previous SDK
+#define SPI_FLASH_RES (BIT(20)) //From previous SDK
+#define SPI_FLASH_HPM (BIT(19)) //From previous SDK
+#define SPI_USR (BIT(18))
+
+#define SPI_ADDR(i) (REG_SPI_BASE(i) + 0x4)
+
+#define SPI_CTRL(i) (REG_SPI_BASE(i) + 0x8)
+#define SPI_WR_BIT_ORDER (BIT(26))
+#define SPI_RD_BIT_ORDER (BIT(25))
+#define SPI_QIO_MODE (BIT(24))
+#define SPI_DIO_MODE (BIT(23))
+#define SPI_TWO_BYTE_STATUS_EN (BIT(22)) //From previous SDK
+#define SPI_WP_REG (BIT(21)) //From previous SDK
+#define SPI_QOUT_MODE (BIT(20))
+#define SPI_SHARE_BUS (BIT(19)) //From previous SDK
+#define SPI_HOLD_MODE (BIT(18)) //From previous SDK
+#define SPI_ENABLE_AHB (BIT(17)) //From previous SDK
+#define SPI_SST_AAI (BIT(16)) //From previous SDK
+#define SPI_RESANDRES (BIT(15)) //From previous SDK
+#define SPI_DOUT_MODE (BIT(14))
+#define SPI_FASTRD_MODE (BIT(13))
+
+#define SPI_CTRL1(i) (REG_SPI_BASE (i) + 0xC) //From previous SDK. Removed _FLASH_ from name to match other registers.
+#define SPI_CS_HOLD_DELAY 0x0000000F //Espressif BBS
+#define SPI_CS_HOLD_DELAY_S 28 //Espressif BBS
+#define SPI_CS_HOLD_DELAY_RES 0x00000FFF //Espressif BBS
+#define SPI_CS_HOLD_DELAY_RES_S 16 //Espressif BBS
+#define SPI_BUS_TIMER_LIMIT 0x0000FFFF //From previous SDK
+#define SPI_BUS_TIMER_LIMIT_S 0 //From previous SDK
+
+
+#define SPI_RD_STATUS(i) (REG_SPI_BASE(i) + 0x10)
+#define SPI_STATUS_EXT 0x000000FF //From previous SDK
+#define SPI_STATUS_EXT_S 24 //From previous SDK
+#define SPI_WB_MODE 0x000000FF //From previous SDK
+#define SPI_WB_MODE_S 16 //From previous SDK
+#define SPI_FLASH_STATUS_PRO_FLAG (BIT(7)) //From previous SDK
+#define SPI_FLASH_TOP_BOT_PRO_FLAG (BIT(5)) //From previous SDK
+#define SPI_FLASH_BP2 (BIT(4)) //From previous SDK
+#define SPI_FLASH_BP1 (BIT(3)) //From previous SDK
+#define SPI_FLASH_BP0 (BIT(2)) //From previous SDK
+#define SPI_FLASH_WRENABLE_FLAG (BIT(1)) //From previous SDK
+#define SPI_FLASH_BUSY_FLAG (BIT(0)) //From previous SDK
+
+#define SPI_CTRL2(i) (REG_SPI_BASE(i) + 0x14)
+#define SPI_CS_DELAY_NUM 0x0000000F
+#define SPI_CS_DELAY_NUM_S 28
+#define SPI_CS_DELAY_MODE 0x00000003
+#define SPI_CS_DELAY_MODE_S 26
+#define SPI_MOSI_DELAY_NUM 0x00000007
+#define SPI_MOSI_DELAY_NUM_S 23
+#define SPI_MOSI_DELAY_MODE 0x00000003 //mode 0 : posedge; data set at positive edge of clk
+ //mode 1 : negedge + 1 cycle delay, only if freq<10MHz ; data set at negitive edge of clk
+ //mode 2 : Do not use this mode.
+#define SPI_MOSI_DELAY_MODE_S 21
+#define SPI_MISO_DELAY_NUM 0x00000007
+#define SPI_MISO_DELAY_NUM_S 18
+#define SPI_MISO_DELAY_MODE 0x00000003
+#define SPI_MISO_DELAY_MODE_S 16
+#define SPI_CK_OUT_HIGH_MODE 0x0000000F
+#define SPI_CK_OUT_HIGH_MODE_S 12
+#define SPI_CK_OUT_LOW_MODE 0x0000000F
+#define SPI_CK_OUT_LOW_MODE_S 8
+#define SPI_HOLD_TIME 0x0000000F
+#define SPI_HOLD_TIME_S 4
+#define SPI_SETUP_TIME 0x0000000F
+#define SPI_SETUP_TIME_S 0
+
+#define SPI_CLOCK(i) (REG_SPI_BASE(i) + 0x18)
+#define SPI_CLK_EQU_SYSCLK (BIT(31))
+#define SPI_CLKDIV_PRE 0x00001FFF
+#define SPI_CLKDIV_PRE_S 18
+#define SPI_CLKCNT_N 0x0000003F
+#define SPI_CLKCNT_N_S 12
+#define SPI_CLKCNT_H 0x0000003F
+#define SPI_CLKCNT_H_S 6
+#define SPI_CLKCNT_L 0x0000003F
+#define SPI_CLKCNT_L_S 0
+
+#define SPI_USER(i) (REG_SPI_BASE(i) + 0x1C)
+#define SPI_USR_COMMAND (BIT(31))
+#define SPI_USR_ADDR (BIT(30))
+#define SPI_USR_DUMMY (BIT(29))
+#define SPI_USR_MISO (BIT(28))
+#define SPI_USR_MOSI (BIT(27))
+#define SPI_USR_DUMMY_IDLE (BIT(26)) //From previous SDK
+#define SPI_USR_MOSI_HIGHPART (BIT(25))
+#define SPI_USR_MISO_HIGHPART (BIT(24))
+#define SPI_USR_PREP_HOLD (BIT(23)) //From previous SDK
+#define SPI_USR_CMD_HOLD (BIT(22)) //From previous SDK
+#define SPI_USR_ADDR_HOLD (BIT(21)) //From previous SDK
+#define SPI_USR_DUMMY_HOLD (BIT(20)) //From previous SDK
+#define SPI_USR_DIN_HOLD (BIT(19)) //From previous SDK
+#define SPI_USR_DOUT_HOLD (BIT(18)) //From previous SDK
+#define SPI_USR_HOLD_POL (BIT(17)) //From previous SDK
+#define SPI_SIO (BIT(16))
+#define SPI_FWRITE_QIO (BIT(15))
+#define SPI_FWRITE_DIO (BIT(14))
+#define SPI_FWRITE_QUAD (BIT(13))
+#define SPI_FWRITE_DUAL (BIT(12))
+#define SPI_WR_BYTE_ORDER (BIT(11))
+#define SPI_RD_BYTE_ORDER (BIT(10))
+#define SPI_AHB_ENDIAN_MODE 0x00000003 //From previous SDK
+#define SPI_AHB_ENDIAN_MODE_S 8 //From previous SDK
+#define SPI_CK_OUT_EDGE (BIT(7))
+#define SPI_CK_I_EDGE (BIT(6))
+#define SPI_CS_SETUP (BIT(5))
+#define SPI_CS_HOLD (BIT(4))
+#define SPI_AHB_USR_COMMAND (BIT(3)) //From previous SDK
+#define SPI_FLASH_MODE (BIT(2))
+#define SPI_AHB_USR_COMMAND_4BYTE (BIT(1)) //From previous SDK
+#define SPI_DOUTDIN (BIT(0)) //From previous SDK
+
+//AHB = http://en.wikipedia.org/wiki/Advanced_Microcontroller_Bus_Architecture ?
+
+
+#define SPI_USER1(i) (REG_SPI_BASE(i) + 0x20)
+#define SPI_USR_ADDR_BITLEN 0x0000003F
+#define SPI_USR_ADDR_BITLEN_S 26
+#define SPI_USR_MOSI_BITLEN 0x000001FF
+#define SPI_USR_MOSI_BITLEN_S 17
+#define SPI_USR_MISO_BITLEN 0x000001FF
+#define SPI_USR_MISO_BITLEN_S 8
+#define SPI_USR_DUMMY_CYCLELEN 0x000000FF
+#define SPI_USR_DUMMY_CYCLELEN_S 0
+
+#define SPI_USER2(i) (REG_SPI_BASE(i) + 0x24)
+#define SPI_USR_COMMAND_BITLEN 0x0000000F
+#define SPI_USR_COMMAND_BITLEN_S 28
+#define SPI_USR_COMMAND_VALUE 0x0000FFFF
+#define SPI_USR_COMMAND_VALUE_S 0
+
+#define SPI_WR_STATUS(i) (REG_SPI_BASE(i) + 0x28)
+ //previously defined as SPI_FLASH_USER3. No further info available.
+
+#define SPI_PIN(i) (REG_SPI_BASE(i) + 0x2C)
+#define SPI_IDLE_EDGE (BIT(29))
+#define SPI_CS2_DIS (BIT(2))
+#define SPI_CS1_DIS (BIT(1))
+#define SPI_CS0_DIS (BIT(0))
+
+#define SPI_SLAVE(i) (REG_SPI_BASE(i) + 0x30)
+#define SPI_SYNC_RESET (BIT(31))
+#define SPI_SLAVE_MODE (BIT(30))
+#define SPI_SLV_WR_RD_BUF_EN (BIT(29))
+#define SPI_SLV_WR_RD_STA_EN (BIT(28))
+#define SPI_SLV_CMD_DEFINE (BIT(27))
+#define SPI_TRANS_CNT 0x0000000F
+#define SPI_TRANS_CNT_S 23
+#define SPI_SLV_LAST_STATE 0x00000007 //From previous SDK
+#define SPI_SLV_LAST_STATE_S 20 //From previous SDK
+#define SPI_SLV_LAST_COMMAND 0x00000007 //From previous SDK
+#define SPI_SLV_LAST_COMMAND_S 17 //From previous SDK
+#define SPI_CS_I_MODE 0x00000003 //From previous SDK
+#define SPI_CS_I_MODE_S 10 //From previous SDK
+#define SPI_TRANS_DONE_EN (BIT(9))
+#define SPI_SLV_WR_STA_DONE_EN (BIT(8))
+#define SPI_SLV_RD_STA_DONE_EN (BIT(7))
+#define SPI_SLV_WR_BUF_DONE_EN (BIT(6))
+#define SPI_SLV_RD_BUF_DONE_EN (BIT(5))
+#define SLV_SPI_INT_EN 0x0000001f
+#define SLV_SPI_INT_EN_S 5
+#define SPI_TRANS_DONE (BIT(4))
+#define SPI_SLV_WR_STA_DONE (BIT(3))
+#define SPI_SLV_RD_STA_DONE (BIT(2))
+#define SPI_SLV_WR_BUF_DONE (BIT(1))
+#define SPI_SLV_RD_BUF_DONE (BIT(0))
+
+#define SPI_SLAVE1(i) (REG_SPI_BASE(i) + 0x34)
+#define SPI_SLV_STATUS_BITLEN 0x0000001F
+#define SPI_SLV_STATUS_BITLEN_S 27
+#define SPI_SLV_STATUS_FAST_EN (BIT(26)) //From previous SDK
+#define SPI_SLV_STATUS_READBACK (BIT(25)) //From previous SDK
+#define SPI_SLV_BUF_BITLEN 0x000001FF
+#define SPI_SLV_BUF_BITLEN_S 16
+#define SPI_SLV_RD_ADDR_BITLEN 0x0000003F
+#define SPI_SLV_RD_ADDR_BITLEN_S 10
+#define SPI_SLV_WR_ADDR_BITLEN 0x0000003F
+#define SPI_SLV_WR_ADDR_BITLEN_S 4
+#define SPI_SLV_WRSTA_DUMMY_EN (BIT(3))
+#define SPI_SLV_RDSTA_DUMMY_EN (BIT(2))
+#define SPI_SLV_WRBUF_DUMMY_EN (BIT(1))
+#define SPI_SLV_RDBUF_DUMMY_EN (BIT(0))
+
+
+
+#define SPI_SLAVE2(i) (REG_SPI_BASE(i) + 0x38)
+#define SPI_SLV_WRBUF_DUMMY_CYCLELEN 0X000000FF
+#define SPI_SLV_WRBUF_DUMMY_CYCLELEN_S 24
+#define SPI_SLV_RDBUF_DUMMY_CYCLELEN 0X000000FF
+#define SPI_SLV_RDBUF_DUMMY_CYCLELEN_S 16
+#define SPI_SLV_WRSTR_DUMMY_CYCLELEN 0X000000FF
+#define SPI_SLV_WRSTR_DUMMY_CYCLELEN_S 8
+#define SPI_SLV_RDSTR_DUMMY_CYCLELEN 0x000000FF
+#define SPI_SLV_RDSTR_DUMMY_CYCLELEN_S 0
+
+#define SPI_SLAVE3(i) (REG_SPI_BASE(i) + 0x3C)
+#define SPI_SLV_WRSTA_CMD_VALUE 0x000000FF
+#define SPI_SLV_WRSTA_CMD_VALUE_S 24
+#define SPI_SLV_RDSTA_CMD_VALUE 0x000000FF
+#define SPI_SLV_RDSTA_CMD_VALUE_S 16
+#define SPI_SLV_WRBUF_CMD_VALUE 0x000000FF
+#define SPI_SLV_WRBUF_CMD_VALUE_S 8
+#define SPI_SLV_RDBUF_CMD_VALUE 0x000000FF
+#define SPI_SLV_RDBUF_CMD_VALUE_S 0
+
+//Previous SDKs referred to these following registers as SPI_C0 etc.
+
+#define SPI_W0(i) (REG_SPI_BASE(i) +0x40)
+#define SPI_W1(i) (REG_SPI_BASE(i) +0x44)
+#define SPI_W2(i) (REG_SPI_BASE(i) +0x48)
+#define SPI_W3(i) (REG_SPI_BASE(i) +0x4C)
+#define SPI_W4(i) (REG_SPI_BASE(i) +0x50)
+#define SPI_W5(i) (REG_SPI_BASE(i) +0x54)
+#define SPI_W6(i) (REG_SPI_BASE(i) +0x58)
+#define SPI_W7(i) (REG_SPI_BASE(i) +0x5C)
+#define SPI_W8(i) (REG_SPI_BASE(i) +0x60)
+#define SPI_W9(i) (REG_SPI_BASE(i) +0x64)
+#define SPI_W10(i) (REG_SPI_BASE(i) +0x68)
+#define SPI_W11(i) (REG_SPI_BASE(i) +0x6C)
+#define SPI_W12(i) (REG_SPI_BASE(i) +0x70)
+#define SPI_W13(i) (REG_SPI_BASE(i) +0x74)
+#define SPI_W14(i) (REG_SPI_BASE(i) +0x78)
+#define SPI_W15(i) (REG_SPI_BASE(i) +0x7C)
+
+ // +0x80 to +0xBC could be SPI_W16 through SPI_W31?
+
+ // +0xC0 to +0xEC not currently defined.
+
+#define SPI_EXT0(i) (REG_SPI_BASE(i) + 0xF0) //From previous SDK. Removed _FLASH_ from name to match other registers.
+#define SPI_T_PP_ENA (BIT(31)) //From previous SDK
+#define SPI_T_PP_SHIFT 0x0000000F //From previous SDK
+#define SPI_T_PP_SHIFT_S 16 //From previous SDK
+#define SPI_T_PP_TIME 0x00000FFF //From previous SDK
+#define SPI_T_PP_TIME_S 0 //From previous SDK
+
+#define SPI_EXT1(i) (REG_SPI_BASE(i) + 0xF4) //From previous SDK. Removed _FLASH_ from name to match other registers.
+#define SPI_T_ERASE_ENA (BIT(31)) //From previous SDK
+#define SPI_T_ERASE_SHIFT 0x0000000F //From previous SDK
+#define SPI_T_ERASE_SHIFT_S 16 //From previous SDK
+#define SPI_T_ERASE_TIME 0x00000FFF //From previous SDK
+#define SPI_T_ERASE_TIME_S 0 //From previous SDK
+
+#define SPI_EXT2(i) (REG_SPI_BASE(i) + 0xF8) //From previous SDK. Removed _FLASH_ from name to match other registers.
+#define SPI_ST 0x00000007 //From previous SDK
+#define SPI_ST_S 0 //From previous SDK
+
+#define SPI_EXT3(i) (REG_SPI_BASE(i) + 0xFC)
+#define SPI_INT_HOLD_ENA 0x00000003
+#define SPI_INT_HOLD_ENA_S 0
+#endif // SPI_REGISTER_H_INCLUDED
diff --git a/esp8266/modmachine.c b/esp8266/modmachine.c
index b3a42618e5..b0b7f3a1a3 100644
--- a/esp8266/modmachine.c
+++ b/esp8266/modmachine.c
@@ -49,6 +49,8 @@
//#define MACHINE_WAKE_SLEEP (0x02)
#define MACHINE_WAKE_DEEPSLEEP (0x04)
+extern const mp_obj_type_t esp_wdt_type;
+
STATIC mp_obj_t machine_freq(mp_uint_t n_args, const mp_obj_t *args) {
if (n_args == 0) {
// get
@@ -246,20 +248,23 @@ STATIC const mp_rom_map_elem_t machine_module_globals_table[] = {
{ 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_WDT), MP_ROM_PTR(&esp_wdt_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(&machine_i2c_type) },
- { MP_ROM_QSTR(MP_QSTR_SPI), MP_ROM_PTR(&pyb_spi_type) },
+ { MP_ROM_QSTR(MP_QSTR_SPI), MP_ROM_PTR(&pyb_hspi_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_PWRON_RESET), MP_ROM_INT(REASON_DEFAULT_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) },
+ { MP_ROM_QSTR(MP_QSTR_WDT_RESET), MP_ROM_INT(REASON_WDT_RST) },
+ { MP_ROM_QSTR(MP_QSTR_SOFT_RESET), MP_ROM_INT(REASON_SOFT_RESTART) },
};
STATIC MP_DEFINE_CONST_DICT(machine_module_globals, machine_module_globals_table);
diff --git a/esp8266/modmachinewdt.c b/esp8266/modmachinewdt.c
new file mode 100644
index 0000000000..6dc4c0d18c
--- /dev/null
+++ b/esp8266/modmachinewdt.c
@@ -0,0 +1,85 @@
+/*
+ * 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 <stdio.h>
+#include <string.h>
+
+#include "py/nlr.h"
+#include "py/obj.h"
+#include "py/runtime.h"
+#include "user_interface.h"
+#include "etshal.h"
+
+const mp_obj_type_t esp_wdt_type;
+
+typedef struct _machine_wdt_obj_t {
+ mp_obj_base_t base;
+} machine_wdt_obj_t;
+
+STATIC machine_wdt_obj_t wdt_default = {{&esp_wdt_type}};
+
+STATIC mp_obj_t machine_wdt_make_new(const mp_obj_type_t *type_in, mp_uint_t n_args, mp_uint_t n_kw, const mp_obj_t *args) {
+ mp_arg_check_num(n_args, n_kw, 0, 1, false);
+
+ mp_int_t id = 0;
+ if (n_args > 0) {
+ id = mp_obj_get_int(args[0]);
+ }
+
+ switch (id) {
+ case 0:
+ return &wdt_default;
+ default:
+ mp_raise_ValueError("");
+ }
+}
+
+STATIC mp_obj_t machine_wdt_feed(mp_obj_t self_in) {
+ (void)self_in;
+ system_soft_wdt_feed();
+ return mp_const_none;
+}
+STATIC MP_DEFINE_CONST_FUN_OBJ_1(machine_wdt_feed_obj, machine_wdt_feed);
+
+STATIC mp_obj_t machine_wdt_deinit(mp_obj_t self_in) {
+ (void)self_in;
+ ets_wdt_disable();
+ return mp_const_none;
+}
+STATIC MP_DEFINE_CONST_FUN_OBJ_1(machine_wdt_deinit_obj, machine_wdt_deinit);
+
+STATIC const mp_map_elem_t machine_wdt_locals_dict_table[] = {
+ { MP_OBJ_NEW_QSTR(MP_QSTR_feed), (mp_obj_t)&machine_wdt_feed_obj },
+ { MP_OBJ_NEW_QSTR(MP_QSTR_deinit), (mp_obj_t)&machine_wdt_deinit_obj },
+};
+STATIC MP_DEFINE_CONST_DICT(machine_wdt_locals_dict, machine_wdt_locals_dict_table);
+
+const mp_obj_type_t esp_wdt_type = {
+ { &mp_type_type },
+ .name = MP_QSTR_WDT,
+ .make_new = machine_wdt_make_new,
+ .locals_dict = (mp_obj_t)&machine_wdt_locals_dict,
+};
diff --git a/esp8266/modnetwork.c b/esp8266/modnetwork.c
index 7cfa3ff77a..7031197fa5 100644
--- a/esp8266/modnetwork.c
+++ b/esp8266/modnetwork.c
@@ -130,17 +130,16 @@ STATIC MP_DEFINE_CONST_FUN_OBJ_1(esp_status_obj, esp_status);
STATIC mp_obj_t *esp_scan_list = NULL;
-STATIC void esp_scan_cb(scaninfo *si, STATUS status) {
+STATIC void esp_scan_cb(void *result, STATUS status) {
if (esp_scan_list == NULL) {
// called unexpectedly
return;
}
- if (si->pbss && status == 0) {
+ if (result && status == 0) {
// we need to catch any memory errors
nlr_buf_t nlr;
if (nlr_push(&nlr) == 0) {
- struct bss_info *bs;
- STAILQ_FOREACH(bs, si->pbss, next) {
+ for (struct bss_info *bs = result; bs; bs = STAILQ_NEXT(bs, next)) {
mp_obj_tuple_t *t = mp_obj_new_tuple(6, NULL);
#if 1
// struct bss_info::ssid_len is not documented in SDK API Guide,
diff --git a/esp8266/modpyb.h b/esp8266/modpyb.h
index dc399ad819..45d0bb8cfd 100644
--- a/esp8266/modpyb.h
+++ b/esp8266/modpyb.h
@@ -10,6 +10,8 @@ extern const mp_obj_type_t pyb_rtc_type;
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;
+extern const mp_obj_type_t pyb_hspi_type;
+extern const mp_obj_type_t machine_spi_type;
MP_DECLARE_CONST_FUN_OBJ(pyb_info_obj);
diff --git a/esp8266/modpybhspi.c b/esp8266/modpybhspi.c
new file mode 100644
index 0000000000..c1cd7f662d
--- /dev/null
+++ b/esp8266/modpybhspi.c
@@ -0,0 +1,224 @@
+/*
+ * 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 "ets_alt_task.h"
+
+#include "py/runtime.h"
+#include "py/stream.h"
+#include "py/mphal.h"
+#include "extmod/machine_spi.h"
+
+#include "hspi.h"
+
+mp_obj_t pyb_spi_make_new(const mp_obj_type_t *type, size_t n_args,
+ size_t n_kw, const mp_obj_t *args);
+
+typedef struct _pyb_hspi_obj_t {
+ mp_obj_base_t base;
+ uint32_t baudrate;
+ uint8_t polarity;
+ uint8_t phase;
+} pyb_hspi_obj_t;
+
+
+STATIC void hspi_transfer(mp_obj_base_t *self_in, size_t src_len, const uint8_t *src_buf, size_t dest_len, uint8_t *dest_buf) {
+ (void)self_in;
+
+ if (dest_len == 0) {
+ // fast case when we only need to write data
+ size_t chunk_size = 1024;
+ size_t count = src_len / chunk_size;
+ size_t i = 0;
+ for (size_t j = 0; j < count; ++j) {
+ for (size_t k = 0; k < chunk_size; ++k) {
+ spi_tx8fast(HSPI, src_buf[i]);
+ ++i;
+ }
+ ets_loop_iter();
+ }
+ while (i < src_len) {
+ spi_tx8fast(HSPI, src_buf[i]);
+ ++i;
+ }
+ } else {
+ // we need to read and write data
+
+ // Process data in chunks, let the pending tasks run in between
+ size_t chunk_size = 1024; // TODO this should depend on baudrate
+ size_t count = dest_len / chunk_size;
+ size_t i = 0;
+ for (size_t j = 0; j < count; ++j) {
+ for (size_t k = 0; k < chunk_size; ++k) {
+ uint32_t data_out;
+ if (src_len == 1) {
+ data_out = src_buf[0];
+ } else {
+ data_out = src_buf[i];
+ }
+ dest_buf[i] = spi_transaction(HSPI, 0, 0, 0, 0, 8, data_out, 8, 0);
+ ++i;
+ }
+ ets_loop_iter();
+ }
+ while (i < dest_len) {
+ uint32_t data_out;
+ if (src_len == 1) {
+ data_out = src_buf[0];
+ } else {
+ data_out = src_buf[i];
+ }
+ dest_buf[i] = spi_transaction(HSPI, 0, 0, 0, 0, 8, data_out, 8, 0);
+ ++i;
+ }
+ }
+}
+
+/******************************************************************************/
+// MicroPython bindings for HSPI
+
+STATIC void pyb_hspi_print(const mp_print_t *print, mp_obj_t self_in, mp_print_kind_t kind) {
+ pyb_hspi_obj_t *self = MP_OBJ_TO_PTR(self_in);
+ mp_printf(print, "HSPI(id=1, baudrate=%u, polarity=%u, phase=%u)",
+ self->baudrate, self->polarity, self->phase);
+}
+
+STATIC void pyb_hspi_init_helper(pyb_hspi_obj_t *self, size_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
+ enum { ARG_id, ARG_baudrate, ARG_polarity, ARG_phase };
+ static const mp_arg_t allowed_args[] = {
+ { MP_QSTR_id, MP_ARG_INT, {.u_int = -1} },
+ { MP_QSTR_baudrate, MP_ARG_INT, {.u_int = -1} },
+ { MP_QSTR_polarity, MP_ARG_INT, {.u_int = -1} },
+ { MP_QSTR_phase, MP_ARG_INT, {.u_int = -1} },
+ };
+ 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);
+
+ if (args[ARG_baudrate].u_int != -1) {
+ self->baudrate = args[ARG_baudrate].u_int;
+ }
+ if (args[ARG_polarity].u_int != -1) {
+ self->polarity = args[ARG_polarity].u_int;
+ }
+ if (args[ARG_phase].u_int != -1) {
+ self->phase = args[ARG_phase].u_int;
+ }
+ if (self->baudrate == 80000000L) {
+ // Special case for full speed.
+ spi_init_gpio(HSPI, SPI_CLK_80MHZ_NODIV);
+ spi_clock(HSPI, 0, 0);
+ } else if (self->baudrate > 40000000L) {
+ nlr_raise(mp_obj_new_exception_msg(&mp_type_ValueError,
+ "impossible baudrate"));
+ } else {
+ uint32_t divider = 40000000L / self->baudrate;
+ uint16_t prediv = MIN(divider, SPI_CLKDIV_PRE + 1);
+ uint16_t cntdiv = (divider / prediv) * 2; // cntdiv has to be even
+ if (cntdiv > SPI_CLKCNT_N + 1 || cntdiv == 0 || prediv == 0) {
+ nlr_raise(mp_obj_new_exception_msg(&mp_type_ValueError,
+ "impossible baudrate"));
+ }
+ self->baudrate = 80000000L / (prediv * cntdiv);
+ spi_init_gpio(HSPI, SPI_CLK_USE_DIV);
+ spi_clock(HSPI, prediv, cntdiv);
+ }
+ // TODO: Make the byte order configurable too (discuss param names)
+ spi_tx_byte_order(HSPI, SPI_BYTE_ORDER_HIGH_TO_LOW);
+ spi_rx_byte_order(HSPI, SPI_BYTE_ORDER_HIGH_TO_LOW);
+ CLEAR_PERI_REG_MASK(SPI_USER(HSPI), SPI_FLASH_MODE | SPI_USR_MISO |
+ SPI_USR_ADDR | SPI_USR_COMMAND | SPI_USR_DUMMY);
+ // Clear Dual or Quad lines transmission mode
+ CLEAR_PERI_REG_MASK(SPI_CTRL(HSPI), SPI_QIO_MODE | SPI_DIO_MODE |
+ SPI_DOUT_MODE | SPI_QOUT_MODE);
+ spi_mode(HSPI, self->phase, self->polarity);
+}
+
+mp_obj_t pyb_hspi_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, 1, true);
+ mp_int_t id = -1;
+ if (n_args > 0) {
+ id = mp_obj_get_int(args[0]);
+ }
+
+ if (id == -1) {
+ // Multiplex to bitbanging SPI
+ if (n_args > 0) {
+ args++;
+ }
+ return pyb_spi_make_new(type, 0, n_kw, args);
+ }
+
+ if (id != 1) {
+ // FlashROM is on SPI0, so far we don't support its usage
+ mp_raise_ValueError("");
+ }
+
+ pyb_hspi_obj_t *self = m_new_obj(pyb_hspi_obj_t);
+ self->base.type = &pyb_hspi_type;
+ // set defaults
+ self->baudrate = 80000000L;
+ self->polarity = 0;
+ self->phase = 0;
+ mp_map_t kw_args;
+ mp_map_init_fixed_table(&kw_args, n_kw, args + n_args);
+ pyb_hspi_init_helper(self, n_args, args, &kw_args);
+ return MP_OBJ_FROM_PTR(self);
+}
+
+STATIC mp_obj_t pyb_hspi_init(size_t n_args, const mp_obj_t *args, mp_map_t *kw_args) {
+ pyb_hspi_init_helper(args[0], n_args - 1, args + 1, kw_args);
+ return mp_const_none;
+}
+MP_DEFINE_CONST_FUN_OBJ_KW(pyb_hspi_init_obj, 1, pyb_hspi_init);
+
+STATIC const mp_rom_map_elem_t pyb_hspi_locals_dict_table[] = {
+ { MP_ROM_QSTR(MP_QSTR_init), MP_ROM_PTR(&pyb_hspi_init_obj) },
+ { MP_ROM_QSTR(MP_QSTR_read), MP_ROM_PTR(&mp_machine_spi_read_obj) },
+ { MP_ROM_QSTR(MP_QSTR_readinto), MP_ROM_PTR(&mp_machine_spi_readinto_obj) },
+ { MP_ROM_QSTR(MP_QSTR_write), MP_ROM_PTR(&mp_machine_spi_write_obj) },
+ { MP_ROM_QSTR(MP_QSTR_write_readinto), MP_ROM_PTR(&mp_machine_spi_write_readinto_obj) },
+};
+
+STATIC MP_DEFINE_CONST_DICT(pyb_hspi_locals_dict, pyb_hspi_locals_dict_table);
+
+STATIC const mp_machine_spi_p_t pyb_hspi_p = {
+ .transfer = hspi_transfer,
+};
+
+const mp_obj_type_t pyb_hspi_type = {
+ { &mp_type_type },
+ .name = MP_QSTR_HSPI,
+ .print = pyb_hspi_print,
+ .make_new = pyb_hspi_make_new,
+ .protocol = &pyb_hspi_p,
+ .locals_dict = (mp_obj_dict_t*)&pyb_hspi_locals_dict,
+};
diff --git a/esp8266/modpybpin.c b/esp8266/modpybpin.c
index 166d6f566f..8916da64f6 100644
--- a/esp8266/modpybpin.c
+++ b/esp8266/modpybpin.c
@@ -244,7 +244,11 @@ STATIC mp_obj_t pyb_pin_obj_init_helper(pyb_pin_obj_t *self, mp_uint_t n_args, c
// configure the GPIO as requested
if (self->phys_port == 16) {
- // TODO: Set pull up/pull down
+ // only pull-down seems to be supported by the hardware, and
+ // we only expose pull-up behaviour in software
+ if (pull != GPIO_PULL_NONE) {
+ nlr_raise(mp_obj_new_exception_msg(&mp_type_ValueError, "Pin(16) doesn't support pull"));
+ }
} else {
PIN_FUNC_SELECT(self->periph, self->func);
#if 0
@@ -301,7 +305,7 @@ STATIC mp_obj_t pyb_pin_call(mp_obj_t self_in, mp_uint_t n_args, mp_uint_t n_kw,
pyb_pin_obj_t *self = self_in;
if (n_args == 0) {
// get pin
- return MP_OBJ_NEW_SMALL_INT(GPIO_INPUT_GET(self->phys_port));
+ return MP_OBJ_NEW_SMALL_INT(pin_get(self->phys_port));
} else {
// set pin
pin_set(self->phys_port, mp_obj_is_true(args[0]));
diff --git a/esp8266/modpybrtc.c b/esp8266/modpybrtc.c
index 9685248034..500b2bc545 100644
--- a/esp8266/modpybrtc.c
+++ b/esp8266/modpybrtc.c
@@ -212,7 +212,7 @@ STATIC mp_obj_t pyb_rtc_alarm(mp_obj_t self_in, mp_obj_t alarm_id, mp_obj_t time
}
// set expiry time (in microseconds)
- pyb_rtc_alarm0_expiry = pyb_rtc_get_us_since_2000() + mp_obj_get_int(time_in) * 1000;
+ pyb_rtc_alarm0_expiry = pyb_rtc_get_us_since_2000() + (uint64_t)mp_obj_get_int(time_in) * 1000;
return mp_const_none;
diff --git a/esp8266/modpybspi.c b/esp8266/modpybspi.c
index c2bcc33edc..4c4b843c5d 100644
--- a/esp8266/modpybspi.c
+++ b/esp8266/modpybspi.c
@@ -35,6 +35,7 @@
#include "py/runtime.h"
#include "py/stream.h"
#include "py/mphal.h"
+#include "extmod/machine_spi.h"
typedef struct _pyb_spi_obj_t {
mp_obj_base_t base;
@@ -46,7 +47,8 @@ typedef struct _pyb_spi_obj_t {
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) {
+STATIC void mp_hal_spi_transfer(mp_obj_base_t *self_in, size_t src_len, const uint8_t *src_buf, size_t dest_len, uint8_t *dest_buf) {
+ pyb_spi_obj_t *self = (pyb_spi_obj_t*)self_in;
// only MSB transfer is implemented
uint32_t delay_half = 500000 / self->baudrate + 1;
for (size_t i = 0; i < src_len || i < dest_len; ++i) {
@@ -131,7 +133,7 @@ STATIC void pyb_spi_init_helper(pyb_spi_obj_t *self, size_t n_args, const mp_obj
mp_hal_pin_input(self->miso);
}
-STATIC mp_obj_t pyb_spi_make_new(const mp_obj_type_t *type, size_t n_args, size_t n_kw, const mp_obj_t *args) {
+mp_obj_t pyb_spi_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_spi_obj_t *self = m_new_obj(pyb_spi_obj_t);
self->base.type = &pyb_spi_type;
@@ -154,69 +156,25 @@ STATIC mp_obj_t pyb_spi_init(size_t n_args, const mp_obj_t *args, mp_map_t *kw_a
}
MP_DEFINE_CONST_FUN_OBJ_KW(pyb_spi_init_obj, 1, pyb_spi_init);
-STATIC mp_obj_t pyb_spi_read(size_t n_args, const mp_obj_t *args) {
- pyb_spi_obj_t *self = MP_OBJ_TO_PTR(args[0]);
- uint8_t write_byte = 0;
- if (n_args == 3) {
- write_byte = mp_obj_get_int(args[2]);
- }
- vstr_t vstr;
- vstr_init_len(&vstr, mp_obj_get_int(args[1]));
- mp_hal_spi_transfer(self, 1, &write_byte, vstr.len, (uint8_t*)vstr.buf);
- return mp_obj_new_str_from_vstr(&mp_type_bytes, &vstr);
-}
-MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(pyb_spi_read_obj, 2, 3, pyb_spi_read);
-
-STATIC mp_obj_t pyb_spi_readinto(size_t n_args, const mp_obj_t *args) {
- pyb_spi_obj_t *self = MP_OBJ_TO_PTR(args[0]);
- mp_buffer_info_t bufinfo;
- mp_get_buffer_raise(args[1], &bufinfo, MP_BUFFER_WRITE);
- uint8_t write_byte = 0;
- if (n_args == 3) {
- write_byte = mp_obj_get_int(args[2]);
- }
- mp_hal_spi_transfer(self, 1, &write_byte, bufinfo.len, (uint8_t*)bufinfo.buf);
- return mp_const_none;
-}
-MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(pyb_spi_readinto_obj, 2, 3, pyb_spi_readinto);
-
-STATIC mp_obj_t pyb_spi_write(mp_obj_t self_in, mp_obj_t wr_buf_in) {
- pyb_spi_obj_t *self = MP_OBJ_TO_PTR(self_in);
- mp_buffer_info_t src_buf;
- mp_get_buffer_raise(wr_buf_in, &src_buf, MP_BUFFER_READ);
- mp_hal_spi_transfer(self, src_buf.len, (const uint8_t*)src_buf.buf, 0, NULL);
- return mp_const_none;
-}
-MP_DEFINE_CONST_FUN_OBJ_2(pyb_spi_write_obj, pyb_spi_write);
-
-STATIC mp_obj_t pyb_spi_write_readinto(mp_obj_t self_in, mp_obj_t wr_buf_in, mp_obj_t rd_buf_in) {
- pyb_spi_obj_t *self = MP_OBJ_TO_PTR(self_in);
- mp_buffer_info_t src_buf;
- mp_get_buffer_raise(wr_buf_in, &src_buf, MP_BUFFER_READ);
- mp_buffer_info_t dest_buf;
- mp_get_buffer_raise(rd_buf_in, &dest_buf, MP_BUFFER_WRITE);
- if (src_buf.len != dest_buf.len) {
- nlr_raise(mp_obj_new_exception_msg_varg(&mp_type_ValueError, "buffers must be the same length"));
- }
- mp_hal_spi_transfer(self, src_buf.len, (const uint8_t*)src_buf.buf, dest_buf.len, (uint8_t*)dest_buf.buf);
- return mp_const_none;
-}
-MP_DEFINE_CONST_FUN_OBJ_3(pyb_spi_write_readinto_obj, pyb_spi_write_readinto);
-
STATIC const mp_rom_map_elem_t pyb_spi_locals_dict_table[] = {
{ MP_ROM_QSTR(MP_QSTR_init), MP_ROM_PTR(&pyb_spi_init_obj) },
- { MP_ROM_QSTR(MP_QSTR_read), MP_ROM_PTR(&pyb_spi_read_obj) },
- { MP_ROM_QSTR(MP_QSTR_readinto), MP_ROM_PTR(&pyb_spi_readinto_obj) },
- { MP_ROM_QSTR(MP_QSTR_write), MP_ROM_PTR(&pyb_spi_write_obj) },
- { MP_ROM_QSTR(MP_QSTR_write_readinto), MP_ROM_PTR(&pyb_spi_write_readinto_obj) },
+ { MP_ROM_QSTR(MP_QSTR_read), MP_ROM_PTR(&mp_machine_spi_read_obj) },
+ { MP_ROM_QSTR(MP_QSTR_readinto), MP_ROM_PTR(&mp_machine_spi_readinto_obj) },
+ { MP_ROM_QSTR(MP_QSTR_write), MP_ROM_PTR(&mp_machine_spi_write_obj) },
+ { MP_ROM_QSTR(MP_QSTR_write_readinto), MP_ROM_PTR(&mp_machine_spi_write_readinto_obj) },
};
STATIC MP_DEFINE_CONST_DICT(pyb_spi_locals_dict, pyb_spi_locals_dict_table);
+STATIC const mp_machine_spi_p_t pyb_spi_p = {
+ .transfer = mp_hal_spi_transfer,
+};
+
const mp_obj_type_t pyb_spi_type = {
{ &mp_type_type },
- .name = MP_QSTR_SPI,
+ .name = MP_QSTR_SoftSPI,
.print = pyb_spi_print,
.make_new = pyb_spi_make_new,
+ .protocol = &pyb_spi_p,
.locals_dict = (mp_obj_dict_t*)&pyb_spi_locals_dict,
};
diff --git a/esp8266/modules/ds18x20.py b/esp8266/modules/ds18x20.py
new file mode 100644
index 0000000000..eb22e2ae30
--- /dev/null
+++ b/esp8266/modules/ds18x20.py
@@ -0,0 +1,46 @@
+# DS18x20 temperature sensor driver for MicroPython.
+# MIT license; Copyright (c) 2016 Damien P. George
+
+_CONVERT = const(0x44)
+_RD_SCRATCH = const(0xbe)
+_WR_SCRATCH = const(0x4e)
+
+class DS18X20:
+ def __init__(self, onewire):
+ self.ow = onewire
+ self.buf = bytearray(9)
+
+ def scan(self):
+ return [rom for rom in self.ow.scan() if rom[0] == 0x10 or rom[0] == 0x28]
+
+ def convert_temp(self):
+ self.ow.reset(True)
+ self.ow.writebyte(self.ow.SKIP_ROM)
+ self.ow.writebyte(_CONVERT)
+
+ def read_scratch(self, rom):
+ self.ow.reset(True)
+ self.ow.select_rom(rom)
+ self.ow.writebyte(_RD_SCRATCH)
+ self.ow.readinto(self.buf)
+ if self.ow.crc8(self.buf):
+ raise Exception('CRC error')
+ return self.buf
+
+ def write_scratch(self, rom, buf):
+ self.ow.reset(True)
+ self.ow.select_rom(rom)
+ self.ow.writebyte(_WR_SCRATCH)
+ self.ow.write(buf)
+
+ def read_temp(self, rom):
+ buf = self.read_scratch(rom)
+ if rom[0] == 0x10:
+ if buf[1]:
+ t = buf[0] >> 1 | 0x80
+ t = -((~t + 1) & 0xff)
+ else:
+ t = buf[0] >> 1
+ return t - 0.25 + (buf[7] - buf[6]) / buf[7]
+ else:
+ return (buf[1] << 8 | buf[0]) / 16
diff --git a/esp8266/scripts/onewire.py b/esp8266/modules/onewire.py
index 686616950a..06b216a57a 100644
--- a/esp8266/scripts/onewire.py
+++ b/esp8266/modules/onewire.py
@@ -15,8 +15,11 @@ class OneWire:
self.pin = pin
self.pin.init(pin.OPEN_DRAIN)
- def reset(self):
- return _ow.reset(self.pin)
+ def reset(self, required=False):
+ reset = _ow.reset(self.pin)
+ if required and not reset:
+ raise OneWireError
+ return reset
def readbit(self):
return _ow.readbit(self.pin)
@@ -24,11 +27,9 @@ class OneWire:
def readbyte(self):
return _ow.readbyte(self.pin)
- def read(self, count):
- buf = bytearray(count)
- for i in range(count):
+ def readinto(self, buf):
+ for i in range(len(buf)):
buf[i] = _ow.readbyte(self.pin)
- return buf
def writebit(self, value):
return _ow.writebit(self.pin, value)
@@ -87,41 +88,3 @@ class OneWire:
def crc8(self, data):
return _ow.crc8(data)
-
-class DS18B20:
- CONVERT = const(0x44)
- RD_SCRATCH = const(0xbe)
- WR_SCRATCH = const(0x4e)
-
- def __init__(self, onewire):
- self.ow = onewire
-
- def scan(self):
- return [rom for rom in self.ow.scan() if rom[0] == 0x28]
-
- def convert_temp(self):
- if not self.ow.reset():
- raise OneWireError
- self.ow.writebyte(SKIP_ROM)
- self.ow.writebyte(CONVERT)
-
- def read_scratch(self, rom):
- if not self.ow.reset():
- 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.writebyte(WR_SCRATCH)
- self.ow.write(buf)
-
- def read_temp(self, rom):
- buf = self.read_scratch(rom)
- return (buf[1] << 8 | buf[0]) / 16
diff --git a/esp8266/moduos.c b/esp8266/moduos.c
index af149625d6..bbbf2b6b8b 100644
--- a/esp8266/moduos.c
+++ b/esp8266/moduos.c
@@ -123,6 +123,10 @@ STATIC mp_obj_t os_rename(mp_obj_t path_old, mp_obj_t path_new) {
}
STATIC MP_DEFINE_CONST_FUN_OBJ_2(os_rename_obj, os_rename);
+STATIC mp_obj_t os_umount(void) {
+ return vfs_proxy_call(MP_QSTR_umount, 0, NULL);
+}
+STATIC MP_DEFINE_CONST_FUN_OBJ_0(os_umount_obj, os_umount);
#endif
STATIC mp_obj_t os_urandom(mp_obj_t num) {
@@ -166,6 +170,7 @@ STATIC const mp_rom_map_elem_t os_module_globals_table[] = {
{ MP_ROM_QSTR(MP_QSTR_remove), MP_ROM_PTR(&os_remove_obj) },
{ MP_ROM_QSTR(MP_QSTR_rename), MP_ROM_PTR(&os_rename_obj) },
{ MP_ROM_QSTR(MP_QSTR_stat), MP_ROM_PTR(&os_stat_obj) },
+ { MP_ROM_QSTR(MP_QSTR_umount), MP_ROM_PTR(&os_umount_obj) },
#endif
};
diff --git a/esp8266/mpconfigport.h b/esp8266/mpconfigport.h
index 7b3558ffc2..4fc8d856b6 100644
--- a/esp8266/mpconfigport.h
+++ b/esp8266/mpconfigport.h
@@ -25,6 +25,7 @@
#define MICROPY_MODULE_WEAK_LINKS (1)
#define MICROPY_CAN_OVERRIDE_BUILTINS (1)
#define MICROPY_USE_INTERNAL_ERRNO (1)
+#define MICROPY_PY_ALL_SPECIAL_METHODS (1)
#define MICROPY_PY_BUILTINS_COMPLEX (0)
#define MICROPY_PY_BUILTINS_STR_UNICODE (1)
#define MICROPY_PY_BUILTINS_BYTEARRAY (1)
@@ -62,6 +63,7 @@
#define MICROPY_PY_MACHINE (1)
#define MICROPY_PY_MACHINE_PULSE (1)
#define MICROPY_PY_MACHINE_I2C (1)
+#define MICROPY_PY_MACHINE_SPI (1)
#define MICROPY_PY_WEBSOCKET (1)
#define MICROPY_PY_WEBREPL (1)
#define MICROPY_PY_WEBREPL_DELAY (20)
@@ -114,8 +116,6 @@
typedef int32_t mp_int_t; // must be pointer size
typedef uint32_t mp_uint_t; // must be pointer size
-typedef void *machine_ptr_t; // must be of pointer size
-typedef const void *machine_const_ptr_t; // must be of pointer size
typedef long mp_off_t;
typedef uint32_t sys_prot_t; // for modlwip
// ssize_t, off_t as required by POSIX-signatured functions in stream.h