Add analogRead, touchRead, dacWrite and updated esp-idf
This commit is contained in:
parent
48abb79ed3
commit
758553a786
183
cores/esp32/esp32-hal-adc.c
Normal file
183
cores/esp32/esp32-hal-adc.c
Normal file
@ -0,0 +1,183 @@
|
|||||||
|
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#include "esp32-hal-adc.h"
|
||||||
|
#include "freertos/FreeRTOS.h"
|
||||||
|
#include "freertos/task.h"
|
||||||
|
#include "rom/ets_sys.h"
|
||||||
|
#include "esp_attr.h"
|
||||||
|
#include "esp_intr.h"
|
||||||
|
#include "soc/rtc_io_reg.h"
|
||||||
|
#include "soc/rtc_cntl_reg.h"
|
||||||
|
#include "soc/sens_reg.h"
|
||||||
|
|
||||||
|
static uint8_t __analogAttenuation = 0;//0db
|
||||||
|
static uint8_t __analogWidth = 3;//12 bits
|
||||||
|
static uint8_t __analogCycles = 8;
|
||||||
|
static uint8_t __analogSamples = 0;//1 sample
|
||||||
|
static uint8_t __analogClockDiv = 1;
|
||||||
|
|
||||||
|
void __analogSetWidth(uint8_t bits){
|
||||||
|
if(bits < 9){
|
||||||
|
bits = 9;
|
||||||
|
} else if(bits > 12){
|
||||||
|
bits = 12;
|
||||||
|
}
|
||||||
|
__analogWidth = bits - 9;
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_START_FORCE_REG, SENS_SAR1_BIT_WIDTH, __analogWidth, SENS_SAR1_BIT_WIDTH_S);
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_READ_CTRL_REG, SENS_SAR1_SAMPLE_BIT, __analogWidth, SENS_SAR1_SAMPLE_BIT_S);
|
||||||
|
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_START_FORCE_REG, SENS_SAR2_BIT_WIDTH, __analogWidth, SENS_SAR2_BIT_WIDTH_S);
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_READ_CTRL2_REG, SENS_SAR2_SAMPLE_BIT, __analogWidth, SENS_SAR2_SAMPLE_BIT_S);
|
||||||
|
}
|
||||||
|
|
||||||
|
void __analogSetCycles(uint8_t cycles){
|
||||||
|
__analogCycles = cycles;
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_READ_CTRL_REG, SENS_SAR1_SAMPLE_CYCLE, __analogCycles, SENS_SAR1_SAMPLE_CYCLE_S);
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_READ_CTRL2_REG, SENS_SAR2_SAMPLE_CYCLE, __analogCycles, SENS_SAR2_SAMPLE_CYCLE_S);
|
||||||
|
}
|
||||||
|
|
||||||
|
void __analogSetSamples(uint8_t samples){
|
||||||
|
if(!samples){
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
__analogSamples = samples - 1;
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_READ_CTRL_REG, SENS_SAR1_SAMPLE_NUM, __analogSamples, SENS_SAR1_SAMPLE_NUM_S);
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_READ_CTRL2_REG, SENS_SAR2_SAMPLE_NUM, __analogSamples, SENS_SAR2_SAMPLE_NUM_S);
|
||||||
|
}
|
||||||
|
|
||||||
|
void __analogSetClockDiv(uint8_t clockDiv){
|
||||||
|
if(!clockDiv){
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
__analogClockDiv = clockDiv;
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_READ_CTRL_REG, SENS_SAR1_CLK_DIV, __analogClockDiv, SENS_SAR1_CLK_DIV_S);
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_READ_CTRL2_REG, SENS_SAR2_CLK_DIV, __analogClockDiv, SENS_SAR2_CLK_DIV_S);
|
||||||
|
}
|
||||||
|
|
||||||
|
void __analogSetAttenuation(uint8_t attenuation){
|
||||||
|
__analogAttenuation = attenuation & 3;
|
||||||
|
uint32_t att_data = 0;
|
||||||
|
int i = 8;
|
||||||
|
while(i--){
|
||||||
|
att_data |= __analogAttenuation << (i * 2);
|
||||||
|
}
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_MEAS_START1_REG, SENS_MEAS1_DATA_SAR, att_data, SENS_MEAS1_DATA_SAR_S);
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_MEAS_START2_REG, SENS_MEAS2_DATA_SAR, att_data, SENS_MEAS2_DATA_SAR_S);
|
||||||
|
}
|
||||||
|
|
||||||
|
void IRAM_ATTR __analogInit(){
|
||||||
|
static bool initialized = false;
|
||||||
|
if(initialized){
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
__analogSetAttenuation(__analogAttenuation);
|
||||||
|
__analogSetCycles(__analogCycles);
|
||||||
|
__analogSetSamples(__analogSamples + 1);//in samples
|
||||||
|
__analogSetClockDiv(__analogClockDiv);
|
||||||
|
__analogSetWidth(__analogWidth + 9);//in bits
|
||||||
|
|
||||||
|
SET_PERI_REG_MASK(SENS_SAR_READ_CTRL_REG, SENS_SAR1_DATA_INV);
|
||||||
|
SET_PERI_REG_MASK(SENS_SAR_READ_CTRL2_REG, SENS_SAR2_DATA_INV);
|
||||||
|
|
||||||
|
SET_PERI_REG_MASK(SENS_SAR_MEAS_START1_REG, SENS_MEAS1_START_FORCE_M); //SAR ADC1 controller (in RTC) is started by SW
|
||||||
|
SET_PERI_REG_MASK(SENS_SAR_MEAS_START1_REG, SENS_SAR1_EN_PAD_FORCE_M); //SAR ADC1 pad enable bitmap is controlled by SW
|
||||||
|
SET_PERI_REG_MASK(SENS_SAR_MEAS_START2_REG, SENS_MEAS2_START_FORCE_M); //SAR ADC2 controller (in RTC) is started by SW
|
||||||
|
SET_PERI_REG_MASK(SENS_SAR_MEAS_START2_REG, SENS_SAR2_EN_PAD_FORCE_M); //SAR ADC2 pad enable bitmap is controlled by SW
|
||||||
|
|
||||||
|
CLEAR_PERI_REG_MASK(SENS_SAR_MEAS_WAIT2_REG, SENS_FORCE_XPD_SAR_M); //force XPD_SAR=0, use XPD_FSM
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_MEAS_WAIT2_REG, SENS_FORCE_XPD_AMP, 0x2, SENS_FORCE_XPD_AMP_S); //force XPD_AMP=0
|
||||||
|
|
||||||
|
CLEAR_PERI_REG_MASK(SENS_SAR_MEAS_CTRL_REG, 0xfff << SENS_AMP_RST_FB_FSM_S); //clear FSM
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_MEAS_WAIT1_REG, SENS_SAR_AMP_WAIT1, 0x1, SENS_SAR_AMP_WAIT1_S);
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_MEAS_WAIT1_REG, SENS_SAR_AMP_WAIT2, 0x1, SENS_SAR_AMP_WAIT2_S);
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_MEAS_WAIT2_REG, SENS_SAR_AMP_WAIT3, 0x1, SENS_SAR_AMP_WAIT3_S);
|
||||||
|
while (GET_PERI_REG_BITS2(SENS_SAR_SLAVE_ADDR1_REG, 0x7, SENS_MEAS_STATUS_S) != 0); //wait det_fsm==
|
||||||
|
|
||||||
|
initialized = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t IRAM_ATTR __analogRead(uint8_t pin)
|
||||||
|
{
|
||||||
|
int8_t channel = digitalPinToAnalogChannel(pin);
|
||||||
|
if(channel < 0){
|
||||||
|
return 0;//not adc pin
|
||||||
|
}
|
||||||
|
int8_t pad = digitalPinToTouchChannel(pin);
|
||||||
|
|
||||||
|
if(pad >= 0){
|
||||||
|
uint32_t touch = READ_PERI_REG(SENS_SAR_TOUCH_ENABLE_REG);
|
||||||
|
if(touch & (1 << pad)){
|
||||||
|
touch &= ~((1 << (pad + SENS_TOUCH_PAD_OUTEN2_S))
|
||||||
|
| (1 << (pad + SENS_TOUCH_PAD_OUTEN1_S))
|
||||||
|
| (1 << (pad + SENS_TOUCH_PAD_WORKEN_S)));
|
||||||
|
WRITE_PERI_REG(SENS_SAR_TOUCH_ENABLE_REG, touch);
|
||||||
|
}
|
||||||
|
} else if(pin == 25){
|
||||||
|
CLEAR_PERI_REG_MASK(RTC_IO_PAD_DAC1_REG, RTC_IO_PDAC1_XPD_DAC | RTC_IO_PDAC1_DAC_XPD_FORCE);//stop dac1
|
||||||
|
} else if(pin == 26){
|
||||||
|
CLEAR_PERI_REG_MASK(RTC_IO_PAD_DAC2_REG, RTC_IO_PDAC2_XPD_DAC | RTC_IO_PDAC2_DAC_XPD_FORCE);//stop dac2
|
||||||
|
}
|
||||||
|
|
||||||
|
pinMode(pin, ANALOG);
|
||||||
|
|
||||||
|
__analogInit();
|
||||||
|
|
||||||
|
if(channel > 7){
|
||||||
|
channel -= 10;
|
||||||
|
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_MEAS_START2_REG, SENS_SAR2_EN_PAD, (1 << channel), SENS_SAR2_EN_PAD_S);
|
||||||
|
CLEAR_PERI_REG_MASK(SENS_SAR_MEAS_START2_REG, SENS_MEAS2_START_SAR_M);
|
||||||
|
SET_PERI_REG_MASK(SENS_SAR_MEAS_START2_REG, SENS_MEAS2_START_SAR_M);
|
||||||
|
while (GET_PERI_REG_MASK(SENS_SAR_MEAS_START2_REG, SENS_MEAS2_DONE_SAR) == 0) {}; //read done
|
||||||
|
return GET_PERI_REG_BITS2(SENS_SAR_MEAS_START2_REG, SENS_MEAS2_DATA_SAR, SENS_MEAS2_DATA_SAR_S);
|
||||||
|
}
|
||||||
|
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_MEAS_START1_REG, SENS_SAR1_EN_PAD, (1 << channel), SENS_SAR1_EN_PAD_S);
|
||||||
|
CLEAR_PERI_REG_MASK(SENS_SAR_MEAS_START1_REG, SENS_MEAS1_START_SAR_M);
|
||||||
|
SET_PERI_REG_MASK(SENS_SAR_MEAS_START1_REG, SENS_MEAS1_START_SAR_M);
|
||||||
|
while (GET_PERI_REG_MASK(SENS_SAR_MEAS_START1_REG, SENS_MEAS1_DONE_SAR) == 0) {}; //read done
|
||||||
|
return GET_PERI_REG_BITS2(SENS_SAR_MEAS_START1_REG, SENS_MEAS1_DATA_SAR, SENS_MEAS1_DATA_SAR_S);
|
||||||
|
}
|
||||||
|
int __hallRead() //hall sensor without LNA
|
||||||
|
{
|
||||||
|
int Sens_Vp0;
|
||||||
|
int Sens_Vn0;
|
||||||
|
int Sens_Vp1;
|
||||||
|
int Sens_Vn1;
|
||||||
|
|
||||||
|
pinMode(36, ANALOG);
|
||||||
|
pinMode(39, ANALOG);
|
||||||
|
SET_PERI_REG_MASK(SENS_SAR_TOUCH_CTRL1_REG, SENS_XPD_HALL_FORCE_M); // hall sens force enable
|
||||||
|
SET_PERI_REG_MASK(RTC_IO_HALL_SENS_REG, RTC_IO_XPD_HALL); // xpd hall
|
||||||
|
SET_PERI_REG_MASK(SENS_SAR_TOUCH_CTRL1_REG, SENS_HALL_PHASE_FORCE_M); // phase force
|
||||||
|
CLEAR_PERI_REG_MASK(RTC_IO_HALL_SENS_REG, RTC_IO_HALL_PHASE); // hall phase
|
||||||
|
Sens_Vp0 = __analogRead(36);
|
||||||
|
Sens_Vn0 = __analogRead(39);
|
||||||
|
SET_PERI_REG_MASK(RTC_IO_HALL_SENS_REG, RTC_IO_HALL_PHASE);
|
||||||
|
Sens_Vp1 = __analogRead(36);
|
||||||
|
Sens_Vn1 = __analogRead(39);
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_MEAS_WAIT2_REG, SENS_FORCE_XPD_SAR, 0, SENS_FORCE_XPD_SAR_S);
|
||||||
|
CLEAR_PERI_REG_MASK(SENS_SAR_TOUCH_CTRL1_REG, SENS_XPD_HALL_FORCE);
|
||||||
|
CLEAR_PERI_REG_MASK(SENS_SAR_TOUCH_CTRL1_REG, SENS_HALL_PHASE_FORCE);
|
||||||
|
return (Sens_Vp1 - Sens_Vp0) - (Sens_Vn1 - Sens_Vn0);
|
||||||
|
}
|
||||||
|
|
||||||
|
extern uint16_t analogRead(uint8_t pin) __attribute__ ((weak, alias("__analogRead")));
|
||||||
|
extern void analogSetWidth(uint8_t bits) __attribute__ ((weak, alias("__analogSetWidth")));
|
||||||
|
extern void analogSetCycles(uint8_t cycles) __attribute__ ((weak, alias("__analogSetCycles")));
|
||||||
|
extern void analogSetSamples(uint8_t samples) __attribute__ ((weak, alias("__analogSetSamples")));
|
||||||
|
extern void analogSetClockDiv(uint8_t clockDiv) __attribute__ ((weak, alias("__analogSetClockDiv")));
|
||||||
|
//extern void analogSetAttenuation(uint8_t attenuation) __attribute__ ((weak, alias("__analogSetAttenuation")));
|
||||||
|
extern int hallRead() __attribute__ ((weak, alias("__hallRead")));
|
74
cores/esp32/esp32-hal-adc.h
Normal file
74
cores/esp32/esp32-hal-adc.h
Normal file
@ -0,0 +1,74 @@
|
|||||||
|
/*
|
||||||
|
Arduino.h - Main include file for the Arduino SDK
|
||||||
|
Copyright (c) 2005-2013 Arduino Team. 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 MAIN_ESP32_HAL_ADC_H_
|
||||||
|
#define MAIN_ESP32_HAL_ADC_H_
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "esp32-hal.h"
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Get ADC value for pin
|
||||||
|
* */
|
||||||
|
uint16_t analogRead(uint8_t pin);
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Sets the sample bits (9 - 12)
|
||||||
|
* */
|
||||||
|
void analogSetWidth(uint8_t bits);
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Set number of cycles per sample
|
||||||
|
* Default is 8 and seems to do well
|
||||||
|
* Range is 1 - 255
|
||||||
|
* */
|
||||||
|
void analogSetCycles(uint8_t cycles);
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Set number of samples in the range.
|
||||||
|
* Default is 1
|
||||||
|
* Range is 1 - 255
|
||||||
|
* This setting splits the range into
|
||||||
|
* "samples" pieces, which could look
|
||||||
|
* like the sensitivity has been multiplied
|
||||||
|
* that many times
|
||||||
|
* */
|
||||||
|
void analogSetSamples(uint8_t samples);
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Set the divider for the ADC clock.
|
||||||
|
* Default is 1
|
||||||
|
* Range is 1 - 255
|
||||||
|
* */
|
||||||
|
void analogSetClockDiv(uint8_t clockDiv);
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Get value for HALL sensor (without LNA)
|
||||||
|
* connected to pins 36(SVP) and 39(SVN)
|
||||||
|
* */
|
||||||
|
int hallRead();
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* MAIN_ESP32_HAL_ADC_H_ */
|
54
cores/esp32/esp32-hal-dac.c
Normal file
54
cores/esp32/esp32-hal-dac.c
Normal file
@ -0,0 +1,54 @@
|
|||||||
|
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#include "esp32-hal-dac.h"
|
||||||
|
#include "freertos/FreeRTOS.h"
|
||||||
|
#include "freertos/task.h"
|
||||||
|
#include "rom/ets_sys.h"
|
||||||
|
#include "esp_attr.h"
|
||||||
|
#include "esp_intr.h"
|
||||||
|
#include "soc/rtc_io_reg.h"
|
||||||
|
#include "soc/rtc_cntl_reg.h"
|
||||||
|
#include "soc/sens_reg.h"
|
||||||
|
|
||||||
|
void IRAM_ATTR __dacWrite(uint8_t pin, uint8_t value)
|
||||||
|
{
|
||||||
|
if(pin < 25 || pin > 26){
|
||||||
|
return;//not dac pin
|
||||||
|
}
|
||||||
|
pinMode(pin, ANALOG);
|
||||||
|
uint8_t channel = pin - 25;
|
||||||
|
|
||||||
|
|
||||||
|
//Disable Tone
|
||||||
|
CLEAR_PERI_REG_MASK(SENS_SAR_DAC_CTRL1_REG, SENS_SW_TONE_EN);
|
||||||
|
|
||||||
|
if (channel) {
|
||||||
|
//Disable Channel Tone
|
||||||
|
CLEAR_PERI_REG_MASK(SENS_SAR_DAC_CTRL2_REG, SENS_DAC_CW_EN2_M);
|
||||||
|
//Set the Dac value
|
||||||
|
SET_PERI_REG_BITS(RTC_IO_PAD_DAC2_REG, RTC_IO_PDAC2_DAC, value, RTC_IO_PDAC2_DAC_S); //dac_output
|
||||||
|
//Channel output enable
|
||||||
|
SET_PERI_REG_MASK(RTC_IO_PAD_DAC2_REG, RTC_IO_PDAC2_XPD_DAC | RTC_IO_PDAC2_DAC_XPD_FORCE);
|
||||||
|
} else {
|
||||||
|
//Disable Channel Tone
|
||||||
|
CLEAR_PERI_REG_MASK(SENS_SAR_DAC_CTRL2_REG, SENS_DAC_CW_EN1_M);
|
||||||
|
//Set the Dac value
|
||||||
|
SET_PERI_REG_BITS(RTC_IO_PAD_DAC1_REG, RTC_IO_PDAC1_DAC, value, RTC_IO_PDAC1_DAC_S); //dac_output
|
||||||
|
//Channel output enable
|
||||||
|
SET_PERI_REG_MASK(RTC_IO_PAD_DAC1_REG, RTC_IO_PDAC1_XPD_DAC | RTC_IO_PDAC1_DAC_XPD_FORCE);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
extern void dacWrite(uint8_t pin, uint8_t value) __attribute__ ((weak, alias("__dacWrite")));
|
35
cores/esp32/esp32-hal-dac.h
Normal file
35
cores/esp32/esp32-hal-dac.h
Normal file
@ -0,0 +1,35 @@
|
|||||||
|
/*
|
||||||
|
Arduino.h - Main include file for the Arduino SDK
|
||||||
|
Copyright (c) 2005-2013 Arduino Team. 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 MAIN_ESP32_HAL_DAC_H_
|
||||||
|
#define MAIN_ESP32_HAL_DAC_H_
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "esp32-hal.h"
|
||||||
|
|
||||||
|
void dacWrite(uint8_t pin, uint8_t value);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* MAIN_ESP32_HAL_DAC_H_ */
|
@ -26,69 +26,97 @@
|
|||||||
|
|
||||||
#define ETS_GPIO_INUM 4
|
#define ETS_GPIO_INUM 4
|
||||||
|
|
||||||
typedef struct {
|
|
||||||
uint32_t mux; /*!< Register to modify various pin settings */
|
|
||||||
uint32_t pud; /*!< Register to modify to enable or disable pullups or pulldowns */
|
|
||||||
uint32_t pu; /*!< Bit to set or clear in the above register to enable or disable the pullup, respectively */
|
|
||||||
uint32_t pd; /*!< Bit to set or clear in the above register to enable or disable the pulldown, respectively */
|
|
||||||
} esp32_gpioMux_t;
|
|
||||||
|
|
||||||
const DRAM_ATTR esp32_gpioMux_t esp32_gpioMux[GPIO_PIN_COUNT]={
|
const DRAM_ATTR esp32_gpioMux_t esp32_gpioMux[GPIO_PIN_COUNT]={
|
||||||
{DR_REG_IO_MUX_BASE + 0x44, RTC_IO_TOUCH_PAD1_REG, RTC_IO_TOUCH_PAD1_RUE_M, RTC_IO_TOUCH_PAD1_RDE_M},
|
{0x44, 11, 11, 1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x88, 0, 0, 0},
|
{0x88, -1, -1, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x40, RTC_IO_TOUCH_PAD2_REG, RTC_IO_TOUCH_PAD2_RUE_M, RTC_IO_TOUCH_PAD2_RDE_M},
|
{0x40, 12, 12, 2},
|
||||||
{DR_REG_IO_MUX_BASE + 0x84, 0, 0, 0},
|
{0x84, -1, -1, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x48, RTC_IO_TOUCH_PAD0_REG, RTC_IO_TOUCH_PAD0_RUE_M, RTC_IO_TOUCH_PAD0_RDE_M},
|
{0x48, 10, 10, 0},
|
||||||
{DR_REG_IO_MUX_BASE + 0x6c, 0, 0, 0},
|
{0x6c, -1, -1, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x60, 0, 0, 0},
|
{0x60, -1, -1, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x64, 0, 0, 0},
|
{0x64, -1, -1, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x68, 0, 0, 0},
|
{0x68, -1, -1, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x54, 0, 0, 0},
|
{0x54, -1, -1, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x58, 0, 0, 0},
|
{0x58, -1, -1, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x5c, 0, 0, 0},
|
{0x5c, -1, -1, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x34, RTC_IO_TOUCH_PAD5_REG, RTC_IO_TOUCH_PAD5_RUE_M, RTC_IO_TOUCH_PAD5_RDE_M},
|
{0x34, 15, 15, 5},
|
||||||
{DR_REG_IO_MUX_BASE + 0x38, RTC_IO_TOUCH_PAD4_REG, RTC_IO_TOUCH_PAD4_RUE_M, RTC_IO_TOUCH_PAD4_RDE_M},
|
{0x38, 14, 14, 4},
|
||||||
{DR_REG_IO_MUX_BASE + 0x30, RTC_IO_TOUCH_PAD6_REG, RTC_IO_TOUCH_PAD6_RUE_M, RTC_IO_TOUCH_PAD6_RDE_M},
|
{0x30, 16, 16, 6},
|
||||||
{DR_REG_IO_MUX_BASE + 0x3c, RTC_IO_TOUCH_PAD3_REG, RTC_IO_TOUCH_PAD3_RUE_M, RTC_IO_TOUCH_PAD3_RDE_M},
|
{0x3c, 13, 13, 3},
|
||||||
{DR_REG_IO_MUX_BASE + 0x4c, 0, 0, 0},
|
{0x4c, -1, -1, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x50, 0, 0, 0},
|
{0x50, -1, -1, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x70, 0, 0, 0},
|
{0x70, -1, -1, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x74, 0, 0, 0},
|
{0x74, -1, -1, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x78, 0, 0, 0},
|
{0x78, -1, -1, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x7c, 0, 0, 0},
|
{0x7c, -1, -1, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x80, 0, 0, 0},
|
{0x80, -1, -1, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x8c, 0, 0, 0},
|
{0x8c, -1, -1, -1},
|
||||||
{0, 0, 0, 0},
|
{0, -1, -1, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x24, RTC_IO_PAD_DAC1_REG, RTC_IO_PDAC1_RUE_M, RTC_IO_PDAC1_RDE_M},
|
{0x24, 6, 18, -1}, //DAC1
|
||||||
{DR_REG_IO_MUX_BASE + 0x28, RTC_IO_PAD_DAC2_REG, RTC_IO_PDAC2_RUE_M, RTC_IO_PDAC2_RDE_M},
|
{0x28, 7, 19, -1}, //DAC2
|
||||||
{DR_REG_IO_MUX_BASE + 0x2c, RTC_IO_TOUCH_PAD7_REG, RTC_IO_TOUCH_PAD7_RUE_M, RTC_IO_TOUCH_PAD7_RDE_M},
|
{0x2c, 17, 17, 7},
|
||||||
{0, 0, 0, 0},
|
{0, -1, -1, -1},
|
||||||
{0, 0, 0, 0},
|
{0, -1, -1, -1},
|
||||||
{0, 0, 0, 0},
|
{0, -1, -1, -1},
|
||||||
{0, 0, 0, 0},
|
{0, -1, -1, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x1c, RTC_IO_XTAL_32K_PAD_REG, RTC_IO_X32P_RUE_M, RTC_IO_X32P_RDE_M},
|
{0x1c, 9, 4, 9},
|
||||||
{DR_REG_IO_MUX_BASE + 0x20, RTC_IO_XTAL_32K_PAD_REG, RTC_IO_X32N_RUE_M, RTC_IO_X32N_RDE_M},
|
{0x20, 8, 5, 8},
|
||||||
{DR_REG_IO_MUX_BASE + 0x14, 0, 0, 0},
|
{0x14, 4, 6, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x18, 0, 0, 0},
|
{0x18, 5, 7, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x04, 0, 0, 0},
|
{0x04, 0, 0, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x08, 0, 0, 0},
|
{0x08, 1, -1, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x0c, 0, 0, 0},
|
{0x0c, 2, -1, -1},
|
||||||
{DR_REG_IO_MUX_BASE + 0x10, 0, 0, 0}
|
{0x10, 3, 3, -1}
|
||||||
};
|
};
|
||||||
|
|
||||||
typedef void (*voidFuncPtr)(void);
|
typedef void (*voidFuncPtr)(void);
|
||||||
static voidFuncPtr __pinInterruptHandlers[GPIO_PIN_COUNT] = {0,};
|
static voidFuncPtr __pinInterruptHandlers[GPIO_PIN_COUNT] = {0,};
|
||||||
|
|
||||||
|
#include "driver/rtc_io.h"
|
||||||
|
|
||||||
extern void IRAM_ATTR __pinMode(uint8_t pin, uint8_t mode)
|
extern void IRAM_ATTR __pinMode(uint8_t pin, uint8_t mode)
|
||||||
{
|
{
|
||||||
|
|
||||||
if(pin > 39 || !esp32_gpioMux[pin].mux) {
|
if(!digitalPinIsValid(pin)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t pinFunction = 0, pinControl = 0;
|
uint32_t rtc_reg = rtc_gpio_desc[pin].reg;
|
||||||
const esp32_gpioMux_t * mux = &esp32_gpioMux[pin];
|
if(mode == ANALOG) {
|
||||||
|
if(!rtc_reg) {
|
||||||
|
return;//not rtc pin
|
||||||
|
}
|
||||||
|
//lock rtc
|
||||||
|
uint32_t reg_val = ESP_REG(rtc_reg);
|
||||||
|
if(reg_val & rtc_gpio_desc[pin].mux){
|
||||||
|
return;//already in adc mode
|
||||||
|
}
|
||||||
|
reg_val &= ~(
|
||||||
|
(RTC_IO_TOUCH_PAD1_FUN_SEL_V << rtc_gpio_desc[pin].func)
|
||||||
|
|rtc_gpio_desc[pin].ie
|
||||||
|
|rtc_gpio_desc[pin].pullup
|
||||||
|
|rtc_gpio_desc[pin].pulldown);
|
||||||
|
ESP_REG(RTC_GPIO_ENABLE_W1TC_REG) = (1 << (rtc_gpio_desc[pin].rtc_num + RTC_GPIO_ENABLE_W1TC_S));
|
||||||
|
ESP_REG(rtc_reg) = reg_val | rtc_gpio_desc[pin].mux;
|
||||||
|
//unlock rtc
|
||||||
|
ESP_REG(DR_REG_IO_MUX_BASE + esp32_gpioMux[pin].reg) = ((uint32_t)2 << MCU_SEL_S) | ((uint32_t)2 << FUN_DRV_S) | FUN_IE;
|
||||||
|
return;
|
||||||
|
} else if(rtc_reg) {
|
||||||
|
//lock rtc
|
||||||
|
ESP_REG(rtc_reg) = ESP_REG(rtc_reg) & ~(rtc_gpio_desc[pin].mux);
|
||||||
|
if(mode & PULLUP) {
|
||||||
|
ESP_REG(rtc_reg) = (ESP_REG(rtc_reg) | rtc_gpio_desc[pin].pullup) & ~(rtc_gpio_desc[pin].pulldown);
|
||||||
|
} else if(mode & PULLDOWN) {
|
||||||
|
ESP_REG(rtc_reg) = (ESP_REG(rtc_reg) | rtc_gpio_desc[pin].pulldown) & ~(rtc_gpio_desc[pin].pullup);
|
||||||
|
} else {
|
||||||
|
ESP_REG(rtc_reg) = ESP_REG(rtc_reg) & ~(rtc_gpio_desc[pin].pullup | rtc_gpio_desc[pin].pulldown);
|
||||||
|
}
|
||||||
|
//unlock rtc
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t pinFunction = 0, pinControl = 0;
|
||||||
|
|
||||||
|
//lock gpio
|
||||||
if(mode & INPUT) {
|
if(mode & INPUT) {
|
||||||
if(pin < 32) {
|
if(pin < 32) {
|
||||||
GPIO.enable_w1tc = ((uint32_t)1 << pin);
|
GPIO.enable_w1tc = ((uint32_t)1 << pin);
|
||||||
@ -102,7 +130,10 @@ extern void IRAM_ATTR __pinMode(uint8_t pin, uint8_t mode)
|
|||||||
pinFunction |= FUN_PD;
|
pinFunction |= FUN_PD;
|
||||||
}
|
}
|
||||||
} else if(mode & OUTPUT) {
|
} else if(mode & OUTPUT) {
|
||||||
if(pin < 32) {
|
if(pin > 33){
|
||||||
|
//unlock gpio
|
||||||
|
return;//pins above 33 can be only inputs
|
||||||
|
} else if(pin < 32) {
|
||||||
GPIO.enable_w1ts = ((uint32_t)1 << pin);
|
GPIO.enable_w1ts = ((uint32_t)1 << pin);
|
||||||
} else {
|
} else {
|
||||||
GPIO.enable1_w1ts.val = ((uint32_t)1 << (pin - 32));
|
GPIO.enable1_w1ts.val = ((uint32_t)1 << (pin - 32));
|
||||||
@ -120,25 +151,14 @@ extern void IRAM_ATTR __pinMode(uint8_t pin, uint8_t mode)
|
|||||||
pinFunction |= ((uint32_t)(mode >> 5) << MCU_SEL_S);
|
pinFunction |= ((uint32_t)(mode >> 5) << MCU_SEL_S);
|
||||||
}
|
}
|
||||||
|
|
||||||
ESP_REG(mux->mux) = pinFunction;
|
ESP_REG(DR_REG_IO_MUX_BASE + esp32_gpioMux[pin].reg) = pinFunction;
|
||||||
|
|
||||||
if(mux->pud){
|
|
||||||
if((mode & INPUT) && (mode & (PULLUP|PULLDOWN))) {
|
|
||||||
if(mode & PULLUP) {
|
|
||||||
ESP_REG(mux->pud) = (ESP_REG(mux->pud) | mux->pu) & ~(mux->pd);
|
|
||||||
} else {
|
|
||||||
ESP_REG(mux->pud) = (ESP_REG(mux->pud) | mux->pd) & ~(mux->pu);
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
ESP_REG(mux->pud) = ESP_REG(mux->pud) & ~(mux->pu | mux->pd);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if(mode & OPEN_DRAIN) {
|
if(mode & OPEN_DRAIN) {
|
||||||
pinControl = (1 << GPIO_PIN0_PAD_DRIVER_S);
|
pinControl = (1 << GPIO_PIN0_PAD_DRIVER_S);
|
||||||
}
|
}
|
||||||
|
|
||||||
GPIO.pin[pin].val = pinControl;
|
GPIO.pin[pin].val = pinControl;
|
||||||
|
//unlock gpio
|
||||||
}
|
}
|
||||||
|
|
||||||
extern void IRAM_ATTR __digitalWrite(uint8_t pin, uint8_t val)
|
extern void IRAM_ATTR __digitalWrite(uint8_t pin, uint8_t val)
|
||||||
@ -146,13 +166,13 @@ extern void IRAM_ATTR __digitalWrite(uint8_t pin, uint8_t val)
|
|||||||
if(val) {
|
if(val) {
|
||||||
if(pin < 32) {
|
if(pin < 32) {
|
||||||
GPIO.out_w1ts = ((uint32_t)1 << pin);
|
GPIO.out_w1ts = ((uint32_t)1 << pin);
|
||||||
} else if(pin < 35) {
|
} else if(pin < 34) {
|
||||||
GPIO.out1_w1ts.val = ((uint32_t)1 << (pin - 32));
|
GPIO.out1_w1ts.val = ((uint32_t)1 << (pin - 32));
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
if(pin < 32) {
|
if(pin < 32) {
|
||||||
GPIO.out_w1tc = ((uint32_t)1 << pin);
|
GPIO.out_w1tc = ((uint32_t)1 << pin);
|
||||||
} else if(pin < 35) {
|
} else if(pin < 34) {
|
||||||
GPIO.out1_w1tc.val = ((uint32_t)1 << (pin - 32));
|
GPIO.out1_w1tc.val = ((uint32_t)1 << (pin - 32));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -215,6 +235,7 @@ extern void __attachInterrupt(uint8_t pin, voidFuncPtr userFunc, int intr_type)
|
|||||||
ESP_INTR_ENABLE(ETS_GPIO_INUM);
|
ESP_INTR_ENABLE(ETS_GPIO_INUM);
|
||||||
}
|
}
|
||||||
__pinInterruptHandlers[pin] = userFunc;
|
__pinInterruptHandlers[pin] = userFunc;
|
||||||
|
//lock gpio
|
||||||
ESP_INTR_DISABLE(ETS_GPIO_INUM);
|
ESP_INTR_DISABLE(ETS_GPIO_INUM);
|
||||||
if(core_id) { //APP_CPU
|
if(core_id) { //APP_CPU
|
||||||
GPIO.pin[pin].int_ena = 1;
|
GPIO.pin[pin].int_ena = 1;
|
||||||
@ -223,15 +244,18 @@ extern void __attachInterrupt(uint8_t pin, voidFuncPtr userFunc, int intr_type)
|
|||||||
}
|
}
|
||||||
GPIO.pin[pin].int_type = intr_type;
|
GPIO.pin[pin].int_type = intr_type;
|
||||||
ESP_INTR_ENABLE(ETS_GPIO_INUM);
|
ESP_INTR_ENABLE(ETS_GPIO_INUM);
|
||||||
|
//unlock gpio
|
||||||
}
|
}
|
||||||
|
|
||||||
extern void __detachInterrupt(uint8_t pin)
|
extern void __detachInterrupt(uint8_t pin)
|
||||||
{
|
{
|
||||||
__pinInterruptHandlers[pin] = NULL;
|
//lock gpio
|
||||||
ESP_INTR_DISABLE(ETS_GPIO_INUM);
|
ESP_INTR_DISABLE(ETS_GPIO_INUM);
|
||||||
|
__pinInterruptHandlers[pin] = NULL;
|
||||||
GPIO.pin[pin].int_ena = 0;
|
GPIO.pin[pin].int_ena = 0;
|
||||||
GPIO.pin[pin].int_type = 0;
|
GPIO.pin[pin].int_type = 0;
|
||||||
ESP_INTR_ENABLE(ETS_GPIO_INUM);
|
ESP_INTR_ENABLE(ETS_GPIO_INUM);
|
||||||
|
//unlock gpio
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -39,11 +39,13 @@ extern "C" {
|
|||||||
#define OPEN_DRAIN 0x10
|
#define OPEN_DRAIN 0x10
|
||||||
#define OUTPUT_OPEN_DRAIN 0x12
|
#define OUTPUT_OPEN_DRAIN 0x12
|
||||||
#define SPECIAL 0xF0
|
#define SPECIAL 0xF0
|
||||||
#define FUNCTION_0 0x00
|
#define FUNCTION_1 0x00
|
||||||
#define FUNCTION_1 0x20
|
#define FUNCTION_2 0x20
|
||||||
#define FUNCTION_2 0x40
|
#define FUNCTION_3 0x40
|
||||||
#define FUNCTION_3 0x70
|
#define FUNCTION_4 0x60
|
||||||
#define FUNCTION_4 0x80
|
#define FUNCTION_5 0x80
|
||||||
|
#define FUNCTION_6 0xA0
|
||||||
|
#define ANALOG 0xC0
|
||||||
|
|
||||||
//Interrupt Modes
|
//Interrupt Modes
|
||||||
#define DISABLED 0x00
|
#define DISABLED 0x00
|
||||||
@ -55,6 +57,22 @@ extern "C" {
|
|||||||
#define ONLOW_WE 0x0C
|
#define ONLOW_WE 0x0C
|
||||||
#define ONHIGH_WE 0x0D
|
#define ONHIGH_WE 0x0D
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
uint8_t reg; /*!< GPIO register offset from DR_REG_IO_MUX_BASE */
|
||||||
|
int8_t rtc; /*!< RTC GPIO number (-1 if not RTC GPIO pin) */
|
||||||
|
int8_t adc; /*!< ADC Channel number (-1 if not ADC pin) */
|
||||||
|
int8_t touch; /*!< Touch Channel number (-1 if not Touch pin) */
|
||||||
|
} esp32_gpioMux_t;
|
||||||
|
|
||||||
|
extern const esp32_gpioMux_t esp32_gpioMux[40];
|
||||||
|
|
||||||
|
#define digitalPinIsValid(pin) ((pin) < 40 && esp32_gpioMux[(pin)].reg)
|
||||||
|
#define digitalPinCanOutput(pin) ((pin) < 34 && esp32_gpioMux[(pin)].reg)
|
||||||
|
#define digitalPinToRtcPin(pin) (((pin) < 40)?esp32_gpioMux[(pin)].rtc:-1)
|
||||||
|
#define digitalPinToAnalogChannel(pin) (((pin) < 40)?esp32_gpioMux[(pin)].adc:-1)
|
||||||
|
#define digitalPinToTouchChannel(pin) (((pin) < 40)?esp32_gpioMux[(pin)].touch:-1)
|
||||||
|
#define digitalPinToDacChannel(pin) (((pin) == 25)?0:((pin) == 26)?1:-1)
|
||||||
|
|
||||||
void pinMode(uint8_t pin, uint8_t mode);
|
void pinMode(uint8_t pin, uint8_t mode);
|
||||||
void digitalWrite(uint8_t pin, uint8_t val);
|
void digitalWrite(uint8_t pin, uint8_t val);
|
||||||
int digitalRead(uint8_t pin);
|
int digitalRead(uint8_t pin);
|
||||||
|
172
cores/esp32/esp32-hal-touch.c
Normal file
172
cores/esp32/esp32-hal-touch.c
Normal file
@ -0,0 +1,172 @@
|
|||||||
|
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#include "esp32-hal-touch.h"
|
||||||
|
#include "freertos/FreeRTOS.h"
|
||||||
|
#include "freertos/task.h"
|
||||||
|
#include "rom/ets_sys.h"
|
||||||
|
#include "esp_attr.h"
|
||||||
|
#include "esp_intr.h"
|
||||||
|
#include "soc/rtc_io_reg.h"
|
||||||
|
#include "soc/rtc_cntl_reg.h"
|
||||||
|
#include "soc/sens_reg.h"
|
||||||
|
|
||||||
|
#define RTC_TOUCH_INUM 5
|
||||||
|
|
||||||
|
static uint16_t __touchSleepCycles = 0x1000;
|
||||||
|
static uint16_t __touchMeasureCycles = 0x1000;
|
||||||
|
|
||||||
|
typedef void (*voidFuncPtr)(void);
|
||||||
|
static voidFuncPtr __touchInterruptHandlers[10] = {0,};
|
||||||
|
|
||||||
|
void IRAM_ATTR __touchISR(void * arg)
|
||||||
|
{
|
||||||
|
uint32_t pad_intr = READ_PERI_REG(SENS_SAR_TOUCH_CTRL2_REG) & 0x3ff;
|
||||||
|
uint32_t rtc_intr = READ_PERI_REG(RTC_CNTL_INT_ST_REG);
|
||||||
|
uint8_t i = 0;
|
||||||
|
//clear interrupt
|
||||||
|
WRITE_PERI_REG(RTC_CNTL_INT_CLR_REG, rtc_intr);
|
||||||
|
SET_PERI_REG_MASK(SENS_SAR_TOUCH_CTRL2_REG, SENS_TOUCH_MEAS_EN_CLR);
|
||||||
|
|
||||||
|
if (rtc_intr & RTC_CNTL_TOUCH_INT_ST) {
|
||||||
|
for (i = 0; i < 10; ++i) {
|
||||||
|
if ((pad_intr >> i) & 0x01) {
|
||||||
|
if(__touchInterruptHandlers[i]){
|
||||||
|
__touchInterruptHandlers[i]();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void __touchSetCycles(uint16_t measure, uint16_t sleep)
|
||||||
|
{
|
||||||
|
__touchSleepCycles = sleep;
|
||||||
|
__touchMeasureCycles = measure;
|
||||||
|
//Touch pad SleepCycle Time
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_TOUCH_CTRL2_REG, SENS_TOUCH_SLEEP_CYCLES, __touchSleepCycles, SENS_TOUCH_SLEEP_CYCLES_S);
|
||||||
|
//Touch Pad Measure Time
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_TOUCH_CTRL1_REG, SENS_TOUCH_MEAS_DELAY, __touchMeasureCycles, SENS_TOUCH_MEAS_DELAY_S);
|
||||||
|
}
|
||||||
|
|
||||||
|
void __touchInit()
|
||||||
|
{
|
||||||
|
static bool initialized = false;
|
||||||
|
if(initialized){
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
SET_PERI_REG_BITS(RTC_IO_TOUCH_CFG_REG, RTC_IO_TOUCH_XPD_BIAS, 1, RTC_IO_TOUCH_XPD_BIAS_S);
|
||||||
|
SET_PERI_REG_MASK(SENS_SAR_TOUCH_CTRL2_REG, SENS_TOUCH_MEAS_EN_CLR);
|
||||||
|
//clear touch enable
|
||||||
|
WRITE_PERI_REG(SENS_SAR_TOUCH_ENABLE_REG, 0x0);
|
||||||
|
SET_PERI_REG_MASK(RTC_CNTL_STATE0_REG, RTC_CNTL_TOUCH_SLP_TIMER_EN);
|
||||||
|
|
||||||
|
__touchSetCycles(__touchMeasureCycles, __touchSleepCycles);
|
||||||
|
|
||||||
|
ESP_INTR_DISABLE(RTC_TOUCH_INUM);
|
||||||
|
intr_matrix_set(xPortGetCoreID(), ETS_RTC_CORE_INTR_SOURCE, RTC_TOUCH_INUM);
|
||||||
|
xt_set_interrupt_handler(RTC_TOUCH_INUM, &__touchISR, NULL);
|
||||||
|
ESP_INTR_ENABLE(RTC_TOUCH_INUM);
|
||||||
|
initialized = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t __touchRead(uint8_t pin)
|
||||||
|
{
|
||||||
|
int8_t pad = digitalPinToTouchChannel(pin);
|
||||||
|
if(pad < 0){
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
pinMode(pin, ANALOG);
|
||||||
|
|
||||||
|
__touchInit();
|
||||||
|
|
||||||
|
uint32_t v0 = READ_PERI_REG(SENS_SAR_TOUCH_ENABLE_REG);
|
||||||
|
//Disable Intr & enable touch pad
|
||||||
|
WRITE_PERI_REG(SENS_SAR_TOUCH_ENABLE_REG,
|
||||||
|
(v0 & ~((1 << (pad + SENS_TOUCH_PAD_OUTEN2_S)) | (1 << (pad + SENS_TOUCH_PAD_OUTEN1_S))))
|
||||||
|
| (1 << (pad + SENS_TOUCH_PAD_WORKEN_S)));
|
||||||
|
|
||||||
|
SET_PERI_REG_MASK(SENS_SAR_TOUCH_ENABLE_REG, (1 << (pad + SENS_TOUCH_PAD_WORKEN_S)));
|
||||||
|
|
||||||
|
uint32_t rtc_tio_reg = RTC_IO_TOUCH_PAD0_REG + pad * 4;
|
||||||
|
WRITE_PERI_REG(rtc_tio_reg, (READ_PERI_REG(rtc_tio_reg)
|
||||||
|
& ~(RTC_IO_TOUCH_PAD0_DAC_M))
|
||||||
|
| (7 << RTC_IO_TOUCH_PAD0_DAC_S)//Touch Set Slope
|
||||||
|
| RTC_IO_TOUCH_PAD0_TIE_OPT_M //Enable Tie,Init Level
|
||||||
|
| RTC_IO_TOUCH_PAD0_START_M //Enable Touch Pad IO
|
||||||
|
| RTC_IO_TOUCH_PAD0_XPD_M); //Enable Touch Pad Power on
|
||||||
|
|
||||||
|
//force oneTime test start
|
||||||
|
SET_PERI_REG_MASK(SENS_SAR_TOUCH_CTRL2_REG, SENS_TOUCH_START_EN_M|SENS_TOUCH_START_FORCE_M);
|
||||||
|
|
||||||
|
SET_PERI_REG_BITS(SENS_SAR_TOUCH_CTRL1_REG, SENS_TOUCH_XPD_WAIT, 10, SENS_TOUCH_XPD_WAIT_S);
|
||||||
|
|
||||||
|
while (GET_PERI_REG_MASK(SENS_SAR_TOUCH_CTRL2_REG, SENS_TOUCH_MEAS_DONE) == 0) {};
|
||||||
|
|
||||||
|
uint16_t touch_value = READ_PERI_REG(SENS_SAR_TOUCH_OUT1_REG + (pad / 2) * 4) >> ((pad & 1) ? SENS_TOUCH_MEAS_OUT1_S : SENS_TOUCH_MEAS_OUT0_S);
|
||||||
|
|
||||||
|
//clear touch force ,select the Touch mode is Timer
|
||||||
|
CLEAR_PERI_REG_MASK(SENS_SAR_TOUCH_CTRL2_REG, SENS_TOUCH_START_EN_M|SENS_TOUCH_START_FORCE_M);
|
||||||
|
|
||||||
|
//restore previous value
|
||||||
|
WRITE_PERI_REG(SENS_SAR_TOUCH_ENABLE_REG, v0);
|
||||||
|
return touch_value;
|
||||||
|
}
|
||||||
|
|
||||||
|
void __touchAttachInterrupt(uint8_t pin, void (*userFunc)(void), uint16_t threshold)
|
||||||
|
{
|
||||||
|
int8_t pad = digitalPinToTouchChannel(pin);
|
||||||
|
if(pad < 0){
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
pinMode(pin, ANALOG);
|
||||||
|
|
||||||
|
__touchInit();
|
||||||
|
|
||||||
|
__touchInterruptHandlers[pad] = userFunc;
|
||||||
|
|
||||||
|
//clear touch force ,select the Touch mode is Timer
|
||||||
|
CLEAR_PERI_REG_MASK(SENS_SAR_TOUCH_CTRL2_REG, SENS_TOUCH_START_EN_M|SENS_TOUCH_START_FORCE_M);
|
||||||
|
|
||||||
|
//interrupt when touch value < threshold
|
||||||
|
CLEAR_PERI_REG_MASK(SENS_SAR_TOUCH_CTRL1_REG, SENS_TOUCH_OUT_SEL);
|
||||||
|
//Intr will give ,when SET0 < threshold
|
||||||
|
SET_PERI_REG_MASK(SENS_SAR_TOUCH_CTRL1_REG, SENS_TOUCH_OUT_1EN);
|
||||||
|
//Enable Rtc Touch Module Intr,the Interrupt need Rtc out Enable
|
||||||
|
SET_PERI_REG_MASK(RTC_CNTL_INT_ENA_REG, RTC_CNTL_TOUCH_INT_ENA);
|
||||||
|
|
||||||
|
//set threshold
|
||||||
|
uint8_t shift = (pad & 1) ? SENS_TOUCH_OUT_TH1_S : SENS_TOUCH_OUT_TH0_S;
|
||||||
|
SET_PERI_REG_BITS((SENS_SAR_TOUCH_THRES1_REG + (pad / 2) * 4), SENS_TOUCH_OUT_TH0, threshold, shift);
|
||||||
|
|
||||||
|
uint32_t rtc_tio_reg = RTC_IO_TOUCH_PAD0_REG + pad * 4;
|
||||||
|
WRITE_PERI_REG(rtc_tio_reg, (READ_PERI_REG(rtc_tio_reg)
|
||||||
|
& ~(RTC_IO_TOUCH_PAD0_DAC_M))
|
||||||
|
| (7 << RTC_IO_TOUCH_PAD0_DAC_S)//Touch Set Slope
|
||||||
|
| RTC_IO_TOUCH_PAD0_TIE_OPT_M //Enable Tie,Init Level
|
||||||
|
| RTC_IO_TOUCH_PAD0_START_M //Enable Touch Pad IO
|
||||||
|
| RTC_IO_TOUCH_PAD0_XPD_M); //Enable Touch Pad Power on
|
||||||
|
|
||||||
|
//Enable Digital rtc control :work mode and out mode
|
||||||
|
SET_PERI_REG_MASK(SENS_SAR_TOUCH_ENABLE_REG,
|
||||||
|
(1 << (pad + SENS_TOUCH_PAD_WORKEN_S)) | \
|
||||||
|
(1 << (pad + SENS_TOUCH_PAD_OUTEN2_S)) | \
|
||||||
|
(1 << (pad + SENS_TOUCH_PAD_OUTEN1_S)));
|
||||||
|
}
|
||||||
|
|
||||||
|
extern uint16_t touchRead(uint8_t pin) __attribute__ ((weak, alias("__touchRead")));
|
||||||
|
extern void touchAttachInterrupt(uint8_t pin, void (*userFunc)(void), uint16_t threshold) __attribute__ ((weak, alias("__touchAttachInterrupt")));
|
||||||
|
extern void touchSetCycles(uint16_t measure, uint16_t sleep) __attribute__ ((weak, alias("__touchSetCycles")));
|
56
cores/esp32/esp32-hal-touch.h
Normal file
56
cores/esp32/esp32-hal-touch.h
Normal file
@ -0,0 +1,56 @@
|
|||||||
|
/*
|
||||||
|
Arduino.h - Main include file for the Arduino SDK
|
||||||
|
Copyright (c) 2005-2013 Arduino Team. 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 MAIN_ESP32_HAL_TOUCH_H_
|
||||||
|
#define MAIN_ESP32_HAL_TOUCH_H_
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "esp32-hal.h"
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Set cycles that measurement operation takes
|
||||||
|
* The result from touchRead, threshold and detection
|
||||||
|
* accuracy depend on these values. Defaults are
|
||||||
|
* 0x1000 for measure and 0x1000 for sleep.
|
||||||
|
* With default values touchRead takes 0.5ms
|
||||||
|
* */
|
||||||
|
void touchSetCycles(uint16_t measure, uint16_t sleep);
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Read touch pad (values close to 0 mean touch detected)
|
||||||
|
* You can use this method to chose a good threshold value
|
||||||
|
* to use as value for touchAttachInterrupt
|
||||||
|
* */
|
||||||
|
uint16_t touchRead(uint8_t pin);
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Set function to be called if touch pad value falls
|
||||||
|
* below the given threshold. Use touchRead to determine
|
||||||
|
* a proper threshold between touched and untouched state
|
||||||
|
* */
|
||||||
|
void touchAttachInterrupt(uint8_t pin, void (*userFunc)(void), uint16_t threshold);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* MAIN_ESP32_HAL_TOUCH_H_ */
|
@ -50,6 +50,9 @@ void vPortYield( void );
|
|||||||
#include "esp32-hal-matrix.h"
|
#include "esp32-hal-matrix.h"
|
||||||
#include "esp32-hal-uart.h"
|
#include "esp32-hal-uart.h"
|
||||||
#include "esp32-hal-gpio.h"
|
#include "esp32-hal-gpio.h"
|
||||||
|
#include "esp32-hal-touch.h"
|
||||||
|
#include "esp32-hal-dac.h"
|
||||||
|
#include "esp32-hal-adc.h"
|
||||||
#include "esp32-hal-spi.h"
|
#include "esp32-hal-spi.h"
|
||||||
#include "esp32-hal-i2c.h"
|
#include "esp32-hal-i2c.h"
|
||||||
#include "esp32-hal-ledc.h"
|
#include "esp32-hal-ledc.h"
|
||||||
|
@ -26,7 +26,7 @@ compiler.S.flags=-c -g3 -x assembler-with-cpp -MMD -mlongcalls
|
|||||||
|
|
||||||
compiler.c.elf.cmd=xtensa-esp32-elf-gcc
|
compiler.c.elf.cmd=xtensa-esp32-elf-gcc
|
||||||
compiler.c.elf.flags="-L{compiler.sdk.path}/lib" "-L{compiler.sdk.path}/ld" -nostdlib -T esp32_out.ld -T esp32.common.ld -T esp32.rom.ld -T esp32.peripherals.ld -u call_user_start_cpu0 -Wl,--gc-sections -Wl,-static -Wl,--undefined=uxTopUsedPriority
|
compiler.c.elf.flags="-L{compiler.sdk.path}/lib" "-L{compiler.sdk.path}/ld" -nostdlib -T esp32_out.ld -T esp32.common.ld -T esp32.rom.ld -T esp32.peripherals.ld -u call_user_start_cpu0 -Wl,--gc-sections -Wl,-static -Wl,--undefined=uxTopUsedPriority
|
||||||
compiler.c.elf.libs=-lapp_update -lbt -lbtdm_app -lc -lcoexist -lcore -ldriver -lesp32 -lethernet -lexpat -lfreertos -lg -lhal -ljson -llog -llwip -lm -lmbedtls -lnet80211 -lnewlib -lnghttp -lnvs_flash -lopenssl -lphy -lpp -lrtc -lsmartconfig -lspi_flash -ltcpip_adapter -lvfs -lwpa -lwpa2 -lwpa_supplicant -lwps -lxtensa-debug-module
|
compiler.c.elf.libs=-lapp_update -lbt -lbtdm_app -lc -lcoexist -lcore -ldriver -lesp32 -lethernet -lexpat -lfreertos -lg -lhal -ljson -llog -llwip -lm -lmbedtls -lnet80211 -lnewlib -lnghttp -lnvs_flash -lopenssl -lphy -lpp -lrtc -lsmartconfig -lspi_flash -ltcpip_adapter -lulp -lvfs -lwpa -lwpa2 -lwpa_supplicant -lwps -lxtensa-debug-module
|
||||||
|
|
||||||
compiler.as.cmd=xtensa-esp32-elf-as
|
compiler.as.cmd=xtensa-esp32-elf-as
|
||||||
|
|
||||||
|
273
tools/esptool.py
273
tools/esptool.py
@ -51,7 +51,7 @@ def check_supported_function(func, check_func):
|
|||||||
if check_func(obj):
|
if check_func(obj):
|
||||||
return func(*args, **kwargs)
|
return func(*args, **kwargs)
|
||||||
else:
|
else:
|
||||||
raise NotImplementedInROMError(obj, func)
|
raise NotImplementedInROMError(obj)
|
||||||
return inner
|
return inner
|
||||||
|
|
||||||
|
|
||||||
@ -112,8 +112,9 @@ class ESPLoader(object):
|
|||||||
|
|
||||||
# Maximum block sized for RAM and Flash writes, respectively.
|
# Maximum block sized for RAM and Flash writes, respectively.
|
||||||
ESP_RAM_BLOCK = 0x1800
|
ESP_RAM_BLOCK = 0x1800
|
||||||
|
ESP_FLASH_BLOCK = 0x400
|
||||||
|
|
||||||
FLASH_WRITE_SIZE = 0x400
|
FLASH_WRITE_SIZE = ESP_FLASH_BLOCK
|
||||||
|
|
||||||
# Default baudrate. The ROM auto-bauds, so we can use more or less whatever we want.
|
# Default baudrate. The ROM auto-bauds, so we can use more or less whatever we want.
|
||||||
ESP_ROM_BAUD = 115200
|
ESP_ROM_BAUD = 115200
|
||||||
@ -125,7 +126,7 @@ class ESPLoader(object):
|
|||||||
ESP_CHECKSUM_MAGIC = 0xef
|
ESP_CHECKSUM_MAGIC = 0xef
|
||||||
|
|
||||||
# Flash sector size, minimum unit of erase.
|
# Flash sector size, minimum unit of erase.
|
||||||
FLASH_SECTOR_SIZE = 0x1000
|
ESP_FLASH_SECTOR = 0x1000
|
||||||
|
|
||||||
UART_DATA_REG_ADDR = 0x60000078
|
UART_DATA_REG_ADDR = 0x60000078
|
||||||
|
|
||||||
@ -323,23 +324,19 @@ class ESPLoader(object):
|
|||||||
return self.check_command("leave RAM download mode", self.ESP_MEM_END,
|
return self.check_command("leave RAM download mode", self.ESP_MEM_END,
|
||||||
struct.pack('<II', int(entrypoint == 0), entrypoint))
|
struct.pack('<II', int(entrypoint == 0), entrypoint))
|
||||||
|
|
||||||
""" Start downloading to Flash (performs an erase)
|
""" Start downloading to Flash (performs an erase) """
|
||||||
|
|
||||||
Returns number of blocks (of size self.FLASH_WRITE_SIZE) to write.
|
|
||||||
"""
|
|
||||||
def flash_begin(self, size, offset):
|
def flash_begin(self, size, offset):
|
||||||
old_tmo = self._port.timeout
|
old_tmo = self._port.timeout
|
||||||
num_blocks = (size + self.FLASH_WRITE_SIZE - 1) / self.FLASH_WRITE_SIZE
|
num_blocks = (size + self.ESP_FLASH_BLOCK - 1) / self.ESP_FLASH_BLOCK
|
||||||
erase_size = self.get_erase_size(offset, size)
|
erase_size = self.get_erase_size(offset, size)
|
||||||
|
|
||||||
self._port.timeout = 20
|
self._port.timeout = 20
|
||||||
t = time.time()
|
t = time.time()
|
||||||
self.check_command("enter Flash download mode", self.ESP_FLASH_BEGIN,
|
self.check_command("enter Flash download mode", self.ESP_FLASH_BEGIN,
|
||||||
struct.pack('<IIII', erase_size, num_blocks, self.FLASH_WRITE_SIZE, offset))
|
struct.pack('<IIII', erase_size, num_blocks, self.ESP_FLASH_BLOCK, offset))
|
||||||
if size != 0 and not self.IS_STUB:
|
if size != 0:
|
||||||
print "Took %.2fs to erase flash block" % (time.time() - t)
|
print "Took %.2fs to erase flash block" % (time.time() - t)
|
||||||
self._port.timeout = old_tmo
|
self._port.timeout = old_tmo
|
||||||
return num_blocks
|
|
||||||
|
|
||||||
""" Write block to flash """
|
""" Write block to flash """
|
||||||
def flash_block(self, data, seq):
|
def flash_block(self, data, seq):
|
||||||
@ -410,24 +407,20 @@ class ESPLoader(object):
|
|||||||
|
|
||||||
@stub_and_esp32_function_only
|
@stub_and_esp32_function_only
|
||||||
def flash_defl_begin(self, size, compsize, offset):
|
def flash_defl_begin(self, size, compsize, offset):
|
||||||
""" Start downloading compressed data to Flash (performs an erase)
|
""" Start downloading compressed data to Flash (performs an erase) """
|
||||||
|
|
||||||
Returns number of blocks (size self.FLASH_WRITE_SIZE) to write.
|
|
||||||
"""
|
|
||||||
old_tmo = self._port.timeout
|
old_tmo = self._port.timeout
|
||||||
num_blocks = (compsize + self.FLASH_WRITE_SIZE - 1) / self.FLASH_WRITE_SIZE
|
num_blocks = (compsize + self.ESP_FLASH_BLOCK - 1) / self.ESP_FLASH_BLOCK
|
||||||
erase_blocks = (size + self.FLASH_WRITE_SIZE - 1) / self.FLASH_WRITE_SIZE
|
erase_blocks = (size + self.ESP_FLASH_BLOCK - 1) / self.ESP_FLASH_BLOCK
|
||||||
|
|
||||||
self._port.timeout = 20
|
self._port.timeout = 20
|
||||||
t = time.time()
|
t = time.time()
|
||||||
print "Compressed %d bytes to %d..." % (size, compsize)
|
print "Compressed %d bytes to %d..." % (size, compsize)
|
||||||
self.check_command("enter compressed flash mode", self.ESP_FLASH_DEFL_BEGIN,
|
self.check_command("enter compressed flash mode", self.ESP_FLASH_DEFL_BEGIN,
|
||||||
struct.pack('<IIII', erase_blocks * self.FLASH_WRITE_SIZE, num_blocks, self.FLASH_WRITE_SIZE, offset))
|
struct.pack('<IIII', erase_blocks * self.ESP_FLASH_BLOCK, num_blocks, self.ESP_FLASH_BLOCK, offset))
|
||||||
if size != 0 and not self.IS_STUB:
|
if size != 0 and not self.IS_STUB:
|
||||||
# (stub erases as it writes, but ROM loaders erase on begin)
|
# (stub erases as it writes, but ROM loaders erase on begin)
|
||||||
print "Took %.2fs to erase flash block" % (time.time() - t)
|
print "Took %.2fs to erase flash block" % (time.time() - t)
|
||||||
self._port.timeout = old_tmo
|
self._port.timeout = old_tmo
|
||||||
return num_blocks
|
|
||||||
|
|
||||||
""" Write block to flash, send compressed """
|
""" Write block to flash, send compressed """
|
||||||
@stub_and_esp32_function_only
|
@stub_and_esp32_function_only
|
||||||
@ -476,9 +469,9 @@ class ESPLoader(object):
|
|||||||
|
|
||||||
@stub_function_only
|
@stub_function_only
|
||||||
def erase_region(self, offset, size):
|
def erase_region(self, offset, size):
|
||||||
if offset % self.FLASH_SECTOR_SIZE != 0:
|
if offset % self.ESP_FLASH_SECTOR != 0:
|
||||||
raise FatalError("Offset to erase from must be a multiple of 4096")
|
raise FatalError("Offset to erase from must be a multiple of 4096")
|
||||||
if size % self.FLASH_SECTOR_SIZE != 0:
|
if size % self.ESP_FLASH_SECTOR != 0:
|
||||||
raise FatalError("Size of data to erase must be a multiple of 4096")
|
raise FatalError("Size of data to erase must be a multiple of 4096")
|
||||||
self.check_command("erase region", self.ESP_ERASE_REGION, struct.pack('<II', offset, size))
|
self.check_command("erase region", self.ESP_ERASE_REGION, struct.pack('<II', offset, size))
|
||||||
|
|
||||||
@ -489,7 +482,7 @@ class ESPLoader(object):
|
|||||||
struct.pack('<IIII',
|
struct.pack('<IIII',
|
||||||
offset,
|
offset,
|
||||||
length,
|
length,
|
||||||
self.FLASH_SECTOR_SIZE,
|
self.ESP_FLASH_BLOCK,
|
||||||
64))
|
64))
|
||||||
# now we expect (length / block_size) SLIP frames with the data
|
# now we expect (length / block_size) SLIP frames with the data
|
||||||
data = ''
|
data = ''
|
||||||
@ -748,7 +741,7 @@ class ESP8266ROM(ESPLoader):
|
|||||||
Provides a workaround for the bootloader erase bug."""
|
Provides a workaround for the bootloader erase bug."""
|
||||||
|
|
||||||
sectors_per_block = 16
|
sectors_per_block = 16
|
||||||
sector_size = self.FLASH_SECTOR_SIZE
|
sector_size = self.ESP_FLASH_SECTOR
|
||||||
num_sectors = (size + sector_size - 1) / sector_size
|
num_sectors = (size + sector_size - 1) / sector_size
|
||||||
start_sector = offset / sector_size
|
start_sector = offset / sector_size
|
||||||
|
|
||||||
@ -772,9 +765,6 @@ class ESP8266StubLoader(ESP8266ROM):
|
|||||||
self._port = rom_loader._port
|
self._port = rom_loader._port
|
||||||
self.flush_input() # resets _slip_reader
|
self.flush_input() # resets _slip_reader
|
||||||
|
|
||||||
def get_erase_size(self, offset, size):
|
|
||||||
return size # stub doesn't have same size bug as ROM loader
|
|
||||||
|
|
||||||
ESP8266ROM.STUB_CLASS = ESP8266StubLoader
|
ESP8266ROM.STUB_CLASS = ESP8266StubLoader
|
||||||
|
|
||||||
|
|
||||||
@ -1093,7 +1083,7 @@ class OTAFirmwareImage(BaseFirmwareImage):
|
|||||||
else:
|
else:
|
||||||
irom_offs = 0
|
irom_offs = 0
|
||||||
return "%s-0x%05x.bin" % (os.path.splitext(input_file)[0],
|
return "%s-0x%05x.bin" % (os.path.splitext(input_file)[0],
|
||||||
irom_offs & ~(ESPLoader.FLASH_SECTOR_SIZE - 1))
|
irom_offs & ~(ESPLoader.ESP_FLASH_SECTOR - 1))
|
||||||
|
|
||||||
def save(self, filename):
|
def save(self, filename):
|
||||||
with open(filename, 'wb') as f:
|
with open(filename, 'wb') as f:
|
||||||
@ -1130,16 +1120,11 @@ class ESP32FirmwareImage(BaseFirmwareImage):
|
|||||||
self.flash_mode = 0
|
self.flash_mode = 0
|
||||||
self.flash_size_freq = 0
|
self.flash_size_freq = 0
|
||||||
self.version = 1
|
self.version = 1
|
||||||
self.encrypt_flag = False
|
self.additional_header = '\x00' * 16
|
||||||
|
|
||||||
if load_file is not None:
|
if load_file is not None:
|
||||||
segments = self.load_common_header(load_file, ESPLoader.ESP_IMAGE_MAGIC)
|
segments = self.load_common_header(load_file, ESPLoader.ESP_IMAGE_MAGIC)
|
||||||
additional_header = list(struct.unpack("B" * 16, load_file.read(16)))
|
self.additional_header = load_file.read(16)
|
||||||
self.encrypt_flag = (additional_header[0] == 0x01)
|
|
||||||
|
|
||||||
# check remaining 14 bytes are unused
|
|
||||||
if additional_header[2:] != [0] * 14:
|
|
||||||
print "WARNING: ESP32 image header contains unknown flags. Possibly this image is from a newer version of esptool.py"
|
|
||||||
|
|
||||||
for i in xrange(segments):
|
for i in xrange(segments):
|
||||||
self.load_segment(load_file)
|
self.load_segment(load_file)
|
||||||
@ -1160,10 +1145,7 @@ class ESP32FirmwareImage(BaseFirmwareImage):
|
|||||||
padding_segments = 0
|
padding_segments = 0
|
||||||
with open(filename, 'wb') as f:
|
with open(filename, 'wb') as f:
|
||||||
self.write_common_header(f, self.segments)
|
self.write_common_header(f, self.segments)
|
||||||
|
f.write(self.additional_header)
|
||||||
f.write(b'\x01' if self.encrypt_flag else b'\x00')
|
|
||||||
# remaining 15 bytes of header are unused
|
|
||||||
f.write(b'\x00' * 15)
|
|
||||||
|
|
||||||
checksum = ESPLoader.ESP_CHECKSUM_MAGIC
|
checksum = ESPLoader.ESP_CHECKSUM_MAGIC
|
||||||
last_addr = None
|
last_addr = None
|
||||||
@ -1337,6 +1319,7 @@ def div_roundup(a, b):
|
|||||||
"""
|
"""
|
||||||
return (int(a) + int(b) - 1) / int(b)
|
return (int(a) + int(b) - 1) / int(b)
|
||||||
|
|
||||||
|
|
||||||
def align_file_position(f, size):
|
def align_file_position(f, size):
|
||||||
""" Align the position in the file to the next block of specified size """
|
""" Align the position in the file to the next block of specified size """
|
||||||
align = (size - 1) - (f.tell() % size)
|
align = (size - 1) - (f.tell() % size)
|
||||||
@ -1389,8 +1372,8 @@ class NotImplementedInROMError(FatalError):
|
|||||||
Wrapper class for the error thrown when a particular ESP bootloader function
|
Wrapper class for the error thrown when a particular ESP bootloader function
|
||||||
is not implemented in the ROM bootloader.
|
is not implemented in the ROM bootloader.
|
||||||
"""
|
"""
|
||||||
def __init__(self, bootloader, func):
|
def __init__(self, bootloader):
|
||||||
FatalError.__init__(self, "%s ROM does not support function %s." % (bootloader.CHIP_NAME, func.func_name))
|
FatalError.__init__(self, "%s ROM does not support this function." % bootloader.CHIP_NAME)
|
||||||
|
|
||||||
# "Operation" commands, executable at command line. One function each
|
# "Operation" commands, executable at command line. One function each
|
||||||
#
|
#
|
||||||
@ -1458,7 +1441,6 @@ def write_flash(esp, args):
|
|||||||
argfile.seek(0)
|
argfile.seek(0)
|
||||||
|
|
||||||
for address, argfile in args.addr_filename:
|
for address, argfile in args.addr_filename:
|
||||||
if args.no_stub:
|
|
||||||
print 'Erasing flash...'
|
print 'Erasing flash...'
|
||||||
image = argfile.read()
|
image = argfile.read()
|
||||||
# Update header with flash parameters
|
# Update header with flash parameters
|
||||||
@ -1469,9 +1451,11 @@ def write_flash(esp, args):
|
|||||||
if args.compress:
|
if args.compress:
|
||||||
uncimage = image
|
uncimage = image
|
||||||
image = zlib.compress(uncimage, 9)
|
image = zlib.compress(uncimage, 9)
|
||||||
blocks = esp.flash_defl_begin(uncsize, len(image), address)
|
blocks = div_roundup(len(image), esp.FLASH_WRITE_SIZE)
|
||||||
|
esp.flash_defl_begin(len(uncimage),len(image), address)
|
||||||
else:
|
else:
|
||||||
blocks = esp.flash_begin(uncsize, address)
|
blocks = div_roundup(len(image), esp.FLASH_WRITE_SIZE)
|
||||||
|
esp.flash_begin(blocks * esp.FLASH_WRITE_SIZE, address)
|
||||||
argfile.seek(0) # in case we need it again
|
argfile.seek(0) # in case we need it again
|
||||||
seq = 0
|
seq = 0
|
||||||
written = 0
|
written = 0
|
||||||
@ -1500,17 +1484,13 @@ def write_flash(esp, args):
|
|||||||
if t > 0.0:
|
if t > 0.0:
|
||||||
speed_msg = " (%.1f kbit/s)" % (written / t * 8 / 1000)
|
speed_msg = " (%.1f kbit/s)" % (written / t * 8 / 1000)
|
||||||
print '\rWrote %d bytes at 0x%08x in %.1f seconds%s...' % (written, address, t, speed_msg)
|
print '\rWrote %d bytes at 0x%08x in %.1f seconds%s...' % (written, address, t, speed_msg)
|
||||||
try:
|
|
||||||
res = esp.flash_md5sum(address, uncsize)
|
res = esp.flash_md5sum(address, uncsize)
|
||||||
if res != calcmd5:
|
if res != calcmd5:
|
||||||
print 'File md5: %s' % calcmd5
|
print 'File md5: %s' % calcmd5
|
||||||
print 'Flash md5: %s' % res
|
print 'Flash md5: %s' % res
|
||||||
print 'MD5 of 0xFF is %s' % (hashlib.md5(b'\xFF' * uncsize).hexdigest())
|
|
||||||
raise FatalError("MD5 of file does not match data in flash!")
|
raise FatalError("MD5 of file does not match data in flash!")
|
||||||
else:
|
else:
|
||||||
print 'Hash of data verified.'
|
print 'Hash of data verified.'
|
||||||
except NotImplementedInROMError:
|
|
||||||
pass
|
|
||||||
print '\nLeaving...'
|
print '\nLeaving...'
|
||||||
if args.flash_mode == 'dio' and esp.CHIP_NAME == "ESP8266":
|
if args.flash_mode == 'dio' and esp.CHIP_NAME == "ESP8266":
|
||||||
esp.flash_unlock_dio()
|
esp.flash_unlock_dio()
|
||||||
@ -1559,10 +1539,6 @@ def elf2image(args):
|
|||||||
print "Creating image for ESP8266..."
|
print "Creating image for ESP8266..."
|
||||||
args.chip == 'esp8266'
|
args.chip == 'esp8266'
|
||||||
|
|
||||||
if args.chip != 'esp32':
|
|
||||||
if args.set_encrypt_flag:
|
|
||||||
raise FatalError("--encrypt-flag only applies to ESP32 images")
|
|
||||||
|
|
||||||
if args.chip == 'esp32':
|
if args.chip == 'esp32':
|
||||||
image = ESP32FirmwareImage()
|
image = ESP32FirmwareImage()
|
||||||
elif args.version == '1': # ESP8266
|
elif args.version == '1': # ESP8266
|
||||||
@ -1574,7 +1550,6 @@ def elf2image(args):
|
|||||||
image.flash_mode = {'qio':0, 'qout':1, 'dio':2, 'dout': 3}[args.flash_mode]
|
image.flash_mode = {'qio':0, 'qout':1, 'dio':2, 'dout': 3}[args.flash_mode]
|
||||||
image.flash_size_freq = image.ROM_LOADER.FLASH_SIZES[args.flash_size]
|
image.flash_size_freq = image.ROM_LOADER.FLASH_SIZES[args.flash_size]
|
||||||
image.flash_size_freq += {'40m':0, '26m':1, '20m':2, '80m': 0xf}[args.flash_freq]
|
image.flash_size_freq += {'40m':0, '26m':1, '20m':2, '80m': 0xf}[args.flash_freq]
|
||||||
image.encrypt_flag = args.set_encrypt_flag
|
|
||||||
|
|
||||||
if args.output is None:
|
if args.output is None:
|
||||||
args.output = image.default_output_name(args.input)
|
args.output = image.default_output_name(args.input)
|
||||||
@ -1583,14 +1558,8 @@ def elf2image(args):
|
|||||||
|
|
||||||
def read_mac(esp, args):
|
def read_mac(esp, args):
|
||||||
mac = esp.read_mac()
|
mac = esp.read_mac()
|
||||||
def print_mac(label, mac):
|
print 'MAC: %s' % ':'.join(map(lambda x: '%02x' % x, mac))
|
||||||
print '%s: %s' % (label, ':'.join(map(lambda x: '%02x' % x, mac)))
|
|
||||||
print("%r" % (mac,))
|
|
||||||
if len(mac) == 1:
|
|
||||||
print_mac("MAC", mac)
|
|
||||||
else:
|
|
||||||
print_mac("WiFi MAC", mac[0])
|
|
||||||
print_mac("BT MAC", mac[1])
|
|
||||||
|
|
||||||
def chip_id(esp, args):
|
def chip_id(esp, args):
|
||||||
chipid = esp.chip_id()
|
chipid = esp.chip_id()
|
||||||
@ -1792,8 +1761,6 @@ def main():
|
|||||||
parser_elf2image.add_argument('input', help='Input ELF file')
|
parser_elf2image.add_argument('input', help='Input ELF file')
|
||||||
parser_elf2image.add_argument('--output', '-o', help='Output filename prefix (for version 1 image), or filename (for version 2 single image)', type=str)
|
parser_elf2image.add_argument('--output', '-o', help='Output filename prefix (for version 1 image), or filename (for version 2 single image)', type=str)
|
||||||
parser_elf2image.add_argument('--version', '-e', help='Output image version', choices=['1','2'], default='1')
|
parser_elf2image.add_argument('--version', '-e', help='Output image version', choices=['1','2'], default='1')
|
||||||
parser_elf2image.add_argument('--set-encrypt-flag', help='Flag image to be encrypted by bootloader after flashing.', action="store_true")
|
|
||||||
|
|
||||||
add_spi_flash_subparsers(parser_elf2image)
|
add_spi_flash_subparsers(parser_elf2image)
|
||||||
|
|
||||||
subparsers.add_parser(
|
subparsers.add_parser(
|
||||||
@ -1877,10 +1844,8 @@ def main():
|
|||||||
esp = esp.run_stub()
|
esp = esp.run_stub()
|
||||||
|
|
||||||
if args.baud > initial_baud:
|
if args.baud > initial_baud:
|
||||||
try:
|
|
||||||
esp.change_baud(args.baud)
|
esp.change_baud(args.baud)
|
||||||
except NotImplementedInROMError:
|
# TODO: handle a NotImplementedInROMError
|
||||||
print "WARNING: ROM doesn't support changing baud rate. Keeping initial baud rate %d" % initial_baud
|
|
||||||
|
|
||||||
# override common SPI flash parameter stuff as required
|
# override common SPI flash parameter stuff as required
|
||||||
if hasattr(args, "ucIsHspi"):
|
if hasattr(args, "ucIsHspi"):
|
||||||
@ -1954,98 +1919,96 @@ class AddrFilenamePairAction(argparse.Action):
|
|||||||
|
|
||||||
# Binary stub code (see flasher_stub dir for source & details)
|
# Binary stub code (see flasher_stub dir for source & details)
|
||||||
ESP8266ROM.STUB_CODE = eval(zlib.decompress(base64.b64decode(b"""
|
ESP8266ROM.STUB_CODE = eval(zlib.decompress(base64.b64decode(b"""
|
||||||
eNrNPGtj1Ma1f0VaG2MbQ2YkrTQyplmvzWIINAaCQ1qntTSSIDTJtZdtTSi9v/3qvDQj7RpD0rT3g0EzO5rHeb9G/7y5qN8tbu4GN0/fNeb0nYraP3V2+k4rr6GWGvJndPuebf+a03dWBdC72f4TB8H6yRS64fcc\
|
eNrFXPt/08aW/1ckJ+RhQjsjydIohF7HCSZw4XMhNCm967YZvaBc2k1c74ayufu3r85LGsk2gb72h4BnNJrHmfP4njNn9D/bi/L9Ynvf2569r8zsvQrqP3Uxe6+VU1BLBfkzun4vr/+q2ftceVC7U/8Tet7m+QSq\
|
||||||
Hvbbf4rewC0YGLZdWa/7Ia3FrSNonSx6I2CfcfvXrqsj3EYSrKnTeTtIDfan3bNR/eem/tIfPKEl5I+m9QECe9K0hI0K3qR2p1LYGY926EWdnr4r4OX2dHYsUID+KXTe93tO3+URPLfAqCOBWtI7c96DCmLq5C2M\
|
4XkKPw7rf2yn4S409OuqpFP9mMbi0gmUzhedFjDPsP6rx9UBTiPyNtRsXjdSvfnp9rdR3d9V+Te38ZiGkD/q1iUIzEnTEHlgeZK6XZXCynCwRy/qePbewsv16vKRUAHqJ1D50K2ZvU8D+F0TowyEalFnzWmHKrhT\
|
||||||
2HxMkGji05trtBwBpgV4XfLWUoaY2twJguSk7YVlahgim7Aw5cud9gwVrjx50XbqbsVoA/5Vav0k5g3WcKhGwTDVNbvx38GK8Hrd655aAq2H3Ziwax4HMfTnj83O7mhrh4nLmtDBXi8j2cjzGZ9BLZFp28jbIxUI\
|
579Ai52nRIkqnG1v0HBEmJrgZcZTi5liamfP86LzuhaGKaGJTCKHLl/t1WsocOTxWV2pmxGDLfhXqc3zkCdYwqIqBc1UU2zafwsjwutlp3qSE2md3Q1pd81TL4T69KnZ2x/s7jFz5cZvaa+XN9nI7wteg1pi07qQ\
|
||||||
DMC5vcVPZkgWid+eTOTp8d/4Bd2b1HSTAhXz+X06qfIeDNsOYrEF9OUhvKV74AHSGgmE4G8B5PEBX6ib3tARIBsBX0F/ELRDTbsHCwQAmyhgfAv9PJ0zLogcOrpoX5kc0IF5zpdAuvC7gd8fxS2l6lhAAQSpy+rs\
|
1kuySAzY8/wu/zJ9tojc8ngsv57+i1/QnU5N0ylwMa/f5ZMi7dCwriARW0Bd6sNbukMeYK2BUAj+FsAeN/hCWXWaDmCzkfAF1Hvegvgsh32GSVhoX1M/jee8F8QODV/Ur4yPaMHc5ytgXXhu4PmTsOZUHQopgCF1\
|
||||||
jB75lfI5/PvovtvXIZKLvAkkjWeEM7XvtXImj/fa3soyHdEDrAojml1H5a9h309lBL4KhAwwSB2netIk6ZPfTNi31530BRDsAHlud0Sco2JH9M8Y3S28rG3ZpoCdpMRQVcosWynmMtNDtXAsEDDgHQhhFSGruyx+\
|
Vlxc0E9+JXsJ/z552M7rGNlF3gSWxjXCmur3aj2Thgd1bZEzH9EPGBVaVPstl7+Beb+QFvgqMDLQIG4l1dEmUZf9piK+neqoq4BgBihz+wOSHBW2TH/K213TK89rsbEwk5gEqohZZAvFUmY6Wy0SCwwM+w6MsIqR\
|
||||||
HOW0OylgihIRD0huKjmsEKCMsTygGA7gDV3NOx6lLpBgEE4ZCSM1vu9WRfkxZrzSzmSY4eX1VfuraICj3k/e32CPwDEdSyEHwdTRLuDPwzSurETMwOsMIWCOhgViBdsnodm+GDLS8SH6OLb626pxW4XsZSRAPF1c\
|
1X1WPy3n1DOx0EWGGw+bXBWyWGFAaZNzA9tvwBNaLzsOpy6QYZBOCSkjNXrYjor6Y8T7SjOTZoaH1+vmV1CDlns/eX69OYLENCKFEgRdB/uwf85O48hK1Ay8zhQyIKCsEAuYPinN+kWfNx1/BB/fre60SpyWlbkM\
|
||||||
oDZgFVTZ4eERbLdpo25j7n16zayC2QXQVCF7CIZbQ3yJAlPvjpC49t8sCSeWQawtxs+QbdXp6f53609FNwGsk60EpiqTP406DrHBzj68/c3WIaM/WYndez5QxqqV6Sa+XqQrX86+9BvnfqN9NiSEiXvsV/iUeH0w\
|
hIizxRVaAzZBRd5fPJLtHk20nVj7Pr1mVtHsCnjKyhy8/tRwv8SAqfcnyFyHb5eUE+sgIGekDg7TzcZS70aNKPCfHnl7h9D861OU7t1j3vXRyk194NJipGpVbsLbNbmQtvn9yi1cuoX6tyH9S4KT/x1/RU4dNEpT\
|
||||||
KM+5kWuH/yX81TnYJ+2QxQXQWAuBXInsJhGLB6lox4TumM8+Xj5747NEerpgkVAR/EBElw3jGPoaoIQaoKWfADgUU/zStKjYu33c4ynUk4CZrFp+p4LT1SSlgBWsOnkMnB2Kyo7csXQx4omWKK8zTVjNxjj6vqwp\
|
LqS63fqlrStTgCZ1k8UVsFetb1Ilapu0Ky6moFnTTofr11+50hDPFqwNCqJkXjNeVvH2Ql0FTFACxfQzIIliZl/qFm16M48H3IV65rF8FcvvFLC6khQUSEGuzp+CUPtirYN2WdoOuKMlpmtQCVvYkFsD39Kwwshx\
|
||||||
pJz22N8S1Cu2AQDQAFJHw5V5CosB7J0sCJYp4rWP+IXfeOc3PvTpw6h+Ox+2jbDKpBIhXLg+Jhk7JJnCs2qupx1dNKBnUl/Z90GOiqLD+A7JIF3EZKUVvFmkweQZC7Ym+hHGXCVbQyIw6KyB2CKa1KRgLCpGFrxa\
|
R/hzInzBCABoDVRtObgwL2A8IH+rCbxlxnjj7v3CLbx3CzddFjGqW077ZSOCMi5EBdu2jrkm73ONdTDN7eyjbQVWJnZNfZfqaCaaTd8jDaRtSBjN8mSRDaNTVmtV8A7arNOsPvEYVJbAbwF1amKAioo3C17NVr7a\
|
||||||
rny1sxNQxW0/haUORXemezK0EJ2Np3xNegLtnpRmBDFb1h6hgylQItWBWm/k3XhTKOrFL6Bp+pxQRsM9FkTWvPA7WtjYks+VTH8kqxrMBDJD2sNUYyFUjeeBlZJ7sAgIYDJSEDL91YslVmi3XrC8c7t48ZJUZFXU\
|
oAQ0cMMXMNSxWM74QJpasdi4yjdkJRD1xNQjKNmsdHgdgECGjAdGvZJ3wx1hqrNfwc50hSEL+nO0xNk88Hsa2OQZryuavCNMDSCBQEi9mGIkjKpxPTBS9AAGAdBEEAUp0x3dLklDPXXL0LydxdkrMpCFLeG5bup/\
|
||||||
8Lvu+n+AfiCZwYZDZ8W0NLCJCLpJCCnhdYtLnH8hVBSj19NDpuMsmIks+acs4Gnxae2UkF0FxrLqdmUIjOCr5Gh1PBVKYB1BCDqic5YpiP6oI9APIAiDF+r4rwDWjO2FGpbottM8SkcHLLrLQzoB0W77dh2zSVHm\
|
hHpgmd6E/RbD1Dywgxu0TRuSwes5DnH5pXBRiD5PZzNbyYKeCMe/YPVOg0/K1gTlq8iYFc2soP+4NvkGN+yFsAHrf9qdE1pkFoP6DxruvAFF6J2p5z8ATROGCiX038ylehIPjlh1Z8c0fWLc+u0yZDSRpVvHgIoN\
|
||||||
G4dgGht0NO7x4iKZTLqCYI1akkyE1SrzWAqxuUJCioCe78CbciJ9yULanXHfIZZcLKSj6Tr89iDzdJ1SwRqLmqz0sIUonTk5DXDOf5VwfPxoYDQ6S0QzBdQojI72SECBbAIZxbqM+RHpCb3cCWwvALb5nvgc6AHg\
|
+hgPeHDRTCZewa1GrdBMsKVF4sgTbuUKDSkKer4Hb8qK9DUr6XaNh+2ukneFTDTZhGePEsfeKeVtsJ5JMmercD+nrZ4G5ZL+Js349EkPL7YgRPa5dNQSWzBy73Xuf828m74YIurFIuouNmyoiPJDRn26a51B56Nj\
|
||||||
iYZlxdLJ7vsynpCMfga6oSAu2v38TLAvltzbnpVG3iiQfMFSCqUHEtwmLA2Yr3vazS7jztjOvki2Tk/xxe3bW/Df5h4pvSpiYZTvfZ7q4SDB10f7D8laZGdvnUUIWhgrXU7tTLEuloCb7bubWk0G4YreS5OePXTT\
|
Ue3sgec+IPcddtzavju7Q9tSqq8811StMm8mbwBDtDub8Zs1QYb3duH3zgHTA2xZEbCCSQ+YQC3RVhgRdvb/cXL4mFAfO22brAwQLqx0HXULqZqYAE626zZqNV7GMfJSzQrb7pP/qqtSorQzF5oBFiAsYTtPOl6q\
|
||||||
H/b3tisnWvc2RtvBBsQ2it4vPVc32PIWbBFtKnznpRcZAZh2b4NCK2ppgNlFi3zwulHblm7eAi07tdJZD8QkUuqY0Nw1tEchhe+2F8Zr6KY7wR6TmoRz3IYS4XfenfJ2p3o/JuzaQaOEc4wHtlzTP0kHY2zI6sa3\
|
t+uMUW+pKfCdV05QA8jYvA3WyJZSANhEg9w41Wgqs7Zfi+hMrfSzPYE0Sj0HMXcKOnC6cD1ua5yCrpoV1NtnUycS004oEnnl2SlndqrzMGKvDAoZrGPUw2JVdyUNjbEgoxvX8Gd5U3iFDcd7TxtYKdKXRY/5V55/\
|
||||||
HUrbNV7iwMnO4w6rwr1l8pCfrL3TGbJkamGjMmS+vu76jkhxkn2iSHG1jccb3Gd4StAvrLqA+wq2N5xpMirWMGh1gPGsKTBKATo/KsDZjwoIaljFTrr15B5ZAQIMDNd9NcqAww3zorHb6FgckDopc/aUTU1yCWYD\
|
0QBRgkpYKAzBzzdN3QlZPQIXiqxOXXi6xXWGuwTjwGEZECTLYKHFFQO7gfGmIwxFTUAiLBjswIKfHliIR5AdcDQ/GUeyFkQMjLT9fZCgcmDxM/kQvKD86KGYAJ/CJ6BUoE8UbbTk+HS45wYv2OeVoVR+yuZ/JdBI\
|
||||||
ZmjQHkDFuL3jB0HYd5bVlH3GRsRKcyVlM7ZgZ9kPHSoQan4MrVMGt1a4LNZpiipb8fvKfv2YY2lEQk/ZHaovpEcmLnmLMtOSQtYiNcN/wAReKEQMJIjl9ONFXjDUCxBueSHSGEKBJhF46tHTA+wZj4oRUAfMa7rg\
|
GINadnLdkJ+KvG7sq9HkK7QHjsdqvkhWPF9Zr085BkbM9IL9n/KqtRXUccZTlJ6WTKkW7eeDLSydEIZAG4jBdOM8ThDTCeztOqHNEEJ4JhJ66sGLI6wZDewAWAP6NU3QImj7MoC/tVYDr5rMFjt7ndkE9ds9PxPB\
|
||||||
R+TmMmDFa61GQTM9XWzu9HYTtW8P/NW8YvQOgwDAXxoaRgIIIApQSbCB0ciy8chfnzVIK5chXhUS+eJ4NoQ0BFKLsec812xvwrFWbqbbrR4OILKuKiYnsZExuhpR5Ao2NtuFwVmU00+59xMosb/TryBEGu60Kfqm\
|
ZrnCeQfh0lAw4vijHhi1BKpk2HDgjs+qr9bDEGfyGUtXZCwAwmiOitrY8XtLBotpumY+MuE06Tcgti4K5igBuBgYDSjoxHSO96F9EqT0NHWeTt/RI1AiFbdXMcKW6khs+T+xuCFP77N+jt912THrjTqb4TPAeDRW\
|
||||||
zQG+jiqjWXNTdW85Kiz99Ug8gnEYizHxkxta9dY3KQtTk/7MusP2Btj0TrdBRdJGDwbsyQCaMJYJn/txHQ3voE1opWswzZo/XMlwmrNw+9cVOaYaA02w9nj2rUCj7TONvES/fdPnxzxbRiOYnWDn5Gyl2fS40zwQ\
|
2bYt3Dl8x/Ux6y2dd3oy8ZfNJBVpHN1poOJIGtS9NcR54sZkNLyAoC6XKncKm25bJW2p82/baeuC3EqNEaKQcV/8DyFEXW0qmXXz+GlXLNNieSsBOgJqSRlpmfiksT4Qh0AwuCTO56ekHkE8kRFw9l9QE5M/8zAA\
|
||||||
uUBDcomPT0raYcXWEXoy6g4NMfZJgBHMk+dsWxVEtbX+1guSJb6eCAKKDsBy2ZLkOhmRJK45MoA2ivpCPKc/0DHQfWf7kUL4fILLpfnaQRHpnBUnOGF1V8NUdz1xV9Nw4owNB26FeQqkTSDbcSPmMEywj5i4yxhy\
|
ef6SxkPsHoAOfuXEuCLXVngeefgwXLKkwM7Z3lUEwGBExCTqS/F+vqKVoBcerByAFnO9YiXzles4Z8EDesWBo/tKak4ystXSPY+N8Cfw+6gSYAvTYVE2TU/KeYzOk4T94mHn6ZTkFx7VzTropt+DlR7uuMHgQqYd\
|
||||||
/QHb/UIzhN8NfwgKQPM4PPAko7+HyCcUm6KembFpP+YZE15UR+1E9z5tIo/D0UoZswkMIf/0ho82iDLGZPTSpJGzW7vZU7JZHdtv47l2QGU/I8qwDVvNFFHuxA9Pk8ccnNSiNmvfQq6Lg6kjKNhyXU9GMF12B+Z/\
|
tHG7Zv4xea0tP+PgZg8s6iltWl4xiqRYbaMduJs05LCfFqsGrgZGJwKXy44m7Y4A/CnL8QB6Tb6AYU55kqPWseQf4G7iuYcWVZNcnKGCPYbK58ceNMAY0Tj0YHq56M9cy9IBEgMGhCg1YRafrAJQpyWGQyGb5yZw\
|
||||||
xrsbO6+XH8AXxrSMFiGWnb1AuX0InceHAQzA6NUkDmBfVsSy1XLmgIAA5wPScwZRyBq78oHhQaiwB0CG3W+Gwp9VHE0lB/KMyXksAgopF2RHI9hiyTt2eBVRgWxWDmSDSr0gtQzkF3GyzEdwR7IzfmM8E6O9+brX\
|
nhkOLIbBRE4XTpnNYgecAlgl6ZbNQ804almnEeZ49vOS8E657ahtR+9N+bBJdZiqbZ0vuQ/VP1qHCOk+WsW+Pcej9xx9FyWHHYbd87KueSjFnrHQS8binNROkQx6lgL8UB34s23Yu3Ir+L6atOtCcAMHRPGrZVSJ\
|
||||||
v4pHePNeZrH2wjQyDqMDCpIyMIvhGGGNPWATmWRFwBe0Yl+WnfwEgQvRiRKlV6D+0P2sTm8CIsuN6E/N1MECDSik7K+dZ6xjfEt2WEXYBAKDsBCZuCGHflmJ6iWpZXZCchmaWu3vb4svtOSaYej3tgRRdLEqPRBT\
|
epheLyVGHmBxNP3abe6zD0QxwO2luPCeL+6DOjwcoouy2W+E8dV7FKIYrIq7hxTGw9WXK+AQ6NN2SnhiGSDACid4evkKrBXQN0VUMz2S5qutfYimPvQCOn3C8wsSv4dt/EbFD3hzPoJXBgxXFcs5ybC9y7wHPJeO\
|
||||||
oBEHpCusrXTiW96YWI3QfounmGR9eXpKoEUd0IA8ouGrjYkYLYk4AAKLOc1C/Oc7srCu2BMfsYhGHFBRzOvEx8Utpr96xsmqxJcqNZu8AuJSkn0QDYTIQ1OVjOEY83vRPLxVFjfIKWElcTMTo5i2biIcEBXj+wAP\
|
XDXqc5iq1C1dMzlCgygbuARVkTF6CfHULJj7dzN7hx6y4t5OBLJScNkE2CCwwMmjH6Rnf3TFUgcna4F/9/LvrO7tMXkpgJkK+6/M7mIne2MOYwMpwXM2GE+fgqBF14SiicN+pgmAi1bmGJAAvQ3bokc772A0uzW3\
|
||||||
OEEZheMLjjdABjAKb51/xYqlOCT+AQKsir+VxRZOsTPhSDvEEAASxhLXkx2RXFIwiAjsf2gH4AjWFsMmwBWAGj3e/BEWLDbmxTpOvL33HHgeIjw4IHmNMdXOmpmxPE40o6UmSUkRMQIGipbwW18mu5gUxL3Aw4H/\
|
m9jr8OAliDvETrBB9AZDlS26YNUbAapGh4eUJAWaiBaoVfzSVcdttAfCSYD04X8DWKmAfzBCkvztProamyB2P3v4e4uNIGi1miqg7PMNwO263qEZDQHWPBVsGz3OvuNztYKMKCqFjL07jpKXUSCemH9OvYCeziuc\
|
||||||
DRhlFfyDcZzsy7vo0KwD5/0c4PMGa1yQcC1gQPLbNXANtAr/SCuA2ZCL9Zw8LL/nDGBF2hXZnz2TgkP5dRKJuxce0SxwKtvkrJVFQCnuoMlmPoVELnHTexcO8BOdmfZPoVRYfG9nEI+R3EQzp5PdOM7wZHfdyVT8\
|
lavruII6m7ocErTHIZ13YQU/0aJpARSihMEPdqYOrsQu57SmO88TXNPjdkkq/FaWouIvWFPL/ON2/g9780/bQysRBeVPnEY5NvLHXIX6Cbz84A1tjVF3QGreDiZWndoos1/CBoHsE9eiR6WX0RVt8cRXp36U+fiS\
|
||||||
XXcisgW9Y6TuGNngGHnkFxL4f8IgKoy9dyy+E3LyEiVEDAGG6DXNZdQN4KU3o2mhnhVJWXwBWAOhALTMoV+zbNwR3qehehYmZYgvhTHRPPFhTT5e0HCuxv7jOEiEX00A6jE+/gY8oPKFRPIuyHtv2HjWY3TT0WF7\
|
HxJvk8SV5Gt5FR945P/93ItEMo0H1i98/jV4ItmZhMOuGOIzqtUj9JXRcXqdOAdSo/GYI+tkSccgMaGqgG/yKfcWL5HfBx1Y7B2lROopBdQopUH+eBOq+MEYN3HXdXX7zMY8OvB2WDpzWp/KISMFAjRVkWbCrNRT\
|
||||||
lXkJtfFkwnkBUrUT4KRYNUBMdsazpbMhNkLipabaOcgJ+DNizz4wGS1Neu9LxO6W72gPqZBpdxRsMuNaOqKycQgxuKbKS6FhmscWtGCH7UjQO5Ij8iKq03BeMpWwys/VRKQ4OGc1cJMpmTS7sO4FR1Aq1Hzr7XHK\
|
bmnIZncD2c6BrLBhBDFgzlkkbSr/Lsaiq8FHKkFuTMY8GLcxfaWuqGtggdrIbe6C2+z5h7t0lARCV4aHHBIDaFicn26ghdxEbQAnGzUtNj5Ci7ShxS4HLvOXDG4r64hSs2zzpyw77yybFTgsg7OPxrxa2Cx9A1vo\
|
||||||
LAj3tygFBmxYx/scoQPjtDoBqdeqzXWUD9UeQuHGR6CQd1DY4oCrfQ6GNUQt7ZJB7hP673D0mUvFoFCHc3Dt1ISPC3jSHwB7AQFLK2e16fQJaSIoMTCQ6W5Pv3bl6edydDR0cR4rpT2JJ1m6M5vfBd0mldRVyEUR\
|
0YtatbBMx88IVsAhvYGz4o8ufi4rRx8H+8klOSb665ZuYgmKyslcrkHDlG8HcBJbAr4Dm9RssmFamENZdi/GlRwcfjr3a/aGcj4TRzGY7+bUQ8YAotXJPuc+5If3YZKNins7eDIQ+tCUeVxU7QgVD9FWvw2fhHAa\
|
||||||
VoPirt9gwrgGuw/0VIdlw7CA2Csde4ijvf1PJ3xQGyWl6XIrgYT5lqUZSo6uOzkdEvE1dh9LoDp592b0aCTwoS3zuqazH/dv47HiRzGkMbTpYBzyQhZIm+a0MqccX8CpMeWWzpyxJnGgXO/B2+XpIh+dLkCzKwp+\
|
oE1DY59Xlh8G0mcufcryhZwaj63iaQvNJCKTatCyZTZbpIPZAqy4ojBEVSOLxf1gtth30YamPsE4qia7JKb5Ui5Rh3B7v0wllMcYDZnsAOl951OZ7CA8J0Na8hFV1yd0jcefpl4kAq9YoAycqprGjFOgvWG2TnLF\
|
||||||
NK21sbgbnS52fQtEk/sI+lJ1tTEpm+t2CXA7b2cSQ2SuRCK7jsUGRLYXn5BurdP/AoO5DKPwWI1h7QVaGhseXTli6yUd9g5mFDtS0bIg2SJDEvOTah5CQLVs5vdlgy+8+CCqoCecSFEHYC6craHRcJOryDJGROWU\
|
wdGUQ/7Bsh7ZpdAMnvGpuQ9xzayaP5QJnjmROjRCzzjfQh0BNLjYQICwzXlYCW9E2TVd6DCV+YoJGJyAaSbAhDJd8jbqbg/w0kJ81V/bo7QVeygpDDFFLZeMjkwB9w4iOsXc330OS6E0rg/wzzWf3ul/w6BQiqUU\
|
||||||
lvhStV2xvsH1Tbf+zDktnYzbAbNpIY70e5f6W4E3rrWA9UpzBSchrsA3q+fh1jFsnYrO3sM/l5xp1P+CBS8pzEqt9LYkaS3AICPtPUeTa6DAUZr1FPg8jERxk8oG9Q0r2vcvzhsOVWDi2bCbjQmrlq/ns77btXQe\
|
35ODzxxokpA9nyPe6pr0ed+gz/1ADDmZcDDnMF7+4eyy4qgBjARaA5Us0q6W8vm076D1VoNHErzsFLdhi4Me6MT5LY8NXoNIoe/gszYpJlDXnKCN1i8JZ1YVvUWJ526G15qgPDRpl1ivuF430C2ZSGxy0hwxhtcE\
|
||||||
zH7E9Ba6khDP0F0cK3RUNXoFzINORMgMWE2hr0v2jT9yqIZ1Wu9Q4sOb7UtNDhgMcUdsT9yeGyCXTSUGOu2yofElRywh7Gajc0rJSAg3T6ZTGTniNGmTjSScLOF9wLNdeO4z7m161L1KfGaMTDGOKF1Sm13OXoAr\
|
NiuIg+XBJZ2TSGg1jSYTaTngs0c8y6Iwr8TcgXPyRd+TnZw0r5LUGSNdjAI6wyjNPh8pgPOdSH/V8GR+3L7MaB1DTPFPPZcXqAucVBVvIVzLAogm/TaFswLeYEQyPGcV8f+kdcpStI7P8fJCFIGzxkM+dC8k0wo7\
|
||||||
nsl8zfbR/NC9zCY7RrTQKdBeGAmgC5nEpnoDYWFmuU/U4ku2DIZARdRY2xc11+uzoYP+682Y2nOMyUET7veOuc8ufyXFYTgpGFp6MmNcA+RqdEFV4OJ9K4yDIyTKbdAmj+JgA16HxAHWo2FxAITEjA5J4HcOEdRq\
|
Bdilx1PeaCBbiW6n8trQ2wqccIIcCd3lT0JvC16HaD4md+FZewwqXPt8FiuOECQ+1ms4xUOsHrNmts+ssmM1O3bBNJrmRGzFg/S3QDHAd+ekOPLg/wmSYKy1OGRrmbsMWdNZbQ43D0lnS+iKkGhruRuYWhPdJ0Bd\
|
||||||
tmd4himzoRUdDelVkNZSZN9+Rn1sfCVx71cZYWDZnZC+sdH/A00R/i+AYJ+D+dan0Rbuan17ff+fLqhFxqjT3Z2l2mIgZKGGiWcdZykhQts44vixSsF31RdvffScQ51JhJw/OX8HSmsOhshL8Ev0ofg/rRbTPv7m\
|
4YGvDpOY4v06D3FnQEJjcFP11Y27I5dzYGuU9PHlezBZkLqRvAK/RB+L/1PbMO1u2dxieFLT4Vlfx8y2D0GdFkSB4WzbSbjBGHPWf8f/mR0/CBLJ1Ia7EzrvNMpJVOixSC2SumaQHYjbobLG3GMe0AQgp3pg7+ES\
|
||||||
BeZ9JVw9kDmnN/d/gF46//bpTS8Ohe8s4T2s2Q+MQpwYt7a9NaVUK+ZIQcIPiaXlT92SyiaE81ByY+E0r2YiYFo9Km7j/u84NekTlh/wc/vfxixD7Aso5Bs1XROSP4SScY2nCe8QHNDbT2QdoDm9RTU7nnZm2wCD\
|
vmjtpMtOpsnCdJcwxEh/6OoklBY12RBGP4asa/hZT+IL2k707SMZB7hN71Lii2OeGRxgeGeOdK5Llmx8asB2QgnO31PIuqgIWKH63eUUPXtckZYDWGuaBAuQh022Iw3R9VfNhi8kA1GHHily+DOc06cx5QS8r1gS\
|
||||||
PnMEctsqSMXnBtQotCD1n0O1SKNGsmK8xaWFxWFDIg8K5UxXGAJcsc5KpYO4TjpsL6ROUscBSXXU/FyLqLFUBjyvVKrDr9DgcDcC9UiZlzTK5LIsoi8vDEcXBILpS2IhDZHEgsrrJQY8LZDRDiFhG88Lc54FHJvW\
|
rNeY7ZBzb6sMnDloZVIZFncwtYZDCUJBiO4hagTgYClDXaK8E4va8RgOTsO5NZeJx0ForQObBH488RM6op77cWB3xqE38c3lFbL+8dzGE2seUYwHIDQaWMA5SaIvT2gpqTpuQ8njsZ7YndYNpdTHcZutbvVU5j6p\
|
||||||
OiqyKEynYUap8XmYRsXmJA6moTm/QLo/nBfptDAPKOpTcQgEeNhkmT4/oqPk6tAFmicTPS02nQtKJZsTV2pf6JnsfdoeaPIWJpiGm4CaePottOak0RvM92VUuU5pBiWvQVVonkwu8WXGLyZDcMkRThNMu4BdrfJ9\
|
FzT+BTqY+DuwNeHkGyjN+YAPj94SSv42sdeYs/o1yK5Mo/E1vsz7C7DB4JAD7MabNNG5UkFyCZGE9QyqlKBe/CUs/vIYmH8uqSLjR8ipUIv91777ol7WhA6WNWcn2qie9+BrVOrOWDUhgXjXNfHqn0of1oQGBZA3\
|
||||||
AQmLGJQmUXv4czj8+SEQ/1zigZMHSKnQi/O3XvuiPdaULhVorqosknbfo29QvHtrtYAE4F22wGsfld5vAQ3cbzsdl7HRWczDDAjDnCMGqEpdGcWsmeMmJkhH5zHlQfPouROJee5ziM5dIL20UgUQ3t7YctVIRSZ5\
|
Zi1h1GnnfgKMYS5xByjRWxnF0pniJMbIR5chaYQ0eNnqxTR1JUSn7TFGlstpvH9va7cNYttETlcYX4jKDjj7LXCPvxAJDmnmNh7Io122iJhqiOkyMLHoivVPNty4HDDhmvMG5g5UbDGH1fT4sRaheUS5XRLYdg+a\
|
||||||
PTY2RHBHXLg3TABatU07L9KR/LQlQeOYXLAaDdbkAo5Sbq+djxhqXSqCSQMzdymH2fTkoRaOeUA1aZJ39VPbOCCbUJIx4z70oW64k3Q1HpYUNp1ki2I2aFbaD3zVyeleDOkAy1i69JE8AhAXMUE6ctFAoPs6ZjVZ\
|
sUEypuO+hOuC5ojGCcTxYmyzmF2K3KCXnt/whaHW6GJgB6Qmp6sT0ROgsg2J2EEb/QPWL0O2j9nkbg2FAPoimItYfcbidR5s9jORPu7CUyIYe/HpX+jFtxsfOJ5p4vgViRuTxB4n7QGEye51xgjbpAPGQJs46oZH\
|
||||||
Tm+1RhGYwWjWJewKp+Jx7q37Kux6952q19iDz/+DHrzDeuR5pZnnX2RLob6py4+b8nZvjdiVObAptI6rrgW08C3alShaDfSD7OLRzyOffiKfflBeqYDpB6WfUrmGuZHj01POe+dSW2KZGhJGvC7FEkkc9sHy7LA/\
|
A9+lWYm51ehCZ10W+tbln8DlH1RZyhP+QWOuUg19o9A7J0G06RjY53RwG/Hm60xQZNRyAGDOhgMGaBtoAgMeCDkAb1Y848T7uL0EVhMX3NBaDrea43saIuwgO+fIFQG2Dn04pYCMQ9hnQClgQxAyaAka5HJc7ziD\
|
||||||
QqVAi4848onYR+J6wtcFUnd1jY1McEFbJtzoagboh7hn4HnpXjS1dQxGWFNKLaCluAkaC1oCBrbL2arOKdwYOqRT1hcKXTYQpyY+i4RbJGUEr5ifRJHAlq807LQVi+bPHN/BEg8ry+dYAkJ5kM6gGhUcvftSmOBT\
|
W32ndMLZNwrdNNCoJrwIRFoSTv7D7LSfxJbAlNeiOp0LrvkPBlSY9ZDL8CkmZNC5R4OsBpYDeH8TIfjUGJbON86JL8RldbF+IwTJaiGYrpCAzi2KwN9cloWWD5Vp5CJ5AEP57Bvlsqkp9ZATNjaWD2t0it1dQ3fL\
|
||||||
41farp0QXZh42WbsmCBbzQSzFRzQu/8RhevLvODoUJmOL7J7sFRICrexgtScZkAxBDqKkzc6x+kuYbplcMDWLgH3l3DI7cvwLddRAkJaGt94RNMsekRCEp7ohOfUVkRigz79Qv8TqeVw9zDiK4fXuuOG+cEZd605\
|
5ICpXcPeX8Mih9eYaANJihD6qnl86wl1s+gwCSl54hPuU8u1hhCAicFrEAhd87fH+8cB3927zQsn3zJ3IV4N6sgV/1C5sG3a9xKuOBszm+CGafQDdTCk7cYz6ulPwCevWVzkjCNYyVov2ROvKv2fMCUfrmfly+cB\
|
||||||
Rx75+8Y32GZDT+GCZXwxRWxpdAd1tE24TjGT8xMQySsvU5AKEJbo6jk75E2DKUaLyR27nAbAUyj99+G22z2HX6MVTtuZ8nbi93H4mPoxm4RA0z8PX192zEOu6ACTCqPoZZzTk5GbOMUmp7NBDJRjqYjRnmassWjC\
|
uAql/7c/7XrO/iuE4zSdCU8n/BD6Z1SPso90w1SFvAts+x65z7nIAKwwop6FKf0CoAhsV9kdPr2OM4rVmPhlq+AbG1nSTUnxgtgKhZzjGY8aEd59nopVbfJyJAsldi5odu3uDofX4XCwwmR2gJpRx9hmf4qxnd5u\
|
||||||
iAfE6icWLkp7/Lt1nIs+XRO5+7WrUpDroaqvccGgUhdE1g1W4IORmfQ0bfm7aNrZ9WqWJSwWHCaUtfy1arb5ZDV743MkzFvObLJxhMZltUrVpv9BVWv+/aqWhUm0rG33OVDuaGciis7RDjpDwZlo2ZSKhjVc/jSE\
|
aVnBYvpfRAeVv9XSVp9sae98jpL5hY8yGSIhxCxWWdv4L7S25o+3tqxPgmWDe8jJpC3vjMXOtbyDLpF3wbxDN2S8XQ23KA3twMJhgPCGLKFx9l1nGx0LiJrt4jWCWzS9+xDxsdUYACrQNY1l86dNtkDfyC5FSjxH\
|
||||||
gYVHAPEHUoXGw7su13rqD8Xa2Ss0a1H37kLgp2gmYJoCXPNUkD/rCghWaNl+tCTwhCSVXbwSy3X2UMoInCjGUhPWLehBqmvCsKUf/jWpC/IgIiHZnIEXl7viSkcTUnGwFlxFF0u4YXeyVB1u9qEStNgd9XCkPBwp\
|
T1KexWvBr9PHrSyJNsasEjYv6EeqW4KxmRsFFge5wctwwJyAL5e22Y4tT0iGwYa3ji+W9oadykw1e3PIF+3s/qCzTcrZJqXrrSGpadKPctoJnW3e8N3PHt7B3JBGDuftxqX6A4z3AYVyWTKPBAHJ5uANlZ+cY801\
|
||||||
3eKFWKaIHfsWeFt3/QPfVx1YO1gj0jHh3GEt13DVuXiPHLnMls/F/hHMjAUzP3m5zCtQRHBVXUXW+tDnACWXT1dCEmVZsP7pkJwuQfLiJZzs0ehKnwS6NRYvtJ7WQ4Zp45UiF1kXOdHlgw+ehZfhic9Fc2NJ1Tl6\
|
O0RkVWEPt3ckQtvJSkKiKvM2vfUC1hj7wKXnZImeV69hcU8Ga50TqMZ8YVt7XY+ZrJWTIWyTJpCis0c3DtRLcOGXYsIxgeoSPcsPMJoGHGUbSn9o0GULMQcY+CnQgiCQA0eArtQP6hGDh246eYfM4x6ZA9GeZz+1\
|
||||||
k+9hNawQLjowv+8MS2ddjjDSU1HRHdhvYP/TtcpRu2J03y9d78F3MoBvJHLzxU9eNVVEPi7PpG9BNiN9Jdgjvm6YWKAmoywEwhgC3QZrqOSLqjXlpd6MuA54PeTIcPmmhK60BDtJpxu8Rlkd8lYk46CQx81VAnsN\
|
e8Xn9tKTvns2fS2iRaJdMbNAzC6zQmWMgA4BE+GxGuSc0QnV2wHn5m5K3Dd7m0FVnAFa0jHA1BhEsjjmechZg0IxN+t09gZCVj7itmzJ03DqOSK4EhcGPXXdRsGDvrpuQM49PkDrg0RWr6S8VQcg2g4iDDtgULSy\
|
||||||
jVXOaResxvN4Fnj8t9IijAay2kXCo6Gs7iyc25w2G5qHLFtJcqueaVj0bMG4ZwaKSPYCvr4xt8LWk3CRby8Q3hJxvHcHhoKlcsMLLisoOsepU6VQvKcaiUhaLnvT+mzCMh1IUemzH8QeSF6xPRBNvSiiZxjo7AwL\
|
E+91Id0KxCdxIxcu0KZFgi72e1ghpwTDq01R5eg7NaYUkvRUJaHJnBPetL4Ys04HJlT64kfBA9FrxgPBxAknOsBAJxeY3/ioFWKD+8vZjx1I0KxjSNJgkG9c55uswgXy7gmsDRhQRW+PMfzWBF3SSBTPMbsxWX43\
|
||||||
Hh84HjaIYrZXeiZBd5Rt4gm64+x73qQVzpCCj+B4QIMqeXOIgbcu3JInInsO2Ycp7a0YsEAZqLRvDpAg6lGar1evJTbDxFbAxwNqzit3dJb/G+hsSGFqlYWA4Isd+1bjj1oIpW8hPLnSQkgmXExbYOHnasF5QcuD\
|
hC2gg6e4CweUWmIz167eymmGOc3icR37pQ2TpX8Ak/XZS61CCEi+NgmbrwGuRQiZixCerUUIEdZM8Uwi9NRqE3TFiQTpOp6auDzVxZiGvrrwWDdfpWhwQgqJXRVP1MaNJy7kiVt2IITI7LAWIR7JZkcrQMIa3Xh4\
|
||||||
3FtNU1Ofpvo2pqGPRTzU3cc0Ojsh1y9JeCB5pJ0rPvNq/ZgcyEJkcrjSQjwQZCcrjIQrJOT+ExFgqJl3DzHZMi3W97+iH0AI7CZ4pQI9Y53yrVa0CKrppxPXUnFZn75Ktm5RpP57Say8Xo69AiFm50sSLOu9QBEG\
|
LtoLLfP+MR60TOzm4df0ADTAfoR3HNA51jFfEEVEUEw+nbmWEsq6/JUxukWU8ceyWHa7EnsNGiyfL6mvpPMCBRkcJSang62tEwpfOtYHCZdKDmeWofOsKAMyrx23PTmRyS7Q/7nEvtEVCOxQHXnfiP57/tAjRDY8\
|
||||||
T45JktBpPIHwuaeDEHDA8yiayhI9Zxg1xrhqCOXroHqb8gz9n3OcG12BqNhWB8G3IgKP7wdkkW0fPjD3uXY78rNx+c5zio3j7bu95yElflFp2/W8nP11NWK8VH+dzyHb1nn4Oxiqx1w433kC8Uqml9pe8/x6XV6O\
|
fgQ5mZiaHcg1HLz4v/eSIuR4/e3gpc/GCm9JbKbZ9IfVG+Oc+Jfp3B86Tv4eBuzxCFyTgQLGINylhhuOa6+z6wEa5LkdoqUVCc8ySUSqPYvmRtpEIFLGYYJi8tCt11jUUgzuh1gR3D8DgYnF/xGFx+xuOY8G77tQ\
|
||||||
UC3Pi23Ut8LhZXnCR2w9i+4O3FQspJJjBNX0vt+vsamlGd2NsSO6+wIYJhX/RwQek3vBBTR4vYbmp001gLyxdGrs1G9esJGunStXFK7uzd2mzTfZjs64agTNih+JWl2F1j30wDCX9MmRzh3aE7lhszccYbkq2jP+\
|
/zSpCjZvJJUaK/XbMwbputXbeKRZundTAQSkO4yjE04eQUDxjri1zdP6Cj0wPFT65GDnHs2J3LDpWw6yrAv4jP68tK2y1Ri/IWWLVxdJQs2Dzz3f3uPjIaIDRi3+Qke0l09Dh6KQoL4iXWvaWvdbltg7Ct4jKNB6\
|
||||||
Xfww6yV3f0Wdlrs7QFU0f/gUMCzluXc4M0SAePFfAYS7gy3JUKhQX1GrNXMa/vPSwTtkDjivG74LZv9dLjfky/E7JWVzxAuxUsLl0b9PuZgGNal8rau/63CK0mQtL11tr7kalaC+Erx5kmOhEBmP7cG34Z7xHFgG\
|
3JM/cpX6GxJ1nVUnPBAbJBwefft42h73FHI3vDtrH6/Q7W2kWXsF0KznZjBdkQ9fpEgxV4hQY73wIVztnYO4AOyKfoVfP5I1NViFYR/4Mbohkav4Szg5+yj4ISTFF0kiMf9j/qpIAd9bQJBtn/NHDFAj5M+fgxtG\
|
||||||
TK/kF3j6gRwFg10Y+oGH8Qdiu4Y/4mPZW7FjDiVlbPwgzCb8LZQKPhSBtnZxzF9fQKlgj4/BG6NS2l7uv+RiyC729S+23SQ1bX+hWlpXArDJePEyi3ijqvD69J/+QqIDuKjrhcRs8WLFD/FVPyRX/TC+6of0qh+y\
|
+bSdNNqIsGEb9/o34zY5n85/pYRaDvrt9JIrnANGvNxknTr9z+9Jd4AYNbVwPmvPVjwI1z2I1j0YrXsQr3uQ9B5gwSAGteE1AujLjUMg9YDoneGl4YtOpljgKvjBftPTcF/w8TWsBa6o4pVki19CqYmPoUo6ya8N\
|
||||||
wQ/YMGiCFvElmtDna/sA5RGBusRbymd+iCDyxftot5toezcA+ASXcJBac/0M2t13ghbqGKek7H2rxb4gDDwjG5tSpn0ktPCWcGwhJU63OUOuCfH9F+Yh5X01oemcVLGlSOIXF5zsL1pUfs/4ta/vEcmWcBtU7q2g\
|
2Ze0EacEs/kafmcvarJLRNbKdfd7fFQuN8xsL+ZJB/K0W5dkjXMKJn4pB2+23tHveJtBr5oHxLwZXNLM5aZS2L8LgveCfDg+QeRnz74lTVCyjgM2BUQHp1A2uCGjgOpBeJYTA2BB+JLp3V1CfuunSI8E9N5AGj7G\
|
||||||
bYf0jzeEQv7AicFTfkecX7NsA7KEXAmknYroAykCFAdCo1wGAFIMXzIzLwxgncTsF+N4ldFyCwuSclWNcd6iDG9tYhlwI5fiRnJ3gQW2BllZbK2Z0/nFNwwp+IvP91xuVY9LuY6BFTQVyoazG2ymln85/kuAX6sY\
|
eW3m393BZOBK7qYN5LICX6TR30O73Q0zm199x2SCv/DyoD1h1aNMbmBg9kyB+uHiDsPU7Pvn33v47YcRnpzMnw9APeZznllyj793h1QtqQ3S/y5/v6Di5LT8hIIE9A2K5mAb7v7jV/MaM12K11QQqMibKK/c/Ul2\
|
||||||
Y9pkfjwCsWjnvLPstvt2n5E7hjl+LiQKb7mPLmCZmj2iaIHBezMdEOATBPi9v05T1+I4WTI40XIt/KtA2Rbc4rBeoT3WP9Uwl/Uil3h/uhi5W1Ym9SsdYTgrFk5jdGPzdoUZH6rgzzB4Y9GhxEp+/LzMyyElQuf3\
|
8QpL3ModJj6V0FfuhC1TDAkN2htV3Vti0JzNCh9jNG3TeoQp55VY+rSe0xbdNOsf8EPE7LZ/KblarpQUBXpriXM9ukoNdDd8JQl5nm7HwTcS1D0PDvHgYK6ZjOYPTOErRubbrHEPXlR4x6Xs0kzRtesIbwiF8GEL\
|
||||||
y524JyVv/Xk4IKDL21KTaHlkTTfm4CMV6nYASTwgONEVWEGZsGme8tdqiv4XJOBdM/4zIygdfmJicHMI72J9wzc4o76ji+UadOmNlV3TfTCAXh7x5fGKbyHRd62eyUV2gJxpOVBMBqCQHD/2E98CvbAW/NFBgLIN\
|
Q/eE8IrXK4Y7OUIzSdZoLrVhMn5GH254amYzjzSACZBQo3O+fI261YiHnBaYH3AX4ORm+00Kcqw9SvtP5cNude/13E+evprN3rx7f9NMBT5A1SesfAVDvt5RNncFec9D9qq0WbFV1C8nUcp2m4P+1xmby2p8lcTw\
|
||||||
sP+jxy9PT1//+O4DbgNvTCXL8JXvdsiXR+ruGiGTG25Wf7ECXRZLJxsP32Zv+GHJ7p4b3i2ZsVgonskFNSwl+ZajVaXbRg4Fh10hjopJSuBXNDa47GO8sc4VPF2UYCqfkYN6kmgbrYUt+WSf8XEnIy2OPF3Iyjia\
|
OV9lT+VOGuaTfMNhqqydTwqJhk02jgpJMeBXLLY492O0tclpPE2QYCKfY4OkkmCIgGFXPn3XSXyVljm2nC1kZGxN2rLz3SVpX6xq336frnmHwndY3N7ztgu7sD/8srBz+LaoVkmYBCoIFD+p6wa9L140dwwj53Oj\
|
||||||
JGbva1Eyvlo13n1Xr3uHonjYvLkT3KyKRfHXt4tiDt9E1SqLs6ilHMW/0HdSex/Z6O4JJt5nUmPPS2ftJ7ZTg99H0WqySX3t08/d0xe8W4Uf3yz5CyEm67r5C5LUuAPb7o0NCIc4ECmbGt9LUZA31F8AKadZ6sbP\
|
oeOks+0T+JRZULH45Y16AvRzRI+pMnQKmp3BuvCEF4Kx29wpyLXx/guomOf48w3tav1rW3KE+m07BWShlc3kZnNduOab2Pj5qcoprOv3O2KHpTYzEnT6GEkozsz4RzpnrX/d5zR6fDHilz++gnWFI7pfttxGGZdw\
|
||||||
4EXckCQWNuqya6yeEQudkuVuQ15h2/hS3JYJ3d/XGISBKh4slleTY6piuWKJ1ctmDV017HUfdk9SU4Znzjuo04UAXuyBB8I8ZQjf8zqruFtD8vOftctPP00r7eay23H3iJIll4/HDPXqUPYN72oNajD7FXnDe7Lu\
|
HA/CApp8eQKmoBkeUSrR9Z9MaeaDUsgVO+OVat3gf2Kh1rgysyxtfmJWb7OM3qdy3LvGDQer7mdMOuVRr9xJNG+/uoJ/vc+z6N7YmLzkfmtDud+qaAuHbsH2PvXT6zPXK76tq3vtde950CuHvXLUK8e9sumV825Z\
|
||||||
Iy34N/iaix6sjTVH/iVq5X/XwjX2/UbRn8MM5rR6xfd89WC8HvweDdrxoJ0M2umgbQZt22/rwX50b3zgN3oj/W/96LNle+h3+9PXtKPPpKHraOo6Ghu202va2TVt89H24iOtnz/S6n8taFXbfrQ9/xjvXPv3uXyb\
|
9+ajO+09t9Bp6X6vR18sf7znT/vTt5SDz+Sh23jqNh7rl+NbysktZfPR8uIjpZ8/Uup+/mdVOf9oef4x2bn173PlNv4sGi0+Y939mVe3aIHezHVvJrpHRd3pb8Mt3HULnW47GVVHbuGlW+hsyC89TdObp+2V8165\
|
||||||
fhaMFp9x7uHOm2ukwGDnerATPYCi7s235jdu+Y3etL1aqAO/8dxv9BDydiBpBvssBm07aNfxCi7R/0Eu/r2lwG+VEr9VivxWKfNbpdB17c/808p9Q7jjwAw5jyoUx8xpSZdlmzPU+NsLHaet0nFXnhSMWPikv2/E\
|
DFdIif4LpfjP1gK/V0v8Xi3ye7XM79VCt5U/80+r9nu+jQQmKHmU5zhqr57zQd2cqcZfJGokbZWNW7vSQQ134fP6LhCOklRFCoBw+fNi/mtTGajY/Pv/ALbA9mA=\
|
||||||
JlmuEgVGbP3zYv5L1xmpPPrX/wFeThnJ\
|
|
||||||
""")))
|
""")))
|
||||||
ESP32ROM.STUB_CODE = eval(zlib.decompress(base64.b64decode(b"""
|
ESP32ROM.STUB_CODE = eval(zlib.decompress(base64.b64decode(b"""
|
||||||
eNqNWnlz1EYW/yrjwdeAs+mWZqSW2Sy2IYMxpBZDmDXUbCWtlgTZSlwwTJVNFr779ru6W5pxav8YI/Xx+vU7fu8Q/z1Yt7frg+PRwfK2MyP/Z/oInhQ+FafLW+UfK+1fG//rlrdOjWjQmOXa/4Untbs4p1lcaf+f\
|
eNqNWnlz1MgV/ypjge0ZY9huaUZquTblA3YwhlQwWYyBSWVbLSlma9cF3qmyIWw+e/pd6pZGTuWPAamP16/f8XuH/O/ddXO33j2Y7K7uWjPx/8wP4UnhU368ulP+sdT+tfa/dnXn1IQGjVmt/b/wpB5enNIsrrT/\
|
||||||
lRroKVogP62EA5U8JT8jHLUzP+2SM2t6Vn5MZeHsCR4ceNrZYG78gejx6yGcsVj1lhwCDaCrzQgGpnCNsdp+A6VOiMU28qcLzyMfC7y0TcK3G8iqqoCFdMAgT1/ullr46fhsBnOde0QE5IcT01Gi5h3hJhvTLYFv\
|
z0oN9BQtkJ9WwoGKnqKfEY6ahZ920ZkVPSs/ptLu7Bke3PG0tcFcckX0+HUKZ1zc9JZMgQbQ1WYCA3O4RqLGb6DUEbHYBP507nnkY4GXpo74dgNZlSWwEA8Y5Onr/VLrfjo8m8Fc6w6JgPxwYj6J1Lwl3KQJ3RL4\
|
||||||
k/vnGVzGyGXuw8jy1s5E6rIeZNRNSz8FL4UZn+SgUk/EOZZg7k/qNHNQCMvJoIaV+dV4z7/mUWRw5a47eeMXaLpcNWPaINDuDiHCZKN7k2d9hZ+jcNew5PxMPYHxZ2fn44u8Gg+EbViQYJPIpRoYKL5U0wfgKo/o\
|
Npl/XsBljFxmD0ZWd3YhUpf1IKN2XvgpeMlNcpSBSj0R51iCmT+p1cxBLixHgxpWZpfJtn/Ngsjgym179NYv0HS5csG0QaDtPUKEyVr3Jk/6Cj9F4a5hyemJegbjL05Ok7OsTAbCNixIsEnkUg0MFF/K+SNwlUO6\
|
||||||
vrZmyZuBSsw0fT85kacX/jKyR/foGqIbVTUFnk+jYvhCV2D/MA/q6S7ObJQtr4CLFEqtQZduufYL2pYW1NtkaQ2pysIz7ALFg/RR0H6ituwUmpln027ZtMNG8IEqNe0acQHXVrzPIlrcVhm4G5/BP7ix9vRdBSTo\
|
r61Y8magEjOP34+O5OmVv4zs0T26hugGVc2B5+OgGL7QJdg/zIN62rMTG2TLK+AiuVJr0KVbrf2CpqEF1ZgsrSFVWXiGXeB6JZta6Scqy06hmXk27YZNu9sIPlDGpl0hLuDakvdZRIu7MgV34zP4BzfWnr4rgQT9\
|
||||||
B2OBnMuukh01STjeI3vGswlt5Dnjs5NzTAlG9GgoBrmljrdsSF4HxLsG/guCIKW++qWGiMEEXNJPrjc9N6DVwPXBjKdzIXc3Skwib00WgBCgD/jJ0o0iI1XnC68B8LGCeG4KhshG9UzgLZ3fR54jkmOAOzrGslps\
|
YKwj59LLaEdFEg73SF/wbEQbeU757OgcU4ARHQ7FILfU4ZY1yWuXeNfAf04QpNR3v9QQMZiAS/rJ9abndmg1cH0w4/lSyN2PErPAW512QAjQB/yk8UaRkaqyC68B8LGceK5zhsha9UzgPZ3fR559kmMHd3SMZbXY\
|
||||||
Q3tQjBk5reX5pmaXZlNpE+cKa9ycIWUgKJMSYeLi6F3xFwQbXjPdXEMXo2scZ4xLWTwTaMi7rscce5B75gAtsyceEYpNhIKWY7fwiMICd8hHbYyzG1uLu1hP46c8X6Uv3g4bcNKZx5nG/A2u6J8qlwwDooFQ/Uux\
|
mvagGFNyWsvzdcUuzabSRM7VrXFLhpSBoExMhImLo7f5/yBY85r55hq6GF3jIGVcSsOZQEPedZVw7EHumQO0zJ54RCg2Egpajh3hEYUF7pBNmhBnN7bm97Eex095voxfvB3W4KQLjzO1eQJX9E+li4YB0UCo/iXf\
|
||||||
s0OnA3IKxHZbGBdbvoyyp7u8fOyp1Q3Bu2uicW5TkY851/3zaKdnykF8wn35cN8FBhenFq9JYjYBnDqhBX5nLUuw3SL8BHwQ1WvZsyfsfgcRSWQ9BqW4oeQ/pNL+mL6s05fbgVJ0L0C/R3ei6Mm+BXx+YC/bsRHr\
|
2qLTATkFYtsRxsWWz4Ps6S6vn3pqVU3w7upgnGMq8jHnun8e7fRMOYhPuC8b7jvD4OLUxd9JYjYCnCqiBX5nLUuwGRF+BD6I6pXs2RZ2H0NEElknoBQ3lPxVLO3P8cs6frkbKEX3AvS/0J0oerJvAZ9X7GVbNmA9\
|
||||||
USYSkG3HuGOesfHCPcpahHC0vAYXNitZd4ciIno8RWgmDy7+nlhp0ceYuNubu0MgvJT05oKWautjtqkoZTDF9wnsIv9eWFVORq4Z+40hqgFE1LM7zMlVW27hyMtcgtOEhVWG6cu/4dnxChRXnfg6n1LzKRDrJF0T\
|
ykQCsm0Zd8wLNl64R1GJEPZX1+DC5kbW3aOIgB7PEZrJg/MfIyvN+xgTdntzdwiE55LenNFSbX3MNiWlDCb/IYJd5N8Lq8zIyDVjvzFEtQMR9eIec3LlyC0ceZmLcJqwsEwxffkHPDtegeKqIl/nUyo+BZIcSddE\
|
||||||
CWyap1Ob5nlx48Gh9r9megpeByteeiZKuewTSD2mT/0VrCPCITESZRSiYRKKS7OaYosKJNXxxMELdmF471NCUMUkWdcJYZZ4XfzIKRl6wld2LcRPRdsh3IFg/M1Wy+t3/gHSnOy5wOObzauAO4KNdi0JBOJk3ez/\
|
Apvm6dSmeZ7denCo/K+eH4PXwYrXnolCLvsMUo/5c38F64hwlxiJMnLRMAnFxVlNPqICSXU8cfCCh5iH/h4RVCFJ1lVEmCVe5T9xSoae8J1dC/FT0XYIdyAYf7Ob1fUH/wBpTvpS4PHt5lXAHcFG24YEAnGyqnd+\
|
||||||
OCbvswjJv8LpI3IJ9Fdm2RbbfdbqbT7LCsPU5whgBbWj7wLOV/u0EeVh/0Xs8f2vebgqZ2FszUmCZdctfwMLnROMYsQsYgIVEeLld4i4FBNOiWf0YsoCc0eZmJcroPb03euXy+UpEYuxr6UB2veEwoHPYq49TNXd\
|
Ssj7LELyL3D6hFwC/ZVZtvm4z1o95rOsMEx99gFWUDv6PuB8s0MbUR72HbHH97/m4bJYdGNrThIsu27xCSx0STCKETMPCVSMECgKSbrV68eIwBQjjkkV6DlSDIBO9PzD5cHb16vVMWcUiqsKl8uih+98udIWHqiq\
|
||||||
ljpjEMSoDNulqIlCKllTddQU5Dh6yhaesa/laQY+9LXjMQep6eTnQ9h8/94E/jmcUhFWDSOj6Zd1JwyYmIPZR+e7HJsQaEFmlu8OmglOqJklN2Tph6C2jMJByyknbsk4lnMuDqik+V+l98iUA7pmSY2Wb0uJjRjD\
|
drPSsEhkAvKfQBjJJveHQOMOEo4289nPU9i492AG/03nVE2VwxBn+vXZESMfJlP28PQhBxlETLgsiFltE7B03qSZJTdk6S+d/FPC9YZzR9ySclDmpBrgRfP/MA/6r1yElGlUb2Vj6a0RxU56qdJVFCNaiS1bwZ9a\
|
||||||
qJdefUjiSifxaCf64DY5WnWPKq1hPEfFdMOkIsSylgKF5dqvygBSkA13KrxkaU2OI3pi0C0hzNjx8Xh0dMoen0/OqyvRaFr03cngoMT85/npMzidahWS+/qEqQ/rJSlXexUpI7jpJTUnvfq6l+4cxDc5Nmb3WEYp\
|
NWKc6gFVTeMJQcdPI/YFzBv143E57YqVmTlIJvvH7IfZ7BSYAbhQ5aXoaQHxqZQMe/TMjQrwb6fHLyDuUylB0lwf8THDckaqyV7ByABrejnHUS8B2Q1vclLIt7GwUTgMTw0Hvd/20EhMylbj3D4+vaL/AO4XbGUY\
|
||||||
HIanlkPs7/fRtkzGxubcET69oH/AKWd8EsYjeYEqtiIeFGnXZ0tXIVi/IBPDpXpKtAoOM1CxUQIXMrkJKRJFM92JZYgp+pU8/SC0Z8/HZUZKATt2GozOPSfAc6hg/6dBy9jhyqSlqq5pk/aIu78Pf98Fu/2NA60W\
|
IeQF6sqS7E+Rjnz+ctmFz1dkK7hUz4lWzsAPNVRTwNW0PMxIPSiNOUxLAZr3a2v6QbBNXyZFSqEYDNJpMB33kmDIoQlaxqNmi1O4huqsuo0aFm5vB/790FnfJw59WtAsNrItStVasCOwTQyLoZxNPfJhZc9jaSWm\
|
||||||
7EzNc0fgLSOrxiAci+fM4yz2EXgsq8VILzYNnXAVzKu2HDubZnMZcIylc0vik7jV6B02l34wuybpWZ2EOrMlPloAkfYVxOQHnpLDV7gOYuDxqtcGgqKtGHaCcJh8JYxWcVSXK8B3tWLw1dnlco1DurrsKPrrUuqJ\
|
d75proR0YFGVZYCo681lwHHFZuuiorrWU7aQaJBoNsKdBB8zErEspGTNG4iSj/y1HL5qkd3BTa8xA2VUPuzN4DD5STdahlFd3ADCqhvO4XV6vlrjkC7PW4rHupAMP5NlmHaAQ+nP2aR9ChybpFdBZ+X5Zo6O6NJs\
|
||||||
XJZhkgPepT/mo+4xcGzGvXo9ry63VASORDQseBznvsCRqUmnNYvZhMOz9HCydI1waEaa0AHXl1Qk6jI9H8Cy6pcpAEh4kLmjfNFDZudSPAsn7A1deUNJIYaQAteWZUWTVTppis806fmbdTyoCkxGUIzZHK2xuyfE\
|
liCOs1HgyFRkHoLZZvxwjgJQOVU5Z0oGQBfKHijbdNE/H1HP9msHyHjtyLiLc7Aev0uxzE5g3NfJChIWhoMc195mJU2W8aTJf6VJz+Ki7XYg/kFm6QPme3xGpECPL9kWaWdnmP6aHd3lRxjmlMq/urCq7p/+UYoT\
|
||||||
KrZD2hiM0oeXQHYOEUbd0LX96+9xVdM/vJEyiJdo15//LjCnKOjrdF5RZg3z/pRcaL2ChxVnXfoGemYAuzKS9WSzky5WvJgO/yWyrUvKDTrzPQfQ8hv4jCveoHQ45ebS17EXQbah29htbTACH5dYOF7PYxMM+zsQ\
|
XqJdf/5xx52i9EH3r5bKvD/lidDC1oHUkrog6etaRtIeha14seLFdPhFYFtnFK8r85ijYYZRz+WvSDyUCHNBWrE1ufxBaICSS337A2u56+WWRCBIKY9Jw2aj5rmgFEGB0ddgr7iH01LjnhIBagBfXIJ9HPzKGJhF\
|
||||||
cEDNZqPGWrwDuismAMHecsJv3FPaTd3mxRVYyJ//4cwnT7Jy/kFPCw8ptx4yBQk4BULDwgJyR6duckh2/jyeR5o9jstuE4DAs4zd5HnBiUgb1CdoEIQ4f4y2/Y++feECqqnmGMDmD2VBF4stuLedpYqb5306utyP\
|
ByhqMeEZxcgZFivLz+iUX+5ggaJszqmiAMQ9+LYckBSei3a0SvRZ1ibL0sNollnfdlTRSXB5gJa9GFlAZc6ywAVdzd+G+geyrVKMLZemRNjpZ2vRzDBKDMhYFSt/uR3FSf00ZASK/HodGZHLb1lpSGpPMpfEvOf2\
|
||||||
y1WhpUV8BnfpEozP2Socd2F0JXvKqF6rBtQrZgbSJ0tEf/0rolb4VqEjcFthKP+GVVaxK98PMpYaQ6dHh3Viu67guoBs976kWePbt9y/MpR3GC4PnIqpDzac1BfyC8Q/bvDJgrYLLbRjaldCSSJlnwY/r7GnBgeU\
|
jqG4bzh7dtzm6voxAIlQZyEYcf9LFjRt12H6RlABSC9Vka782RW2nBSqepcSmK4rsuD1KddlaTBaYUdrQZOCaFkbvgxQc0gJuqlbTvLU7eQzNbpc3F3SQUol5m3ZkvyIhPllDyTZyY35KVhi7hSOKWTaQKeJ3Mik\
|
||||||
9yj5C12fGS/PuO7MoqsIN1rLYEmkrI1fPqj5RcDKOI/ZqMpH3MhzafdMRyFV0DBAZy/IgZXSJPSuDYJjjsSy3TkcFBRloJdG0dBkaJm3rznFmAloQWZXcpoMxYwpUruNEOLSWhnHBshhbH8jEjKbTrBmvttBkoNL\
|
zxHZ37GpLwQ8ILEqOPcEdZsiNqHgyi6uJHFs4MGm6m/EY8ymPa5pyrSDhAOX7JwCbnWajTworOHZfou9a04UE2rHblOLFONKaOuOxolPwyBxQVeuTRQkREEIXB1A3sL6aqf4yMj/V3S0D6F2Q/DVRRMjqYaSywFW\
|
||||||
9s85gJJq530k6Jlh/yOC/NTn0UdsOO9RvO066T8DilXFtvD0dhibFuT6zSyJTaIixWGRgLmE9fV+/o4Dzk/o3ZexOkXQ13mbIrjOIWMrfkpKL83JNdYfe0NIOhzD8O4mUrlggiN9esx5VV2TExDWw87RHa3RnDvU\
|
St5p9Y6k80+G2DBNYPjxJmS4zvomX46/cYJTVeQABLiwc3ZP1zDj5q3eHut8nfWTYovfQFJwhYRTEfkqUps3FIStlB5QZcfFMUX/tB/9gVGN3bBq0vdb2OIqcngM7nNJUw/jwJ1FvpiyY2l2rI4aJFgF1wxYjZDx\
|
||||||
Olal/Q7faT83t/itJwOXGHMSJF9/GvOKvw3IFwRASOnHbc05gE/MOep61Hdd2IJZGdZ+0o8uCuFGMqc8cUgkeiNfiG5GgdyKU72AcmSaOtifJQXT98GSuh5tto8HWRJhqzAhm9jDPaBSLQ9iqwApgiM33EwEJ7az\
|
6UauZiEkYVcYbBbNIIVcVd1YGmoU5kUzOwVAc+VqN9TQSA88uOYuG3ivXdxxOQbup7eIVZSw4RWc02K9xXoqubZzkk05SlThaq2McW9EFZsa8yh9De61Dbj5hVwV+imWRQ3GUpUwC3JyiqEbYBv0Zg2jqisnZFWw\
|
||||||
NVeQRhJXy1ZmeIU08VquuHPu62ti3LFSGq7GOxmTfne7mf5VDQT22uwBen4if4W2kWVpg7nUFcxSrORgArEAbMEaxlZXjciuYBOkeqoYRQqQbDf8fSVplTS8tyN0abmfBnUjRdwRFXcA9NLcI7G1nJsHcU04F4EM\
|
qQKm8kmgAGZc84eHqIdQ896WgKXhRhNUbBT4JlRWgftJ10vEhpZTxRKbEV/OPac2EJW9HRRM8cvdCTtyTkqg7IPgThoV1NKVerKY/QzDmIpdQLrTECG42TwJgLkJKTJZAgV/CGbo0+SCineXxc42lnLyeLE5rhgi\
|
||||||
AVpdVKMHMDjEr5Nn7MpFDG/4HcPFZgyVvVLSlpOfQ0a5wADUEqUx27Fg5iaqyGQFJBDYMEE+HC+oHRq+epRcf3SbyjFSiA3GFZs1jBs2n1AaDWmI8Sj+AJLzuTBePARCPmpmODuK3x3r6YKjQTF/OHBpKDVqBLcZ\
|
0brZfLpW+JCGGI8iwZZyLoznz4DIXWJSyKKxE8LRsprD9+jaLp8NHBrS/QpBbUGHi9hiwCW3n4vPk/MvpIWVEqhaF1V6mZQlwGlBbCLcLwR5e0CyuMEDTNoEKzB8yxZzS/RxxP2vV/RWm0flNAQmPMZky+8RnHaX\
|
||||||
FbsivGH/aAsAzPbITLpulaQTjsDRqs/AIIcU6lxl4cBXoxge5dZVZperlhosXfeJv8c18dpkHdV7TM0e4MYDOhgEAZbmigWbRbiXg0wG4amFcqgDQKAeOcm5LrboBL/3/0DlKodhuIVki0idotEfnNKo97QswJ2T\
|
c+aEEaqB+NQiorugraoZ0Qp+Cv+T6kYjV/iPdJ2SEOI6cHO/c15D1QIkAQWpifz7F7BULj8Rzpp+Mwg3u/w31GIaVWJfg0gppt7ILcl6E0IHNH00sK4Pg26WhDCHAT7D73iGIzm3n/A7SSl/WgDel30nV6d2yw67\
|
||||||
njGvqMOKpJduN4q4bxI9/xBthlLwS4zIKp9/RgtEA64JHoBD7MO3oVeEfjaOwQ7DfI7fKw3Hc+6X4fegSv4LBXhg/pV8nbo+++xmZh9afLN5v3MeujDpFzp1eI+CcGWgBHPjSZIZFIMNTpZycuIY6qqN7y/oGnID\
|
mNmBjtli2e8odzle/OVKTR9QwVAaSOddMmOR52z08QYnSzktcYx05cZ3CYREuYGRGyDtJJxOG76TZOhld3+yW9u1/ecfa3sDfw2iVZEtFnlmFM/QX4hI5wbWw9+NxOvnWabzufEzzfX65ms3mKl0/ud/AYyHY9Q=\
|
||||||
IzdA2uN4Om34SpKhl4Oj0UFj1/aXz2u7gv/1olWZz2ZFbhTP0P+EkZ4RrIf/H5Oun+a5LqbGz7TX69WXMJirWfbtf+tUt2o=\
|
|
||||||
""")))
|
""")))
|
||||||
|
|
||||||
if __name__ == '__main__':
|
if __name__ == '__main__':
|
||||||
|
Binary file not shown.
@ -16,6 +16,7 @@
|
|||||||
#define __BT_H__
|
#define __BT_H__
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
#include <stdbool.h>
|
||||||
#include "esp_err.h"
|
#include "esp_err.h"
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
|
@ -17,13 +17,16 @@
|
|||||||
#define CONFIG_FREERTOS_THREAD_LOCAL_STORAGE_POINTERS 1
|
#define CONFIG_FREERTOS_THREAD_LOCAL_STORAGE_POINTERS 1
|
||||||
#define CONFIG_BT_RESERVE_DRAM 0x10000
|
#define CONFIG_BT_RESERVE_DRAM 0x10000
|
||||||
#define CONFIG_LOG_BOOTLOADER_LEVEL_ERROR 1
|
#define CONFIG_LOG_BOOTLOADER_LEVEL_ERROR 1
|
||||||
|
#define CONFIG_CONSOLE_UART_BAUDRATE 115200
|
||||||
#define CONFIG_LWIP_MAX_SOCKETS 4
|
#define CONFIG_LWIP_MAX_SOCKETS 4
|
||||||
#define CONFIG_ESP32_ENABLE_STACK_BT 1
|
#define CONFIG_ESP32_ENABLE_STACK_BT 1
|
||||||
#define CONFIG_ULP_COPROC_RESERVE_MEM 0
|
#define CONFIG_ULP_COPROC_RESERVE_MEM 0
|
||||||
#define CONFIG_ESPTOOLPY_BAUD 921600
|
#define CONFIG_ESPTOOLPY_BAUD 921600
|
||||||
#define CONFIG_TOOLPREFIX "xtensa-esp32-elf-"
|
#define CONFIG_TOOLPREFIX "xtensa-esp32-elf-"
|
||||||
|
#define CONFIG_CONSOLE_UART_NUM 0
|
||||||
#define CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC 1
|
#define CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC 1
|
||||||
#define CONFIG_LWIP_THREAD_LOCAL_STORAGE_INDEX 0
|
#define CONFIG_LWIP_THREAD_LOCAL_STORAGE_INDEX 0
|
||||||
|
#define CONFIG_CONSOLE_UART_DEFAULT 1
|
||||||
#define CONFIG_MBEDTLS_SSL_MAX_CONTENT_LEN 16384
|
#define CONFIG_MBEDTLS_SSL_MAX_CONTENT_LEN 16384
|
||||||
#define CONFIG_AUTOSTART_ARDUINO 1
|
#define CONFIG_AUTOSTART_ARDUINO 1
|
||||||
#define CONFIG_LOG_DEFAULT_LEVEL_ERROR 1
|
#define CONFIG_LOG_DEFAULT_LEVEL_ERROR 1
|
||||||
@ -58,6 +61,7 @@
|
|||||||
#define CONFIG_MBEDTLS_HARDWARE_SHA 1
|
#define CONFIG_MBEDTLS_HARDWARE_SHA 1
|
||||||
#define CONFIG_FREERTOS_CORETIMER_0 1
|
#define CONFIG_FREERTOS_CORETIMER_0 1
|
||||||
#define CONFIG_PARTITION_TABLE_CUSTOM_FILENAME "partitions.csv"
|
#define CONFIG_PARTITION_TABLE_CUSTOM_FILENAME "partitions.csv"
|
||||||
|
#define CONFIG_MBEDTLS_HAVE_TIME 1
|
||||||
#define CONFIG_FREERTOS_ISR_STACKSIZE 1536
|
#define CONFIG_FREERTOS_ISR_STACKSIZE 1536
|
||||||
#define CONFIG_OPTIMIZATION_LEVEL_DEBUG 1
|
#define CONFIG_OPTIMIZATION_LEVEL_DEBUG 1
|
||||||
#define CONFIG_SYSTEM_EVENT_QUEUE_SIZE 32
|
#define CONFIG_SYSTEM_EVENT_QUEUE_SIZE 32
|
||||||
|
122
tools/sdk/include/driver/driver/adc.h
Normal file
122
tools/sdk/include/driver/driver/adc.h
Normal file
@ -0,0 +1,122 @@
|
|||||||
|
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#ifndef _DRIVER_ADC_H_
|
||||||
|
#define _DRIVER_ADC_H_
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include "esp_err.h"
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
ADC_ATTEN_0db = 0, /*!<The input voltage of ADC will be reduced to about 1/1 */
|
||||||
|
ADC_ATTEN_2_5db = 1, /*!<The input voltage of ADC will be reduced to about 1/1.34 */
|
||||||
|
ADC_ATTEN_6db = 2, /*!<The input voltage of ADC will be reduced to about 1/2 */
|
||||||
|
ADC_ATTEN_11db = 3, /*!<The input voltage of ADC will be reduced to about 1/3.6*/
|
||||||
|
} adc_atten_t;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
ADC_WIDTH_9Bit = 0, /*!< ADC capture width is 9Bit*/
|
||||||
|
ADC_WIDTH_10Bit = 1, /*!< ADC capture width is 10Bit*/
|
||||||
|
ADC_WIDTH_11Bit = 2, /*!< ADC capture width is 11Bit*/
|
||||||
|
ADC_WIDTH_12Bit = 3, /*!< ADC capture width is 12Bit*/
|
||||||
|
} adc_bits_width_t;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
ADC1_CHANNEL_0 = 0, /*!< ADC1 channel 0 is GPIO36 */
|
||||||
|
ADC1_CHANNEL_1, /*!< ADC1 channel 1 is GPIO37 */
|
||||||
|
ADC1_CHANNEL_2, /*!< ADC1 channel 2 is GPIO38 */
|
||||||
|
ADC1_CHANNEL_3, /*!< ADC1 channel 3 is GPIO39 */
|
||||||
|
ADC1_CHANNEL_4, /*!< ADC1 channel 4 is GPIO32 */
|
||||||
|
ADC1_CHANNEL_5, /*!< ADC1 channel 5 is GPIO33 */
|
||||||
|
ADC1_CHANNEL_6, /*!< ADC1 channel 6 is GPIO34 */
|
||||||
|
ADC1_CHANNEL_7, /*!< ADC1 channel 7 is GPIO35 */
|
||||||
|
ADC1_CHANNEL_MAX,
|
||||||
|
} adc1_channel_t;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Configuration ADC1 capture width.
|
||||||
|
*
|
||||||
|
* The configuration is in effect for all channels of ADC1
|
||||||
|
*
|
||||||
|
* @param width_bit ADC1
|
||||||
|
*
|
||||||
|
* @return
|
||||||
|
* - ESP_OK success
|
||||||
|
* - ESP_ERR_INVALID_ARG Parameter error
|
||||||
|
*/
|
||||||
|
esp_err_t adc1_config_width(adc_bits_width_t width_bit);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Configuration ADC1 capture attenuation of channels.
|
||||||
|
*
|
||||||
|
* @param channel the ADC1 channel
|
||||||
|
* @param atten attenuation
|
||||||
|
*
|
||||||
|
* @return
|
||||||
|
* - ESP_OK success
|
||||||
|
* - ESP_ERR_INVALID_ARG Parameter error
|
||||||
|
*/
|
||||||
|
esp_err_t adc1_config_channel_atten(adc1_channel_t channel, adc_atten_t atten);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief ADC1 get the value of the voltage.
|
||||||
|
*
|
||||||
|
* @param channel the ADC1 channel
|
||||||
|
*
|
||||||
|
* @return
|
||||||
|
* - -1 Parameter error
|
||||||
|
* - Other the value of ADC1 channel
|
||||||
|
*/
|
||||||
|
int adc1_get_voltage(adc1_channel_t channel);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Hall Sensor output value.
|
||||||
|
* @note
|
||||||
|
* The Hall Sensor uses Channel_0 and Channel_3 of ADC1.
|
||||||
|
* So, firstly: please configure ADC1 module by calling adc1_config_width before calling hall_sensor_read.
|
||||||
|
We recommend that the WIDTH ADC1 be configured as 12Bit, because the values of hall_sensor_read are small and almost the same if WIDTH ADC1 is configured as 9Bit, 10Bit or 11Bit.
|
||||||
|
* secondly: when you use the hall sensor, please do not use Channel_0 and Channel_3 of ADC1 as
|
||||||
|
* ADC channels.
|
||||||
|
*
|
||||||
|
* @return the value of hall sensor
|
||||||
|
*/
|
||||||
|
int hall_sensor_read();
|
||||||
|
|
||||||
|
/**
|
||||||
|
*----------EXAMPLE TO USE ADC1------------ *
|
||||||
|
* @code{c}
|
||||||
|
* adc1_config_width(ADC_WIDTH_12Bit);//config adc1 width
|
||||||
|
* adc1_config_channel_atten(ADC1_CHANNEL_0,ADC_ATTEN_0db);//config channel0 attenuation
|
||||||
|
* int val=adc1_get_voltage(ADC1_CHANNEL_0);//get the val of channel0
|
||||||
|
* @endcode
|
||||||
|
**/
|
||||||
|
|
||||||
|
/**
|
||||||
|
*----------EXAMPLE TO USE HALL SENSOR------------ *
|
||||||
|
* @code{c}
|
||||||
|
* adc1_config_width(ADC_WIDTH_12Bit);//config adc1 width
|
||||||
|
* int val=hall_sensor_read();
|
||||||
|
* @endcode
|
||||||
|
**/
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /*_DRIVER_ADC_H_*/
|
||||||
|
|
57
tools/sdk/include/driver/driver/dac.h
Normal file
57
tools/sdk/include/driver/driver/dac.h
Normal file
@ -0,0 +1,57 @@
|
|||||||
|
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#ifndef _DRIVER_DAC_H_
|
||||||
|
#define _DRIVER_DAC_H_
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include "esp_err.h"
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
DAC_CHANNEL_1 = 1, /*!< DAC channel 1 is GPIO25 */
|
||||||
|
DAC_CHANNEL_2, /*!< DAC channel 2 is GPIO26 */
|
||||||
|
DAC_CHANNEL_MAX,
|
||||||
|
} dac_channel_t;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Set Dac output voltage.
|
||||||
|
*
|
||||||
|
* Dac width is 8bit ,and the voltage max is vdd
|
||||||
|
*
|
||||||
|
* @param channel dac channel
|
||||||
|
* @param dac_value dac output value
|
||||||
|
*
|
||||||
|
* @return
|
||||||
|
* - ESP_OK success
|
||||||
|
* - ESP_ERR_INVALID_ARG Parameter error
|
||||||
|
*/
|
||||||
|
esp_err_t dac_out_voltage(dac_channel_t channel, uint8_t dac_value);
|
||||||
|
|
||||||
|
/**
|
||||||
|
*----------EXAMPLE TO USE DAC------------ *
|
||||||
|
* @code{c}
|
||||||
|
* dac_out_voltage(DAC_CHANNEL_1,200);//the dac out voltage ≈ 200*vdd/255
|
||||||
|
* @endcode
|
||||||
|
**/
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /*_DRIVER_DAC_H_*/
|
||||||
|
|
@ -117,32 +117,6 @@ extern const uint32_t GPIO_PIN_MUX_REG[GPIO_PIN_COUNT];
|
|||||||
#define GPIO_IS_VALID_GPIO(gpio_num) ((gpio_num < GPIO_PIN_COUNT && GPIO_PIN_MUX_REG[gpio_num] != 0)) //to decide whether it is a valid GPIO number
|
#define GPIO_IS_VALID_GPIO(gpio_num) ((gpio_num < GPIO_PIN_COUNT && GPIO_PIN_MUX_REG[gpio_num] != 0)) //to decide whether it is a valid GPIO number
|
||||||
#define GPIO_IS_VALID_OUTPUT_GPIO(gpio_num) ((GPIO_IS_VALID_GPIO(gpio_num)) && (gpio_num < 34)) //to decide whether it can be a valid GPIO number of output mode
|
#define GPIO_IS_VALID_OUTPUT_GPIO(gpio_num) ((GPIO_IS_VALID_GPIO(gpio_num)) && (gpio_num < 34)) //to decide whether it can be a valid GPIO number of output mode
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Pullup/pulldown information for a single GPIO pad
|
|
||||||
*/
|
|
||||||
typedef struct {
|
|
||||||
uint32_t reg; /*!< Register to modify to enable or disable pullups or pulldowns */
|
|
||||||
uint32_t pu; /*!< Bit to set or clear in the above register to enable or disable the pullup, respectively */
|
|
||||||
uint32_t pd; /*!< Bit to set or clear in the above register to enable or disable the pulldown, respectively */
|
|
||||||
} gpio_pu_pd_desc_t;
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Per-GPIO pullup/pulldown information
|
|
||||||
* On the ESP32, some GPIOs need their pullups and pulldowns enabled and disabled in the RTC
|
|
||||||
* peripheral instead of in the GPIO peripheral. This array documents for every GPIO what bit
|
|
||||||
* to set or clear.
|
|
||||||
*
|
|
||||||
* This array is non-static, so if you need a very quick way of toggling the pull-up/downs, you can just
|
|
||||||
* do e.g. REG_SET_BIT(gpio_pu_pd_desc[gpio_num].reg, gpio_pu_pd_desc[gpio_num].pu); inline.
|
|
||||||
*
|
|
||||||
* ToDo: Functions using the contents of this array will do a read/modify/write on GPIO as well as RTC
|
|
||||||
* registers. We may need to look into muxes/locks for other code that accesses these RTC registers when we
|
|
||||||
* write drivers for the RTC stuff.
|
|
||||||
*/
|
|
||||||
extern const gpio_pu_pd_desc_t gpio_pu_pd_desc[GPIO_PIN_COUNT];
|
|
||||||
|
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
GPIO_NUM_0 = 0, /*!< GPIO0, input and output */
|
GPIO_NUM_0 = 0, /*!< GPIO0, input and output */
|
||||||
GPIO_NUM_1 = 1, /*!< GPIO1, input and output */
|
GPIO_NUM_1 = 1, /*!< GPIO1, input and output */
|
||||||
|
@ -27,9 +27,9 @@ typedef enum {
|
|||||||
} pcnt_ctrl_mode_t;
|
} pcnt_ctrl_mode_t;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
PCNT_COUNT_DIS = 0, /*!< Counter mode: Decrease counter value*/
|
PCNT_COUNT_DIS = 0, /*!< Counter mode: Inhibit counter(counter value will not change in this condition)*/
|
||||||
PCNT_COUNT_INC = 1, /*!< Counter mode: Increase counter value*/
|
PCNT_COUNT_INC = 1, /*!< Counter mode: Increase counter value*/
|
||||||
PCNT_COUNT_DEC = 2, /*!< Counter mode: Inhibit counter(counter value will not change in this condition)*/
|
PCNT_COUNT_DEC = 2, /*!< Counter mode: Decrease counter value*/
|
||||||
PCNT_COUNT_MAX
|
PCNT_COUNT_MAX
|
||||||
} pcnt_count_mode_t;
|
} pcnt_count_mode_t;
|
||||||
|
|
||||||
|
167
tools/sdk/include/driver/driver/rtc_io.h
Normal file
167
tools/sdk/include/driver/driver/rtc_io.h
Normal file
@ -0,0 +1,167 @@
|
|||||||
|
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#ifndef _DRIVER_RTC_GPIO_H_
|
||||||
|
#define _DRIVER_RTC_GPIO_H_
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include "esp_err.h"
|
||||||
|
#include "driver/gpio.h"
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pullup/pulldown information for a single GPIO pad
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint32_t reg; /*!< Register of Rtc Pad */
|
||||||
|
uint32_t mux; /*!< Mux seletct the Rtc pad is Digital Pad or Rtc pad */
|
||||||
|
uint32_t func; /*!< Select Rtc Pad Func */
|
||||||
|
uint32_t ie; /*!< Input Enable */
|
||||||
|
uint32_t pullup; /*!< Pullup Enable */
|
||||||
|
uint32_t pulldown; /*!< PullDown Enable */
|
||||||
|
int rtc_num; /*!< The Rtc number */
|
||||||
|
} rtc_gpio_desc_t;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
RTC_GPIO_MODE_INPUT_ONLY , /*!< Pad output */
|
||||||
|
RTC_GPIO_MODE_OUTPUT_ONLY, /*!< Pad input */
|
||||||
|
RTC_GPIO_MODE_INPUT_OUTUT, /*!< Pad pull output + input */
|
||||||
|
RTC_GPIO_MODE_DISABLED, /*!< Pad (output + input) disable */
|
||||||
|
} rtc_gpio_mode_t;
|
||||||
|
|
||||||
|
#define RTC_GPIO_IS_VALID_GPIO(gpio_num) ((gpio_num < GPIO_PIN_COUNT && rtc_gpio_desc[gpio_num].reg != 0)) //to decide whether it is a valid GPIO number
|
||||||
|
|
||||||
|
extern const rtc_gpio_desc_t rtc_gpio_desc[GPIO_PIN_COUNT] ;
|
||||||
|
|
||||||
|
/*
|
||||||
|
* @brief Init a gpio as rtc gpio
|
||||||
|
*
|
||||||
|
* when init a pad as analog function,need to call this funciton
|
||||||
|
*
|
||||||
|
* @param gpio_num gpio_num GPIO number. If you want to set the trigger type of e.g. of GPIO16, gpio_num should be GPIO_NUM_12 (12);
|
||||||
|
*
|
||||||
|
* @return
|
||||||
|
* - ESP_OK success
|
||||||
|
* - ESP_ERR_INVALID_ARG Parameter error
|
||||||
|
*/
|
||||||
|
esp_err_t rtc_gpio_init(gpio_num_t gpio_num);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Init a gpio as digital gpio
|
||||||
|
*
|
||||||
|
* @param gpio_num gpio_num GPIO number. If you want to set the trigger type of e.g. of GPIO16, gpio_num should be GPIO_NUM_12 (12);
|
||||||
|
*
|
||||||
|
* @return
|
||||||
|
* - ESP_OK success
|
||||||
|
* - ESP_ERR_INVALID_ARG Parameter error
|
||||||
|
*/
|
||||||
|
esp_err_t rtc_gpio_deinit(gpio_num_t gpio_num);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get the rtc io input level
|
||||||
|
*
|
||||||
|
* @param gpio_num gpio_num GPIO number. If you want to set the trigger type of e.g. of GPIO16, gpio_num should be GPIO_NUM_12 (12);
|
||||||
|
*
|
||||||
|
* @return
|
||||||
|
* - 1 High level
|
||||||
|
* - 0 Low level
|
||||||
|
*/
|
||||||
|
uint32_t rtc_gpio_get_level(gpio_num_t gpio_num);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Set the rtc io output level
|
||||||
|
*
|
||||||
|
* @param gpio_num GPIO number. If you want to set the trigger type of e.g. of GPIO16, gpio_num should be GPIO_NUM_12 (12);
|
||||||
|
* @param level output level;
|
||||||
|
*
|
||||||
|
* @return
|
||||||
|
* - 1 High level
|
||||||
|
* - 0 Low level
|
||||||
|
*/
|
||||||
|
esp_err_t rtc_gpio_set_level(gpio_num_t gpio_num, uint32_t level);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Rtc gpio set direction
|
||||||
|
*
|
||||||
|
* Configure Rtc gpio direction,such as output_only,input_only,output_and_input
|
||||||
|
*
|
||||||
|
* @param gpio_num Configure GPIO pins number, it should be GPIO number. If you want to set direction of e.g. GPIO12, gpio_num should be GPIO_NUM_12 (12);
|
||||||
|
* @param mode GPIO direction
|
||||||
|
*
|
||||||
|
* @return
|
||||||
|
* - ESP_OK Success
|
||||||
|
* - ESP_ERR_INVALID_ARG GPIO error
|
||||||
|
*/
|
||||||
|
esp_err_t rtc_gpio_set_direction(gpio_num_t gpio_num, rtc_gpio_mode_t mode);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Rtc gpio pullup enable
|
||||||
|
*
|
||||||
|
* If the user needs to configure the GPIO pull ,Please call gpio_set_pull_mode.This function will be called in gpio_set_pull
|
||||||
|
*
|
||||||
|
* @param gpio_num GPIO number. If you want to set pull up or down mode for e.g. GPIO12, gpio_num should be GPIO_NUM_12 (12);
|
||||||
|
*
|
||||||
|
* @return
|
||||||
|
* - True the gpio number is Rts pad
|
||||||
|
* - False the gpio number is Digital pad
|
||||||
|
*/
|
||||||
|
esp_err_t rtc_gpio_pullup_en(gpio_num_t gpio_num);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Rtc gpio pulldown enable
|
||||||
|
*
|
||||||
|
* If the user needs to configure the GPIO pull ,Please call gpio_set_pull_mode.This function will be called in gpio_set_pull
|
||||||
|
*
|
||||||
|
* @param gpio_num GPIO number. If you want to set pull up or down mode for e.g. GPIO12, gpio_num should be GPIO_NUM_12 (12);
|
||||||
|
*
|
||||||
|
* @return
|
||||||
|
* - True the gpio number is Rts pad
|
||||||
|
* - False the gpio number is Digital pad
|
||||||
|
*/
|
||||||
|
esp_err_t rtc_gpio_pulldown_en(gpio_num_t gpio_num);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Rtc gpio pullup clear
|
||||||
|
*
|
||||||
|
* If the user needs to configure the GPIO pull ,Please call gpio_set_pull_mode.This function will be called in gpio_set_pull
|
||||||
|
*
|
||||||
|
* @param gpio_num GPIO number. If you want to set pull up or down mode for e.g. GPIO12, gpio_num should be GPIO_NUM_12 (12);
|
||||||
|
*
|
||||||
|
* @return
|
||||||
|
* - True the gpio number is Rts pad
|
||||||
|
* - False the gpio number is Digital pad
|
||||||
|
*/
|
||||||
|
esp_err_t rtc_gpio_pullup_dis(gpio_num_t gpio_num);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Rtc gpio pulldown clear
|
||||||
|
*
|
||||||
|
* If the user needs to configure the GPIO pull ,Please call gpio_set_pull_mode.This function will be called in gpio_set_pull
|
||||||
|
*
|
||||||
|
* @param gpio_num GPIO number. If you want to set pull up or down mode for e.g. GPIO12, gpio_num should be GPIO_NUM_12 (12);
|
||||||
|
*
|
||||||
|
* @return
|
||||||
|
* - True the gpio number is Rts pad
|
||||||
|
* - False the gpio number is Digital pad
|
||||||
|
*/
|
||||||
|
esp_err_t rtc_gpio_pulldown_dis(gpio_num_t gpio_num);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
165
tools/sdk/include/driver/driver/touch_pad.h
Normal file
165
tools/sdk/include/driver/driver/touch_pad.h
Normal file
@ -0,0 +1,165 @@
|
|||||||
|
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#ifndef _DRIVER_TOUCH_PAD_H_
|
||||||
|
#define _DRIVER_TOUCH_PAD_H_
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
#include "esp_intr.h"
|
||||||
|
#include "esp_err.h"
|
||||||
|
#define TOUCH_PAD_SLEEP_CYCLE_CONFIG (0x1000)//The Time is 150Khz,the Max value is 0xffff
|
||||||
|
#define TOUCH_PAD_MEASURE_CYCLE_CONFIG (0xffff)//The Time is 8Mhz,the Max value is 0xffff
|
||||||
|
typedef enum {
|
||||||
|
TOUCH_PAD_NUM0 = 0, /*!< Touch pad channel 0 is GPIO4 */
|
||||||
|
TOUCH_PAD_NUM1, /*!< Touch pad channel 0 is GPIO0 */
|
||||||
|
TOUCH_PAD_NUM2, /*!< Touch pad channel 0 is GPIO2 */
|
||||||
|
TOUCH_PAD_NUM3, /*!< Touch pad channel 0 is GPIO15 */
|
||||||
|
TOUCH_PAD_NUM4, /*!< Touch pad channel 0 is GPIO13 */
|
||||||
|
TOUCH_PAD_NUM5, /*!< Touch pad channel 0 is GPIO12 */
|
||||||
|
TOUCH_PAD_NUM6, /*!< Touch pad channel 0 is GPIO14 */
|
||||||
|
TOUCH_PAD_NUM7, /*!< Touch pad channel 0 is GPIO27*/
|
||||||
|
TOUCH_PAD_NUM8, /*!< Touch pad channel 0 is GPIO33*/
|
||||||
|
TOUCH_PAD_NUM9, /*!< Touch pad channel 0 is GPIO32*/
|
||||||
|
TOUCH_PAD_MAX,
|
||||||
|
} touch_pad_t;
|
||||||
|
/**
|
||||||
|
* @brief Initialize touch module.
|
||||||
|
*
|
||||||
|
*This function int touch pad module ,enable touch module
|
||||||
|
*
|
||||||
|
* @return None
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
void touch_pad_init();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Configure touch pad interrupt threshold.
|
||||||
|
*
|
||||||
|
*
|
||||||
|
* @param[in] touch_num : config touch num
|
||||||
|
*
|
||||||
|
* @param[in] threshold : interrupt threshold ,When the touch_pad_register less than threshold,
|
||||||
|
* will trigger the touch interrupt.User can use touch_pad_read function
|
||||||
|
* to determine the threshold.
|
||||||
|
*
|
||||||
|
* @return - ESP_OK Success
|
||||||
|
* - ESP_ERR_INVALID_ARG Touch pad error
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
esp_err_t touch_pad_config(touch_pad_t touch_num, uint16_t threshold);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief get touch pad touch_pad_register counter.
|
||||||
|
*
|
||||||
|
*User can use this function to determine the the interrupt threshold .When you do not touch the
|
||||||
|
*pad ,read the touch_pad_read number(NumNotTouch) by the touch_pad_register.When you touch the pad ,read the touch_pad_register
|
||||||
|
*number(NumTouch) by the touch_pad_read.Normal NumNotTouch>NumTouch,so you can select a interrupt threshold.
|
||||||
|
*
|
||||||
|
* @param[in] touch_num : touch num
|
||||||
|
* @param[out] touch_value : touch output value
|
||||||
|
*
|
||||||
|
* @return - ESP_OK Success
|
||||||
|
* - ESP_ERR_INVALID_ARG Touch pad error
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
esp_err_t touch_pad_read(touch_pad_t touch_num, uint16_t * touch_value);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief register TouchPad interrupt handler, the handler is an ISR.
|
||||||
|
* The handler will be attached to the same CPU core that this function is running on.
|
||||||
|
* @note
|
||||||
|
* Users should know that which CPU is running and then pick a INUM that is not used by system.
|
||||||
|
* We can find the information of INUM and interrupt level in soc.h.
|
||||||
|
*
|
||||||
|
* @param touch_intr_num Touch interrupt number,check the info in soc.h, and please see the core-isa.h for more details
|
||||||
|
* @param fn Interrupt handler function.
|
||||||
|
*
|
||||||
|
* @note
|
||||||
|
* Note that the handler function MUST be defined with attribution of "IRAM_ATTR".
|
||||||
|
*
|
||||||
|
* @param arg Parameter for handler function
|
||||||
|
*
|
||||||
|
* @return
|
||||||
|
* - ESP_OK Success ;
|
||||||
|
* - ESP_ERR_INVALID_ARG GPIO error
|
||||||
|
*/
|
||||||
|
esp_err_t touch_pad_isr_handler_register(uint32_t touch_intr_num, void(*fn)(void*), void *arg);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* *************** ATTENTION ********************/
|
||||||
|
/**
|
||||||
|
*@attention
|
||||||
|
*Touch button is through the body's capacitive characteristics,
|
||||||
|
*there is a charge discharge circuit inside the. When the hands touch,
|
||||||
|
*the charge and discharge time will be slow.
|
||||||
|
*Because of the different hardware, each pad needs to be calibrated at the factory.
|
||||||
|
*We use touch_pad_read to determine factory parament.
|
||||||
|
*/
|
||||||
|
/**
|
||||||
|
*----------EXAMPLE TO CONIFGURE GPIO AS OUTPUT ------------ *
|
||||||
|
* @code{c}
|
||||||
|
* touch_pad_init();
|
||||||
|
* void taskA(void* arg)
|
||||||
|
* {
|
||||||
|
* for(;;){
|
||||||
|
* vtaskDelay(20/portTICK_PERIOD_MS);
|
||||||
|
* ets_printf("tocuch pad value %u\n",touch_pad_read(0));//Take the touched status and untouched status value
|
||||||
|
* }
|
||||||
|
* }
|
||||||
|
* @endcode
|
||||||
|
**/
|
||||||
|
/**
|
||||||
|
*----------EXAMPLE TO SET ISR HANDLER ----------------------
|
||||||
|
* @code{c}
|
||||||
|
* //the first parameter is INUM, you can pick one form interrupt level 1/2 which is not used by the system.
|
||||||
|
* touch_pad_isr_handler_register(19,rtc_intr,NULL); //hook the isr handler for TouchPad interrupt
|
||||||
|
* @endcode
|
||||||
|
* @note
|
||||||
|
* 1. user should arrange the INUMs that used, better not to use a same INUM for different interrupt.
|
||||||
|
* 2. do not pick the INUM that already occupied by the system.
|
||||||
|
* 3. refer to soc.h to check which INUMs that can be used.
|
||||||
|
*/
|
||||||
|
/**
|
||||||
|
*----------EXAMPLE TO USE TOUCH_PAD------------ *
|
||||||
|
* @code{c}
|
||||||
|
* touch_pad_init();//only init one time
|
||||||
|
* touch_pad_config(0,300);//set the intr threshold,use touch_pad_read to determine this threshold
|
||||||
|
* touch_pad_isr_handler_register(19,rtc_intr,NULL)
|
||||||
|
* #include "esp_attr.h"
|
||||||
|
* void IRAM_ATTR rtc_intr(void * arg)
|
||||||
|
* {
|
||||||
|
* uint32_t pad_intr = READ_PERI_REG(SARADC_SAR_TOUCH_CTRL2_REG) & 0x3ff;
|
||||||
|
* uint8_t i = 0;
|
||||||
|
* uint32_t rtc_intr = READ_PERI_REG(RTC_CNTL_INT_ST_REG);
|
||||||
|
* WRITE_PERI_REG(RTC_CNTL_INT_CLR_REG, rtc_intr);
|
||||||
|
* SET_PERI_REG_MASK(SARADC_SAR_TOUCH_CTRL2_REG, SARADC_TOUCH_MEAS_EN_CLR);
|
||||||
|
* if (rtc_intr & RTC_CNTL_TOUCH_INT_ST) {
|
||||||
|
* for (i = 0; i < TOUCH_PAD_MAX; ++i) {
|
||||||
|
* if ((pad_intr >> i) & 0x01) {
|
||||||
|
* ets_printf("touch pad intr %u\n",i);
|
||||||
|
* }
|
||||||
|
* }
|
||||||
|
* }
|
||||||
|
* }
|
||||||
|
* @endcode
|
||||||
|
**/
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif/*_DRIVER_TOUCH_PAD_H_*/
|
||||||
|
|
46
tools/sdk/include/esp32/esp_coexist.h
Normal file
46
tools/sdk/include/esp32/esp_coexist.h
Normal file
@ -0,0 +1,46 @@
|
|||||||
|
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Init software coexist
|
||||||
|
*
|
||||||
|
* @return Init ok or failed.
|
||||||
|
*/
|
||||||
|
esp_err_t coex_init(void);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get software coexist enable or not
|
||||||
|
*
|
||||||
|
* @return software coexist enable status.
|
||||||
|
*/
|
||||||
|
bool coexist_get_enable(void);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Set software coexist enable or not
|
||||||
|
*
|
||||||
|
* @param enable software coexist or disable it
|
||||||
|
*
|
||||||
|
* @return Void.
|
||||||
|
*/
|
||||||
|
void coexist_set_enable(bool enable);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
@ -18,6 +18,8 @@
|
|||||||
#include "esp_types.h"
|
#include "esp_types.h"
|
||||||
#include "esp_attr.h"
|
#include "esp_attr.h"
|
||||||
#include "ets_sys.h"
|
#include "ets_sys.h"
|
||||||
|
#include "soc/soc.h"
|
||||||
|
#include "soc/uart_reg.h"
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
extern "C" {
|
extern "C" {
|
||||||
@ -260,11 +262,16 @@ void uart_tx_flush(uint8_t uart_no);
|
|||||||
/**
|
/**
|
||||||
* @brief Wait until uart tx full empty and the last char send ok.
|
* @brief Wait until uart tx full empty and the last char send ok.
|
||||||
*
|
*
|
||||||
* @param uint8_t uart_no : 0 for UART0, 1 for UART1.
|
* @param uart_no : 0 for UART0, 1 for UART1, 2 for UART2
|
||||||
*
|
*
|
||||||
* @return None.
|
* The function defined in ROM code has a bug, so we define the correct version
|
||||||
|
* here for compatibility.
|
||||||
*/
|
*/
|
||||||
void uart_tx_wait_idle(uint8_t uart_no);
|
static inline void uart_tx_wait_idle(uint8_t uart_no) {
|
||||||
|
while(REG_GET_FIELD(UART_STATUS_REG(uart_no), UART_ST_UTX_OUT)) {
|
||||||
|
;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Get an input char from message channel.
|
* @brief Get an input char from message channel.
|
||||||
|
File diff suppressed because it is too large
Load Diff
1047
tools/sdk/include/esp32/soc/sens_reg.h
Normal file
1047
tools/sdk/include/esp32/soc/sens_reg.h
Normal file
File diff suppressed because it is too large
Load Diff
@ -153,7 +153,7 @@
|
|||||||
#define DR_REG_FRC_TIMER_BASE 0x3ff47000
|
#define DR_REG_FRC_TIMER_BASE 0x3ff47000
|
||||||
#define DR_REG_RTCCNTL_BASE 0x3ff48000
|
#define DR_REG_RTCCNTL_BASE 0x3ff48000
|
||||||
#define DR_REG_RTCIO_BASE 0x3ff48400
|
#define DR_REG_RTCIO_BASE 0x3ff48400
|
||||||
#define DR_REG_SARADC_BASE 0x3ff48800
|
#define DR_REG_SENS_BASE 0x3ff48800
|
||||||
#define DR_REG_IO_MUX_BASE 0x3ff49000
|
#define DR_REG_IO_MUX_BASE 0x3ff49000
|
||||||
#define DR_REG_RTCMEM0_BASE 0x3ff61000
|
#define DR_REG_RTCMEM0_BASE 0x3ff61000
|
||||||
#define DR_REG_RTCMEM1_BASE 0x3ff62000
|
#define DR_REG_RTCMEM1_BASE 0x3ff62000
|
||||||
@ -213,10 +213,10 @@
|
|||||||
#define ETS_TG1_LACT_LEVEL_INTR_SOURCE 21/**< interrupt of TIMER_GROUP1, LACT, level*/
|
#define ETS_TG1_LACT_LEVEL_INTR_SOURCE 21/**< interrupt of TIMER_GROUP1, LACT, level*/
|
||||||
#define ETS_GPIO_INTR_SOURCE 22/**< interrupt of GPIO, level*/
|
#define ETS_GPIO_INTR_SOURCE 22/**< interrupt of GPIO, level*/
|
||||||
#define ETS_GPIO_NMI_SOURCE 23/**< interrupt of GPIO, NMI*/
|
#define ETS_GPIO_NMI_SOURCE 23/**< interrupt of GPIO, NMI*/
|
||||||
#define ETS_FROM_CPU_INTR0_SOURCE 24/**< interrupt0 generated from a CPU, level*/
|
#define ETS_FROM_CPU_INTR0_SOURCE 24/**< interrupt0 generated from a CPU, level*/ /* Used for FreeRTOS */
|
||||||
#define ETS_FROM_CPU_INTR1_SOURCE 25/**< interrupt1 generated from a CPU, level*/
|
#define ETS_FROM_CPU_INTR1_SOURCE 25/**< interrupt1 generated from a CPU, level*/ /* Used for FreeRTOS */
|
||||||
#define ETS_FROM_CPU_INTR2_SOURCE 26/**< interrupt2 generated from a CPU, level*/
|
#define ETS_FROM_CPU_INTR2_SOURCE 26/**< interrupt2 generated from a CPU, level*/ /* Used for VHCI */
|
||||||
#define ETS_FROM_CPU_INTR3_SOURCE 27/**< interrupt3 generated from a CPU, level*/
|
#define ETS_FROM_CPU_INTR3_SOURCE 27/**< interrupt3 generated from a CPU, level*/ /* Reserved */
|
||||||
#define ETS_SPI0_INTR_SOURCE 28/**< interrupt of SPI0, level, SPI0 is for Cache Access, do not use this*/
|
#define ETS_SPI0_INTR_SOURCE 28/**< interrupt of SPI0, level, SPI0 is for Cache Access, do not use this*/
|
||||||
#define ETS_SPI1_INTR_SOURCE 29/**< interrupt of SPI1, level, SPI1 is for flash read/write, do not use this*/
|
#define ETS_SPI1_INTR_SOURCE 29/**< interrupt of SPI1, level, SPI1 is for flash read/write, do not use this*/
|
||||||
#define ETS_SPI2_INTR_SOURCE 30/**< interrupt of SPI2, level*/
|
#define ETS_SPI2_INTR_SOURCE 30/**< interrupt of SPI2, level*/
|
||||||
|
@ -1841,3 +1841,22 @@ PROVIDE ( _xtos_syscall_handler = 0x40000790 );
|
|||||||
PROVIDE ( _xtos_unhandled_exception = 0x4000c024 );
|
PROVIDE ( _xtos_unhandled_exception = 0x4000c024 );
|
||||||
PROVIDE ( _xtos_unhandled_interrupt = 0x4000c01c );
|
PROVIDE ( _xtos_unhandled_interrupt = 0x4000c01c );
|
||||||
PROVIDE ( _xtos_vpri_enabled = 0x3ffe0654 );
|
PROVIDE ( _xtos_vpri_enabled = 0x3ffe0654 );
|
||||||
|
/* Following are static data, but can be used, not generated by script <<<<< btdm data */
|
||||||
|
PROVIDE ( ld_acl_env = 0x3ffb8258 );
|
||||||
|
PROVIDE ( ld_active_ch_map = 0x3ffb8334 );
|
||||||
|
PROVIDE ( ld_bcst_acl_env = 0x3ffb8274 );
|
||||||
|
PROVIDE ( ld_csb_rx_env = 0x3ffb8278 );
|
||||||
|
PROVIDE ( ld_csb_tx_env = 0x3ffb827c );
|
||||||
|
PROVIDE ( ld_env = 0x3ffb9510 );
|
||||||
|
PROVIDE ( ld_fm_env = 0x3ffb8284 );
|
||||||
|
PROVIDE ( ld_inq_env = 0x3ffb82e4 );
|
||||||
|
PROVIDE ( ld_iscan_env = 0x3ffb82e8 );
|
||||||
|
PROVIDE ( ld_page_env = 0x3ffb82f0 );
|
||||||
|
PROVIDE ( ld_pca_env = 0x3ffb82f4 );
|
||||||
|
PROVIDE ( ld_pscan_env = 0x3ffb8308 );
|
||||||
|
PROVIDE ( ld_sched_env = 0x3ffb830c );
|
||||||
|
PROVIDE ( ld_sched_params = 0x3ffb96c0 );
|
||||||
|
PROVIDE ( ld_sco_env = 0x3ffb824c );
|
||||||
|
PROVIDE ( ld_sscan_env = 0x3ffb832c );
|
||||||
|
PROVIDE ( ld_strain_env = 0x3ffb8330 );
|
||||||
|
/* Above are static data, but can be used, not generated by script >>>>> btdm data */
|
||||||
|
Binary file not shown.
Binary file not shown.
BIN
tools/sdk/lib/libbtdm_app.a
Normal file → Executable file
BIN
tools/sdk/lib/libbtdm_app.a
Normal file → Executable file
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
BIN
tools/sdk/lib/libulp.a
Normal file
BIN
tools/sdk/lib/libulp.a
Normal file
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Loading…
Reference in New Issue
Block a user