1
0
mirror of https://github.com/esp8266/Arduino.git synced 2025-10-25 18:38:07 +03:00

Merge pull request #453 from me-no-dev/esp8266

Esp8266
This commit is contained in:
Ivan Grokhotkov
2015-06-26 20:21:23 +03:00
10 changed files with 609 additions and 46 deletions

View File

@@ -42,12 +42,12 @@ extern "C" {
#define UART_TX_FIFO_SIZE 0x80
struct uart_ {
int uart_nr;
int uart_nr;
int baud_rate;
bool rxEnabled;
bool txEnabled;
uint8_t rxPin;
uint8_t txPin;
uint8_t rxPin;
uint8_t txPin;
};
static const int UART0 = 0;
@@ -271,7 +271,7 @@ int uart_get_baudrate(uart_t* uart) {
return uart->baud_rate;
}
uart_t* uart_init(int uart_nr, int baudrate, byte config) {
uart_t* uart_init(int uart_nr, int baudrate, byte config, byte mode) {
uint32_t conf1 = 0x00000000;
uart_t* uart = (uart_t*) os_malloc(sizeof(uart_t));
@@ -284,24 +284,25 @@ uart_t* uart_init(int uart_nr, int baudrate, byte config) {
switch(uart->uart_nr) {
case UART0:
pinMode(1, SPECIAL);
pinMode(3, SPECIAL);
uart->rxEnabled = true;
uart->txEnabled = true;
uart->rxPin = 3;
uart->txPin = 1;
uart->rxEnabled = (mode != SERIAL_TX_ONLY);
uart->txEnabled = (mode != SERIAL_RX_ONLY);
uart->rxPin = (uart->rxEnabled)?3:255;
uart->txPin = (uart->txEnabled)?1:255;
if(uart->rxEnabled) pinMode(uart->rxPin, SPECIAL);
if(uart->txEnabled) pinMode(uart->txPin, SPECIAL);
break;
case UART1:
pinMode(2, SPECIAL);
uart->rxEnabled = false;
uart->txEnabled = true;
uart->txEnabled = (mode != SERIAL_RX_ONLY);
uart->rxPin = 255;
uart->txPin = 2;
uart->txPin = (uart->txEnabled)?2:255;
if(uart->txEnabled) pinMode(uart->txPin, SPECIAL);
break;
case UART_NO:
default:
// big fail!
break;
os_free(uart);
return 0;
}
uart_set_baudrate(uart, baudrate);
USC0(uart->uart_nr) = config;
@@ -356,22 +357,30 @@ void uart_swap(uart_t* uart) {
return;
switch(uart->uart_nr) {
case UART0:
if(uart->txPin == 1 && uart->rxPin == 3) {
pinMode(15, FUNCTION_4); //TX
pinMode(13, FUNCTION_4); //RX
if((uart->txPin == 1 && uart->txEnabled) || (uart->rxPin == 3 && uart->rxEnabled)) {
if(uart->txEnabled) pinMode(15, FUNCTION_4); //TX
if(uart->rxEnabled) pinMode(13, FUNCTION_4); //RX
IOSWAP |= (1 << IOSWAPU0);
pinMode(1, INPUT); //TX
pinMode(3, INPUT); //RX
uart->rxPin = 13;
uart->txPin = 15;
if(uart->txEnabled){ //TX
pinMode(1, INPUT);
uart->txPin = 15;
}
if(uart->rxEnabled){ //RX
pinMode(3, INPUT);
uart->rxPin = 13;
}
} else {
pinMode(1, SPECIAL); //TX
pinMode(3, SPECIAL); //RX
if(uart->txEnabled) pinMode(1, SPECIAL); //TX
if(uart->rxEnabled) pinMode(3, SPECIAL); //RX
IOSWAP &= ~(1 << IOSWAPU0);
pinMode(15, INPUT); //TX
pinMode(13, INPUT); //RX
uart->rxPin = 3;
uart->txPin = 1;
if(uart->txEnabled){ //TX
pinMode(15, INPUT);
uart->txPin = 1;
}
if(uart->rxEnabled){ //RX
pinMode(13, INPUT); //RX
uart->rxPin = 3;
}
}
break;
@@ -471,14 +480,14 @@ HardwareSerial::HardwareSerial(int uart_nr) :
_uart_nr(uart_nr), _uart(0), _tx_buffer(0), _rx_buffer(0), _written(false) {
}
void HardwareSerial::begin(unsigned long baud, byte config) {
void HardwareSerial::begin(unsigned long baud, byte config, byte mode) {
// disable debug for this interface
if(uart_get_debug() == _uart_nr) {
uart_set_debug(UART_NO);
}
_uart = uart_init(_uart_nr, baud, config);
_uart = uart_init(_uart_nr, baud, config, mode);
if(_uart == 0) {
return;
@@ -518,7 +527,10 @@ void HardwareSerial::setDebugOutput(bool en) {
if(_uart == 0)
return;
if(en) {
uart_set_debug(_uart->uart_nr);
if(_uart->txEnabled)
uart_set_debug(_uart->uart_nr);
else
uart_set_debug(UART_NO);
} else {
// disable debug for this interface
if(uart_get_debug() == _uart_nr) {

View File

@@ -60,6 +60,10 @@
#define SERIAL_7O2 0x3b
#define SERIAL_8O2 0x3f
#define SERIAL_FULL 0
#define SERIAL_RX_ONLY 1
#define SERIAL_TX_ONLY 2
class cbuf;
struct uart_;
@@ -70,9 +74,12 @@ class HardwareSerial: public Stream {
HardwareSerial(int uart_nr);
void begin(unsigned long baud) {
begin(baud, SERIAL_8N1);
begin(baud, SERIAL_8N1, SERIAL_FULL);
}
void begin(unsigned long, uint8_t);
void begin(unsigned long baud, uint8_t config) {
begin(baud, config, SERIAL_FULL);
}
void begin(unsigned long, uint8_t, uint8_t);
void end();
void swap(); //toggle between use of GPIO13/GPIO15 or GPIO3/GPIO1 as RX and TX
int available(void) override;

View File

@@ -0,0 +1,223 @@
/*
i2s.c - Software I2S library for esp8266
Code taken and reworked from espessif's I2S example
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 "Arduino.h"
#include "osapi.h"
#include "ets_sys.h"
#include "i2s_reg.h"
#include "i2s.h"
extern void ets_wdt_enable(void);
extern void ets_wdt_disable(void);
#define SLC_BUF_CNT (8) //Number of buffers in the I2S circular buffer
#define SLC_BUF_LEN (64) //Length of one buffer, in 32-bit words.
//We use a queue to keep track of the DMA buffers that are empty. The ISR will push buffers to the back of the queue,
//the mp3 decode will pull them from the front and fill them. For ease, the queue will contain *pointers* to the DMA
//buffers, not the data itself. The queue depth is one smaller than the amount of buffers we have, because there's
//always a buffer that is being used by the DMA subsystem *right now* and we don't want to be able to write to that
//simultaneously.
struct slc_queue_item {
uint32 blocksize:12;
uint32 datalen:12;
uint32 unused:5;
uint32 sub_sof:1;
uint32 eof:1;
uint32 owner:1;
uint32 buf_ptr;
uint32 next_link_ptr;
};
static uint32_t i2s_slc_queue[SLC_BUF_CNT-1];
static uint8_t i2s_slc_queue_len;
static uint32_t *i2s_slc_buf_pntr[SLC_BUF_CNT]; //Pointer to the I2S DMA buffer data
static struct slc_queue_item i2s_slc_items[SLC_BUF_CNT]; //I2S DMA buffer descriptors
uint32_t ICACHE_FLASH_ATTR i2s_slc_queue_next_item(){ //pop the top off the queue
uint8_t i;
uint32_t item = i2s_slc_queue[0];
i2s_slc_queue_len--;
for(i=0;i<i2s_slc_queue_len;i++)
i2s_slc_queue[i] = i2s_slc_queue[i+1];
return item;
}
//This routine is called as soon as the DMA routine has something to tell us. All we
//handle here is the RX_EOF_INT status, which indicate the DMA has sent a buffer whose
//descriptor has the 'EOF' field set to 1.
void ICACHE_FLASH_ATTR i2s_slc_isr(void) {
uint32_t slc_intr_status = SLCIS;
SLCIC = 0xFFFFFFFF;
if (slc_intr_status & SLCIRXEOF) {
ETS_SLC_INTR_DISABLE();
struct slc_queue_item *finished_item = (struct slc_queue_item*)SLCRXEDA;
if (i2s_slc_queue_len >= SLC_BUF_CNT-1) { //All buffers are empty. This means we have an underflow
i2s_slc_queue_next_item(); //free space for finished_item
}
i2s_slc_queue[i2s_slc_queue_len++] = finished_item->buf_ptr;
ETS_SLC_INTR_ENABLE();
}
}
void ICACHE_FLASH_ATTR i2s_slc_begin(){
i2s_slc_queue_len = 0;
int x, y;
for (x=0; x<SLC_BUF_CNT; x++) {
i2s_slc_buf_pntr[x] = malloc(SLC_BUF_LEN*4);
for (y=0; y<SLC_BUF_LEN; y++) i2s_slc_buf_pntr[x][y] = 0;
i2s_slc_items[x].unused = 0;
i2s_slc_items[x].owner = 1;
i2s_slc_items[x].eof = 1;
i2s_slc_items[x].sub_sof = 0;
i2s_slc_items[x].datalen = SLC_BUF_LEN*4;
i2s_slc_items[x].blocksize = SLC_BUF_LEN*4;
i2s_slc_items[x].buf_ptr = (uint32_t)&i2s_slc_buf_pntr[x][0];
i2s_slc_items[x].next_link_ptr = (int)((x<(SLC_BUF_CNT-1))?(&i2s_slc_items[x+1]):(&i2s_slc_items[0]));
}
ETS_SLC_INTR_DISABLE();
SLCC0 |= SLCRXLR | SLCTXLR;
SLCC0 &= ~(SLCRXLR | SLCTXLR);
SLCIC = 0xFFFFFFFF;
//Configure DMA
SLCC0 &= ~(SLCMM << SLCM); //clear DMA MODE
SLCC0 |= (1 << SLCM); //set DMA MODE to 1
SLCRXDC |= SLCBINR | SLCBTNR; //enable INFOR_NO_REPLACE and TOKEN_NO_REPLACE
SLCRXDC &= ~(SLCBRXFE | SLCBRXEM | SLCBRXFM); //disable RX_FILL, RX_EOF_MODE and RX_FILL_MODE
//Feed DMA the 1st buffer desc addr
//To send data to the I2S subsystem, counter-intuitively we use the RXLINK part, not the TXLINK as you might
//expect. The TXLINK part still needs a valid DMA descriptor, even if it's unused: the DMA engine will throw
//an error at us otherwise. Just feed it any random descriptor.
SLCTXL &= ~(SLCTXLAM << SLCTXLA); // clear TX descriptor address
SLCTXL |= (uint32)&i2s_slc_items[1] << SLCTXLA; //set TX descriptor address. any random desc is OK, we don't use TX but it needs to be valid
SLCRXL &= ~(SLCRXLAM << SLCRXLA); // clear RX descriptor address
SLCRXL |= (uint32)&i2s_slc_items[0] << SLCRXLA; //set RX descriptor address
ETS_SLC_INTR_ATTACH(i2s_slc_isr, NULL);
SLCIE = SLCIRXEOF; //Enable only for RX EOF interrupt
ETS_SLC_INTR_ENABLE();
//Start transmission
SLCTXL |= SLCTXLS;
SLCRXL |= SLCRXLS;
}
void ICACHE_FLASH_ATTR i2s_slc_end(){
ETS_SLC_INTR_DISABLE();
SLCIC = 0xFFFFFFFF;
SLCIE = 0;
SLCTXL &= ~(SLCTXLAM << SLCTXLA); // clear TX descriptor address
SLCRXL &= ~(SLCRXLAM << SLCRXLA); // clear RX descriptor address
}
//This routine pushes a single, 32-bit sample to the I2S buffers. Call this at (on average)
//at least the current sample rate. You can also call it quicker: it will suspend the calling
//thread if the buffer is full and resume when there's room again.
static uint32_t *i2s_curr_slc_buf=NULL;
static int i2s_curr_slc_buf_pos=0;
bool ICACHE_FLASH_ATTR i2s_write_sample(uint32_t sample) {
if (i2s_curr_slc_buf_pos==SLC_BUF_LEN || i2s_curr_slc_buf==NULL) {
if(i2s_slc_queue_len == 0){
while(1){
if(i2s_slc_queue_len > 0){
break;
} else {
ets_wdt_disable();
ets_wdt_enable();
}
}
}
ETS_SLC_INTR_DISABLE();
i2s_curr_slc_buf = (uint32_t *)i2s_slc_queue_next_item();
ETS_SLC_INTR_ENABLE();
i2s_curr_slc_buf_pos=0;
}
i2s_curr_slc_buf[i2s_curr_slc_buf_pos++]=sample;
return true;
}
bool ICACHE_FLASH_ATTR i2s_write_lr(int16_t left, int16_t right){
int sample = right & 0xFFFF;
sample = sample << 16;
sample |= left & 0xFFFF;
return i2s_write_sample(sample);
}
// END DMA
// =========
// START I2S
static uint32_t _i2s_sample_rate;
void ICACHE_FLASH_ATTR i2s_set_rate(uint32_t rate){ //Rate in HZ
if(rate == _i2s_sample_rate) return;
_i2s_sample_rate = rate;
uint32_t i2s_clock_div = (I2SBASEFREQ/(_i2s_sample_rate*32)) & I2SCDM;
uint8_t i2s_bck_div = (I2SBASEFREQ/(_i2s_sample_rate*i2s_clock_div*2)) & I2SBDM;
//os_printf("Rate %u Div %u Bck %u Frq %u\n", _i2s_sample_rate, i2s_clock_div, i2s_bck_div, I2SBASEFREQ/(i2s_clock_div*i2s_bck_div*2));
//!trans master, !bits mod, rece slave mod, rece msb shift, right first, msb right
I2SC &= ~(I2STSM | (I2SBMM << I2SBM) | (I2SBDM << I2SBD) | (I2SCDM << I2SCD));
I2SC |= I2SRF | I2SMR | I2SRSM | I2SRMS | ((i2s_bck_div-1) << I2SBD) | ((i2s_clock_div-1) << I2SCD);
}
void ICACHE_FLASH_ATTR i2s_begin(){
_i2s_sample_rate = 0;
i2s_slc_begin();
pinMode(2, FUNCTION_1); //I2SO_WS (LRCK)
pinMode(3, FUNCTION_1); //I2SO_DATA (SDIN)
pinMode(15, FUNCTION_1); //I2SO_BCK (SCLK)
I2S_CLK_ENABLE();
I2SIC = 0x3F;
I2SIE = 0;
//Reset I2S
I2SC &= ~(I2SRST);
I2SC |= I2SRST;
I2SC &= ~(I2SRST);
I2SFC &= ~(I2SDE | (I2STXFMM << I2STXFM) | (I2SRXFMM << I2SRXFM)); //Set RX/TX FIFO_MOD=0 and disable DMA (FIFO only)
I2SFC |= I2SDE; //Enable DMA
I2SCC &= ~((I2STXCMM << I2STXCM) | (I2SRXCMM << I2SRXCM)); //Set RX/TX CHAN_MOD=0
i2s_set_rate(44100);
I2SC |= I2STXS; //Start transmission
}
void ICACHE_FLASH_ATTR i2s_end(){
i2s_slc_end();
pinMode(2, INPUT);
pinMode(3, INPUT);
pinMode(15, INPUT);
}

View File

@@ -27,6 +27,11 @@
#define ESP8266_DREG(addr) *((volatile uint32_t *)(0x3FF00000+(addr)))
#define ESP8266_CLOCK 80000000UL
#define i2c_readReg_Mask(block, host_id, reg_add, Msb, Lsb) rom_i2c_readReg_Mask(block, host_id, reg_add, Msb, Lsb)
#define i2c_readReg_Mask_def(block, reg_add) i2c_readReg_Mask(block, block##_hostid, reg_add, reg_add##_msb, reg_add##_lsb)
#define i2c_writeReg_Mask(block, host_id, reg_add, Msb, Lsb, indata) rom_i2c_writeReg_Mask(block, host_id, reg_add, Msb, Lsb, indata)
#define i2c_writeReg_Mask_def(block, reg_add, indata) i2c_writeReg_Mask(block, block##_hostid, reg_add, reg_add##_msb, reg_add##_lsb, indata)
//CPU Register
#define CPU2X ESP8266_DREG(0x14) //when bit 0 is set, F_CPU = 160MHz
@@ -77,9 +82,6 @@
#define GPCD 2 //DRIVER 0:normal,1:open drain
#define GPCS 0 //SOURCE 0:GPIO_DATA,1:SigmaDelta
extern uint8_t esp8266_gpioToFn[16];
#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)
@@ -99,6 +101,9 @@ extern uint8_t esp8266_gpioToFn[16];
#define GPF14 ESP8266_REG(0x80C)
#define GPF15 ESP8266_REG(0x810)
extern uint8_t esp8266_gpioToFn[16];
#define GPF(p) ESP8266_REG(0x800 + esp8266_gpioToFn[(p & 0xF)])
//GPIO (0-15) PIN Function Bits
#define GPFSOE 0 //Sleep OE
#define GPFSS 1 //Sleep Sel
@@ -579,4 +584,254 @@ extern uint8_t esp8266_gpioToFn[16];
#define SPIE2IHEN 0x3 //SPI_INT_HOLD_ENA
#define SPIE2IHEN_S 0 //SPI_INT_HOLD_ENA_S
//SLC (DMA) Registers
#define SLCC0 ESP8266_REG(0xB00) //SLC_CONF0
#define SLCIR ESP8266_REG(0xB04) //SLC_INT_RAW
#define SLCIS ESP8266_REG(0xB08) //SLC_INT_STATUS
#define SLCIE ESP8266_REG(0xB0C) //SLC_INT_ENA
#define SLCIC ESP8266_REG(0xB10) //SLC_INT_CLR
#define SLCRXS ESP8266_REG(0xB14) //SLC_RX_STATUS
#define SLCRXP ESP8266_REG(0xB18) //SLC_RX_FIFO_PUSH
#define SLCTXS ESP8266_REG(0xB1C) //SLC_TX_STATUS
#define SLCTXP ESP8266_REG(0xB20) //SLC_TX_FIFO_POP
#define SLCRXL ESP8266_REG(0xB24) //SLC_RX_LINK
#define SLCTXL ESP8266_REG(0xB28) //SLC_TX_LINK
#define SLCIVTH ESP8266_REG(0xB2C) //SLC_INTVEC_TOHOST
#define SLCT0 ESP8266_REG(0xB30) //SLC_TOKEN0
#define SLCT1 ESP8266_REG(0xB34) //SLC_TOKEN1
#define SLCC1 ESP8266_REG(0xB38) //SLC_CONF1
#define SLCS0 ESP8266_REG(0xB3C) //SLC_STATE0
#define SLCS1 ESP8266_REG(0xB40) //SLC_STATE1
#define SLCBC ESP8266_REG(0xB44) //SLC_BRIDGE_CONF
#define SLCRXEDA ESP8266_REG(0xB48) //SLC_RX_EOF_DES_ADDR
#define SLCTXEDA ESP8266_REG(0xB4C) //SLC_TX_EOF_DES_ADDR
#define SLCRXEBDA ESP8266_REG(0xB50) //SLC_RX_EOF_BFR_DES_ADDR
#define SLCAT ESP8266_REG(0xB54) //SLC_AHB_TEST
#define SLCSS ESP8266_REG(0xB58) //SLC_SDIO_ST
#define SLCRXDC ESP8266_REG(0xB5C) //SLC_RX_DSCR_CONF
#define SLCTXD ESP8266_REG(0xB60) //SLC_TXLINK_DSCR
#define SLCTXDB0 ESP8266_REG(0xB64) //SLC_TXLINK_DSCR_BF0
#define SLCTXDB1 ESP8266_REG(0xB68) //SLC_TXLINK_DSCR_BF1
#define SLCRXD ESP8266_REG(0xB6C) //SLC_RXLINK_DSCR
#define SLCRXDB0 ESP8266_REG(0xB70) //SLC_RXLINK_DSCR_BF0
#define SLCRXDB1 ESP8266_REG(0xB74) //SLC_RXLINK_DSCR_BF1
#define SLCDT ESP8266_REG(0xB78) //SLC_DATE
#define SLCID ESP8266_REG(0xB7C) //SLC_ID
#define SLCHIR ESP8266_REG(0xB88) //SLC_HOST_INTR_RAW
#define SLCHC0 ESP8266_REG(0xB94) //SLC_HOST_CONF_W0
#define SLCHC1 ESP8266_REG(0xB98) //SLC_HOST_CONF_W1
#define SLCHIS ESP8266_REG(0xB9C) //SLC_HOST_INTR_ST
#define SLCHC2 ESP8266_REG(0xBA0) //SLC_HOST_CONF_W2
#define SLCHC3 ESP8266_REG(0xBA4) //SLC_HOST_CONF_W3
#define SLCHC4 ESP8266_REG(0xBA8) //SLC_HOST_CONF_W4
#define SLCHIC ESP8266_REG(0xBB0) //SLC_HOST_INTR_CLR
#define SLCHIE ESP8266_REG(0xBB4) //SLC_HOST_INTR_ENA
#define SLCHC5 ESP8266_REG(0xBBC) //SLC_HOST_CONF_W5
//SLC (DMA) CONF0
#define SLCMM (0x3) //SLC_MODE
#define SLCM (12) //SLC_MODE_S
#define SLCDTBE (1 << 9) //SLC_DATA_BURST_EN
#define SLCDBE (1 << 8) //SLC_DSCR_BURST_EN
#define SLCRXNRC (1 << 7) //SLC_RX_NO_RESTART_CLR
#define SLCRXAW (1 << 6) //SLC_RX_AUTO_WRBACK
#define SLCRXLT (1 << 5) //SLC_RX_LOOP_TEST
#define SLCTXLT (1 << 4) //SLC_TX_LOOP_TEST
#define SLCAR (1 << 3) //SLC_AHBM_RST
#define SLCAFR (1 << 2) //SLC_AHBM_FIFO_RST
#define SLCRXLR (1 << 1) //SLC_RXLINK_RST
#define SLCTXLR (1 << 0) //SLC_TXLINK_RST
//SLC (DMA) INT
#define SLCITXDE (1 << 21) //SLC_TX_DSCR_EMPTY_INT
#define SLCIRXDER (1 << 20) //SLC_RX_DSCR_ERR_INT
#define SLCITXDER (1 << 19) //SLC_TX_DSCR_ERR_INT
#define SLCITH (1 << 18) //SLC_TOHOST_INT
#define SLCIRXEOF (1 << 17) //SLC_RX_EOF_INT
#define SLCIRXD (1 << 16) //SLC_RX_DONE_INT
#define SLCITXEOF (1 << 15) //SLC_TX_EOF_INT
#define SLCITXD (1 << 14) //SLC_TX_DONE_INT
#define SLCIT0 (1 << 13) //SLC_TOKEN1_1TO0_INT
#define SLCIT1 (1 << 12) //SLC_TOKEN0_1TO0_INT
#define SLCITXO (1 << 11) //SLC_TX_OVF_INT
#define SLCIRXU (1 << 10) //SLC_RX_UDF_INT
#define SLCITXS (1 << 9) //SLC_TX_START_INT
#define SLCIRXS (1 << 8) //SLC_RX_START_INT
#define SLCIFH7 (1 << 7) //SLC_FRHOST_BIT7_INT
#define SLCIFH6 (1 << 6) //SLC_FRHOST_BIT6_INT
#define SLCIFH5 (1 << 5) //SLC_FRHOST_BIT5_INT
#define SLCIFH4 (1 << 4) //SLC_FRHOST_BIT4_INT
#define SLCIFH3 (1 << 3) //SLC_FRHOST_BIT3_INT
#define SLCIFH2 (1 << 2) //SLC_FRHOST_BIT2_INT
#define SLCIFH1 (1 << 1) //SLC_FRHOST_BIT1_INT
#define SLCIFH0 (1 << 0) //SLC_FRHOST_BIT0_INT
//SLC (DMA) RX_STATUS
#define SLCRXE (1 << 1) //SLC_RX_EMPTY
#define SLCRXF (1 << 0) //SLC_RX_FULL
//SLC (DMA) TX_STATUS
#define SLCTXE (1 << 1) //SLC_TX_EMPTY
#define SLCTXF (1 << 0) //SLC_TX_FULL
//SLC (DMA) RX_FIFO_PUSH
#define SLCRXFP (1 << 16) //SLC_RXFIFO_PUSH
#define SLCRXWDM (0x1FF) //SLC_RXFIFO_WDATA
#define SLCRXWD (0) //SLC_RXFIFO_WDATA_S
//SLC (DMA) TX_FIFO_POP
#define SLCTXFP (1 << 16) //SLC_TXFIFO_POP
#define SLCTXRDM (0x7FF) //SLC_TXFIFO_RDATA
#define SLCTXRD (0) //SLC_TXFIFO_RDATA_S
//SLC (DMA) RX_LINK
#define SLCRXLP (1 << 31) //SLC_RXLINK_PARK
#define SLCRXLRS (1 << 30) //SLC_RXLINK_RESTART
#define SLCRXLS (1 << 29) //SLC_RXLINK_START
#define SLCRXLE (1 << 28) //SLC_RXLINK_STOP
#define SLCRXLAM (0xFFFF) //SLC_RXLINK_DESCADDR_MASK
#define SLCRXLA (0) //SLC_RXLINK_ADDR_S
//SLC (DMA) TX_LINK
#define SLCTXLP (1 << 31) //SLC_TXLINK_PARK
#define SLCTXLRS (1 << 30) //SLC_TXLINK_RESTART
#define SLCTXLS (1 << 29) //SLC_TXLINK_START
#define SLCTXLE (1 << 28) //SLC_TXLINK_STOP
#define SLCTXLAM (0xFFFF) //SLC_TXLINK_DESCADDR_MASK
#define SLCTXLA (0) //SLC_TXLINK_ADDR_S
//SLC (DMA) TOKENx
#define SLCTM (0xFFF) //SLC_TOKENx_MASK
#define SLCTT (16) //SLC_TOKENx_S
#define SLCTIM (1 << 14) //SLC_TOKENx_LOCAL_INC_MORE
#define SLCTI (1 << 13) //SLC_TOKENx_LOCAL_INC
#define SLCTW (1 << 12) //SLC_TOKENx_LOCAL_WR
#define SLCTDM (0xFFF) //SLC_TOKENx_LOCAL_WDATA
#define SLCTD (0) //SLC_TOKENx_LOCAL_WDATA_S
//SLC (DMA) BRIDGE_CONF
#define SLCBFMEM (0xF) //SLC_FIFO_MAP_ENA
#define SLCBFME (8) //SLC_FIFO_MAP_ENA_S
#define SLCBTEEM (0x3F) //SLC_TXEOF_ENA
#define SLCBTEE (0) //SLC_TXEOF_ENA_S
//SLC (DMA) AHB_TEST
#define SLCATAM (0x3) //SLC_AHB_TESTADDR
#define SLCATA (4) //SLC_AHB_TESTADDR_S
#define SLCATMM (0x7) //SLC_AHB_TESTMODE
#define SLCATM (0) //SLC_AHB_TESTMODE_S
//SLC (DMA) SDIO_ST
#define SLCSBM (0x7) //SLC_BUS_ST
#define SLCSB (12) //SLC_BUS_ST_S
#define SLCSW (1 << 8) //SLC_SDIO_WAKEUP
#define SLCSFM (0xF) //SLC_FUNC_ST
#define SLCSF (4) //SLC_FUNC_ST_S
#define SLCSCM (0x7) //SLC_CMD_ST
#define SLCSC (0) //SLC_CMD_ST_S
//SLC (DMA) RX_DSCR_CONF
#define SLCBRXFE (1 << 20) //SLC_RX_FILL_EN
#define SLCBRXEM (1 << 19) //SLC_RX_EOF_MODE
#define SLCBRXFM (1 << 18) //SLC_RX_FILL_MODE
#define SLCBINR (1 << 17) //SLC_INFOR_NO_REPLACE
#define SLCBTNR (1 << 16) //SLC_TOKEN_NO_REPLACE
#define SLCBPICM (0xFFFF) //SLC_POP_IDLE_CNT
#define SLCBPIC (0) //SLC_POP_IDLE_CNT_S
// I2S Registers
#define i2c_bbpll 0x67
#define i2c_bbpll_hostid 4
#define i2c_bbpll_en_audio_clock_out 4
#define i2c_bbpll_en_audio_clock_out_msb 7
#define i2c_bbpll_en_audio_clock_out_lsb 7
#define I2S_CLK_ENABLE() i2c_writeReg_Mask_def(i2c_bbpll, i2c_bbpll_en_audio_clock_out, 1)
#define I2SBASEFREQ (12000000L)
#define I2STXF ESP8266_REG(0xe00) //I2STXFIFO (32bit)
#define I2SRXF ESP8266_REG(0xe04) //I2SRXFIFO (32bit)
#define I2SC ESP8266_REG(0xe08) //I2SCONF
#define I2SIR ESP8266_REG(0xe0C) //I2SINT_RAW
#define I2SIS ESP8266_REG(0xe10) //I2SINT_ST
#define I2SIE ESP8266_REG(0xe14) //I2SINT_ENA
#define I2SIC ESP8266_REG(0xe18) //I2SINT_CLR
#define I2ST ESP8266_REG(0xe1C) //I2STIMING
#define I2SFC ESP8266_REG(0xe20) //I2S_FIFO_CONF
#define I2SRXEN ESP8266_REG(0xe24) //I2SRXEOF_NUM (32bit)
#define I2SCSD ESP8266_REG(0xe28) //I2SCONF_SIGLE_DATA (32bit)
#define I2SCC ESP8266_REG(0xe2C) //I2SCONF_CHAN
// I2S CONF
#define I2SBDM (0x3F) //I2S_BCK_DIV_NUM
#define I2SBD (22) //I2S_BCK_DIV_NUM_S
#define I2SCDM (0x3F) //I2S_CLKM_DIV_NUM
#define I2SCD (16) //I2S_CLKM_DIV_NUM_S
#define I2SBMM (0xF) //I2S_BITS_MOD
#define I2SBM (12) //I2S_BITS_MOD_S
#define I2SRMS (1 << 11) //I2S_RECE_MSB_SHIFT
#define I2STMS (1 << 10) //I2S_TRANS_MSB_SHIFT
#define I2SRXS (1 << 9) //I2S_I2S_RX_START
#define I2STXS (1 << 8) //I2S_I2S_TX_START
#define I2SMR (1 << 7) //I2S_MSB_RIGHT
#define I2SRF (1 << 6) //I2S_RIGHT_FIRST
#define I2SRSM (1 << 5) //I2S_RECE_SLAVE_MOD
#define I2STSM (1 << 4) //I2S_TRANS_SLAVE_MOD
#define I2SRXFR (1 << 3) //I2S_I2S_RX_FIFO_RESET
#define I2STXFR (1 << 2) //I2S_I2S_TX_FIFO_RESET
#define I2SRXR (1 << 1) //I2S_I2S_RX_RESET
#define I2STXR (1 << 0) //I2S_I2S_TX_RESET
#define I2SRST (0xF) //I2S_I2S_RESET_MASK
//I2S INT
#define I2SITXRE (1 << 5) //I2S_I2S_TX_REMPTY_INT
#define I2SITXWF (1 << 4) //I2S_I2S_TX_WFULL_INT
#define I2SIRXRE (1 << 3) //I2S_I2S_RX_REMPTY_INT
#define I2SIRXWF (1 << 2) //I2S_I2S_RX_WFULL_INT
#define I2SITXPD (1 << 1) //I2S_I2S_TX_PUT_DATA_INT
#define I2SIRXTD (1 << 0) //I2S_I2S_RX_TAKE_DATA_INT
//I2S TIMING
#define I2STBII (1 << 22) //I2S_TRANS_BCK_IN_INV
#define I2SRDS (1 << 21) //I2S_RECE_DSYNC_SW
#define I2STDS (1 << 20) //I2S_TRANS_DSYNC_SW
#define I2SRBODM (0x3) //I2S_RECE_BCK_OUT_DELAY
#define I2SRBOD (18) //I2S_RECE_BCK_OUT_DELAY_S
#define I2SRWODM (0x3) //I2S_RECE_WS_OUT_DELAY
#define I2SRWOD (16) //I2S_RECE_WS_OUT_DELAY_S
#define I2STSODM (0x3) //I2S_TRANS_SD_OUT_DELAY
#define I2STSOD (14) //I2S_TRANS_SD_OUT_DELAY_S
#define I2STWODM (0x3) //I2S_TRANS_WS_OUT_DELAY
#define I2STWOD (12) //I2S_TRANS_WS_OUT_DELAY_S
#define I2STBODM (0x3) //I2S_TRANS_BCK_OUT_DELAY
#define I2STBOD (10) //I2S_TRANS_BCK_OUT_DELAY_S
#define I2SRSIDM (0x3) //I2S_RECE_SD_IN_DELAY
#define I2SRSID (8) //I2S_RECE_SD_IN_DELAY_S
#define I2SRWIDM (0x3) //I2S_RECE_WS_IN_DELAY
#define I2SRWID (6) //I2S_RECE_WS_IN_DELAY_S
#define I2SRBIDM (0x3) //I2S_RECE_BCK_IN_DELAY
#define I2SRBID (4) //I2S_RECE_BCK_IN_DELAY_S
#define I2STWIDM (0x3) //I2S_TRANS_WS_IN_DELAY
#define I2STWID (2) //I2S_TRANS_WS_IN_DELAY_S
#define I2STBIDM (0x3) //I2S_TRANS_BCK_IN_DELAY
#define I2STBID (0) //I2S_TRANS_BCK_IN_DELAY_S
//I2S FIFO CONF
#define I2SRXFMM (0x7) //I2S_I2S_RX_FIFO_MOD
#define I2SRXFM (16) //I2S_I2S_RX_FIFO_MOD_S
#define I2STXFMM (0x7) //I2S_I2S_TX_FIFO_MOD
#define I2STXFM (13) //I2S_I2S_TX_FIFO_MOD_S
#define I2SDE (1 << 12) //I2S_I2S_DSCR_EN
#define I2STXDNM (0x3F) //I2S_I2S_TX_DATA_NUM
#define I2STXDN (6) //I2S_I2S_TX_DATA_NUM_S
#define I2SRXDNM (0x3F) //I2S_I2S_RX_DATA_NUM
#define I2SRXDN (0) //I2S_I2S_RX_DATA_NUM_S
//I2S CONF CHAN
#define I2SRXCMM (0x3) //I2S_RX_CHAN_MOD
#define I2SRXCM (3) //I2S_RX_CHAN_MOD_S
#define I2STXCMM (0x7) //I2S_TX_CHAN_MOD
#define I2STXCM (0) //I2S_TX_CHAN_MOD_S
#endif

53
cores/esp8266/i2s.h Normal file
View File

@@ -0,0 +1,53 @@
/*
i2s.h - Software I2S 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 I2S_h
#define I2S_h
/*
How does this work? Basically, to get sound, you need to:
- Connect an I2S codec to the I2S pins on the ESP.
- Start up a thread that's going to do the sound output
- Call i2s_begin()
- Call i2s_set_rate() with the sample rate you want.
- Generate sound and call i2s_write_sample() with 32-bit samples.
The 32bit samples basically are 2 16-bit signed values (the analog values for
the left and right channel) concatenated as (Rout<<16)+Lout
i2s_write_sample will block when you're sending data too quickly, so you can just
generate and push data as fast as you can and i2s_write_sample will regulate the
speed.
*/
#ifdef __cplusplus
extern "C" {
#endif
void i2s_begin();
void i2s_end();
void i2s_set_rate(uint32_t rate);
bool i2s_write_sample(uint32_t sample);
bool i2s_write_lr(int16_t left, int16_t right);
#ifdef __cplusplus
}
#endif
#endif

View File

@@ -173,6 +173,7 @@ void ESP8266WiFiClass::softAP(const char* ssid)
void ESP8266WiFiClass::softAP(const char* ssid, const char* passphrase, int channel)
{
_useApMode = true;
if(_useClientMode) {
// turn on AP+STA mode
mode(WIFI_AP_STA);

View File

@@ -41,9 +41,11 @@ extern "C" {
/* This is the aligned version of ip_addr_t,
used as local variable, on the stack, etc. */
#if !defined(IP2STR)
struct ip_addr {
u32_t addr;
};
#endif
/* This is the packed version of ip_addr_t,
used in network headers that are itself packed */
@@ -61,7 +63,9 @@ PACK_STRUCT_END
/** ip_addr_t uses a struct for convenience only, so that the same defines can
* operate both on ip_addr_t as well as on ip_addr_p_t. */
#if !defined(IP2STR)
typedef struct ip_addr ip_addr_t;
#endif
typedef struct ip_addr_packed ip_addr_p_t;
/*
@@ -93,11 +97,15 @@ extern const ip_addr_t ip_addr_broadcast;
#define IP_ADDR_BROADCAST ((ip_addr_t *)&ip_addr_broadcast)
/** 255.255.255.255 */
#if !defined(IPADDR_NONE)
#define IPADDR_NONE ((u32_t)0xffffffffUL)
#endif
/** 127.0.0.1 */
#define IPADDR_LOOPBACK ((u32_t)0x7f000001UL)
/** 0.0.0.0 */
#if !defined(IPADDR_ANY)
#define IPADDR_ANY ((u32_t)0x00000000UL)
#endif
/** 255.255.255.255 */
#define IPADDR_BROADCAST ((u32_t)0xffffffffUL)
@@ -134,6 +142,7 @@ extern const ip_addr_t ip_addr_broadcast;
#define IP_LOOPBACKNET 127 /* official! */
#if !defined(IP4_ADDR)
#if BYTE_ORDER == BIG_ENDIAN
/** Set an IP address given by the four byte-parts */
#define IP4_ADDR(ipaddr, a,b,c,d) \
@@ -150,6 +159,7 @@ extern const ip_addr_t ip_addr_broadcast;
((u32_t)((b) & 0xff) << 8) | \
(u32_t)((a) & 0xff)
#endif
#endif
/** MEMCPY-like copying of IP addresses where addresses are known to be
* 16-bit-aligned if the port is correctly configured (so a port could define
@@ -217,6 +227,7 @@ u8_t ip4_addr_netmask_valid(u32_t netmask)ICACHE_FLASH_ATTR;
ipaddr != NULL ? ip4_addr4_16(ipaddr) : 0))
/* Get one byte from the 4-byte address */
#if !defined(IP2STR)
#define ip4_addr1(ipaddr) (((u8_t*)(ipaddr))[0])
#define ip4_addr2(ipaddr) (((u8_t*)(ipaddr))[1])
#define ip4_addr3(ipaddr) (((u8_t*)(ipaddr))[2])
@@ -227,16 +238,20 @@ u8_t ip4_addr_netmask_valid(u32_t netmask)ICACHE_FLASH_ATTR;
#define ip4_addr2_16(ipaddr) ((u16_t)ip4_addr2(ipaddr))
#define ip4_addr3_16(ipaddr) ((u16_t)ip4_addr3(ipaddr))
#define ip4_addr4_16(ipaddr) ((u16_t)ip4_addr4(ipaddr))
#endif
/** For backwards compatibility */
#define ip_ntoa(ipaddr) ipaddr_ntoa(ipaddr)
#if !defined(IP2STR)
u32_t ipaddr_addr(const char *cp)ICACHE_FLASH_ATTR;
#endif
int ipaddr_aton(const char *cp, ip_addr_t *addr)ICACHE_FLASH_ATTR;
/** returns ptr to static buffer; not reentrant! */
char *ipaddr_ntoa(const ip_addr_t *addr)ICACHE_FLASH_ATTR;
char *ipaddr_ntoa_r(const ip_addr_t *addr, char *buf, int buflen)ICACHE_FLASH_ATTR;
#if !defined(IP2STR)
#define IP2STR(ipaddr) ip4_addr1_16(ipaddr), \
ip4_addr2_16(ipaddr), \
ip4_addr3_16(ipaddr), \
@@ -249,6 +264,7 @@ struct ip_info {
struct ip_addr netmask;
struct ip_addr gw;
};
#endif
#ifdef __cplusplus
}
#endif

View File

@@ -30,7 +30,7 @@ void TFT::TFTinit (void)
pinMode(4, OUTPUT);
pinMode(15, OUTPUT);
SPI.begin();
SPI.setClockDivider(2);
SPI.setClockDivider(SPI_CLOCK_DIV2);
TFT_CS_HIGH;
TFT_DC_HIGH;
@@ -570,4 +570,4 @@ INT8U TFT::drawFloat(float floatNumber,INT16U poX, INT16U poY,INT16U size,INT16U
TFT Tft=TFT();
/*********************************************************************************************************
END FILE
*********************************************************************************************************/
*********************************************************************************************************/

View File

@@ -55,6 +55,8 @@ TwoWire::TwoWire(){}
// Public Methods //////////////////////////////////////////////////////////////
void TwoWire::begin(int sda, int scl){
default_sda_pin = sda;
default_scl_pin = scl;
twi_init(sda, scl);
flush();
}

View File

@@ -10,17 +10,11 @@ struct ip_addr {
typedef struct ip_addr ip_addr_t;
struct ip_info {
struct ip_addr ip;
struct ip_addr netmask;
struct ip_addr gw;
ip_addr_t ip;
ip_addr_t netmask;
ip_addr_t gw;
};
#define IP4_ADDR(ipaddr, a,b,c,d) \
(ipaddr)->addr = ((uint32)((d) & 0xff) << 24) | \
((uint32)((c) & 0xff) << 16) | \
((uint32)((b) & 0xff) << 8) | \
(uint32)((a) & 0xff)
/**
* Determine if two address are on the same network.
*