1
0
mirror of https://github.com/esp8266/Arduino.git synced 2025-06-15 00:02:49 +03:00

Merge remote-tracking branch 'remotes/esp8266/esp8266' into esp8266

This commit is contained in:
Markus Sattler
2015-05-01 13:57:13 +02:00
36 changed files with 1756 additions and 1486 deletions

View File

@ -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

View File

@ -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);
}

View File

@ -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")));

View File

@ -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")));

View File

@ -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;
}

View File

@ -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; i<pwm_temp_steps_len; i++){
pwm_temp_masks[i] = pwm_get_mask(pwm_temp_steps[i]);
}
for(i=pwm_temp_steps_len; i>0; 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")));

View File

@ -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

View File

@ -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 <Arduino.h>
#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);
}
}

View File

@ -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 <stdint.h>
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

172
cores/esp8266/si2c.c Normal file
View File

@ -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<v;i++) reg = GPI;
}
static bool twi_write_start(void) {
SCL_HIGH();
SDA_HIGH();
if (SDA_READ() == 0) return false;
twi_delay(twi_dcount);
SDA_LOW();
twi_delay(twi_dcount);
return true;
}
static bool twi_write_stop(void){
uint8_t i = 0;
SCL_LOW();
SDA_LOW();
twi_delay(twi_dcount);
SCL_HIGH();
while (SCL_READ() == 0 && (i++) < TWI_CLOCK_STRETCH);// Clock stretching (up to 100us)
twi_delay(twi_dcount);
SDA_HIGH();
twi_delay(twi_dcount);
return true;
}
static bool twi_write_bit(bool bit) {
uint8_t i = 0;
SCL_LOW();
if (bit) SDA_HIGH();
else SDA_LOW();
twi_delay(twi_dcount+1);
SCL_HIGH();
while (SCL_READ() == 0 && (i++) < TWI_CLOCK_STRETCH);// Clock stretching (up to 100us)
twi_delay(twi_dcount+1);
return true;
}
static bool twi_read_bit(void) {
uint8_t i = 0;
SCL_LOW();
SDA_HIGH();
twi_delay(twi_dcount+1);
SCL_HIGH();
while (SCL_READ() == 0 && (i++) < TWI_CLOCK_STRETCH);// Clock stretching (up to 100us)
bool bit = SDA_READ();
twi_delay(twi_dcount);
return bit;
}
static bool twi_write_byte(uint8_t byte) {
uint8_t bit;
for (bit = 0; bit < 8; bit++) {
twi_write_bit(byte & 0x80);
byte <<= 1;
}
return twi_read_bit();//NACK/ACK
}
static uint8_t twi_read_byte(bool nack) {
uint8_t byte = 0;
uint8_t bit;
for (bit = 0; bit < 8; bit++) byte = (byte << 1) | twi_read_bit();
twi_write_bit(nack);
return byte;
}
uint8_t twi_writeTo(uint8_t address, uint8_t * buf, uint32_t len, uint8_t sendStop){
uint32_t i;
if(!twi_write_start()) return 4;//line busy
if(!twi_write_byte(((address << 1) | 0) & 0xFF)) return 2;//received NACK on transmit of address
for(i=0; i<len; i++){
if(!twi_write_byte(buf[i])) return 3;//received NACK on transmit of data
}
if(sendStop) twi_write_stop();
return 0;
}
uint8_t twi_readFrom(uint8_t address, uint8_t* buf, uint32_t len, uint8_t sendStop){
uint32_t i;
if(!twi_write_start()) return 4;//line busy
if(!twi_write_byte(((address << 1) | 1) & 0xFF)) return 2;//received NACK on transmit of address
for(i=0; i<len; i++) buf[i] = twi_read_byte(false);
if(sendStop){
twi_write_stop();
i = 0;
while(SDA_READ() == 0 && (i++) < 10){
SCL_LOW();
twi_delay(twi_dcount);
SCL_HIGH();
twi_delay(twi_dcount);
}
}
return 0;
}

31
cores/esp8266/si2c.h Normal file
View File

@ -0,0 +1,31 @@
/*
si2c.h - 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
*/
#ifndef SI2C_h
#define SI2C_h
#include "Arduino.h"
void twi_init(uint8_t sda, uint8_t scl);
void twi_stop(void);
void twi_setClock(uint32_t freq);
uint8_t twi_writeTo(uint8_t address, uint8_t * buf, uint32_t len, uint8_t sendStop);
uint8_t twi_readFrom(uint8_t address, uint8_t * buf, uint32_t len, uint8_t sendStop);
#endif