diff --git a/.gitignore b/.gitignore
index 998ac8f41..4400c7eb4 100644
--- a/.gitignore
+++ b/.gitignore
@@ -56,3 +56,5 @@ avr-toolchain-*.zip
/hardware/tools/gcc-arm-none-eabi-4.8.3-2014q1/
/hardware/tools/bossac.exe
/hardware/tools/listComPorts.exe
+
+build/macosx/esptool-*-osx.zip
diff --git a/build/build.xml b/build/build.xml
index 934982707..20566b252 100644
--- a/build/build.xml
+++ b/build/build.xml
@@ -784,12 +784,12 @@
-
+
-
+
diff --git a/hardware/esp8266com/esp8266/cores/esp8266/Arduino.h b/hardware/esp8266com/esp8266/cores/esp8266/Arduino.h
index 19c25e899..408e6f0ad 100644
--- a/hardware/esp8266com/esp8266/cores/esp8266/Arduino.h
+++ b/hardware/esp8266com/esp8266/cores/esp8266/Arduino.h
@@ -36,17 +36,27 @@ extern "C" {
#include "stdlib_noniso.h"
#include "binary.h"
#include "pgmspace.h"
+#include "esp8266_peri.h"
+#include "si2c.h"
void yield(void);
#define HIGH 0x1
#define LOW 0x0
-#define INPUT 0x0
-#define OUTPUT 0x1
-#define INPUT_PULLUP 0x2
-#define INPUT_PULLDOWN 0x3
-#define OUTPUT_OPEN_DRAIN 0x4
+#define PWMRANGE 1023
+
+//GPIO FUNCTIONS
+#define INPUT 0x00
+#define OUTPUT 0x01
+#define INPUT_PULLUP 0x02
+#define INPUT_PULLDOWN 0x04
+#define SPECIAL 0xF8 //defaults to the usable BUSes uart0rx/tx uart1tx and hspi
+#define FUNCTION_0 0x08
+#define FUNCTION_1 0x18
+#define FUNCTION_2 0x28
+#define FUNCTION_3 0x38
+#define FUNCTION_4 0x48
#define PI 3.1415926535897932384626433832795
#define HALF_PI 1.5707963267948966192313216916398
@@ -61,13 +71,41 @@ void yield(void);
#define LSBFIRST 0
#define MSBFIRST 1
-#define CHANGE 1
-#define FALLING 2
-#define RISING 3
+//Interrupt Modes
+#define DISABLED 0x00
+#define RISING 0x01
+#define FALLING 0x02
+#define CHANGE 0x03
+#define ONLOW 0x04
+#define ONHIGH 0x05
+#define ONLOW_WE 0x0C
+#define ONHIGH_WE 0x0D
#define DEFAULT 1
#define EXTERNAL 0
+//timer dividers
+#define TIM_DIV1 0 //80MHz (80 ticks/us - 104857.588 us max)
+#define TIM_DIV16 1 //5MHz (5 ticks/us - 1677721.4 us max)
+#define TIM_DIV265 3 //312.5Khz (1 tick = 3.2us - 26843542.4 us max)
+//timer int_types
+#define TIM_EDGE 0
+#define TIM_LEVEL 1
+//timer reload values
+#define TIM_SINGLE 0 //on interrupt routine you need to write a new value to start the timer again
+#define TIM_LOOP 1 //on interrupt the counter will start with the same value again
+
+#define timer1_read() (T1V)
+#define timer1_enabled() ((T1C & (1 << TCTE)) != 0)
+#define timer1_interrupted() ((T1C & (1 << TCIS)) != 0)
+
+void timer1_isr_init(void);
+void timer1_enable(uint8_t divider, uint8_t int_type, uint8_t reload);
+void timer1_disable(void);
+void timer1_attachInterrupt(void (*userFunc)(void));
+void timer1_detachInterrupt(void);
+void timer1_write(uint32_t ticks); //maximum ticks 8388607
+
// undefine stdlib's abs if encountered
#ifdef abs
#undef abs
@@ -145,13 +183,12 @@ void loop(void);
uint32_t digitalPinToPort(uint32_t pin);
uint32_t digitalPinToBitMask(uint32_t pin);
-#define analogInPinToBit(P) (P)
volatile uint32_t* portOutputRegister(uint32_t port);
volatile uint32_t* portInputRegister(uint32_t port);
volatile uint32_t* portModeRegister(uint32_t port);
-#define NOT_A_PIN 0
-#define NOT_A_PORT 0
+#define NOT_A_PIN -1
+#define NOT_A_PORT -1
#define NOT_AN_INTERRUPT -1
#ifdef __cplusplus
diff --git a/hardware/esp8266com/esp8266/cores/esp8266/core_esp8266_timer.c b/hardware/esp8266com/esp8266/cores/esp8266/core_esp8266_timer.c
new file mode 100644
index 000000000..54ec65692
--- /dev/null
+++ b/hardware/esp8266com/esp8266/cores/esp8266/core_esp8266_timer.c
@@ -0,0 +1,61 @@
+/*
+ timer.c - Timer1 library for esp8266
+
+ Copyright (c) 2015 Hristo Gochkov. All rights reserved.
+ This file is part of the esp8266 core for Arduino environment.
+
+ This library is free software; you can redistribute it and/or
+ modify it under the terms of the GNU Lesser General Public
+ License as published by the Free Software Foundation; either
+ version 2.1 of the License, or (at your option) any later version.
+
+ This library is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with this library; if not, write to the Free Software
+ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+*/
+#include "wiring_private.h"
+#include "pins_arduino.h"
+#include "c_types.h"
+
+void (*timer1_user_cb)(void);
+
+void timer1_isr_handler(void *para){
+ if((T1C & ((1 << TCAR) | (1 << TCIT))) == 0) TEIE &= ~TEIE1;//edge int disable
+ T1I = 0;
+ if(timer1_user_cb) timer1_user_cb();
+}
+
+void timer1_attachInterrupt(void (*userFunc)(void)) {
+ timer1_user_cb = userFunc;
+ ETS_FRC1_INTR_ENABLE();
+}
+
+void timer1_detachInterrupt() {
+ timer1_user_cb = 0;
+ TEIE &= ~TEIE1;//edge int disable
+ ETS_FRC1_INTR_DISABLE();
+}
+
+void timer1_enable(uint8_t divider, uint8_t int_type, uint8_t reload){
+ T1C = (1 << TCTE) | ((divider & 3) << TCPD) | ((int_type & 1) << TCIT) | ((reload & 1) << TCAR);
+ T1I = 0;
+}
+
+void timer1_write(uint32_t ticks){
+ T1L = ((ticks) & 0x7FFFFF);
+ if((T1C & (1 << TCIT)) == 0) TEIE |= TEIE1;//edge int enable
+}
+
+void timer1_disable(){
+ T1C = 0;
+ T1I = 0;
+}
+
+void timer1_isr_init(){
+ ETS_FRC_TIMER1_INTR_ATTACH(timer1_isr_handler, NULL);
+}
\ No newline at end of file
diff --git a/hardware/esp8266com/esp8266/cores/esp8266/core_esp8266_wiring_analog.c b/hardware/esp8266com/esp8266/cores/esp8266/core_esp8266_wiring_analog.c
index 40226b4e9..bb5151018 100644
--- a/hardware/esp8266com/esp8266/cores/esp8266/core_esp8266_wiring_analog.c
+++ b/hardware/esp8266com/esp8266/cores/esp8266/core_esp8266_wiring_analog.c
@@ -1,35 +1,56 @@
/*
- core_esp8266_analog.c - an interface to the esp8266 ADC
+ analog.c - analogRead implementation for esp8266
- Copyright (c) 2014 Ivan Grokhotkov. All rights reserved.
- This file is part of the esp8266 core for Arduino environment.
+ Copyright (c) 2015 Hristo Gochkov. All rights reserved.
+ This file is part of the esp8266 core for Arduino environment.
- This library is free software; you can redistribute it and/or
- modify it under the terms of the GNU Lesser General Public
- License as published by the Free Software Foundation; either
- version 2.1 of the License, or (at your option) any later version.
+ This library is free software; you can redistribute it and/or
+ modify it under the terms of the GNU Lesser General Public
+ License as published by the Free Software Foundation; either
+ version 2.1 of the License, or (at your option) any later version.
- This library is distributed in the hope that it will be useful,
- but WITHOUT ANY WARRANTY; without even the implied warranty of
- MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
- Lesser General Public License for more details.
-
- You should have received a copy of the GNU Lesser General Public
- License along with this library; if not, write to the Free Software
- Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
- */
+ This library is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+ You should have received a copy of the GNU Lesser General Public
+ License along with this library; if not, write to the Free Software
+ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+*/
#include "wiring_private.h"
#include "pins_arduino.h"
-void analogReference(uint8_t mode) {
-}
+void analogReference(uint8_t mode) {}
extern int __analogRead(uint8_t pin) {
- if(pin == 0)
- return system_adc_read();
+ if(pin == 17){
+ //return system_adc_read();
+ uint8_t i;
+ uint16_t data[8];
- return 0;
+ rom_i2c_writeReg_Mask(0x6C,2,0,5,5,1);
+
+ ESP8266_REG(0xD5C) |= (1 << 21);
+ while ((ESP8266_REG(0xD50) & (7 << 24)) > 0);
+ ESP8266_REG(0xD50) &= ~(1 << 1);
+ ESP8266_REG(0xD50) |= (1 << 1);
+ delayMicroseconds(2);
+ while ((ESP8266_REG(0xD50) & (7 << 24)) > 0);
+
+ read_sar_dout(data);
+ rom_i2c_writeReg_Mask(0x6C,2,0,5,5,1);
+
+ while ((ESP8266_REG(0xD50) & (7 << 24)) > 0);
+ ESP8266_REG(0xD5C) &= ~(1 << 21);
+ ESP8266_REG(0xD60) |= (1 << 0);
+ ESP8266_REG(0xD60) &= ~(1 << 0);
+
+ uint16_t tout = 0;
+ for (i = 0; i < 8; i++) tout += data[i];
+ return tout >> 4;//tout is 10 bits fraction
+ }
+ return digitalRead(pin) * 1023;
}
extern int analogRead(uint8_t pin) __attribute__ ((weak, alias("__analogRead")));
diff --git a/hardware/esp8266com/esp8266/cores/esp8266/core_esp8266_wiring_digital.c b/hardware/esp8266com/esp8266/cores/esp8266/core_esp8266_wiring_digital.c
index cf9ddce52..5ac670e63 100644
--- a/hardware/esp8266com/esp8266/cores/esp8266/core_esp8266_wiring_digital.c
+++ b/hardware/esp8266com/esp8266/cores/esp8266/core_esp8266_wiring_digital.c
@@ -1,45 +1,30 @@
/*
- core_esp8266_wiring_digital.c - implementation of Wiring API for esp8266
+ digital.c - wiring digital implementation for esp8266
- Copyright (c) 2014 Ivan Grokhotkov. All rights reserved.
- This file is part of the esp8266 core for Arduino environment.
+ Copyright (c) 2015 Hristo Gochkov. All rights reserved.
+ This file is part of the esp8266 core for Arduino environment.
- This library is free software; you can redistribute it and/or
- modify it under the terms of the GNU Lesser General Public
- License as published by the Free Software Foundation; either
- version 2.1 of the License, or (at your option) any later version.
+ This library is free software; you can redistribute it and/or
+ modify it under the terms of the GNU Lesser General Public
+ License as published by the Free Software Foundation; either
+ version 2.1 of the License, or (at your option) any later version.
- This library is distributed in the hope that it will be useful,
- but WITHOUT ANY WARRANTY; without even the implied warranty of
- MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
- Lesser General Public License for more details.
-
- You should have received a copy of the GNU Lesser General Public
- License along with this library; if not, write to the Free Software
- Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
- */
+ This library is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+ You should have received a copy of the GNU Lesser General Public
+ License along with this library; if not, write to the Free Software
+ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+*/
#define ARDUINO_MAIN
#include "wiring_private.h"
#include "pins_arduino.h"
#include "c_types.h"
#include "eagle_soc.h"
-#include "gpio.h"
#include "ets_sys.h"
-#define MODIFY_PERI_REG(reg, mask, val) WRITE_PERI_REG(reg, (READ_PERI_REG(reg) & (~mask)) | (uint32_t) val)
-
-#define PINCOUNT 16
-
-static const uint32_t g_pin_muxes[PINCOUNT] = { [0] = PERIPHS_IO_MUX_GPIO0_U, [1] = PERIPHS_IO_MUX_U0TXD_U, [2] = PERIPHS_IO_MUX_GPIO2_U, [3] = PERIPHS_IO_MUX_U0RXD_U, [4] = PERIPHS_IO_MUX_GPIO4_U, [5] = PERIPHS_IO_MUX_GPIO5_U,
-
-// These 6 pins are used for SPI flash interface
-[6] = 0, [7] = 0, [8] = 0, [9] = 0, [10] = 0, [11] = 0,
-
-[12] = PERIPHS_IO_MUX_MTDI_U, [13] = PERIPHS_IO_MUX_MTCK_U, [14] = PERIPHS_IO_MUX_MTMS_U, [15] = PERIPHS_IO_MUX_MTDO_U, };
-
-static const uint32_t g_pin_funcs[PINCOUNT] = { [0] = FUNC_GPIO0, [1] = FUNC_GPIO1, [2] = FUNC_GPIO2, [3] = FUNC_GPIO3, [4] = FUNC_GPIO4, [5] = FUNC_GPIO5, [12] = FUNC_GPIO12, [13] = FUNC_GPIO13, [14] = FUNC_GPIO14, [15] = FUNC_GPIO15, };
-
uint32_t digitalPinToPort(uint32_t pin) {
return 0;
}
@@ -49,126 +34,141 @@ uint32_t digitalPinToBitMask(uint32_t pin) {
}
volatile uint32_t* portOutputRegister(uint32_t port) {
- return (volatile uint32_t*) (PERIPHS_GPIO_BASEADDR + GPIO_OUT_ADDRESS);
+ return (volatile uint32_t*)GPO;
}
volatile uint32_t* portInputRegister(uint32_t port) {
- return (volatile uint32_t*) (PERIPHS_GPIO_BASEADDR + GPIO_IN_ADDRESS);
+ return (volatile uint32_t*)GPI;
}
volatile uint32_t* portModeRegister(uint32_t port) {
- return (volatile uint32_t*) (PERIPHS_GPIO_BASEADDR + GPIO_ENABLE_ADDRESS);
+ return (volatile uint32_t*)GPE;
}
-enum PinFunction {
- GPIO, PWM
-};
-
extern void __pinMode(uint8_t pin, uint8_t mode) {
- if(pin == 16) {
- uint32_t val = (mode == OUTPUT) ? 1 : 0;
-
- MODIFY_PERI_REG(PAD_XPD_DCDC_CONF, 0x43, 1);
- MODIFY_PERI_REG(RTC_GPIO_CONF, 1, 0);
- MODIFY_PERI_REG(RTC_GPIO_ENABLE, 1, val);
- return;
+ if(pin < 16){
+ if(mode == SPECIAL){
+ GPC(pin) = (GPC(pin) & (0xF << GPCI)); //SOURCE(GPIO) | DRIVER(NORMAL) | INT_TYPE(UNCHANGED) | WAKEUP_ENABLE(DISABLED)
+ GPEC = (1 << pin); //Disable
+ GPF(pin) = GPFFS(GPFFS_BUS(pin));//Set mode to BUS (RX0, TX0, TX1, SPI, HSPI or CLK depending in the pin)
+ } else if(mode & FUNCTION_0){
+ GPC(pin) = (GPC(pin) & (0xF << GPCI)); //SOURCE(GPIO) | DRIVER(NORMAL) | INT_TYPE(UNCHANGED) | WAKEUP_ENABLE(DISABLED)
+ GPEC = (1 << pin); //Disable
+ GPF(pin) = GPFFS((mode >> 4) & 0x07);
+ } else if(mode == OUTPUT){
+ GPF(pin) = GPFFS(GPFFS_GPIO(pin));//Set mode to GPIO
+ GPC(pin) = (GPC(pin) & (0xF << GPCI)); //SOURCE(GPIO) | DRIVER(NORMAL) | INT_TYPE(UNCHANGED) | WAKEUP_ENABLE(DISABLED)
+ GPES = (1 << pin); //Enable
+ } else if(mode == INPUT || mode == INPUT_PULLUP){
+ GPF(pin) = GPFFS(GPFFS_GPIO(pin));//Set mode to GPIO
+ GPC(pin) = (GPC(pin) & (0xF << GPCI)) | (1 << GPCD); //SOURCE(GPIO) | DRIVER(OPEN_DRAIN) | INT_TYPE(UNCHANGED) | WAKEUP_ENABLE(DISABLED)
+ GPEC = (1 << pin); //Disable
+ if(mode == INPUT_PULLUP){
+ GPF(pin) |= (1 << GPFPU);//Enable Pullup
+ }
}
-
- uint32_t mux = g_pin_muxes[pin];
- if(mode == INPUT) {
- gpio_output_set(0, 0, 0, 1 << pin);
- PIN_PULLUP_DIS(mux);
- } else if(mode == INPUT_PULLUP) {
- gpio_output_set(0, 0, 0, 1 << pin);
- PIN_PULLDWN_DIS(mux);
- PIN_PULLUP_EN(mux);
- } else if(mode == INPUT_PULLDOWN) {
- gpio_output_set(0, 0, 0, 1 << pin);
- PIN_PULLUP_DIS(mux);
- PIN_PULLDWN_EN(mux);
- } else if(mode == OUTPUT) {
- gpio_output_set(0, 0, 1 << pin, 0);
- } else if(mode == OUTPUT_OPEN_DRAIN) {
- GPIO_REG_WRITE(GPIO_PIN_ADDR(GPIO_ID_PIN(pin)), GPIO_REG_READ(GPIO_PIN_ADDR(GPIO_ID_PIN(pin))) | GPIO_PIN_PAD_DRIVER_SET(GPIO_PAD_DRIVER_ENABLE));
-
- GPIO_REG_WRITE(GPIO_ENABLE_ADDRESS, GPIO_REG_READ(GPIO_ENABLE_ADDRESS) | (1 << pin));
+ } else if(pin == 16){
+ GPF16 = GP16FFS(GPFFS_GPIO(pin));//Set mode to GPIO
+ GPC16 = 0;
+ if(mode == INPUT || mode == INPUT_PULLDOWN){
+ if(mode == INPUT_PULLDOWN){
+ GPF16 |= (1 << GP16FPD);//Enable Pulldown
+ }
+ GP16E &= ~1;
+ } else if(mode == OUTPUT){
+ GP16E |= 1;
}
+ }
}
extern void __digitalWrite(uint8_t pin, uint8_t val) {
- if(pin == 16) {
- MODIFY_PERI_REG(RTC_GPIO_OUT, 1, (val & 1));
- return;
- }
-
- uint32_t mask = 1 << pin;
- if(val)
- GPIO_REG_WRITE(GPIO_OUT_W1TS_ADDRESS, mask);
- else
- GPIO_REG_WRITE(GPIO_OUT_W1TC_ADDRESS, mask);
+ val &= 0x01;
+ if(pin < 16){
+ if(val) GPOS = (1 << pin);
+ else GPOC = (1 << pin);
+ } else if(pin == 16){
+ if(val) GP16O |= 1;
+ else GP16O &= ~1;
+ }
}
extern int __digitalRead(uint8_t pin) {
- if(pin == 16)
- return (READ_PERI_REG(RTC_GPIO_IN_DATA) & 1);
- else
- return ((gpio_input_get() >> pin) & 1);
+ if(pin < 16){
+ return GPIP(pin);
+ } else if(pin == 16){
+ return GP16I & 0x01;
+ }
}
-extern void __analogWrite(uint8_t pin, int val) {
-}
+/*
+ GPIO INTERRUPTS
+*/
typedef void (*voidFuncPtr)(void);
-static voidFuncPtr g_handlers[PINCOUNT] = { 0 };
+
+typedef struct {
+ uint8_t mode;
+ void (*fn)(void);
+} interrupt_handler_t;
+
+static interrupt_handler_t interrupt_handlers[16];
+static uint32_t interrupt_reg = 0;
void interrupt_handler(void *arg) {
- uint32_t intr_mask = GPIO_REG_READ(GPIO_STATUS_ADDRESS);
- for(int pin = 0; intr_mask; intr_mask >>= 1, ++pin) {
- if((intr_mask & 1) && g_handlers[pin]) {
- GPIO_REG_WRITE(GPIO_STATUS_W1TC_ADDRESS, 1 << pin);
- (*g_handlers[pin])();
- }
- }
+ uint32_t status = GPIE;
+ GPIEC = status;//clear them interrupts
+ if(status == 0 || interrupt_reg == 0) return;
+ ETS_GPIO_INTR_DISABLE();
+ int i = 0;
+ uint32_t changedbits = status & interrupt_reg;
+ while(changedbits){
+ while(!(changedbits & (1 << i))) i++;
+ changedbits &= ~(1 << i);
+ interrupt_handler_t *handler = &interrupt_handlers[i];
+ if(((handler->mode & 1) == digitalRead(i)) && handler->fn) handler->fn();
+ }
+ ETS_GPIO_INTR_ENABLE();
}
-extern void __attachInterrupt(uint8_t pin, voidFuncPtr handler, int mode) {
- if(pin < 0 || pin > PINCOUNT)
- return;
-
- g_handlers[pin] = handler;
-
- if(mode == RISING) {
- gpio_pin_intr_state_set(pin, GPIO_PIN_INTR_POSEDGE);
- } else if(mode == FALLING) {
- gpio_pin_intr_state_set(pin, GPIO_PIN_INTR_NEGEDGE);
- } else if(mode == CHANGE) {
- gpio_pin_intr_state_set(pin, GPIO_PIN_INTR_ANYEDGE);
- } else {
- gpio_pin_intr_state_set(pin, GPIO_PIN_INTR_DISABLE);
- }
+extern void __attachInterrupt(uint8_t pin, voidFuncPtr userFunc, int mode) {
+ if(pin < 16) {
+ interrupt_handler_t *handler = &interrupt_handlers[pin];
+ handler->mode = mode;
+ handler->fn = userFunc;
+ interrupt_reg |= (1 << pin);
+ GPC(pin) &= ~(0xF << GPCI);//INT mode disabled
+ GPIEC = (1 << pin); //Clear Interrupt for this pin
+ GPC(pin) |= ((mode & 0xF) << GPCI);//INT mode "mode"
+ }
}
extern void __detachInterrupt(uint8_t pin) {
- g_handlers[pin] = 0;
- gpio_pin_intr_state_set(pin, GPIO_PIN_INTR_DISABLE);
+ if(pin < 16) {
+ GPC(pin) &= ~(0xF << GPCI);//INT mode disabled
+ GPIEC = (1 << pin); //Clear Interrupt for this pin
+ interrupt_reg &= ~(1 << pin);
+ interrupt_handler_t *handler = &interrupt_handlers[pin];
+ handler->mode = 0;
+ handler->fn = 0;
+ }
}
void initPins() {
- gpio_init();
- for(int i = 0; i < PINCOUNT; ++i) {
- uint32_t mux = g_pin_muxes[i];
- if(mux) {
- uint32_t func = g_pin_funcs[i];
- PIN_FUNC_SELECT(mux, func);
- }
- }
- ETS_GPIO_INTR_ATTACH(&interrupt_handler, NULL);
+ for (int i = 0; i <= 5; ++i) {
+ pinMode(i, INPUT);
+ }
+ // pins 6-11 are used for the SPI flash interface
+ for (int i = 12; i <= 16; ++i) {
+ pinMode(i, INPUT);
+ }
+
+ ETS_GPIO_INTR_ATTACH(interrupt_handler, &interrupt_reg);
+ ETS_GPIO_INTR_ENABLE();
}
extern void pinMode(uint8_t pin, uint8_t mode) __attribute__ ((weak, alias("__pinMode")));
extern void digitalWrite(uint8_t pin, uint8_t val) __attribute__ ((weak, alias("__digitalWrite")));
extern int digitalRead(uint8_t pin) __attribute__ ((weak, alias("__digitalRead")));
-extern void analogWrite(uint8_t pin, int val) __attribute__ ((weak, alias("__analogWrite")));
extern void attachInterrupt(uint8_t pin, voidFuncPtr handler, int mode) __attribute__ ((weak, alias("__attachInterrupt")));
extern void detachInterrupt(uint8_t pin) __attribute__ ((weak, alias("__detachInterrupt")));
diff --git a/hardware/esp8266com/esp8266/cores/esp8266/core_esp8266_wiring_pulse.c b/hardware/esp8266com/esp8266/cores/esp8266/core_esp8266_wiring_pulse.c
index d5b8686bb..16b2ccc06 100644
--- a/hardware/esp8266com/esp8266/cores/esp8266/core_esp8266_wiring_pulse.c
+++ b/hardware/esp8266com/esp8266/cores/esp8266/core_esp8266_wiring_pulse.c
@@ -1,31 +1,32 @@
/*
- core_esp8266_wiring_pulse.c - implementation of pulseIn function
+ pulse.c - wiring pulseIn implementation for esp8266
- Copyright (c) 2014 Ivan Grokhotkov. All rights reserved.
- This file is part of the esp8266 core for Arduino environment.
+ Copyright (c) 2015 Hristo Gochkov. All rights reserved.
+ This file is part of the esp8266 core for Arduino environment.
- This library is free software; you can redistribute it and/or
- modify it under the terms of the GNU Lesser General Public
- License as published by the Free Software Foundation; either
- version 2.1 of the License, or (at your option) any later version.
+ This library is free software; you can redistribute it and/or
+ modify it under the terms of the GNU Lesser General Public
+ License as published by the Free Software Foundation; either
+ version 2.1 of the License, or (at your option) any later version.
- This library is distributed in the hope that it will be useful,
- but WITHOUT ANY WARRANTY; without even the implied warranty of
- MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
- Lesser General Public License for more details.
-
- You should have received a copy of the GNU Lesser General Public
- License along with this library; if not, write to the Free Software
- Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
- */
+ This library is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+ You should have received a copy of the GNU Lesser General Public
+ License along with this library; if not, write to the Free Software
+ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+*/
#include "wiring_private.h"
#include "pins_arduino.h"
-/* Measures the length (in microseconds) of a pulse on the pin; state is HIGH
- * or LOW, the type of pulse to measure. Works on pulses from 2-3 microseconds
- * to 3 minutes in length, but must be called at least a few dozen microseconds
- * before the start of the pulse. */
unsigned long pulseIn(uint8_t pin, uint8_t state, unsigned long timeout) {
- return 0;
+ pinMode(pin, INPUT);
+ uint32_t start = micros();
+ while(digitalRead(pin) == state && (micros() - start) < timeout);
+ while(digitalRead(pin) != state && (micros() - start) < timeout);
+ start = micros();
+ while(digitalRead(pin) == state && (micros() - start) < timeout);
+ return micros() - start;
}
diff --git a/hardware/esp8266com/esp8266/cores/esp8266/core_esp8266_wiring_pwm.c b/hardware/esp8266com/esp8266/cores/esp8266/core_esp8266_wiring_pwm.c
new file mode 100644
index 000000000..25ddceb2e
--- /dev/null
+++ b/hardware/esp8266com/esp8266/cores/esp8266/core_esp8266_wiring_pwm.c
@@ -0,0 +1,142 @@
+/*
+ pwm.c - analogWrite implementation for esp8266
+
+ Copyright (c) 2015 Hristo Gochkov. All rights reserved.
+ This file is part of the esp8266 core for Arduino environment.
+
+ This library is free software; you can redistribute it and/or
+ modify it under the terms of the GNU Lesser General Public
+ License as published by the Free Software Foundation; either
+ version 2.1 of the License, or (at your option) any later version.
+
+ This library is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with this library; if not, write to the Free Software
+ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+*/
+#include "wiring_private.h"
+#include "pins_arduino.h"
+#include "c_types.h"
+#include "eagle_soc.h"
+#include "ets_sys.h"
+
+uint32_t pwm_mask = 0;
+uint16_t pwm_values[17] = {0,};
+uint32_t pwm_freq = 1000;
+
+uint32_t pwm_multiplier = 0;
+uint16_t pwm_steps[17];
+uint8_t pwm_steps_len = 0;
+uint32_t pwm_steps_mask[17];
+
+int pwm_sort_asc(const void* a, const void* b){
+ return (*((uint16_t*)a) > *((uint16_t*)b)) - (*((uint16_t*)a) < *((uint16_t*)b));
+}
+
+int pwm_sort_array(uint16_t a[], uint16_t al){
+ qsort(a, al, sizeof(uint16_t), pwm_sort_asc);
+ int i;
+ int bl = 1;
+ for(i = 1; i < al; i++){
+ if(a[i] != a[i-1]) a[bl++] = a[i];
+ }
+ return bl;
+}
+
+uint32_t pwm_get_mask(uint16_t value){
+ uint32_t mask = 0;
+ int i;
+ for(i=0; i<17; i++){
+ if((pwm_mask & (1 << i)) != 0 && pwm_values[i] == value) mask |= (1 << i);
+ }
+ return mask;
+}
+
+void prep_pwm_steps(){
+ if(pwm_mask == 0){
+ pwm_steps_len = 0;
+ return;
+ }
+
+ int pwm_temp_steps_len = 0;
+ uint16_t pwm_temp_steps[17];
+ uint32_t pwm_temp_masks[17];
+
+ int i;
+ for(i=0; i<17; i++){
+ if((pwm_mask & (1 << i)) != 0 && pwm_values[i] != 0) pwm_temp_steps[pwm_temp_steps_len++] = pwm_values[i];
+ }
+ pwm_temp_steps[pwm_temp_steps_len++] = PWMRANGE;
+ pwm_temp_steps_len = pwm_sort_array(pwm_temp_steps, pwm_temp_steps_len) - 1;
+ for(i=0; i0; i--){
+ pwm_temp_steps[i] = pwm_temp_steps[i] - pwm_temp_steps[i-1];
+ }
+ ETS_FRC1_INTR_DISABLE();
+ pwm_steps_len = pwm_temp_steps_len;
+ os_memcpy(pwm_steps, pwm_temp_steps, (pwm_temp_steps_len + 1) * 2);
+ os_memcpy(pwm_steps_mask, pwm_temp_masks, pwm_temp_steps_len * 4);
+ pwm_multiplier = F_CPU/(PWMRANGE * pwm_freq);
+ ETS_FRC1_INTR_ENABLE();
+}
+
+void pwm_timer_isr(){
+ static uint8_t current_step = 0;
+ static uint8_t stepcount = 0;
+ static uint16_t steps[17];
+ static uint32_t masks[17];
+ if(current_step < stepcount){
+ GPOC = masks[current_step] & 0xFFFF;
+ if(masks[current_step] & 0x10000) GP16O &= ~1;
+ current_step++;
+ timer1_write(pwm_steps[current_step] * pwm_multiplier);
+ } else {
+
+ current_step = 0;
+ stepcount = 0;
+ if(pwm_mask == 0) return;
+ GPOS = pwm_mask & 0xFFFF;
+ if(pwm_mask & 0x10000) GP16O |= 1;
+ timer1_write(pwm_steps[0] * pwm_multiplier);
+ stepcount = pwm_steps_len;
+ memcpy(steps, pwm_steps, (stepcount + 1) * 2);
+ memcpy(masks, pwm_steps_mask, stepcount * 4);
+ }
+}
+
+void pwm_start_timer(){
+ timer1_disable();
+ timer1_attachInterrupt(pwm_timer_isr);
+ timer1_enable(TIM_DIV1, TIM_EDGE, TIM_SINGLE);
+ timer1_write(1);
+}
+
+extern void __analogWrite(uint8_t pin, int value) {
+ bool start_timer = false;
+ if(value == 0){
+ pwm_mask &= ~(1 << pin);
+ prep_pwm_steps();
+ digitalWrite(pin, LOW);
+ if(pwm_mask == 0) timer1_disable();
+ return;
+ }
+ if((pwm_mask & (1 << pin)) == 0){
+ if(pwm_mask == 0) start_timer = true;
+ pwm_mask |= (1 << pin);
+ pinMode(pin, OUTPUT);
+ digitalWrite(pin, LOW);
+ }
+ pwm_values[pin] = value % (PWMRANGE + 1);
+ prep_pwm_steps();
+ if(start_timer){
+ pwm_start_timer();
+ }
+}
+
+extern void analogWrite(uint8_t pin, int val) __attribute__ ((weak, alias("__analogWrite")));
diff --git a/hardware/esp8266com/esp8266/cores/esp8266/esp8266_peri.h b/hardware/esp8266com/esp8266/cores/esp8266/esp8266_peri.h
new file mode 100644
index 000000000..f905d34b3
--- /dev/null
+++ b/hardware/esp8266com/esp8266/cores/esp8266/esp8266_peri.h
@@ -0,0 +1,529 @@
+/*
+ esp8266_peri.h - Peripheral registers exposed in more AVR style for esp8266
+
+ Copyright (c) 2015 Hristo Gochkov. All rights reserved.
+ This file is part of the esp8266 core for Arduino environment.
+
+ This library is free software; you can redistribute it and/or
+ modify it under the terms of the GNU Lesser General Public
+ License as published by the Free Software Foundation; either
+ version 2.1 of the License, or (at your option) any later version.
+
+ This library is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with this library; if not, write to the Free Software
+ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+*/
+#ifndef ESP8266_PERI_H_INCLUDED
+#define ESP8266_PERI_H_INCLUDED
+
+#include "c_types.h"
+
+#define ESP8266_REG(addr) *((volatile uint32_t *)(0x60000000+(addr)))
+#define ESP8266_DREG(addr) *((volatile uint32_t *)(0x3FF00000+(addr)))
+
+//GPIO (0-15) Control Registers
+#define GPO ESP8266_REG(0x300) //GPIO_OUT R/W (Output Level)
+#define GPOS ESP8266_REG(0x304) //GPIO_OUT_SET WO
+#define GPOC ESP8266_REG(0x308) //GPIO_OUT_CLR WO
+#define GPE ESP8266_REG(0x30C) //GPIO_ENABLE R/W (Enable)
+#define GPES ESP8266_REG(0x310) //GPIO_ENABLE_SET WO
+#define GPEC ESP8266_REG(0x314) //GPIO_ENABLE_CLR WO
+#define GPI ESP8266_REG(0x318) //GPIO_IN RO (Read Input Level)
+#define GPIE ESP8266_REG(0x31C) //GPIO_STATUS R/W (Interrupt Enable)
+#define GPIES ESP8266_REG(0x320) //GPIO_STATUS_SET WO
+#define GPIEC ESP8266_REG(0x324) //GPIO_STATUS_CLR WO
+
+#define GPOP(p) ((GPO & (1 << ((p) & 0xF))) != 0)
+#define GPEP(p) ((GPE & (1 << ((p) & 0xF))) != 0)
+#define GPIP(p) ((GPI & (1 << ((p) & 0xF))) != 0)
+#define GPIEP(p) ((GPIE & (1 << ((p) & 0xF))) != 0)
+
+//GPIO (0-15) PIN Control Registers
+#define GPC(p) ESP8266_REG(0x328 + ((p & 0xF) * 4))
+#define GPC0 ESP8266_REG(0x328) //GPIO_PIN0
+#define GPC1 ESP8266_REG(0x32C) //GPIO_PIN1
+#define GPC2 ESP8266_REG(0x330) //GPIO_PIN2
+#define GPC3 ESP8266_REG(0x334) //GPIO_PIN3
+#define GPC4 ESP8266_REG(0x338) //GPIO_PIN4
+#define GPC5 ESP8266_REG(0x33C) //GPIO_PIN5
+#define GPC6 ESP8266_REG(0x340) //GPIO_PIN6
+#define GPC7 ESP8266_REG(0x344) //GPIO_PIN7
+#define GPC8 ESP8266_REG(0x348) //GPIO_PIN8
+#define GPC9 ESP8266_REG(0x34C) //GPIO_PIN9
+#define GPC10 ESP8266_REG(0x350) //GPIO_PIN10
+#define GPC11 ESP8266_REG(0x354) //GPIO_PIN11
+#define GPC12 ESP8266_REG(0x358) //GPIO_PIN12
+#define GPC13 ESP8266_REG(0x35C) //GPIO_PIN13
+#define GPC14 ESP8266_REG(0x360) //GPIO_PIN14
+#define GPC15 ESP8266_REG(0x364) //GPIO_PIN15
+
+//GPIO (0-15) PIN Control Bits
+#define GPCWE 10 //WAKEUP_ENABLE (can be 1 only when INT_TYPE is high or low)
+#define GPCI 7 //INT_TYPE (3bits) 0:disable,1:rising,2:falling,3:change,4:low,5:high
+#define GPCD 2 //DRIVER 0:normal,1:open drain
+#define GPCS 0 //SOURCE 0:GPIO_DATA,1:SigmaDelta
+
+static uint8_t esp8266_gpioToFn[16] = {0x34, 0x18, 0x38, 0x14, 0x3C, 0x40, 0x1C, 0x20, 0x24, 0x28, 0x2C, 0x30, 0x04, 0x08, 0x0C, 0x10};
+#define GPF(p) ESP8266_REG(0x800 + esp8266_gpioToFn[(p & 0xF)])
+
+#define GPMUX ESP8266_REG(0x800)
+//GPIO (0-15) PIN Function Registers
+#define GPF0 ESP8266_REG(0x834)
+#define GPF1 ESP8266_REG(0x818)
+#define GPF2 ESP8266_REG(0x838)
+#define GPF3 ESP8266_REG(0x814)
+#define GPF4 ESP8266_REG(0x83C)
+#define GPF5 ESP8266_REG(0x840)
+#define GPF6 ESP8266_REG(0x81C)
+#define GPF7 ESP8266_REG(0x820)
+#define GPF8 ESP8266_REG(0x824)
+#define GPF9 ESP8266_REG(0x828)
+#define GPF10 ESP8266_REG(0x82C)
+#define GPF11 ESP8266_REG(0x830)
+#define GPF12 ESP8266_REG(0x804)
+#define GPF13 ESP8266_REG(0x808)
+#define GPF14 ESP8266_REG(0x80C)
+#define GPF15 ESP8266_REG(0x810)
+
+//GPIO (0-15) PIN Function Bits
+#define GPFSOE 0 //Sleep OE
+#define GPFSS 1 //Sleep Sel
+#define GPFSPU 3 //Sleep Pullup
+#define GPFFS0 4 //Function Select bit 0
+#define GPFFS1 5 //Function Select bit 1
+#define GPFPU 7 //Pullup
+#define GPFFS2 8 //Function Select bit 2
+#define GPFFS(f) (((((f) & 4) != 0) << GPFFS2) | ((((f) & 2) != 0) << GPFFS1) | ((((f) & 1) != 0) << GPFFS0))
+#define GPFFS_GPIO(p) (((p)==0||(p)==2||(p)==4||(p)==5)?0:((p)==16)?1:3)
+#define GPFFS_BUS(p) (((p)==1||(p)==3)?0:((p)==2||(p)==12||(p)==13||(p)==14||(p)==15)?2:((p)==0)?4:1)
+
+//GPIO 16 Control Registers
+#define GP16O ESP8266_REG(0x768)
+#define GP16E ESP8266_REG(0x774)
+#define GP16I ESP8266_REG(0x78C)
+
+//GPIO 16 PIN Control Register
+#define GP16C ESP8266_REG(0x790)
+#define GPC16 GP16C
+
+//GPIO 16 PIN Function Register
+#define GP16F ESP8266_REG(0x7A0)
+#define GPF16 GP16F
+
+//GPIO 16 PIN Function Bits
+#define GP16FFS0 0 //Function Select bit 0
+#define GP16FFS1 1 //Function Select bit 1
+#define GP16FPD 3 //Pulldown
+#define GP16FSPD 5 //Sleep Pulldown
+#define GP16FFS2 6 //Function Select bit 2
+#define GP16FFS(f) (((f) & 0x03) | (((f) & 0x04) << 4))
+
+//Timer 1 Registers (23bit CountDown Timer)
+#define T1L ESP8266_REG(0x600) //Load Value (Starting Value of Counter) 23bit (0-8388607)
+#define T1V ESP8266_REG(0x604) //(RO) Current Value
+#define T1C ESP8266_REG(0x608) //Control Register
+#define T1I ESP8266_REG(0x60C) //Interrupt Status Register (1bit) write to clear
+//edge interrupt enable register
+#define TEIE ESP8266_DREG(0x04)
+#define TEIE1 0x02 //it for timer 1
+
+//Timer 2 Registers (32bit CountUp Timer)
+#define T2L ESP8266_REG(0x620) //Load Value (Starting Value of Counter)
+#define T2V ESP8266_REG(0x624) //(RO) Current Value
+#define T2C ESP8266_REG(0x628) //Control Register
+#define T2I ESP8266_REG(0x62C) //Interrupt Status Register (1bit) write to clear
+#define T2A ESP8266_REG(0x630) //Alarm Value
+
+//Timer Control Bits
+#define TCIS 8 //Interrupt Status
+#define TCTE 7 //Timer Enable
+#define TCAR 6 //AutoReload (restart timer when condition is reached)
+#define TCPD 2 //Prescale Devider (2bit) 0:1(12.5ns/tick), 1:16(0.2us/tick), 2/3:256(3.2us/tick)
+#define TCIT 0 //Interrupt Type 0:edge, 1:level
+
+
+//UART 0 Registers
+#define U0F ESP8266_REG(0x000) //UART FIFO
+#define U0IR ESP8266_REG(0x004) //INT_RAW
+#define U0IS ESP8266_REG(0x008) //INT_STATUS
+#define U0IE ESP8266_REG(0x00c) //INT_ENABLE
+#define U0IC ESP8266_REG(0x010) //INT_CLEAR
+#define U0D ESP8266_REG(0x014) //CLKDIV
+#define U0A ESP8266_REG(0x018) //AUTOBAUD
+#define U0S ESP8266_REG(0x01C) //STATUS
+#define U0C0 ESP8266_REG(0x020) //CONF0
+#define U0C1 ESP8266_REG(0x024) //CONF1
+#define U0LP ESP8266_REG(0x028) //LOW_PULSE
+#define U0HP ESP8266_REG(0x02C) //HIGH_PULSE
+#define U0PN ESP8266_REG(0x030) //PULSE_NUM
+#define U0DT ESP8266_REG(0x078) //DATE
+#define U0ID ESP8266_REG(0x07C) //ID
+
+//UART 1 Registers
+#define U1F ESP8266_REG(0xF00) //UART FIFO
+#define U1IR ESP8266_REG(0xF04) //INT_RAW
+#define U1IS ESP8266_REG(0xF08) //INT_STATUS
+#define U1IE ESP8266_REG(0xF0c) //INT_ENABLE
+#define U1IC ESP8266_REG(0xF10) //INT_CLEAR
+#define U1D ESP8266_REG(0xF14) //CLKDIV
+#define U1A ESP8266_REG(0xF18) //AUTOBAUD
+#define U1S ESP8266_REG(0xF1C) //STATUS
+#define U1C0 ESP8266_REG(0xF20) //CONF0
+#define U1C1 ESP8266_REG(0xF24) //CONF1
+#define U1LP ESP8266_REG(0xF28) //LOW_PULSE
+#define U1HP ESP8266_REG(0xF2C) //HIGH_PULSE
+#define U1PN ESP8266_REG(0xF30) //PULSE_NUM
+#define U1DT ESP8266_REG(0xF78) //DATE
+#define U1ID ESP8266_REG(0xF7C) //ID
+
+//UART INT Registers Bits
+#define UITO 8 //RX FIFO TimeOut
+#define UIBD 7 //Break Detected
+#define UICTS 6 //CTS Changed
+#define UIDSR 5 //DSR Change
+#define UIOF 4 //RX FIFO OverFlow
+#define UIFR 3 //Frame Error
+#define UIPE 2 //Parity Error
+#define UIFE 1 //TX FIFO Empty
+#define UIFF 0 //RX FIFO Full
+
+//UART STATUS Registers Bits
+#define USTX 31 //TX PIN Level
+#define USRTS 30 //RTS PIN Level
+#define USDTR 39 //DTR PIN Level
+#define USTXC 16 //TX FIFO COUNT (8bit)
+#define USRXD 15 //RX PIN Level
+#define USCTS 14 //CTS PIN Level
+#define USDSR 13 //DSR PIN Level
+#define USRXC 0 //RX FIFO COUNT (8bit)
+
+//UART CONF0 Registers Bits
+#define UCDTRI 24 //Invert DTR
+#define UCRTSI 23 //Invert RTS
+#define UCTXI 22 //Invert TX
+#define UCDSRI 21 //Invert DSR
+#define UCCTSI 20 //Invert CTS
+#define UCRXI 19 //Invert RX
+#define UCTXRST 18 //Reset TX FIFO
+#define UCRXRST 17 //Reset RX FIFO
+#define UCTXHFE 15 //TX Harware Flow Enable
+#define UCLBE 14 //LoopBack Enable
+#define UCBRK 8 //Send Break on the TX line
+#define UCSWDTR 7 //Set this bit to assert DTR
+#define UCSWRTS 6 //Set this bit to assert RTS
+#define UCSBN 4 //StopBits Count (2bit) 0:disable, 1:1bit, 2:1.5bit, 3:2bit
+#define UCBN 2 //DataBits Count (2bin) 0:5bit, 1:6bit, 2:7bit, 3:8bit
+#define UCPAE 1 //Parity Enable
+#define UCPA 0 //Parity 0:even, 1:odd
+
+//UART CONF1 Registers Bits
+#define UCTOE 31 //RX TimeOut Enable
+#define UCTOT 24 //RX TimeOut Treshold (7bit)
+#define UCRXHFE 23 //RX Harware Flow Enable
+#define UCRXHFT 16 //RX Harware Flow Treshold (7bit)
+#define UCFET 8 //TX FIFO Empty Treshold (7bit)
+#define UCFFT 0 //RX FIFO Full Treshold (7bit)
+
+//WDT Register used for UART
+#define WDTRST ESP8266_REG(0x914)
+#define WDT_RESET() (WDTRST = 0x73)
+
+//SPI0 Registers (SPI0 is used for the flash)
+#define SPI0CMD ESP8266_REG(0x200)
+#define SPI0A ESP8266_REG(0x204)
+#define SPI0C ESP8266_REG(0x208)
+#define SPI0C1 ESP8266_REG(0x20C)
+#define SPI0RS ESP8266_REG(0x210)
+#define SPI0C2 ESP8266_REG(0x214)
+#define SPI0CLK ESP8266_REG(0x218)
+#define SPI0U ESP8266_REG(0x21C)
+#define SPI0U1 ESP8266_REG(0x220)
+#define SPI0U2 ESP8266_REG(0x224)
+#define SPI0WS ESP8266_REG(0x228)
+#define SPI0P ESP8266_REG(0x22C)
+#define SPI0S ESP8266_REG(0x230)
+#define SPI0S1 ESP8266_REG(0x234)
+#define SPI0S2 ESP8266_REG(0x238)
+#define SPI0S3 ESP8266_REG(0x23C)
+#define SPI0W0 ESP8266_REG(0x240)
+#define SPI0W1 ESP8266_REG(0x244)
+#define SPI0W2 ESP8266_REG(0x248)
+#define SPI0W3 ESP8266_REG(0x24C)
+#define SPI0W4 ESP8266_REG(0x250)
+#define SPI0W5 ESP8266_REG(0x254)
+#define SPI0W6 ESP8266_REG(0x258)
+#define SPI0W7 ESP8266_REG(0x25C)
+#define SPI0W8 ESP8266_REG(0x260)
+#define SPI0W9 ESP8266_REG(0x264)
+#define SPI0W10 ESP8266_REG(0x268)
+#define SPI0W11 ESP8266_REG(0x26C)
+#define SPI0W12 ESP8266_REG(0x270)
+#define SPI0W13 ESP8266_REG(0x274)
+#define SPI0W14 ESP8266_REG(0x278)
+#define SPI0W15 ESP8266_REG(0x27C)
+#define SPI0E3 ESP8266_REG(0x2FC)
+#define SPI0W(p) ESP8266_REG(0x240 + ((p & 0xF) * 4))
+
+//SPI1 Registers
+#define SPI1CMD ESP8266_REG(0x100)
+#define SPI1A ESP8266_REG(0x104)
+#define SPI1C ESP8266_REG(0x108)
+#define SPI1C1 ESP8266_REG(0x10C)
+#define SPI1RS ESP8266_REG(0x110)
+#define SPI1C2 ESP8266_REG(0x114)
+#define SPI1CLK ESP8266_REG(0x118)
+#define SPI1U ESP8266_REG(0x11C)
+#define SPI1U1 ESP8266_REG(0x120)
+#define SPI1U2 ESP8266_REG(0x124)
+#define SPI1WS ESP8266_REG(0x128)
+#define SPI1P ESP8266_REG(0x12C)
+#define SPI1S ESP8266_REG(0x130)
+#define SPI1S1 ESP8266_REG(0x134)
+#define SPI1S2 ESP8266_REG(0x138)
+#define SPI1S3 ESP8266_REG(0x13C)
+#define SPI1W0 ESP8266_REG(0x140)
+#define SPI1W1 ESP8266_REG(0x144)
+#define SPI1W2 ESP8266_REG(0x148)
+#define SPI1W3 ESP8266_REG(0x14C)
+#define SPI1W4 ESP8266_REG(0x150)
+#define SPI1W5 ESP8266_REG(0x154)
+#define SPI1W6 ESP8266_REG(0x158)
+#define SPI1W7 ESP8266_REG(0x15C)
+#define SPI1W8 ESP8266_REG(0x160)
+#define SPI1W9 ESP8266_REG(0x164)
+#define SPI1W10 ESP8266_REG(0x168)
+#define SPI1W11 ESP8266_REG(0x16C)
+#define SPI1W12 ESP8266_REG(0x170)
+#define SPI1W13 ESP8266_REG(0x174)
+#define SPI1W14 ESP8266_REG(0x178)
+#define SPI1W15 ESP8266_REG(0x17C)
+#define SPI1E0 ESP8266_REG(0x1F0)
+#define SPI1E1 ESP8266_REG(0x1F4)
+#define SPI1E2 ESP8266_REG(0x1F8)
+#define SPI1E3 ESP8266_REG(0x1FC)
+#define SPI1W(p) ESP8266_REG(0x140 + ((p & 0xF) * 4))
+
+//SPI0, SPI1 & I2S Interupt Register
+#define SPIIR ESP8266_DREG(0x20)
+#define SPII0 4 //SPI0 Interrupt
+#define SPII1 7 //SPI1 Interrupt
+#define SPII2 9 //I2S Interrupt
+
+//SPI CMD
+#define SPICMDREAD (1 << 31) //SPI_FLASH_READ
+#define SPICMDWREN (1 << 30) //SPI_FLASH_WREN
+#define SPICMDWRDI (1 << 29) //SPI_FLASH_WRDI
+#define SPICMDRDID (1 << 28) //SPI_FLASH_RDID
+#define SPICMDRDSR (1 << 27) //SPI_FLASH_RDSR
+#define SPICMDWRSR (1 << 26) //SPI_FLASH_WRSR
+#define SPICMDPP (1 << 25) //SPI_FLASH_PP
+#define SPICMDSE (1 << 24) //SPI_FLASH_SE
+#define SPICMDBE (1 << 23) //SPI_FLASH_BE
+#define SPICMDCE (1 << 22) //SPI_FLASH_CE
+#define SPICMDDP (1 << 21) //SPI_FLASH_DP
+#define SPICMDRES (1 << 20) //SPI_FLASH_RES
+#define SPICMDHPM (1 << 19) //SPI_FLASH_HPM
+#define SPICMDUSR (1 << 18) //SPI_FLASH_USR
+#define SPIBUSY (1 << 18) //SPI_USR
+
+//SPI CTRL (SPIxC)
+#define SPICWBO (1 << 26) //SPI_WR_BIT_ODER
+#define SPICRBO (1 << 25) //SPI_RD_BIT_ODER
+#define SPICQIO (1 << 24) //SPI_QIO_MODE
+#define SPICDIO (1 << 23) //SPI_DIO_MODE
+#define SPIC2BSE (1 << 22) //SPI_TWO_BYTE_STATUS_EN
+#define SPICWPR (1 << 21) //SPI_WP_REG
+#define SPICQOUT (1 << 20) //SPI_QOUT_MODE
+#define SPICSHARE (1 << 19) //SPI_SHARE_BUS
+#define SPICHOLD (1 << 18) //SPI_HOLD_MODE
+#define SPICAHB (1 << 17) //SPI_ENABLE_AHB
+#define SPICSSTAAI (1 << 16) //SPI_SST_AAI
+#define SPICRESANDRES (1 << 15) //SPI_RESANDRES
+#define SPICDOUT (1 << 14) //SPI_DOUT_MODE
+#define SPICFASTRD (1 << 13) //SPI_FASTRD_MODE
+
+//SPI CTRL1 (SPIxC1)
+#define SPIC1TCSH 0xF //SPI_T_CSH
+#define SPIC1TCSH_S 28 //SPI_T_CSH_S
+#define SPIC1TRES 0xFFF //SPI_T_RES
+#define SPIC1TRES_S 16 //SPI_T_RES_S
+#define SPIC1BTL 0xFFFF //SPI_BUS_TIMER_LIMIT
+#define SPIC1BTL_S 0 //SPI_BUS_TIMER_LIMIT_S
+
+//SPI Status (SPIxRS)
+#define SPIRSEXT 0xFF //SPI_STATUS_EXT
+#define SPIRSEXT_S 24 //SPI_STATUS_EXT_S
+#define SPIRSWB 0xFF //SPI_WB_MODE
+#define SPIRSWB_S 16 //SPI_WB_MODE_S
+#define SPIRSSP (1 << 7) //SPI_FLASH_STATUS_PRO_FLAG
+#define SPIRSTBP (1 << 5) //SPI_FLASH_TOP_BOT_PRO_FLAG
+#define SPIRSBP2 (1 << 4) //SPI_FLASH_BP2
+#define SPIRSBP1 (1 << 3) //SPI_FLASH_BP1
+#define SPIRSBP0 (1 << 2) //SPI_FLASH_BP0
+#define SPIRSWRE (1 << 1) //SPI_FLASH_WRENABLE_FLAG
+#define SPIRSBUSY (1 << 0) //SPI_FLASH_BUSY_FLAG
+
+//SPI CTRL2 (SPIxC2)
+#define SPIC2CSDN 0xF //SPI_CS_DELAY_NUM
+#define SPIC2CSDN_S 28 //SPI_CS_DELAY_NUM_S
+#define SPIC2CSDM 0x3 //SPI_CS_DELAY_MODE
+#define SPIC2CSDM_S 26 //SPI_CS_DELAY_MODE_S
+#define SPIC2MOSIDN 0x7 //SPI_MOSI_DELAY_NUM
+#define SPIC2MOSIDN_S 23 //SPI_MOSI_DELAY_NUM_S
+#define SPIC2MOSIDM 0x3 //SPI_MOSI_DELAY_MODE
+#define SPIC2MOSIDM_S 21 //SPI_MOSI_DELAY_MODE_S
+#define SPIC2MISODN 0x7 //SPI_MISO_DELAY_NUM
+#define SPIC2MISODN_S 18 //SPI_MISO_DELAY_NUM_S
+#define SPIC2MISODM 0x3 //SPI_MISO_DELAY_MODE
+#define SPIC2MISODM_S 16 //SPI_MISO_DELAY_MODE_S
+#define SPIC2CKOHM 0xF //SPI_CK_OUT_HIGH_MODE
+#define SPIC2CKOHM_S 12 //SPI_CK_OUT_HIGH_MODE_S
+#define SPIC2CKOLM 0xF //SPI_CK_OUT_LOW_MODE
+#define SPIC2CKOLM_S 8 //SPI_CK_OUT_LOW_MODE_S
+#define SPIC2HT 0xF //SPI_HOLD_TIME
+#define SPIC2HT_S 4 //SPI_HOLD_TIME_S
+#define SPIC2ST 0xF //SPI_SETUP_TIME
+#define SPIC2ST_S 0 //SPI_SETUP_TIME_S
+
+//SPI CLK (SPIxCLK)
+#define SPICLK_EQU_SYSCLK (1 << 31) //SPI_CLK_EQU_SYSCLK
+#define SPICLKDIVPRE 0x1FFF //SPI_CLKDIV_PRE
+#define SPICLKDIVPRE_S 18 //SPI_CLKDIV_PRE_S
+#define SPICLKCN 0x3F //SPI_CLKCNT_N
+#define SPICLKCN_S 12 //SPI_CLKCNT_N_S
+#define SPICLKCH 0x3F //SPI_CLKCNT_H
+#define SPICLKCH_S 6 //SPI_CLKCNT_H_S
+#define SPICLKCL 0x3F //SPI_CLKCNT_L
+#define SPICLKCL_S 0 //SPI_CLKCNT_L_S
+
+//SPI Phases (SPIxU)
+#define SPIUCOMMAND (1 << 31) //COMMAND pahse, SPI_USR_COMMAND
+#define SPIUADDR (1 << 30) //ADDRESS phase, SPI_FLASH_USR_ADDR
+#define SPIUDUMMY (1 << 29) //DUMMY phase, SPI_FLASH_USR_DUMMY
+#define SPIUMISO (1 << 28) //MISO phase, SPI_FLASH_USR_DIN
+#define SPIUMOSI (1 << 27) //MOSI phase, SPI_FLASH_DOUT
+#define SPIUDUMMYIDLE (1 << 26) //SPI_USR_DUMMY_IDLE
+#define SPIUMOSIH (1 << 25) //MOSI phase uses W8-W15, SPI_USR_DOUT_HIGHPART
+#define SPIUMISOH (1 << 24) //MISO pahse uses W8-W15, SPI_USR_DIN_HIGHPART
+#define SPIUPREPHOLD (1 << 23) //SPI_USR_PREP_HOLD
+#define SPIUCMDHOLD (1 << 22) //SPI_USR_CMD_HOLD
+#define SPIUADDRHOLD (1 << 21) //SPI_USR_ADDR_HOLD
+#define SPIUDUMMYHOLD (1 << 20) //SPI_USR_DUMMY_HOLD
+#define SPIUMISOHOLD (1 << 19) //SPI_USR_DIN_HOLD
+#define SPIUMOSIHOLD (1 << 18) //SPI_USR_DOUT_HOLD
+#define SPIUHOLDPOL (1 << 17) //SPI_USR_HOLD_POL
+#define SPIUSIO (1 << 16) //SPI_SIO
+#define SPIUFWQIO (1 << 15) //SPI_FWRITE_QIO
+#define SPIUFWDIO (1 << 14) //SPI_FWRITE_DIO
+#define SPIUFWQUAD (1 << 13) //SPI_FWRITE_QUAD
+#define SPIUFWDUAL (1 << 12) //SPI_FWRITE_DUAL
+#define SPIUWRBYO (1 << 11) //SPI_WR_BYTE_ORDER
+#define SPIURDBYO (1 << 10) //SPI_RD_BYTE_ORDER
+#define SPIUAHBEM 0x3 //SPI_AHB_ENDIAN_MODE
+#define SPIUAHBEM_S 8 //SPI_AHB_ENDIAN_MODE_S
+#define SPIUSME (1 << 7) //SPI Master Edge (0:falling, 1:rising), SPI_CK_OUT_EDGE
+#define SPIUSSE (1 << 6) //SPI Slave Edge (0:falling, 1:rising), SPI_CK_I_EDGE
+#define SPIUCSSETUP (1 << 5) //SPI_CS_SETUP
+#define SPIUCSHOLD (1 << 4) //SPI_CS_HOLD
+#define SPIUAHBUCMD (1 << 3) //SPI_AHB_USR_COMMAND
+#define SPIUAHBUCMD4B (1 << 1) //SPI_AHB_USR_COMMAND_4BYTE
+#define SPIUDUPLEX (1 << 0) //SPI_DOUTDIN
+
+//SPI Phase Length Locations
+#define SPILCOMMAND 28 //4 bit in SPIxU2 default 7 (8bit)
+#define SPILADDR 16 //6 bit in SPIxU1 default:23 (24bit)
+#define SPILDUMMY 0 //8 bit in SPIxU1 default:0 (0 cycles)
+#define SPILMISO 8 //9 bit in SPIxU1 default:0 (1bit)
+#define SPILMOSI 17 //9 bit in SPIxU1 default:0 (1bit)
+//SPI Phase Length Masks
+#define SPIMCOMMAND 0xF
+#define SPIMADDR 0x3F
+#define SPIMDUMMY 0xFF
+#define SPIMMISO 0x1FF
+#define SPIMMOSI 0x1FF
+
+//SPI Slave (SPIxS)
+#define SPISSRES (1 << 31) //SYNC RESET, SPI_SYNC_RESET
+#define SPISE (1 << 30) //Slave Enable, SPI_SLAVE_MODE
+#define SPISBE (1 << 29) //WR/RD BUF enable, SPI_SLV_WR_RD_BUF_EN
+#define SPISSE (1 << 28) //STA enable, SPI_SLV_WR_RD_STA_EN
+#define SPISCD (1 << 27) //CMD define, SPI_SLV_CMD_DEFINE
+#define SPISTRCNT 0xF //SPI_TRANS_CNT
+#define SPISTRCNT_S 23 //SPI_TRANS_CNT_S
+#define SPISSLS 0x7 //SPI_SLV_LAST_STATE
+#define SPISSLS_S 20 //SPI_SLV_LAST_STATE_S
+#define SPISSLC 0x7 //SPI_SLV_LAST_COMMAND
+#define SPISSLC_S 17 //SPI_SLV_LAST_COMMAND_S
+#define SPISCSIM 0x3 //SPI_CS_I_MODE
+#define SPIDCSIM_S 10 //SPI_CS_I_MODE_S
+#define SPISTRIE (1 << 9) //TRANS interrupt enable
+#define SPISWSIE (1 << 8) //WR_STA interrupt enable
+#define SPISRSIE (1 << 7) //RD_STA interrupt enable
+#define SPISWBIE (1 << 6) //WR_BUF interrupt enable
+#define SPISRBIE (1 << 5) //RD_BUF interrupt enable
+#define SPISTRIS (1 << 4) //TRANS interrupt status
+#define SPISWSIS (1 << 3) //WR_STA interrupt status
+#define SPISRSIS (1 << 2) //RD_STA interrupt status
+#define SPISWBIS (1 << 1) //WR_BUF interrupt status
+#define SPISRBIS (1 << 0) //RD_BUF interrupt status
+
+//SPI Slave1 (SPIxS1)
+#define SPIS1LSTA 27 //5 bit in SPIxS1 default:0 (1bit), SPI_SLV_STATUS_BITLEN
+#define SPIS1FE (1 << 26) //SPI_SLV_STATUS_FAST_EN
+#define SPIS1RSTA (1 << 25) //default:0 enable STA read from Master, SPI_SLV_STATUS_READBACK
+#define SPIS1LBUF 16 //9 bit in SPIxS1 default:0 (1bit), SPI_SLV_BUF_BITLEN
+#define SPIS1LRBA 10 //6 bit in SPIxS1 default:0 (1bit), SPI_SLV_RD_ADDR_BITLEN
+#define SPIS1LWBA 4 //6 bit in SPIxS1 default:0 (1bit), SPI_SLV_WR_ADDR_BITLEN
+#define SPIS1WSDE (1 << 3) //SPI_SLV_WRSTA_DUMMY_EN
+#define SPIS1RSDE (1 << 2) //SPI_SLV_RDSTA_DUMMY_EN
+#define SPIS1WBDE (1 << 1) //SPI_SLV_WRBUF_DUMMY_EN
+#define SPIS1RBDE (1 << 0) //SPI_SLV_RDBUF_DUMMY_EN
+
+//SPI Slave2 (SPIxS2)
+#define SPIS2WBDL 0xFF //SPI_SLV_WRBUF_DUMMY_CYCLELEN
+#define SPIS2WBDL_S 24 //SPI_SLV_WRBUF_DUMMY_CYCLELEN_S
+#define SPIS2RBDL 0xFF //SPI_SLV_RDBUF_DUMMY_CYCLELEN
+#define SPIS2RBDL_S 16 //SPI_SLV_RDBUF_DUMMY_CYCLELEN_S
+#define SPIS2WSDL 0xFF //SPI_SLV_WRSTA_DUMMY_CYCLELEN
+#define SPIS2WSDL_S 8 //SPI_SLV_WRSTA_DUMMY_CYCLELEN_S
+#define SPIS2RSDL 0xFF //SPI_SLV_RDSTA_DUMMY_CYCLELEN
+#define SPIS2RSDL_S 0 //SPI_SLV_RDSTA_DUMMY_CYCLELEN_S
+
+//SPI Slave3 (SPIxS3)
+#define SPIS3WSCV 0xFF //SPI_SLV_WRSTA_CMD_VALUE
+#define SPIS3WSCV_S 24 //SPI_SLV_WRSTA_CMD_VALUE_S
+#define SPIS3RSCV 0xFF //SPI_SLV_RDSTA_CMD_VALUE
+#define SPIS3RSCV_S 16 //SPI_SLV_RDSTA_CMD_VALUE_S
+#define SPIS3WBCV 0xFF //SPI_SLV_WRBUF_CMD_VALUE
+#define SPIS3WBCV_S 8 //SPI_SLV_WRBUF_CMD_VALUE_S
+#define SPIS3RBCV 0xFF //SPI_SLV_RDBUF_CMD_VALUE
+#define SPIS3RBCV_S 0 //SPI_SLV_RDBUF_CMD_VALUE_S
+
+//SPI EXT0 (SPIxE0)
+#define SPIE0TPPEN (1 << 31) //SPI_T_PP_ENA
+#define SPIE0TPPS 0xF //SPI_T_PP_SHIFT
+#define SPIE0TPPS_S 16 //SPI_T_PP_SHIFT_S
+#define SPIE0TPPT 0xFFF //SPI_T_PP_TIME
+#define SPIE0TPPT_S 0 //SPI_T_PP_TIME_S
+
+//SPI EXT1 (SPIxE1)
+#define SPIE1TEREN (1 << 31) //SPI_T_ERASE_ENA
+#define SPIE1TERS 0xF //SPI_T_ERASE_SHIFT
+#define SPIE1TERS_S 16 //SPI_T_ERASE_SHIFT_S
+#define SPIE1TERT 0xFFF //SPI_T_ERASE_TIME
+#define SPIE1TERT_S 0 //SPI_T_ERASE_TIME_S
+
+//SPI EXT2 (SPIxE2)
+#define SPIE2ST 0x7 //SPI_ST
+#define SPIE2ST_S 0 //SPI_ST_S
+
+//SPI EXT3 (SPIxE3)
+#define SPIE2IHEN 0x3 //SPI_INT_HOLD_ENA
+#define SPIE2IHEN_S 0 //SPI_INT_HOLD_ENA_S
+
+#endif
diff --git a/hardware/esp8266com/esp8266/cores/esp8266/i2c.cpp b/hardware/esp8266com/esp8266/cores/esp8266/i2c.cpp
deleted file mode 100644
index e5510add4..000000000
--- a/hardware/esp8266com/esp8266/cores/esp8266/i2c.cpp
+++ /dev/null
@@ -1,223 +0,0 @@
-/*
- i2c.cpp - esp8266 i2c bit-banging library
-
- Copyright (c) 2014 Ivan Grokhotkov. All rights reserved.
- This file is part of the esp8266 core for Arduino environment.
-
- This library is free software; you can redistribute it and/or
- modify it under the terms of the GNU Lesser General Public
- License as published by the Free Software Foundation; either
- version 2.1 of the License, or (at your option) any later version.
-
- This library is distributed in the hope that it will be useful,
- but WITHOUT ANY WARRANTY; without even the implied warranty of
- MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
- Lesser General Public License for more details.
-
- You should have received a copy of the GNU Lesser General Public
- License along with this library; if not, write to the Free Software
- Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
- */
-
-#include
-#include "i2c.h"
-
-extern "C" {
-#include "ets_sys.h"
-#include "osapi.h"
-#include "gpio.h"
-#include "debug.h"
-}
-
-static uint8_t s_sda_pin = 0;
-static uint8_t s_scl_pin = 2;
-static uint32_t s_i2c_delay = 5;
-
-static inline void i2c_digital_write(int pin, int val) {
- uint32_t mask = 1 << pin;
- if(val)
- GPIO_REG_WRITE(GPIO_OUT_W1TS_ADDRESS, mask);
- else
- GPIO_REG_WRITE(GPIO_OUT_W1TC_ADDRESS, mask);
-}
-
-static inline void i2c_set(int sda, int scl) {
- i2c_digital_write(s_sda_pin, sda);
- i2c_digital_write(s_scl_pin, scl);
-}
-
-static inline void i2c_set_sda(int sda) {
- i2c_digital_write(s_sda_pin, sda);
-}
-
-static inline void i2c_set_scl(int scl) {
- i2c_digital_write(s_scl_pin, scl);
-}
-
-static inline uint8_t i2c_get_sda() {
- return GPIO_INPUT_GET(GPIO_ID_PIN(s_sda_pin));
-}
-
-static inline uint8_t i2c_get_scl() {
- return GPIO_INPUT_GET(GPIO_ID_PIN(s_scl_pin));
-}
-
-static inline void i2c_wait() {
- delayMicroseconds(s_i2c_delay);
-}
-
-void ICACHE_FLASH_ATTR i2c_freq(int freq_hz) {
- s_i2c_delay = 1000000 / freq_hz / 4 - 1;
- if(s_i2c_delay < 0)
- s_i2c_delay = 0;
-}
-
-void ICACHE_FLASH_ATTR i2c_init(int sda_pin, int scl_pin) {
- s_sda_pin = sda_pin;
- s_scl_pin = scl_pin;
- pinMode(ESP_PINS_OFFSET + sda_pin, OUTPUT_OPEN_DRAIN);
- pinMode(ESP_PINS_OFFSET + scl_pin, OUTPUT_OPEN_DRAIN);
- i2c_set(1, 1);
- i2c_wait();
-}
-
-void ICACHE_FLASH_ATTR i2c_release() {
- pinMode(ESP_PINS_OFFSET + s_sda_pin, INPUT);
- pinMode(ESP_PINS_OFFSET + s_scl_pin, INPUT);
-}
-
-void i2c_start() {
- i2c_set(1, 1);
- i2c_wait();
- i2c_set_sda(0);
- i2c_wait();
- i2c_wait();
- i2c_set_scl(0);
- i2c_wait();
-}
-
-void i2c_stop() {
- i2c_wait();
- i2c_set_scl(1);
- i2c_wait();
- i2c_set_sda(1);
- i2c_wait();
-}
-
-void i2c_set_ack(int ack) {
- i2c_set_sda(!ack);
- i2c_wait();
- i2c_set_scl(1);
- i2c_wait();
- i2c_set_scl(0);
- i2c_wait();
- i2c_set_sda(0);
- i2c_wait();
-}
-
-int i2c_get_ack() {
- i2c_set_scl(1);
- i2c_wait();
- int result = i2c_get_sda();
- i2c_set_scl(0);
- i2c_wait();
- i2c_set_sda(0);
- i2c_wait();
- return result;
-}
-
-uint8_t i2c_read(void) {
- uint8_t result = 0;
- for(int i = 7; i >= 0; --i) {
- i2c_wait();
- i2c_set_scl(1);
- i2c_wait();
- result <<= 1;
- result |= i2c_get_sda();
- i2c_set_scl(0);
- }
- return result;
-}
-
-void i2c_write(uint8_t val) {
- for(int i = 7; i >= 0; --i) {
- i2c_set_sda((val >> i) & 1);
- i2c_wait();
- i2c_set_scl(1);
- i2c_wait();
- i2c_set_scl(0);
- }
- i2c_wait();
- i2c_set_sda(1);
-}
-
-size_t ICACHE_FLASH_ATTR i2c_master_read_from(int address, uint8_t* data, size_t size, bool sendStop) {
- i2c_start();
- i2c_write(address << 1 | 1);
- int ack = i2c_get_ack();
- uint8_t* end = data + size;
- for(; data != end; ++data) {
- i2c_set_sda(1);
- pinMode(ESP_PINS_OFFSET + s_sda_pin, INPUT);
- *data = i2c_read();
- pinMode(ESP_PINS_OFFSET + s_sda_pin, OUTPUT_OPEN_DRAIN);
- if(data == end - 1)
- i2c_set_ack(0);
- else
- i2c_set_ack(1);
- }
- if(sendStop)
- i2c_stop();
- return size;
-}
-
-size_t ICACHE_FLASH_ATTR i2c_master_write_to(int address, const uint8_t* data, size_t size, bool sendStop) {
- i2c_start();
- i2c_write(address << 1);
- int ack = i2c_get_ack();
- const uint8_t* end = data + size;
- for(; data != end; ++data) {
- i2c_write(*data);
- ack = i2c_get_ack();
- }
- if(sendStop)
- i2c_stop();
- return size;
-}
-
-// some stubs for libraries that use private twi.h interface
-extern "C" {
-void twi_init(void) {
-}
-
-void twi_setAddress(uint8_t) {
-}
-
-uint8_t ICACHE_FLASH_ATTR twi_readFrom(uint8_t addr, uint8_t* data, uint8_t size, uint8_t sendStop) {
- return i2c_master_read_from(addr, data, size, sendStop);
-}
-
-uint8_t ICACHE_FLASH_ATTR twi_writeTo(uint8_t addr, uint8_t* data, uint8_t size, uint8_t wait, uint8_t sendStop) {
- return i2c_master_write_to(addr, data, size, sendStop);
-}
-
-uint8_t twi_transmit(const uint8_t* data, uint8_t length) {
- //TODO implement twi_transmit
- return 0;
-}
-
-void twi_attachSlaveRxEvent(void (*)(uint8_t*, int)) {
-}
-void twi_attachSlaveTxEvent(void (*)(void)) {
-}
-void twi_reply(uint8_t) {
-}
-void twi_stop(void) {
- i2c_stop();
-}
-
-void twi_releaseBus(void) {
- i2c_set(1, 1);
-}
-}
-
diff --git a/hardware/esp8266com/esp8266/cores/esp8266/i2c.h b/hardware/esp8266com/esp8266/cores/esp8266/i2c.h
deleted file mode 100644
index 8a2d30548..000000000
--- a/hardware/esp8266com/esp8266/cores/esp8266/i2c.h
+++ /dev/null
@@ -1,47 +0,0 @@
-/*
- i2c.h - esp8266 i2c bit-banging library
-
- Copyright (c) 2014 Ivan Grokhotkov. All rights reserved.
- This file is part of the esp8266 core for Arduino environment.
-
- This library is free software; you can redistribute it and/or
- modify it under the terms of the GNU Lesser General Public
- License as published by the Free Software Foundation; either
- version 2.1 of the License, or (at your option) any later version.
-
- This library is distributed in the hope that it will be useful,
- but WITHOUT ANY WARRANTY; without even the implied warranty of
- MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
- Lesser General Public License for more details.
-
- You should have received a copy of the GNU Lesser General Public
- License along with this library; if not, write to the Free Software
- Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
- */
-
-#ifndef I2C_H
-#define I2C_H
-
-#include
-
-void i2c_init(int sda_pin, int scl_pin);
-void i2c_freq(int freq_hz);
-void i2c_release();
-void i2c_start();
-void i2c_stop();
-void i2c_set_ack(int ack);
-int i2c_get_ack();
-uint8_t i2c_read(void);
-void i2c_write(uint8_t val);
-
-size_t i2c_master_read_from(int address, uint8_t* data, size_t size, bool sendStop);
-size_t i2c_master_write_to(int address, const uint8_t* data, size_t size, bool sendStop);
-
-// todo: implement i2c slave functions
-//
-// void i2c_slave_setAddress(uint8_t);
-// int i2c_slave_transmit(const uint8_t* data, size_t size);
-// void i2c_slave_attach_rx_callback( void (*)(uint8_t*, int) );
-// void i2c_slave_attach_tx_callback( void (*)(void) );
-
-#endif//I2C_H
diff --git a/hardware/esp8266com/esp8266/cores/esp8266/si2c.c b/hardware/esp8266com/esp8266/cores/esp8266/si2c.c
new file mode 100644
index 000000000..f9bdda52c
--- /dev/null
+++ b/hardware/esp8266com/esp8266/cores/esp8266/si2c.c
@@ -0,0 +1,172 @@
+/*
+ si2c.c - Software I2C library for esp8266
+
+ Copyright (c) 2015 Hristo Gochkov. All rights reserved.
+ This file is part of the esp8266 core for Arduino environment.
+
+ This library is free software; you can redistribute it and/or
+ modify it under the terms of the GNU Lesser General Public
+ License as published by the Free Software Foundation; either
+ version 2.1 of the License, or (at your option) any later version.
+
+ This library is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with this library; if not, write to the Free Software
+ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+*/
+#include "si2c.h"
+#include "pins_arduino.h"
+#include "wiring_private.h"
+
+uint8_t twi_dcount = 18;
+static uint8_t twi_sda, twi_scl;
+
+#define SDA_LOW() (GPES = (1 << twi_sda)) //Enable SDA (becomes output and since GPO is 0 for the pin, it will pull the line low)
+#define SDA_HIGH() (GPEC = (1 << twi_sda)) //Disable SDA (becomes input and since it has pullup it will go high)
+#define SDA_READ() ((GPI & (1 << twi_sda)) != 0)
+#define SCL_LOW() (GPES = (1 << twi_scl))
+#define SCL_HIGH() (GPEC = (1 << twi_scl))
+#define SCL_READ() ((GPI & (1 << twi_scl)) != 0)
+
+#ifndef FCPU80
+#define FCPU80 80000000L
+#endif
+
+#if F_CPU == FCPU80
+#define TWI_CLOCK_STRETCH 200
+#else
+#define TWI_CLOCK_STRETCH 400
+#endif
+
+void twi_setClock(uint32_t freq){
+#if F_CPU == FCPU80
+ if(freq <= 100000) twi_dcount = 18;//about 100KHz
+ else if(freq <= 200000) twi_dcount = 8;//about 200KHz
+ else if(freq <= 300000) twi_dcount = 4;//about 300KHz
+ else if(freq <= 400000) twi_dcount = 2;//about 370KHz
+ else twi_dcount = 1;//about 450KHz
+#else
+ if(freq <= 100000) twi_dcount = 32;//about 100KHz
+ else if(freq <= 200000) twi_dcount = 16;//about 200KHz
+ else if(freq <= 300000) twi_dcount = 8;//about 300KHz
+ else if(freq <= 400000) twi_dcount = 4;//about 370KHz
+ else twi_dcount = 2;//about 450KHz
+#endif
+}
+
+void twi_init(uint8_t sda, uint8_t scl){
+ twi_sda = sda;
+ twi_scl = scl;
+ pinMode(twi_sda, INPUT_PULLUP);
+ pinMode(twi_scl, INPUT_PULLUP);
+ twi_setClock(100000);
+}
+
+void twi_stop(void){
+ pinMode(twi_sda, INPUT);
+ pinMode(twi_scl, INPUT);
+}
+
+static void twi_delay(uint8_t v){
+ uint8_t i;
+ uint32_t reg;
+ for(i=0;i
#include
#include
+#include
-const char* ssid = "...............";
-const char* password = "...............";
-
+const char* ssid = "........";
+const char* password = "........";
+MDNSResponder mdns;
ESP8266WebServer server(80);
-
-const int led = 13;
-
-void handle_root() {
- digitalWrite(led, 1);
+
+void handleRoot() {
server.send(200, "text/plain", "hello from esp8266!");
- delay(100);
- digitalWrite(led, 0);
+}
+
+void handleNotFound(){
+ String message = "URI: ";
+ message += server.uri();
+ message += "\nMethod: ";
+ message += (server.method() == HTTP_GET)?"GET":"POST";
+ message += "\nNot Found!\n\n";
+ message += "\nArguments: ";
+ message += server.args();
+ message += "\n";
+ for (uint8_t i=0; inext;
- delete handler;
- handler = next;
- }
+ if (!_firstHandler)
+ return;
+ RequestHandler* handler = _firstHandler;
+ while (handler) {
+ RequestHandler* next = handler->next;
+ delete handler;
+ handler = next;
+ }
}
void ESP8266WebServer::begin() {
- _server.begin();
+ _server.begin();
}
void ESP8266WebServer::on(const char* uri, ESP8266WebServer::THandlerFunction handler)
{
- on(uri, HTTP_ANY, handler);
+ on(uri, HTTP_ANY, handler);
}
void ESP8266WebServer::on(const char* uri, HTTPMethod method, ESP8266WebServer::THandlerFunction fn)
{
- RequestHandler* handler = new RequestHandler(fn, uri, method);
- if (!_lastHandler) {
- _firstHandler = handler;
- _lastHandler = handler;
- }
- else {
- _lastHandler->next = handler;
- _lastHandler = handler;
- }
+ RequestHandler* handler = new RequestHandler(fn, uri, method);
+ if (!_lastHandler) {
+ _firstHandler = handler;
+ _lastHandler = handler;
+ }
+ else {
+ _lastHandler->next = handler;
+ _lastHandler = handler;
+ }
}
void ESP8266WebServer::handleClient()
{
- WiFiClient client = _server.available();
- if (!client) {
- return;
- }
+ WiFiClient client = _server.available();
+ if (!client) {
+ return;
+ }
#ifdef DEBUG
- Serial.println("New client");
+ Serial.println("New client");
#endif
- // Wait for data from client to become available
- while(client.connected() && !client.available()){
- delay(1);
- }
+ // Wait for data from client to become available
+ while(client.connected() && !client.available()){
+ delay(1);
+ }
- // Read the first line of HTTP request
- String req = client.readStringUntil('\r');
- client.readStringUntil('\n');
+ // Read the first line of HTTP request
+ String req = client.readStringUntil('\r');
+ client.readStringUntil('\n');
- HTTPMethod method = HTTP_GET;
- if (req.startsWith("POST")) {
- method = HTTP_POST;
- }
+ HTTPMethod method = HTTP_GET;
+ if (req.startsWith("POST")) {
+ method = HTTP_POST;
+ }
-
- // First line of HTTP request looks like "GET /path HTTP/1.1"
- // Retrieve the "/path" part by finding the spaces
- int addr_start = req.indexOf(' ');
- int addr_end = req.indexOf(' ', addr_start + 1);
- if (addr_start == -1 || addr_end == -1) {
+ // First line of HTTP request looks like "GET /path HTTP/1.1"
+ // Retrieve the "/path" part by finding the spaces
+ int addr_start = req.indexOf(' ');
+ int addr_end = req.indexOf(' ', addr_start + 1);
+ if (addr_start == -1 || addr_end == -1) {
#ifdef DEBUG
- Serial.print("Invalid request: ");
- Serial.println(req);
+ Serial.print("Invalid request: ");
+ Serial.println(req);
#endif
- return;
- }
+ return;
+ }
- req = req.substring(addr_start + 1, addr_end);
+ req = req.substring(addr_start + 1, addr_end);
- String formData;
- if (method == HTTP_POST)
- {
- int contentLength = -1;
- int headerCount = 0;
- while(headerCount < 1024) { // there shouldn't be that much really
- String line = client.readStringUntil('\r');
- client.readStringUntil('\n');
+ String formData;
+ if (method == HTTP_POST) {
+ int contentLength = -1;
+ int headerCount = 0;
+ while(headerCount < 1024) { // there shouldn't be that much really
+ String line = client.readStringUntil('\r');
+ client.readStringUntil('\n');
- if (line.length() > 0) { // this is a header
- ++headerCount;
- if (contentLength < 0 && line.startsWith("Content-Length")) {
- // get content length from the header
- int valuePos = line.indexOf(' ', 14);
- if (valuePos > 0) {
- String valueStr = line.substring(valuePos+1);
- contentLength = valueStr.toInt();
+ if (line.length() > 0) { // this is a header
+ ++headerCount;
+ if (contentLength < 0 && line.startsWith("Content-Length")) {
+ // get content length from the header
+ int valuePos = line.indexOf(' ', 14);
+ if (valuePos > 0) {
+ String valueStr = line.substring(valuePos+1);
+ contentLength = valueStr.toInt();
#ifdef DEBUG
- Serial.print("Content-Length: ");
- Serial.println(contentLength);
+ Serial.print("Content-Length: ");
+ Serial.println(contentLength);
#endif
- }
- }
- }
- else {
- break;
- }
- }
+ }
+ }
+ }
+ else {
+ break;
+ }
+ }
#ifdef DEBUG
- Serial.print("headerCount=");
- Serial.println(headerCount);
+ Serial.print("headerCount=");
+ Serial.println(headerCount);
#endif
- if (contentLength >= 0) {
- formData = "";
- int n = 0; // timeout counter
- while (formData.length() < contentLength && ++n < 3)
- formData += client.readString();
- }
- else {
- formData = client.readStringUntil('\r'); // will return after timing out once
- }
- // read form data
- // formData =
- }
- else if (method == HTTP_GET)
- {
- int args_start = req.indexOf('?');
- if (args_start != -1)
- {
- formData = req.substring(args_start + 1);
- req = req.substring(0, args_start);
- }
- }
+ if (contentLength >= 0) {
+ formData = "";
+ int n = 0; // timeout counter
+ while (formData.length() < contentLength && ++n < 3)
+ formData += client.readString();
+ }
+ else {
+ formData = client.readStringUntil('\r'); // will return after timing out once
+ }
+ }
+ else if (method == HTTP_GET) {
+ int args_start = req.indexOf('?');
+ if (args_start != -1) {
+ formData = req.substring(args_start + 1);
+ req = req.substring(0, args_start);
+ }
+ }
- client.flush();
+ client.flush();
#ifdef DEBUG
- Serial.print("Request: ");
- Serial.println(req);
- Serial.print("Args: ");
- Serial.println(formData);
+ Serial.print("Request: ");
+ Serial.println(req);
+ Serial.print("Args: ");
+ Serial.println(formData);
#endif
- _parseArguments(formData);
- _handleRequest(client, req, method);
+ _parseArguments(formData);
+ _handleRequest(client, req, method);
}
void ESP8266WebServer::send(int code, const char* content_type, String content) {
- String response = "HTTP/1.1 ";
- response += String(code);
- response += " ";
- if (code == 200)
- response += "OK";
- else if (code == 404)
- response += "Not found";
- response += "\r\n";
- if (!content_type)
- content_type = "text/html";
- response += "Content-Type: ";
- response += content_type;
- response += "\r\n\r\n";
- response += content;
- _currentClient.print(response);
+ String response = "HTTP/1.1 ";
+ response += String(code);
+ response += " ";
+ response += _responseCodeToString(code);
+ response += "\r\n";
+
+ if (!content_type)
+ content_type = "text/html";
+ _appendHeader(response, "Content-Type", content_type);
+
+ response += "\r\n";
+ response += content;
+ _currentClient.print(response);
}
-String ESP8266WebServer::arg(const char* name)
-{
- for (int i = 0; i < _currentArgCount; ++i) {
- if (_currentArgs[i].key == name)
- return _currentArgs[i].value;
- }
- return String();
+String ESP8266WebServer::arg(const char* name) {
+ for (int i = 0; i < _currentArgCount; ++i) {
+ if (_currentArgs[i].key == name)
+ return _currentArgs[i].value;
+ }
+ return String();
}
+String ESP8266WebServer::arg(int i) {
+ if (i < _currentArgCount)
+ return _currentArgs[i].value;
+ return String();
+}
-void ESP8266WebServer::_parseArguments(String data)
-{
- if (_currentArgs)
- delete[] _currentArgs;
- _currentArgs = 0;
- if (data.length() == 0) {
- _currentArgCount = 0;
- return;
- }
- _currentArgCount = 1;
+String ESP8266WebServer::argName(int i) {
+ if (i < _currentArgCount)
+ return _currentArgs[i].key;
+ return String();
+}
- for (int i = 0; i < data.length(); ) {
- i = data.indexOf('&', i);
- if (i == -1)
- break;
- ++i;
- ++_currentArgCount;
- }
+int ESP8266WebServer::args() {
+ return _currentArgCount;
+}
+
+bool ESP8266WebServer::hasArg(const char* name) {
+ for (int i = 0; i < _currentArgCount; ++i) {
+ if (_currentArgs[i].key == name)
+ return true;
+ }
+ return false;
+}
+
+void ESP8266WebServer::_parseArguments(String data) {
+ if (_currentArgs)
+ delete[] _currentArgs;
+ _currentArgs = 0;
+ if (data.length() == 0) {
+ _currentArgCount = 0;
+ return;
+ }
+ _currentArgCount = 1;
+
+ for (int i = 0; i < data.length(); ) {
+ i = data.indexOf('&', i);
+ if (i == -1)
+ break;
+ ++i;
+ ++_currentArgCount;
+ }
#ifdef DEBUG
- Serial.print("args count: ");
- Serial.println(_currentArgCount);
+ Serial.print("args count: ");
+ Serial.println(_currentArgCount);
#endif
- _currentArgs = new RequestArgument[_currentArgCount];
- int pos = 0;
- int iarg;
- for (iarg = 0; iarg < _currentArgCount;) {
- int equal_sign_index = data.indexOf('=', pos);
- int next_arg_index = data.indexOf('&', pos);
+ _currentArgs = new RequestArgument[_currentArgCount];
+ int pos = 0;
+ int iarg;
+ for (iarg = 0; iarg < _currentArgCount;) {
+ int equal_sign_index = data.indexOf('=', pos);
+ int next_arg_index = data.indexOf('&', pos);
#ifdef DEBUG
- Serial.print("pos ");
- Serial.print(pos);
- Serial.print("=@ ");
- Serial.print(equal_sign_index);
- Serial.print(" &@ ");
- Serial.println(next_arg_index);
+ Serial.print("pos ");
+ Serial.print(pos);
+ Serial.print("=@ ");
+ Serial.print(equal_sign_index);
+ Serial.print(" &@ ");
+ Serial.println(next_arg_index);
#endif
- if ((equal_sign_index == -1) || ((equal_sign_index > next_arg_index) && (next_arg_index != -1))) {
+ if ((equal_sign_index == -1) || ((equal_sign_index > next_arg_index) && (next_arg_index != -1))) {
#ifdef DEBUG
- Serial.print("arg missing value: ");
- Serial.println(iarg);
+ Serial.print("arg missing value: ");
+ Serial.println(iarg);
#endif
- if (next_arg_index == -1)
- break;
- pos = next_arg_index + 1;
- continue;
- }
- RequestArgument& arg = _currentArgs[iarg];
- arg.key = data.substring(pos, equal_sign_index);
- arg.value = data.substring(equal_sign_index + 1, next_arg_index);
+ if (next_arg_index == -1)
+ break;
+ pos = next_arg_index + 1;
+ continue;
+ }
+ RequestArgument& arg = _currentArgs[iarg];
+ arg.key = data.substring(pos, equal_sign_index);
+ arg.value = data.substring(equal_sign_index + 1, next_arg_index);
#ifdef DEBUG
- Serial.print("arg ");
- Serial.print(iarg);
- Serial.print(" key: ");
- Serial.print(arg.key);
- Serial.print(" value: ");
- Serial.println(arg.value);
+ Serial.print("arg ");
+ Serial.print(iarg);
+ Serial.print(" key: ");
+ Serial.print(arg.key);
+ Serial.print(" value: ");
+ Serial.println(arg.value);
#endif
- ++iarg;
- if (next_arg_index == -1)
- break;
- pos = next_arg_index + 1;
- }
- _currentArgCount = iarg;
+ ++iarg;
+ if (next_arg_index == -1)
+ break;
+ pos = next_arg_index + 1;
+ }
+ _currentArgCount = iarg;
#ifdef DEBUG
- Serial.print("args count: ");
- Serial.println(_currentArgCount);
+ Serial.print("args count: ");
+ Serial.println(_currentArgCount);
#endif
}
+void ESP8266WebServer::onNotFound(THandlerFunction fn) {
+ _notFoundHandler = fn;
+}
void ESP8266WebServer::_handleRequest(WiFiClient& client, String uri, HTTPMethod method) {
- _currentClient = client;
- _currentUri = uri;
- _currentMethod = method;
+ _currentClient = client;
+ _currentUri = uri;
+ _currentMethod = method;
- RequestHandler* handler;
- for (handler = _firstHandler; handler; handler = handler->next)
- {
- if (handler->method != HTTP_ANY && handler->method != method)
- continue;
+ RequestHandler* handler;
+ for (handler = _firstHandler; handler; handler = handler->next)
+ {
+ if (handler->method != HTTP_ANY && handler->method != method)
+ continue;
- if (handler->uri != uri)
- continue;
+ if (handler->uri != uri)
+ continue;
- handler->fn();
- break;
- }
+ handler->fn();
+ break;
+ }
- if (!handler)
- {
+ if (!handler){
#ifdef DEBUG
- Serial.println("request handler not found");
+ Serial.println("request handler not found");
#endif
- send(404, "text/plain", String("Not found: ") + uri);
- }
- _currentClient = WiFiClient();
- _currentUri = String();
-
+ if(_notFoundHandler) {
+ _notFoundHandler();
+ }
+ else {
+ send(404, "text/plain", String("Not found: ") + uri);
+ }
+ }
+
+ _currentClient = WiFiClient();
+ _currentUri = String();
+
+}
+
+const char* ESP8266WebServer::_responseCodeToString(int code) {
+ switch (code) {
+ case 200: return "OK";
+ case 404: return "Not found";
+ default: return "";
+ }
+}
+
+void ESP8266WebServer::_appendHeader(String& response, const char* name, const char* value) {
+ response += name;
+ response += ": ";
+ response += value;
+ response += "\r\n";
}
diff --git a/hardware/esp8266com/esp8266/libraries/ESP8266WebServer/src/ESP8266WebServer.h b/hardware/esp8266com/esp8266/libraries/ESP8266WebServer/src/ESP8266WebServer.h
index 6d9c5ffb5..3b31eab5a 100644
--- a/hardware/esp8266com/esp8266/libraries/ESP8266WebServer/src/ESP8266WebServer.h
+++ b/hardware/esp8266com/esp8266/libraries/ESP8266WebServer/src/ESP8266WebServer.h
@@ -32,50 +32,57 @@ class ESP8266WebServer
{
public:
- ESP8266WebServer(int port = 80);
- ~ESP8266WebServer();
+ ESP8266WebServer(int port = 80);
+ ~ESP8266WebServer();
- void begin();
- void handleClient();
+ void begin();
+ void handleClient();
- typedef std::function THandlerFunction;
- void on(const char* uri, THandlerFunction handler);
- void on(const char* uri, HTTPMethod method, THandlerFunction fn);
+ typedef std::function THandlerFunction;
+ void on(const char* uri, THandlerFunction handler);
+ void on(const char* uri, HTTPMethod method, THandlerFunction fn);
+ void onNotFound(THandlerFunction fn); //called when handler is not assigned
- String uri() { return _currentUri; }
- HTTPMethod method() { return _currentMethod; }
- WiFiClient client() { return _currentClient; }
-
- // send response to the client
- // code - HTTP response code, can be 200 or 404
- // content_type - HTTP content type, like "text/plain" or "image/png"
- // content - actual content body
- void send(int code, const char* content_type = NULL, String content = String(""));
-
- // get request argument value
- String arg(const char* name);
+ String uri() { return _currentUri; }
+ HTTPMethod method() { return _currentMethod; }
+ WiFiClient client() { return _currentClient; }
+
+ String arg(const char* name); // get request argument value by name
+ String arg(int i); // get request argument value by number
+ String argName(int i); // get request argument name by number
+ int args(); // get arguments count
+ bool hasArg(const char* name); // check if argument exists
+
+ // send response to the client
+ // code - HTTP response code, can be 200 or 404
+ // content_type - HTTP content type, like "text/plain" or "image/png"
+ // content - actual content body
+ void send(int code, const char* content_type = NULL, String content = String(""));
protected:
- void _handleRequest(WiFiClient& client, String uri, HTTPMethod method);
- void _parseArguments(String data);
+ void _handleRequest(WiFiClient& client, String uri, HTTPMethod method);
+ void _parseArguments(String data);
+ static const char* _responseCodeToString(int code);
+ static void _appendHeader(String& response, const char* name, const char* value);
+
+ struct RequestHandler;
+ struct RequestArgument {
+ String key;
+ String value;
+ };
- struct RequestHandler;
- struct RequestArgument {
- String key;
- String value;
- };
+ WiFiServer _server;
- WiFiServer _server;
+ WiFiClient _currentClient;
+ HTTPMethod _currentMethod;
+ String _currentUri;
- WiFiClient _currentClient;
- HTTPMethod _currentMethod;
- String _currentUri;
+ size_t _currentArgCount;
+ RequestArgument* _currentArgs;
- size_t _currentArgCount;
- RequestArgument* _currentArgs;
-
- RequestHandler* _firstHandler;
- RequestHandler* _lastHandler;
+ RequestHandler* _firstHandler;
+ RequestHandler* _lastHandler;
+ THandlerFunction _notFoundHandler;
};
diff --git a/hardware/esp8266com/esp8266/libraries/ESP8266WiFi/src/ESP8266WiFi.cpp b/hardware/esp8266com/esp8266/libraries/ESP8266WiFi/src/ESP8266WiFi.cpp
index cb97c6f9a..caf63982c 100644
--- a/hardware/esp8266com/esp8266/libraries/ESP8266WiFi/src/ESP8266WiFi.cpp
+++ b/hardware/esp8266com/esp8266/libraries/ESP8266WiFi/src/ESP8266WiFi.cpp
@@ -49,6 +49,7 @@ void ESP8266WiFiClass::mode(WiFiMode m)
ETS_UART_INTR_ENABLE();
}
+
int ESP8266WiFiClass::begin(const char* ssid)
{
return begin(ssid, 0);
@@ -57,7 +58,7 @@ int ESP8266WiFiClass::begin(const char* ssid)
int ESP8266WiFiClass::begin(const char* ssid, const char *passphrase)
{
- if (wifi_get_opmode() == WIFI_AP)
+ if ((wifi_get_opmode() & 1) == 0)//1 and 3 have STA enabled
{
// turn on AP+STA mode
mode(WIFI_AP_STA);
@@ -111,7 +112,7 @@ void ESP8266WiFiClass::softAP(const char* ssid)
void ESP8266WiFiClass::softAP(const char* ssid, const char* passphrase, int channel)
{
- if (wifi_get_opmode() == WIFI_STA)
+ if (wifi_get_opmode() < WIFI_AP)//will be OFF or STA
{
// turn on AP+STA mode
mode(WIFI_AP_STA);
@@ -260,7 +261,7 @@ void ESP8266WiFiClass::_scanDone(void* result, int status)
int8_t ESP8266WiFiClass::scanNetworks()
{
- if (wifi_get_opmode() == WIFI_AP)
+ if ((wifi_get_opmode() & 1) == 0)//1 and 3 have STA enabled
{
mode(WIFI_AP_STA);
}
@@ -381,7 +382,10 @@ void ESP8266WiFiClass::beginSmartConfig()
if (_smartConfigStarted)
return;
- WiFi.mode(WIFI_STA);
+ if ((wifi_get_opmode() & 1) == 0)//1 and 3 have STA enabled
+ {
+ mode(WIFI_AP_STA);
+ }
_smartConfigStarted = true;
diff --git a/hardware/esp8266com/esp8266/libraries/ESP8266WiFi/src/ESP8266WiFi.h b/hardware/esp8266com/esp8266/libraries/ESP8266WiFi/src/ESP8266WiFi.h
index 1a28b0c12..c98f32b8b 100644
--- a/hardware/esp8266com/esp8266/libraries/ESP8266WiFi/src/ESP8266WiFi.h
+++ b/hardware/esp8266com/esp8266/libraries/ESP8266WiFi/src/ESP8266WiFi.h
@@ -32,7 +32,7 @@ extern "C" {
#include "WiFiClient.h"
#include "WiFiServer.h"
-enum WiFiMode { WIFI_STA = 1, WIFI_AP = 2, WIFI_AP_STA = 3 };
+enum WiFiMode { WIFI_OFF = 0, WIFI_STA = 1, WIFI_AP = 2, WIFI_AP_STA = 3 };
class ESP8266WiFiClass
{
@@ -41,6 +41,7 @@ public:
ESP8266WiFiClass();
void mode(WiFiMode);
+
/* Start Wifi connection for OPEN networks
*
diff --git a/hardware/esp8266com/esp8266/libraries/SPI/HSPI.cpp b/hardware/esp8266com/esp8266/libraries/SPI/HSPI.cpp
deleted file mode 100644
index f24e64233..000000000
--- a/hardware/esp8266com/esp8266/libraries/SPI/HSPI.cpp
+++ /dev/null
@@ -1,94 +0,0 @@
-#include "include/HSPI.h"
-#include "include/spi_register.h"
-
-#define __min(a,b) ((a > b) ? (b):(a))
-
-void HSPI::begin()
-{
- spi_fifo = (uint32_t*)SPI_FLASH_C0(hspi_port);
- //bit9 of PERIPHS_IO_MUX should be cleared when HSPI clock doesn't equal CPU clock
- WRITE_PERI_REG(PERIPHS_IO_MUX, 0x105);
- PIN_FUNC_SELECT(PERIPHS_IO_MUX_MTDI_U, FUNC_HSPIQ_MISO); // gpio12
- PIN_FUNC_SELECT(PERIPHS_IO_MUX_MTCK_U, FUNC_HSPID_MOSI); // gpio13
- PIN_FUNC_SELECT(PERIPHS_IO_MUX_MTMS_U, FUNC_HSPI_CLK); // gpio14
-
- // SPI clock=CPU clock/8
- WRITE_PERI_REG(SPI_FLASH_CLOCK(hspi_port),
- ((1&SPI_CLKDIV_PRE)<
- * Copyright (c) 2014 by Paul Stoffregen (Transaction API)
- * Copyright (c) 2014 by Matthijs Kooijman (SPISettings AVR)
- * SPI Master library for arduino.
- *
- * This file is free software; you can redistribute it and/or modify
- * it under the terms of either the GNU General Public License version 2
- * or the GNU Lesser General Public License version 2.1, both as
- * published by the Free Software Foundation.
- */
+/*
+ SPI.cpp - SPI library for esp8266
+
+ Copyright (c) 2015 Hristo Gochkov. All rights reserved.
+ This file is part of the esp8266 core for Arduino environment.
+
+ This library is free software; you can redistribute it and/or
+ modify it under the terms of the GNU Lesser General Public
+ License as published by the Free Software Foundation; either
+ version 2.1 of the License, or (at your option) any later version.
+
+ This library is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with this library; if not, write to the Free Software
+ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+*/
#include "SPI.h"
-#include "include/HSPI.h"
SPIClass SPI;
+SPIClass::SPIClass(){}
-SPIClass::SPIClass()
-: _impl(0)
-{
+void SPIClass::begin(){
+ pinMode(SCK, SPECIAL);
+ pinMode(MISO, SPECIAL);
+ pinMode(MOSI, SPECIAL);
+
+ GPMUX = 0x105;
+ SPI1C = 0;
+ SPI1CLK = SPI_CLOCK_DIV16;//1MHz
+ SPI1U = SPIUMOSI | SPIUDUPLEX | SPIUSSE;
+ SPI1U1 = (7 << SPILMOSI) | (7 << SPILMISO);
+ SPI1C1 = 0;
}
-void SPIClass::begin()
-{
- if (_impl)
- end();
- _impl = new HSPI;
- _impl->begin();
+void SPIClass::end() {
+ pinMode(SCK, INPUT);
+ pinMode(MISO, INPUT);
+ pinMode(MOSI, INPUT);
}
-void SPIClass::end()
-{
- if (!_impl)
- return;
- _impl->end();
- delete _impl;
- _impl = 0;
+void SPIClass::beginTransaction(SPISettings settings) {
+ setClockDivider(settings._clock);
+ setBitOrder(settings._bitOrder);
+ setDataMode(settings._dataMode);
}
-void SPIClass::beginTransaction(SPISettings settings)
-{
- if (!_impl)
- return;
- _impl->setBitOrder(settings._bitOrder);
- _impl->setDataMode(settings._dataMode);
- _impl->setClockDivider(settings._clock);
+void SPIClass::endTransaction() {}
+
+void SPIClass::setDataMode(uint8_t dataMode) {
+
}
-uint8_t SPIClass::transfer(uint8_t data)
-{
- if (!_impl)
- return 0;
- return _impl->transfer(data);
+void SPIClass::setBitOrder(uint8_t bitOrder) {
+ if (bitOrder == MSBFIRST){
+ SPI1C &= ~(SPICWBO | SPICRBO);
+ } else {
+ SPI1C |= (SPICWBO | SPICRBO);
+ }
}
-uint16_t SPIClass::transfer16(uint16_t data)
-{
- if (!_impl)
- return 0;
- return _impl->transfer16(data);
+void SPIClass::setClockDivider(uint32_t clockDiv) {
+ SPI1CLK = clockDiv;
}
-void SPIClass::transfer(void *buf, size_t count)
-{
- if (!_impl)
- return;
- _impl->transfer(buf, count);
-}
-
-void SPIClass::setBitOrder(uint8_t bitOrder)
-{
- if (!_impl)
- return;
- _impl->setBitOrder(bitOrder);
-}
-
-void SPIClass::setDataMode(uint8_t dataMode)
-{
- if (!_impl)
- return;
- _impl->setDataMode(dataMode);
-}
-
-void SPIClass::setClockDivider(uint8_t clockDiv)
-{
- if (!_impl)
- return;
- _impl->setClockDivider(clockDiv);
+uint8_t SPIClass::transfer(uint8_t data) {
+ while(SPI1CMD & SPIBUSY);
+ SPI1W0 = data;
+ SPI1CMD |= SPIBUSY;
+ while(SPI1CMD & SPIBUSY);
+ return (uint8_t)(SPI1W0 & 0xff);
}
diff --git a/hardware/esp8266com/esp8266/libraries/SPI/SPI.h b/hardware/esp8266com/esp8266/libraries/SPI/SPI.h
index 5113455df..d62d96df3 100644
--- a/hardware/esp8266com/esp8266/libraries/SPI/SPI.h
+++ b/hardware/esp8266com/esp8266/libraries/SPI/SPI.h
@@ -1,62 +1,86 @@
-/*
- * Copyright (c) 2010 by Cristian Maglie
- * Copyright (c) 2014 by Paul Stoffregen (Transaction API)
- * Copyright (c) 2014 by Matthijs Kooijman (SPISettings AVR)
- * SPI Master library for arduino.
- *
- * This file is free software; you can redistribute it and/or modify
- * it under the terms of either the GNU General Public License version 2
- * or the GNU Lesser General Public License version 2.1, both as
- * published by the Free Software Foundation.
- */
+/*
+ SPI.h - SPI library for esp8266
+ Copyright (c) 2015 Hristo Gochkov. All rights reserved.
+ This file is part of the esp8266 core for Arduino environment.
+
+ This library is free software; you can redistribute it and/or
+ modify it under the terms of the GNU Lesser General Public
+ License as published by the Free Software Foundation; either
+ version 2.1 of the License, or (at your option) any later version.
+
+ This library is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with this library; if not, write to the Free Software
+ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+*/
#ifndef _SPI_H_INCLUDED
#define _SPI_H_INCLUDED
#include
#include
-#include "include/SPIdef.h"
+#define FCPU80 80000000L
+#if F_CPU == FCPU80
+#define SPI_CLOCK_DIV80M 0x80000000 //80 MHz
+#define SPI_CLOCK_DIV40M 0x00001001 //40 MHz
+#define SPI_CLOCK_DIV20M 0x00041001 //20 MHz
+#define SPI_CLOCK_DIV16M 0x000fffc0 //16 MHz
+#define SPI_CLOCK_DIV10M 0x000c1001 //10 MHz
+#define SPI_CLOCK_DIV2 0x00101001 //8 MHz
+#define SPI_CLOCK_DIV5M 0x001c1001 //5 MHz
+#define SPI_CLOCK_DIV4 0x00241001 //4 MHz
+#define SPI_CLOCK_DIV8 0x004c1001 //2 MHz
+#define SPI_CLOCK_DIV16 0x009c1001 //1 MHz
+#define SPI_CLOCK_DIV32 0x013c1001 //500 KHz
+#define SPI_CLOCK_DIV64 0x027c1001 //250 KHz
+#define SPI_CLOCK_DIV128 0x04fc1001 //125 KHz
+#else
+#define SPI_CLOCK_DIV160M 0x80000000 //160 MHz
+#define SPI_CLOCK_DIV80M 0x00001001 //80 MHz
+#define SPI_CLOCK_DIV40M 0x00041001 //40 MHz
+#define SPI_CLOCK_DIV32M 0x000fffc0 //32 MHz
+#define SPI_CLOCK_DIV20M 0x000c1001 //20 MHz
+#define SPI_CLOCK_DIV16M 0x00101001 //16 MHz
+#define SPI_CLOCK_DIV10M 0x001c1001 //10 MHz
+#define SPI_CLOCK_DIV2 0x00241001 //8 MHz
+#define SPI_CLOCK_DIV4 0x004c1001 //4 MHz
+#define SPI_CLOCK_DIV8 0x009c1001 //2 MHz
+#define SPI_CLOCK_DIV16 0x013c1001 //1 MHz
+#define SPI_CLOCK_DIV32 0x027c1001 //500 KHz
+#define SPI_CLOCK_DIV64 0x04fc1001 //250 KHz
+#endif
-struct SPISettings
-{
- SPISettings(uint32_t clock, uint8_t bitOrder, uint8_t dataMode)
- : _clock(clock)
- , _bitOrder(bitOrder)
- , _dataMode(dataMode)
- {
- }
+const uint8_t SPI_MODE0 = 0x00;
+const uint8_t SPI_MODE1 = 0x04;
+const uint8_t SPI_MODE2 = 0x08;
+const uint8_t SPI_MODE3 = 0x0C;
+class SPISettings {
+public:
+ SPISettings() :_clock(SPI_CLOCK_DIV16), _bitOrder(LSBFIRST), _dataMode(SPI_MODE0){}
+ SPISettings(uint32_t clock, uint8_t bitOrder, uint8_t dataMode) :_clock(clock), _bitOrder(bitOrder), _dataMode(dataMode){}
uint32_t _clock;
uint8_t _bitOrder;
uint8_t _dataMode;
};
-class SPIImpl;
-
-class SPIClass
-{
+class SPIClass {
public:
SPIClass();
-
void begin();
-
- // void usingInterrupt(uint8_t interruptNumber);
- void beginTransaction(SPISettings settings);
- uint8_t transfer(uint8_t data);
- uint16_t transfer16(uint16_t data);
- void transfer(void *buf, size_t count);
- void endTransaction(void);
-
void end();
-
void setBitOrder(uint8_t bitOrder);
void setDataMode(uint8_t dataMode);
- void setClockDivider(uint8_t clockDiv);
-
-private:
- SPIImpl* _impl;
+ void setClockDivider(uint32_t clockDiv);
+ void beginTransaction(SPISettings settings);
+ uint8_t transfer(uint8_t data);
+ void endTransaction(void);
};
extern SPIClass SPI;
diff --git a/hardware/esp8266com/esp8266/libraries/SPI/include/HSPI.h b/hardware/esp8266com/esp8266/libraries/SPI/include/HSPI.h
deleted file mode 100644
index cf9125522..000000000
--- a/hardware/esp8266com/esp8266/libraries/SPI/include/HSPI.h
+++ /dev/null
@@ -1,51 +0,0 @@
-#ifndef HSPI_H
-#define HSPI_H
-
-#include "SPIImpl.h"
-#include "SPIdef.h"
-
-extern "C" {
- #include "spi_register.h"
- #include "ets_sys.h"
- #include "osapi.h"
- #include "os_type.h"
-}
-
-class HSPI : public SPIImpl
-{
-public:
- virtual void begin();
- virtual void end();
- virtual void setBitOrder(uint8_t bitOrder);
- virtual void setDataMode(uint8_t dataMode);
- virtual void setClockDivider(uint8_t clockDiv);
- virtual uint8_t transfer(uint8_t data);
- virtual uint16_t transfer16(uint16_t data);
- virtual void transfer(void *buf, size_t count);
-
-private:
- uint32_t _clkDiv;
- uint32_t *spi_fifo;
- const uint32_t hspi_port = 1;
- const uint32_t hspi_fifo_size = 16;
-
-private:
- inline void hspi_wait_ready(void){while (READ_PERI_REG(SPI_FLASH_CMD(hspi_port))&SPI_FLASH_USR);}
- inline void hspi_start_tx(){SET_PERI_REG_MASK(SPI_FLASH_CMD(hspi_port), SPI_FLASH_USR);}
- inline void hspi_prepare_tx(uint32_t bytecount)
- {
- uint32_t bitcount = bytecount * 8 - 1;
- WRITE_PERI_REG(SPI_FLASH_USER1(hspi_port), (bitcount & SPI_USR_OUT_BITLEN) << SPI_USR_OUT_BITLEN_S);
- }
- inline void hspi_prepare_txrx(uint32_t bytecount)
- {
- uint32_t bitcount = bytecount * 8 - 1;
- WRITE_PERI_REG(SPI_FLASH_USER1(hspi_port), ((bitcount & SPI_USR_OUT_BITLEN) << SPI_USR_OUT_BITLEN_S) |
- ((bitcount & SPI_USR_DIN_BITLEN) << SPI_USR_DIN_BITLEN_S));
- }
-
-};
-
-
-
-#endif//HSPI_H
diff --git a/hardware/esp8266com/esp8266/libraries/SPI/include/SPIImpl.h b/hardware/esp8266com/esp8266/libraries/SPI/include/SPIImpl.h
deleted file mode 100644
index f8c04f0a5..000000000
--- a/hardware/esp8266com/esp8266/libraries/SPI/include/SPIImpl.h
+++ /dev/null
@@ -1,21 +0,0 @@
-#ifndef SPIIMPL_H
-#define SPIIMPL_H
-
-#include
-#include
-class SPIImpl
-{
-public:
- virtual void begin() = 0;
- virtual uint8_t transfer(uint8_t data) = 0;
- virtual uint16_t transfer16(uint16_t data) = 0;
- virtual void transfer(void *buf, size_t count) = 0;
- virtual void end() = 0;
-
- virtual void setBitOrder(uint8_t bitOrder) = 0;
- virtual void setDataMode(uint8_t dataMode) = 0;
- virtual void setClockDivider(uint8_t clockDiv) = 0;
-};
-
-
-#endif//SPIIMPL_H
diff --git a/hardware/esp8266com/esp8266/libraries/SPI/include/SPIdef.h b/hardware/esp8266com/esp8266/libraries/SPI/include/SPIdef.h
deleted file mode 100644
index c10e1cd86..000000000
--- a/hardware/esp8266com/esp8266/libraries/SPI/include/SPIdef.h
+++ /dev/null
@@ -1,28 +0,0 @@
-#ifndef SPIDEF_H
-#define SPIDEF_H
-
-
-#ifndef LSBFIRST
-#define LSBFIRST 0
-#endif
-#ifndef MSBFIRST
-#define MSBFIRST 1
-#endif
-
-
-// AVR compatibility definitions
-const uint8_t SPI_CLOCK_DIV4 = 4;
-const uint8_t SPI_CLOCK_DIV16 = 16;
-const uint8_t SPI_CLOCK_DIV64 = 64;
-const uint8_t SPI_CLOCK_DIV128 = 128;
-const uint8_t SPI_CLOCK_DIV2 = 2;
-const uint8_t SPI_CLOCK_DIV8 = 8;
-const uint8_t SPI_CLOCK_DIV32 = 32;
-
-const uint8_t SPI_MODE0 = 0x00;
-const uint8_t SPI_MODE1 = 0x04;
-const uint8_t SPI_MODE2 = 0x08;
-const uint8_t SPI_MODE3 = 0x0C;
-
-
-#endif//SPIDEF_H
diff --git a/hardware/esp8266com/esp8266/libraries/SPI/include/spi_register.h b/hardware/esp8266com/esp8266/libraries/SPI/include/spi_register.h
deleted file mode 100644
index f4dd5b627..000000000
--- a/hardware/esp8266com/esp8266/libraries/SPI/include/spi_register.h
+++ /dev/null
@@ -1,239 +0,0 @@
-//Generated at 2014-07-29 11:03:29
-/*
- * Copyright (c) 2010 - 2011 Espressif System
- *
- */
-
-#ifndef SPI_REGISTER_H_INCLUDED
-#define SPI_REGISTER_H_INCLUDED
-
-#define REG_SPI_BASE(i) (0x60000200-i*0x100)
-
-#define SPI_FLASH_CMD(i) (REG_SPI_BASE(i) + 0x0)
-#define SPI_FLASH_READ (BIT(31))
-#define SPI_FLASH_WREN (BIT(30))
-#define SPI_FLASH_WRDI (BIT(29))
-#define SPI_FLASH_RDID (BIT(28))
-#define SPI_FLASH_RDSR (BIT(27))
-#define SPI_FLASH_WRSR (BIT(26))
-#define SPI_FLASH_PP (BIT(25))
-#define SPI_FLASH_SE (BIT(24))
-#define SPI_FLASH_BE (BIT(23))
-#define SPI_FLASH_CE (BIT(22))
-#define SPI_FLASH_DP (BIT(21))
-#define SPI_FLASH_RES (BIT(20))
-#define SPI_FLASH_HPM (BIT(19))
-#define SPI_FLASH_USR (BIT(18))
-
-#define SPI_FLASH_ADDR(i) (REG_SPI_BASE(i) + 0x4)
-
-#define SPI_FLASH_CTRL(i) (REG_SPI_BASE(i) + 0x8)
-#define SPI_WR_BIT_ODER (BIT(26))
-#define SPI_RD_BIT_ODER (BIT(25))
-#define SPI_QIO_MODE (BIT(24))
-#define SPI_DIO_MODE (BIT(23))
-#define SPI_TWO_BYTE_STATUS_EN (BIT(22))
-#define SPI_WP_REG (BIT(21))
-#define SPI_QOUT_MODE (BIT(20))
-#define SPI_SHARE_BUS (BIT(19))
-#define SPI_HOLD_MODE (BIT(18))
-#define SPI_ENABLE_AHB (BIT(17))
-#define SPI_SST_AAI (BIT(16))
-#define SPI_RESANDRES (BIT(15))
-#define SPI_DOUT_MODE (BIT(14))
-#define SPI_FASTRD_MODE (BIT(13))
-
-#define SPI_FLASH_CTRL1(i) (REG_SPI_BASE (i) + 0xC)
-#define SPI_T_CSH 0x0000000F
-#define SPI_T_CSH_S 28
-#define SPI_T_RES 0x00000FFF
-#define SPI_T_RES_S 16
-#define SPI_BUS_TIMER_LIMIT 0x0000FFFF
-#define SPI_BUS_TIMER_LIMIT_S 0
-
-#define SPI_FLASH_STATUS(i) (REG_SPI_BASE(i) + 0x10)
-#define SPI_STATUS_EXT 0x000000FF
-#define SPI_STATUS_EXT_S 24
-#define SPI_WB_MODE 0x000000FF
-#define SPI_WB_MODE_S 16
-#define SPI_FLASH_STATUS_PRO_FLAG (BIT(7))
-#define SPI_FLASH_TOP_BOT_PRO_FLAG (BIT(5))
-#define SPI_FLASH_BP2 (BIT(4))
-#define SPI_FLASH_BP1 (BIT(3))
-#define SPI_FLASH_BP0 (BIT(2))
-#define SPI_FLASH_WRENABLE_FLAG (BIT(1))
-#define SPI_FLASH_BUSY_FLAG (BIT(0))
-
-#define SPI_FLASH_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
-#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_FLASH_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_FLASH_USER(i) (REG_SPI_BASE(i) + 0x1C)
-#define SPI_USR_COMMAND (BIT(31))
-#define SPI_FLASH_USR_ADDR (BIT(30))
-#define SPI_FLASH_USR_DUMMY (BIT(29))
-#define SPI_FLASH_USR_DIN (BIT(28))
-#define SPI_FLASH_DOUT (BIT(27))
-#define SPI_USR_DUMMY_IDLE (BIT(26))
-#define SPI_USR_DOUT_HIGHPART (BIT(25))
-#define SPI_USR_DIN_HIGHPART (BIT(24))
-#define SPI_USR_PREP_HOLD (BIT(23))
-#define SPI_USR_CMD_HOLD (BIT(22))
-#define SPI_USR_ADDR_HOLD (BIT(21))
-#define SPI_USR_DUMMY_HOLD (BIT(20))
-#define SPI_USR_DIN_HOLD (BIT(19))
-#define SPI_USR_DOUT_HOLD (BIT(18))
-#define SPI_USR_HOLD_POL (BIT(17))
-#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
-#define SPI_AHB_ENDIAN_MODE_S 8
-#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))
-#define SPI_AHB_USR_COMMAND_4BYTE (BIT(1))
-#define SPI_DOUTDIN (BIT(0))
-
-#define SPI_FLASH_USER1(i) (REG_SPI_BASE(i) + 0x20)
-#define SPI_USR_ADDR_BITLEN 0x0000003F
-#define SPI_USR_ADDR_BITLEN_S 26
-#define SPI_USR_OUT_BITLEN 0x000001FF
-#define SPI_USR_OUT_BITLEN_S 17
-#define SPI_USR_DIN_BITLEN 0x000001FF
-#define SPI_USR_DIN_BITLEN_S 8
-#define SPI_USR_DUMMY_CYCLELEN 0x000000FF
-#define SPI_USR_DUMMY_CYCLELEN_S 0
-
-#define SPI_FLASH_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_FLASH_USER3(i) (REG_SPI_BASE(i) + 0x28)
-#define SPI_FLASH_PIN(i) (REG_SPI_BASE(i) + 0x2C)
-#define SPI_FLASH_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
-#define SPI_SLV_LAST_STATE_S 20
-#define SPI_SLV_LAST_COMMAND 0x00000007
-#define SPI_SLV_LAST_COMMAND_S 17
-#define SPI_CS_I_MODE 0x00000003
-#define SPI_CS_I_MODE_S 10
-#define SPI_INT_EN 0x0000001F
-#define 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_FLASH_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))
-#define SPI_SLV_STATUS_READBACK (BIT(25))
-#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_FLASH_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_WRSTA_DUMMY_CYCLELEN 0x000000FF
-#define SPI_SLV_WRSTA_DUMMY_CYCLELEN_S 8
-#define SPI_SLV_RDSTA_DUMMY_CYCLELEN 0x000000FF
-#define SPI_SLV_RDSTA_DUMMY_CYCLELEN_S 0
-
-#define SPI_FLASH_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
-
-#define SPI_FLASH_C0(i) (REG_SPI_BASE(i) +0x40)
-#define SPI_FLASH_C1(i) (REG_SPI_BASE(i) +0x44)
-#define SPI_FLASH_C2(i) (REG_SPI_BASE(i) +0x48)
-#define SPI_FLASH_C3(i) (REG_SPI_BASE(i) +0x4C)
-#define SPI_FLASH_C4(i) (REG_SPI_BASE(i) +0x50)
-#define SPI_FLASH_C5(i) (REG_SPI_BASE(i) +0x54)
-#define SPI_FLASH_C6(i) (REG_SPI_BASE(i) +0x58)
-#define SPI_FLASH_C7(i) (REG_SPI_BASE(i) +0x5C)
-
-#define SPI_FLASH_EXT0(i) (REG_SPI_BASE(i) + 0xF0)
-#define SPI_T_PP_ENA (BIT(31))
-#define SPI_T_PP_SHIFT 0x0000000F
-#define SPI_T_PP_SHIFT_S 16
-#define SPI_T_PP_TIME 0x00000FFF
-#define SPI_T_PP_TIME_S 0
-
-#define SPI_FLASH_EXT1(i) (REG_SPI_BASE(i) + 0xF4)
-#define SPI_T_ERASE_ENA (BIT(31))
-#define SPI_T_ERASE_SHIFT 0x0000000F
-#define SPI_T_ERASE_SHIFT_S 16
-#define SPI_T_ERASE_TIME 0x00000FFF
-#define SPI_T_ERASE_TIME_S 0
-
-#define SPI_FLASH_EXT2(i) (REG_SPI_BASE(i) + 0xF8)
-#define SPI_ST 0x00000007
-#define SPI_ST_S 0
-
-#define SPI_FLASH_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/hardware/esp8266com/esp8266/libraries/Wire/Wire.cpp b/hardware/esp8266com/esp8266/libraries/Wire/Wire.cpp
index bf363f6b7..36e3c6670 100644
--- a/hardware/esp8266com/esp8266/libraries/Wire/Wire.cpp
+++ b/hardware/esp8266com/esp8266/libraries/Wire/Wire.cpp
@@ -1,5 +1,5 @@
/*
- TwoWire.cpp - TWI/I2C library for Wiring & Arduino
+ TwoWire.cpp - TWI/I2C library for Arduino & Wiring
Copyright (c) 2006 Nicholas Zambetti. All right reserved.
This library is free software; you can redistribute it and/or
@@ -15,9 +15,10 @@
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
-
+
Modified 2012 by Todd Krein (todd@krein.org) to implement repeated starts
Modified December 2014 by Ivan Grokhotkov (ivan@esp8266.com) - esp8266 support
+ Modified April 2015 by Hrsto Gochkov (ficeto@ficeto.com) - alternative esp8266 support
*/
extern "C" {
@@ -26,7 +27,7 @@ extern "C" {
#include
}
-#include "i2c.h"
+#include "si2c.h"
#include "Wire.h"
// Initialize Class Variables //////////////////////////////////////////////////
@@ -46,215 +47,137 @@ void (*TwoWire::user_onReceive)(int);
// Constructors ////////////////////////////////////////////////////////////////
-TwoWire::TwoWire()
-{
-}
+TwoWire::TwoWire(){}
// Public Methods //////////////////////////////////////////////////////////////
-void TwoWire::pins(int sda, int scl)
-{
- i2c_init(sda, scl);
+void TwoWire::begin(int sda, int scl){
+ twi_init(sda, scl);
+ flush();
}
-void TwoWire::begin(void)
-{
- rxBufferIndex = 0;
- rxBufferLength = 0;
-
- txBufferIndex = 0;
- txBufferLength = 0;
-
+void TwoWire::begin(void){
+ begin(SDA, SCL);
}
-void TwoWire::begin(uint8_t address)
-{
+void TwoWire::begin(uint8_t address){
// twi_setAddress(address);
// twi_attachSlaveTxEvent(onRequestService);
// twi_attachSlaveRxEvent(onReceiveService);
- // begin();
+ begin();
}
-void TwoWire::begin(int address)
-{
- // begin((uint8_t)address);
+void TwoWire::begin(int address){
+ begin((uint8_t)address);
}
-void TwoWire::setClock(uint32_t frequency)
-{
- i2c_freq(frequency);
+void TwoWire::setClock(uint32_t frequency){
+ twi_setClock(frequency);
}
-size_t TwoWire::requestFrom(uint8_t address, size_t size, bool sendStop)
-{
- // clamp to buffer length
+
+size_t TwoWire::requestFrom(uint8_t address, size_t size, bool sendStop){
if(size > BUFFER_LENGTH){
size = BUFFER_LENGTH;
}
- // perform blocking read into buffer
- size_t read = i2c_master_read_from(address, rxBuffer, size, sendStop);
- // set rx buffer iterator vars
+ size_t read = (twi_readFrom(address, rxBuffer, size, sendStop) == 0)?size:0;
rxBufferIndex = 0;
rxBufferLength = read;
-
return read;
}
-uint8_t TwoWire::requestFrom(uint8_t address, uint8_t quantity, uint8_t sendStop)
-{
+uint8_t TwoWire::requestFrom(uint8_t address, uint8_t quantity, uint8_t sendStop){
return requestFrom(address, static_cast(quantity), static_cast(sendStop));
}
-uint8_t TwoWire::requestFrom(uint8_t address, uint8_t quantity)
-{
+uint8_t TwoWire::requestFrom(uint8_t address, uint8_t quantity){
return requestFrom(address, static_cast(quantity), true);
}
-uint8_t TwoWire::requestFrom(int address, int quantity)
-{
+uint8_t TwoWire::requestFrom(int address, int quantity){
return requestFrom(static_cast(address), static_cast(quantity), true);
}
-uint8_t TwoWire::requestFrom(int address, int quantity, int sendStop)
-{
+uint8_t TwoWire::requestFrom(int address, int quantity, int sendStop){
return requestFrom(static_cast(address), static_cast(quantity), static_cast(sendStop));
}
-void TwoWire::beginTransmission(uint8_t address)
-{
- // indicate that we are transmitting
+void TwoWire::beginTransmission(uint8_t address){
transmitting = 1;
- // set address of targeted slave
txAddress = address;
- // reset tx buffer iterator vars
txBufferIndex = 0;
txBufferLength = 0;
}
-void TwoWire::beginTransmission(int address)
-{
+void TwoWire::beginTransmission(int address){
beginTransmission((uint8_t)address);
}
-//
-// Originally, 'endTransmission' was an f(void) function.
-// It has been modified to take one parameter indicating
-// whether or not a STOP should be performed on the bus.
-// Calling endTransmission(false) allows a sketch to
-// perform a repeated start.
-//
-// WARNING: Nothing in the library keeps track of whether
-// the bus tenure has been properly ended with a STOP. It
-// is very possible to leave the bus in a hung state if
-// no call to endTransmission(true) is made. Some I2C
-// devices will behave oddly if they do not see a STOP.
-//
-uint8_t TwoWire::endTransmission(uint8_t sendStop)
-{
- // transmit buffer (blocking)
- int8_t ret = i2c_master_write_to(txAddress, txBuffer, txBufferLength, sendStop);
- // reset tx buffer iterator vars
+uint8_t TwoWire::endTransmission(uint8_t sendStop){
+ int8_t ret = twi_writeTo(txAddress, txBuffer, txBufferLength, sendStop);
txBufferIndex = 0;
txBufferLength = 0;
- // indicate that we are done transmitting
transmitting = 0;
return ret;
}
-// This provides backwards compatibility with the original
-// definition, and expected behaviour, of endTransmission
-//
-uint8_t TwoWire::endTransmission(void)
-{
+uint8_t TwoWire::endTransmission(void){
return endTransmission(true);
}
-// must be called in:
-// slave tx event callback
-// or after beginTransmission(address)
-size_t TwoWire::write(uint8_t data)
-{
+size_t TwoWire::write(uint8_t data){
if(transmitting){
- // in master transmitter mode
- // don't bother if buffer is full
if(txBufferLength >= BUFFER_LENGTH){
setWriteError();
return 0;
}
- // put byte in tx buffer
txBuffer[txBufferIndex] = data;
++txBufferIndex;
- // update amount in buffer
txBufferLength = txBufferIndex;
- }else{
- // in slave send mode
- // reply to master
+ } else {
// i2c_slave_transmit(&data, 1);
}
return 1;
}
-// must be called in:
-// slave tx event callback
-// or after beginTransmission(address)
-size_t TwoWire::write(const uint8_t *data, size_t quantity)
-{
+size_t TwoWire::write(const uint8_t *data, size_t quantity){
if(transmitting){
- // in master transmitter mode
for(size_t i = 0; i < quantity; ++i){
- write(data[i]);
+ if(!write(data[i])) return i;
}
}else{
- // in slave send mode
- // reply to master
// i2c_slave_transmit(data, quantity);
}
return quantity;
}
-// must be called in:
-// slave rx event callback
-// or after requestFrom(address, numBytes)
-int TwoWire::available(void)
-{
+int TwoWire::available(void){
return rxBufferLength - rxBufferIndex;
}
-// must be called in:
-// slave rx event callback
-// or after requestFrom(address, numBytes)
-int TwoWire::read(void)
-{
+int TwoWire::read(void){
int value = -1;
-
- // get each successive byte on each call
if(rxBufferIndex < rxBufferLength){
value = rxBuffer[rxBufferIndex];
++rxBufferIndex;
}
-
return value;
}
-// must be called in:
-// slave rx event callback
-// or after requestFrom(address, numBytes)
-int TwoWire::peek(void)
-{
+int TwoWire::peek(void){
int value = -1;
-
if(rxBufferIndex < rxBufferLength){
value = rxBuffer[rxBufferIndex];
}
-
return value;
}
-void TwoWire::flush(void)
-{
- // XXX: to be implemented.
+void TwoWire::flush(void){
+ rxBufferIndex = 0;
+ rxBufferLength = 0;
+ txBufferIndex = 0;
+ txBufferLength = 0;
}
-// behind the scenes function that is called when data is received
void TwoWire::onReceiveService(uint8_t* inBytes, int numBytes)
{
// don't bother if user hasn't registered a callback
@@ -279,9 +202,7 @@ void TwoWire::onReceiveService(uint8_t* inBytes, int numBytes)
// user_onReceive(numBytes);
}
-// behind the scenes function that is called when data is requested
-void TwoWire::onRequestService(void)
-{
+void TwoWire::onRequestService(void){
// // don't bother if user hasn't registered a callback
// if(!user_onRequest){
// return;
@@ -294,16 +215,12 @@ void TwoWire::onRequestService(void)
// user_onRequest();
}
-// sets function called on slave write
-void TwoWire::onReceive( void (*function)(int) )
-{
- // user_onReceive = function;
+void TwoWire::onReceive( void (*function)(int) ){
+ //user_onReceive = function;
}
-// sets function called on slave read
-void TwoWire::onRequest( void (*function)(void) )
-{
- // user_onRequest = function;
+void TwoWire::onRequest( void (*function)(void) ){
+ //user_onRequest = function;
}
// Preinstantiate Objects //////////////////////////////////////////////////////
diff --git a/hardware/esp8266com/esp8266/libraries/Wire/Wire.h b/hardware/esp8266com/esp8266/libraries/Wire/Wire.h
index a0455f0b4..3404fda7f 100644
--- a/hardware/esp8266com/esp8266/libraries/Wire/Wire.h
+++ b/hardware/esp8266com/esp8266/libraries/Wire/Wire.h
@@ -18,6 +18,7 @@
Modified 2012 by Todd Krein (todd@krein.org) to implement repeated starts
Modified December 2014 by Ivan Grokhotkov (ivan@esp8266.com) - esp8266 support
+ Modified April 2015 by Hrsto Gochkov (ficeto@ficeto.com) - alternative esp8266 support
*/
#ifndef TwoWire_h
@@ -49,7 +50,7 @@ class TwoWire : public Stream
static void onReceiveService(uint8_t*, int);
public:
TwoWire();
- void pins(int sda, int scl);
+ void begin(int sda, int scl);
void begin();
void begin(uint8_t);
void begin(int);
diff --git a/hardware/esp8266com/esp8266/libraries/Wire/utility/twi.h b/hardware/esp8266com/esp8266/libraries/Wire/utility/twi.h
deleted file mode 100644
index 652659339..000000000
--- a/hardware/esp8266com/esp8266/libraries/Wire/utility/twi.h
+++ /dev/null
@@ -1,53 +0,0 @@
-/*
- twi.h - TWI/I2C library for Wiring & Arduino
- Copyright (c) 2006 Nicholas Zambetti. All right reserved.
-
- This library is free software; you can redistribute it and/or
- modify it under the terms of the GNU Lesser General Public
- License as published by the Free Software Foundation; either
- version 2.1 of the License, or (at your option) any later version.
-
- This library is distributed in the hope that it will be useful,
- but WITHOUT ANY WARRANTY; without even the implied warranty of
- MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
- Lesser General Public License for more details.
-
- You should have received a copy of the GNU Lesser General Public
- License along with this library; if not, write to the Free Software
- Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
-*/
-
-#ifndef twi_h
-#define twi_h
-
- #include
-
- //#define ATMEGA8
-
- #ifndef TWI_FREQ
- #define TWI_FREQ 100000L
- #endif
-
- #ifndef TWI_BUFFER_LENGTH
- #define TWI_BUFFER_LENGTH 32
- #endif
-
- #define TWI_READY 0
- #define TWI_MRX 1
- #define TWI_MTX 2
- #define TWI_SRX 3
- #define TWI_STX 4
-
- void twi_init(void);
- void twi_setAddress(uint8_t);
- uint8_t twi_readFrom(uint8_t, uint8_t*, uint8_t, uint8_t);
- uint8_t twi_writeTo(uint8_t, uint8_t*, uint8_t, uint8_t, uint8_t);
- uint8_t twi_transmit(const uint8_t*, uint8_t);
- void twi_attachSlaveRxEvent( void (*)(uint8_t*, int) );
- void twi_attachSlaveTxEvent( void (*)(void) );
- void twi_reply(uint8_t);
- void twi_stop(void);
- void twi_releaseBus(void);
-
-#endif
-
diff --git a/hardware/esp8266com/esp8266/platform.txt b/hardware/esp8266com/esp8266/platform.txt
index fe99019fe..b3aa18f36 100644
--- a/hardware/esp8266com/esp8266/platform.txt
+++ b/hardware/esp8266com/esp8266/platform.txt
@@ -23,7 +23,7 @@ compiler.S.flags=-c -g -x assembler-with-cpp -MMD
compiler.c.elf.ldscript=eagle.app.v6.ld
compiler.c.elf.flags=-nostdlib -Wl,--no-check-sections -u call_user_start -Wl,-static "-L{compiler.sdk.path}/lib" "-L{compiler.sdk.path}/ld" "-T{compiler.c.elf.ldscript}"
compiler.c.elf.cmd=xtensa-lx106-elf-gcc
-compiler.c.elf.libs=-lgcc -lm -lhal -lphy -lnet80211 -llwip -lwpa -lmain -lpp -lsmartconfig
+compiler.c.elf.libs=-lc -lm -lg -lgcc -lhal -lphy -lnet80211 -llwip -lwpa -lmain -lpp -lsmartconfig
compiler.cpp.cmd=xtensa-lx106-elf-g++
compiler.cpp.flags=-c -Os -mlongcalls -mtext-section-literals -fno-exceptions -fno-rtti -std=c++11 -MMD
@@ -92,4 +92,3 @@ tools.esptool.upload.protocol=esp
tools.esptool.upload.params.verbose=-vv
tools.esptool.upload.params.quiet=
tools.esptool.upload.pattern="{path}/{cmd}" {upload.verbose} -cd {upload.resetmethod} -cb {upload.speed} -cp "{serial.port}" -ca 0x00000 -cf "{build.path}/{build.project_name}_00000.bin" -ca 0x40000 -cf "{build.path}/{build.project_name}_40000.bin"
-
diff --git a/hardware/esp8266com/esp8266/variants/generic/pins_arduino.h b/hardware/esp8266com/esp8266/variants/generic/pins_arduino.h
index ab5d6e9a0..b2ff8f1cd 100644
--- a/hardware/esp8266com/esp8266/variants/generic/pins_arduino.h
+++ b/hardware/esp8266com/esp8266/variants/generic/pins_arduino.h
@@ -26,34 +26,25 @@
#ifndef Pins_Arduino_h
#define Pins_Arduino_h
-#define NUM_DIGITAL_PINS 16
-#define NUM_ANALOG_INPUTS 1
-#define ESP_PINS_OFFSET 0
+#define EXTERNAL_NUM_INTERRUPTS 16
+#define NUM_DIGITAL_PINS 17
+#define NUM_ANALOG_INPUTS 1
-static const uint8_t SDA = 0;
-static const uint8_t SCL = 2;
+#define analogInputToDigitalPin(p) ((p > 0)?NOT_A_PIN:0)
+#define digitalPinToInterrupt(p) (((p) < EXTERNAL_NUM_INTERRUPTS)?p:NOT_A_PIN)
+#define digitalPinHasPWM(p) (((p) < NUM_DIGITAL_PINS)?p:NOT_A_PIN)
-static const uint8_t SS = 12;
-static const uint8_t MOSI = 13;
-static const uint8_t MISO = 14;
-static const uint8_t SCK = 15;
+static const uint8_t SDA = 4;
+static const uint8_t SCL = 5;
+
+static const uint8_t SS = 15;
+static const uint8_t MOSI = 13;
+static const uint8_t MISO = 12;
+static const uint8_t SCK = 14;
static const uint8_t BUILTIN_LED = 1;
-static const uint8_t A0 = 0;
-
-static const uint8_t E0 = ESP_PINS_OFFSET + 0;
-static const uint8_t E1 = ESP_PINS_OFFSET + 1;
-static const uint8_t E2 = ESP_PINS_OFFSET + 2;
-static const uint8_t E3 = ESP_PINS_OFFSET + 3;
-static const uint8_t E4 = ESP_PINS_OFFSET + 4;
-static const uint8_t E5 = ESP_PINS_OFFSET + 5;
-static const uint8_t E11 = ESP_PINS_OFFSET + 11;
-static const uint8_t E12 = ESP_PINS_OFFSET + 12;
-static const uint8_t E13 = ESP_PINS_OFFSET + 13;
-static const uint8_t E14 = ESP_PINS_OFFSET + 14;
-static const uint8_t E15 = ESP_PINS_OFFSET + 15;
-static const uint8_t E16 = ESP_PINS_OFFSET + 16;
+static const uint8_t A0 = 17;
// These serial port names are intended to allow libraries and architecture-neutral
// sketches to automatically default to the correct port name for a particular type
diff --git a/hardware/esp8266com/esp8266/variants/wifio/WifioProtocol.h b/hardware/esp8266com/esp8266/variants/wifio/WifioProtocol.h
index dbb9d9e7e..525ca81b4 100644
--- a/hardware/esp8266com/esp8266/variants/wifio/WifioProtocol.h
+++ b/hardware/esp8266com/esp8266/variants/wifio/WifioProtocol.h
@@ -24,12 +24,11 @@
#include
#include "Arduino.h"
-#include "i2c.h"
inline void protocolError()
{
delay(5);
- i2c_stop();
+ twi_stop();
}
namespace wifio {
@@ -119,7 +118,7 @@ void sendCommand(uint8_t addr, T& t)
{
// TODO: calculate parity
t.parity = 1;
- if (i2c_master_write_to(addr, reinterpret_cast(&t), sizeof(T), true) != sizeof(T))
+ if (twi_writeTo(addr, reinterpret_cast(&t), sizeof(T), true) != sizeof(T))
{
protocolError();
}
@@ -129,7 +128,7 @@ template
bool sendCommandWaitForReply(uint8_t addr, TC& c, Command rt, TR& r, int32_t d_us)
{
c.parity = 1;
- if (i2c_master_write_to(addr, reinterpret_cast(&c), sizeof(TC), true) != sizeof(TC))
+ if (twi_writeTo(addr, reinterpret_cast(&c), sizeof(TC), true) != sizeof(TC))
{
protocolError();
return false;
@@ -138,7 +137,7 @@ bool sendCommandWaitForReply(uint8_t addr, TC& c, Command rt, TR& r, int32_t d_u
{
delayMicroseconds(d_us);
}
- if (i2c_master_read_from(addr, reinterpret_cast(&r), sizeof(TR), true) != sizeof(TR) || r.header.cmd != rt)
+ if (twi_readFrom(addr, reinterpret_cast(&r), sizeof(TR), true) != sizeof(TR) || r.header.cmd != rt)
{
protocolError();
return false;
diff --git a/hardware/esp8266com/esp8266/variants/wifio/WifioWiring.cpp b/hardware/esp8266com/esp8266/variants/wifio/WifioWiring.cpp
index e487eb268..d2b607b4f 100644
--- a/hardware/esp8266com/esp8266/variants/wifio/WifioWiring.cpp
+++ b/hardware/esp8266com/esp8266/variants/wifio/WifioWiring.cpp
@@ -113,8 +113,7 @@ extern "C" void analogWrite(uint8_t pin, int value) {
}
-void initVariant()
-{
- i2c_freq(100000);
- i2c_init(SDA, SCL);
+void initVariant() {
+ twi_setClock(100000);
+ twi_init(SDA, SCL);
}
diff --git a/libraries/SD/src/utility/Sd2Card.cpp b/libraries/SD/src/utility/Sd2Card.cpp
index a72d3d271..0535d0053 100644
--- a/libraries/SD/src/utility/Sd2Card.cpp
+++ b/libraries/SD/src/utility/Sd2Card.cpp
@@ -120,13 +120,13 @@ uint8_t Sd2Card::cardCommand(uint8_t cmd, uint32_t arg) {
for (int8_t s = 24; s >= 0; s -= 8) spiSend(arg >> s);
// send CRC
- uint8_t crc = 0XFF;
- if (cmd == CMD0) crc = 0X95; // correct crc for CMD0 with arg 0
- if (cmd == CMD8) crc = 0X87; // correct crc for CMD8 with arg 0X1AA
+ uint8_t crc = 0xFF;
+ if (cmd == CMD0) crc = 0x95; // correct crc for CMD0 with arg 0
+ if (cmd == CMD8) crc = 0x87; // correct crc for CMD8 with arg 0X1AA
spiSend(crc);
// wait for response
- for (uint8_t i = 0; ((status_ = spiRec()) & 0X80) && i != 0XFF; i++)
+ for (uint8_t i = 0; ((status_ = spiRec()) & 0x80) && i != 0xFF; i++)
;
return status_;
}
@@ -239,7 +239,11 @@ uint8_t Sd2Card::eraseSingleBlockEnable(void) {
* the value zero, false, is returned for failure. The reason for failure
* can be determined by calling errorCode() and errorData().
*/
+#ifdef ESP8266
+uint8_t Sd2Card::init(uint32_t sckRateID, uint8_t chipSelectPin) {
+#else
uint8_t Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
+#endif
errorCode_ = inBlock_ = partialBlockRead_ = type_ = 0;
chipSelectPin_ = chipSelectPin;
// 16-bit init start time allows over a minute
@@ -266,7 +270,11 @@ uint8_t Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
SPSR &= ~(1 << SPI2X);
#else // USE_SPI_LIB
SPI.begin();
+ #ifdef ESP8266
+ settings = SPISettings(SPI_CLOCK_DIV64, MSBFIRST, SPI_MODE0);
+ #else
settings = SPISettings(250000, MSBFIRST, SPI_MODE0);
+ #endif
#endif // USE_SPI_LIB
#endif // SOFTWARE_SPI
@@ -498,11 +506,15 @@ uint8_t Sd2Card::readRegister(uint8_t cmd, void* buf) {
* \return The value one, true, is returned for success and the value zero,
* false, is returned for an invalid value of \a sckRateID.
*/
+#ifdef ESP8266
+uint8_t Sd2Card::setSckRate(uint32_t sckRateID) {
+#else
uint8_t Sd2Card::setSckRate(uint8_t sckRateID) {
if (sckRateID > 6) {
error(SD_CARD_ERROR_SCK_RATE);
return false;
}
+#endif
#ifndef USE_SPI_LIB
// see avr processor datasheet for SPI register bit definitions
if ((sckRateID & 1) || sckRateID == 6) {
@@ -514,6 +526,9 @@ uint8_t Sd2Card::setSckRate(uint8_t sckRateID) {
SPCR |= (sckRateID & 4 ? (1 << SPR1) : 0)
| (sckRateID & 2 ? (1 << SPR0) : 0);
#else // USE_SPI_LIB
+ #ifdef ESP8266
+ settings = SPISettings(sckRateID, MSBFIRST, SPI_MODE0);
+ #else
switch (sckRateID) {
case 0: settings = SPISettings(25000000, MSBFIRST, SPI_MODE0); break;
case 1: settings = SPISettings(4000000, MSBFIRST, SPI_MODE0); break;
@@ -523,6 +538,7 @@ uint8_t Sd2Card::setSckRate(uint8_t sckRateID) {
case 5: settings = SPISettings(250000, MSBFIRST, SPI_MODE0); break;
default: settings = SPISettings(125000, MSBFIRST, SPI_MODE0);
}
+ #endif
#endif // USE_SPI_LIB
return true;
}
diff --git a/libraries/SD/src/utility/Sd2Card.h b/libraries/SD/src/utility/Sd2Card.h
index 989d3d8bf..a7935e4eb 100644
--- a/libraries/SD/src/utility/Sd2Card.h
+++ b/libraries/SD/src/utility/Sd2Card.h
@@ -25,15 +25,23 @@
*/
#include "Sd2PinMap.h"
#include "SdInfo.h"
+
+#ifdef ESP8266
+#include "SPI.h"
+uint32_t const SPI_FULL_SPEED = SPI_CLOCK_DIV2;
+uint32_t const SPI_HALF_SPEED = SPI_CLOCK_DIV4;
+uint32_t const SPI_QUARTER_SPEED = SPI_CLOCK_DIV8;
+#else
/** Set SCK to max rate of F_CPU/2. See Sd2Card::setSckRate(). */
uint8_t const SPI_FULL_SPEED = 0;
/** Set SCK rate to F_CPU/4. See Sd2Card::setSckRate(). */
uint8_t const SPI_HALF_SPEED = 1;
/** Set SCK rate to F_CPU/8. Sd2Card::setSckRate(). */
uint8_t const SPI_QUARTER_SPEED = 2;
+#endif
/**
* USE_SPI_LIB: if set, use the SPI library bundled with Arduino IDE, otherwise
- * run with a standalone driver for AVR.
+ * run with a standalone driver for AVR.
*/
#define USE_SPI_LIB
/**
@@ -181,10 +189,17 @@ class Sd2Card {
* and the default SD chip select pin.
* See sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin).
*/
+ #ifdef ESP8266
+ uint8_t init(uint32_t sckRateID) {
+ return init(sckRateID, SD_CHIP_SELECT_PIN);
+ }
+ uint8_t init(uint32_t sckRateID, uint8_t chipSelectPin);
+ #else
uint8_t init(uint8_t sckRateID) {
return init(sckRateID, SD_CHIP_SELECT_PIN);
}
uint8_t init(uint8_t sckRateID, uint8_t chipSelectPin);
+ #endif
void partialBlockRead(uint8_t value);
/** Returns the current value, true or false, for partial block read. */
uint8_t partialBlockRead(void) const {return partialBlockRead_;}
@@ -205,7 +220,11 @@ class Sd2Card {
return readRegister(CMD9, csd);
}
void readEnd(void);
+ #ifdef ESP8266
+ uint8_t setSckRate(uint32_t sckRateID);
+ #else
uint8_t setSckRate(uint8_t sckRateID);
+ #endif
/** Return the card type: SD V1, SD V2 or SDHC */
uint8_t type(void) const {return type_;}
uint8_t writeBlock(uint32_t blockNumber, const uint8_t* src);
diff --git a/libraries/SD/src/utility/Sd2PinMap.h b/libraries/SD/src/utility/Sd2PinMap.h
index 02ad52f5f..7f4d9dd60 100644
--- a/libraries/SD/src/utility/Sd2PinMap.h
+++ b/libraries/SD/src/utility/Sd2PinMap.h
@@ -31,6 +31,19 @@ uint8_t const SCK_PIN = SCK;
#endif // Sd2PinMap_h
+#elif defined(ESP8266) // Other AVR based Boards follows
+#ifndef Sd2PinMap_h
+#define Sd2PinMap_h
+
+#include
+
+uint8_t const SS_PIN = SS;
+uint8_t const MOSI_PIN = MOSI;
+uint8_t const MISO_PIN = MISO;
+uint8_t const SCK_PIN = SCK;
+
+#endif // Sd2PinMap_h
+
#elif defined(__AVR__) // Other AVR based Boards follows
// Warning this file was generated by a program.
diff --git a/libraries/SD/src/utility/SdFile.cpp b/libraries/SD/src/utility/SdFile.cpp
index e7b6f0971..b6012b17f 100644
--- a/libraries/SD/src/utility/SdFile.cpp
+++ b/libraries/SD/src/utility/SdFile.cpp
@@ -22,6 +22,7 @@
#include
#endif
#include
+#define PRINT_PORT Serial
//------------------------------------------------------------------------------
// callback function for date/time
void (*SdFile::dateTime_)(uint16_t* date, uint16_t* time) = NULL;
@@ -215,7 +216,7 @@ void SdFile::ls(uint8_t flags, uint8_t indent) {
if (!DIR_IS_FILE_OR_SUBDIR(p)) continue;
// print any indent spaces
- for (int8_t i = 0; i < indent; i++) Serial.print(' ');
+ for (int8_t i = 0; i < indent; i++) PRINT_PORT.print(' ');
// print file name with possible blank fill
printDirName(*p, flags & (LS_DATE | LS_SIZE) ? 14 : 0);
@@ -223,15 +224,15 @@ void SdFile::ls(uint8_t flags, uint8_t indent) {
// print modify date/time if requested
if (flags & LS_DATE) {
printFatDate(p->lastWriteDate);
- Serial.print(' ');
+ PRINT_PORT.print(' ');
printFatTime(p->lastWriteTime);
}
// print size if requested
if (!DIR_IS_SUBDIR(p) && (flags & LS_SIZE)) {
- Serial.print(' ');
- Serial.print(p->fileSize);
+ PRINT_PORT.print(' ');
+ PRINT_PORT.print(p->fileSize);
}
- Serial.println();
+ PRINT_PORT.println();
// list subdirectory content if requested
if ((flags & LS_R) && DIR_IS_SUBDIR(p)) {
@@ -595,18 +596,18 @@ void SdFile::printDirName(const dir_t& dir, uint8_t width) {
for (uint8_t i = 0; i < 11; i++) {
if (dir.name[i] == ' ')continue;
if (i == 8) {
- Serial.print('.');
+ PRINT_PORT.print('.');
w++;
}
- Serial.write(dir.name[i]);
+ PRINT_PORT.write(dir.name[i]);
w++;
}
if (DIR_IS_SUBDIR(&dir)) {
- Serial.print('/');
+ PRINT_PORT.print('/');
w++;
}
while (w < width) {
- Serial.print(' ');
+ PRINT_PORT.print(' ');
w++;
}
}
@@ -618,10 +619,10 @@ void SdFile::printDirName(const dir_t& dir, uint8_t width) {
* \param[in] fatDate The date field from a directory entry.
*/
void SdFile::printFatDate(uint16_t fatDate) {
- Serial.print(FAT_YEAR(fatDate));
- Serial.print('-');
+ PRINT_PORT.print(FAT_YEAR(fatDate));
+ PRINT_PORT.print('-');
printTwoDigits(FAT_MONTH(fatDate));
- Serial.print('-');
+ PRINT_PORT.print('-');
printTwoDigits(FAT_DAY(fatDate));
}
//------------------------------------------------------------------------------
@@ -633,9 +634,9 @@ void SdFile::printFatDate(uint16_t fatDate) {
*/
void SdFile::printFatTime(uint16_t fatTime) {
printTwoDigits(FAT_HOUR(fatTime));
- Serial.print(':');
+ PRINT_PORT.print(':');
printTwoDigits(FAT_MINUTE(fatTime));
- Serial.print(':');
+ PRINT_PORT.print(':');
printTwoDigits(FAT_SECOND(fatTime));
}
//------------------------------------------------------------------------------
@@ -648,7 +649,7 @@ void SdFile::printTwoDigits(uint8_t v) {
str[0] = '0' + v/10;
str[1] = '0' + v % 10;
str[2] = 0;
- Serial.print(str);
+ PRINT_PORT.print(str);
}
//------------------------------------------------------------------------------
/**