forked from espressif/arduino-esp32
Initial Esp32c3 Support (#5060)
This commit is contained in:
@ -37,6 +37,8 @@ extern "C" {
|
||||
#include "soc/efuse_reg.h"
|
||||
#elif CONFIG_IDF_TARGET_ESP32S2
|
||||
#include "esp32s2/rom/spi_flash.h"
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
#include "esp32c3/rom/spi_flash.h"
|
||||
#else
|
||||
#error Target CONFIG_IDF_TARGET is not supported
|
||||
#endif
|
||||
@ -265,6 +267,10 @@ const char * EspClass::getChipModel(void)
|
||||
}
|
||||
#elif CONFIG_IDF_TARGET_ESP32S2
|
||||
return "ESP32-S2";
|
||||
#elif CONFIG_IDF_TARGET_ESP32S3
|
||||
return "ESP32-S3";
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
return "ESP32-C3";
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -66,6 +66,9 @@ void HardwareSerial::begin(unsigned long baud, uint32_t config, int8_t rxPin, in
|
||||
#elif CONFIG_IDF_TARGET_ESP32S2
|
||||
rxPin = 44;
|
||||
txPin = 43;
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
rxPin = 20;
|
||||
txPin = 21;
|
||||
#endif
|
||||
}
|
||||
if(_uart_nr == 1 && rxPin < 0 && txPin < 0) {
|
||||
|
@ -28,6 +28,8 @@
|
||||
#include "esp32/rom/md5_hash.h"
|
||||
#elif CONFIG_IDF_TARGET_ESP32S2
|
||||
#include "esp32s2/rom/md5_hash.h"
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
#include "esp32c3/rom/md5_hash.h"
|
||||
#else
|
||||
#error Target CONFIG_IDF_TARGET is not supported
|
||||
#endif
|
||||
|
@ -16,16 +16,15 @@
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
#include "esp_attr.h"
|
||||
#include "soc/rtc_io_reg.h"
|
||||
#include "soc/rtc_cntl_reg.h"
|
||||
#include "soc/sens_reg.h"
|
||||
|
||||
#include "driver/adc.h"
|
||||
|
||||
#include "esp_system.h"
|
||||
#ifdef ESP_IDF_VERSION_MAJOR // IDF 4+
|
||||
#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
|
||||
#include "esp_adc_cal.h"
|
||||
#include "soc/sens_reg.h"
|
||||
#include "soc/rtc_io_reg.h"
|
||||
#include "esp32/rom/ets_sys.h"
|
||||
#include "esp_intr_alloc.h"
|
||||
#define DEFAULT_VREF 1100
|
||||
@ -34,6 +33,10 @@ static uint16_t __analogVRef = 0;
|
||||
static uint8_t __analogVRefPin = 0;
|
||||
#elif CONFIG_IDF_TARGET_ESP32S2
|
||||
#include "esp32s2/rom/ets_sys.h"
|
||||
#include "soc/sens_reg.h"
|
||||
#include "soc/rtc_io_reg.h"
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
#include "esp32c3/rom/ets_sys.h"
|
||||
#else
|
||||
#error Target CONFIG_IDF_TARGET is not supported
|
||||
#endif
|
||||
@ -51,7 +54,9 @@ void __analogSetClockDiv(uint8_t clockDiv){
|
||||
clockDiv = 1;
|
||||
}
|
||||
__analogClockDiv = clockDiv;
|
||||
#if CONFIG_IDF_TARGET_ESP32 || CONFIG_IDF_TARGET_ESP32S2
|
||||
adc_set_clk_div(__analogClockDiv);
|
||||
#endif
|
||||
}
|
||||
|
||||
void __analogSetAttenuation(adc_attenuation_t attenuation)
|
||||
@ -114,11 +119,14 @@ bool __adcAttachPin(uint8_t pin){
|
||||
WRITE_PERI_REG(SENS_SAR_TOUCH_ENABLE_REG, touch);
|
||||
}
|
||||
#endif
|
||||
} else if(pin == 25){
|
||||
}
|
||||
#if CONFIG_IDF_TARGET_ESP32 || CONFIG_IDF_TARGET_ESP32S2
|
||||
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
|
||||
}
|
||||
#endif
|
||||
|
||||
pinMode(pin, ANALOG);
|
||||
__analogSetPinAttenuation(pin, __analogAttenuation);
|
||||
|
@ -16,7 +16,6 @@
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/semphr.h"
|
||||
#include "freertos/task.h"
|
||||
#include "freertos/xtensa_timer.h"
|
||||
#include "esp_attr.h"
|
||||
#include "esp_log.h"
|
||||
#include "soc/rtc.h"
|
||||
@ -29,9 +28,13 @@
|
||||
#include "esp_system.h"
|
||||
#ifdef ESP_IDF_VERSION_MAJOR // IDF 4+
|
||||
#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
|
||||
#include "freertos/xtensa_timer.h"
|
||||
#include "esp32/rom/rtc.h"
|
||||
#elif CONFIG_IDF_TARGET_ESP32S2
|
||||
#include "freertos/xtensa_timer.h"
|
||||
#include "esp32s2/rom/rtc.h"
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
#include "esp32c3/rom/rtc.h"
|
||||
#else
|
||||
#error Target CONFIG_IDF_TARGET is not supported
|
||||
#endif
|
||||
@ -141,10 +144,14 @@ bool removeApbChangeCallback(void * arg, apb_change_cb_t cb){
|
||||
}
|
||||
|
||||
static uint32_t calculateApb(rtc_cpu_freq_config_t * conf){
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
return APB_CLK_FREQ;
|
||||
#else
|
||||
if(conf->freq_mhz >= 80){
|
||||
return 80 * MHZ;
|
||||
}
|
||||
return (conf->source_freq_mhz * MHZ) / conf->div;
|
||||
#endif
|
||||
}
|
||||
|
||||
void esp_timer_impl_update_apb_freq(uint32_t apb_ticks_per_us); //private in IDF
|
||||
@ -219,8 +226,12 @@ bool setCpuFrequencyMhz(uint32_t cpu_freq_mhz){
|
||||
esp_timer_impl_update_apb_freq(apb / MHZ);
|
||||
}
|
||||
//Update FreeRTOS Tick Divisor
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
|
||||
#else
|
||||
uint32_t fcpu = (conf.freq_mhz >= 80)?(conf.freq_mhz * MHZ):(apb);
|
||||
_xt_tick_divisor = fcpu / XT_TICK_PER_SEC;
|
||||
#endif
|
||||
//Call peripheral functions after the APB change
|
||||
if(apb_change_callbacks){
|
||||
triggerApbChangeCallback(APB_AFTER_CHANGE, capb, apb);
|
||||
|
@ -13,24 +13,29 @@
|
||||
// limitations under the License.
|
||||
|
||||
#include "esp32-hal.h"
|
||||
#include "esp_attr.h"
|
||||
|
||||
#if CONFIG_IDF_TARGET_ESP32
|
||||
#include "soc/rtc_io_reg.h"
|
||||
#define DAC1 25
|
||||
#define DAC2 26
|
||||
#elif CONFIG_IDF_TARGET_ESP32S2
|
||||
#include "soc/rtc_io_reg.h"
|
||||
#define DAC1 17
|
||||
#define DAC2 18
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
#define NODAC
|
||||
#else
|
||||
#error Target CONFIG_IDF_TARGET is not supported
|
||||
#endif
|
||||
|
||||
#ifndef NODAC
|
||||
#include "esp_attr.h"
|
||||
#include "soc/rtc_cntl_reg.h"
|
||||
#include "soc/rtc_io_periph.h"
|
||||
#include "soc/sens_reg.h"
|
||||
#include "soc/sens_struct.h"
|
||||
#include "driver/dac.h"
|
||||
|
||||
#if CONFIG_IDF_TARGET_ESP32
|
||||
#define DAC1 25
|
||||
#define DAC2 26
|
||||
#elif CONFIG_IDF_TARGET_ESP32S2
|
||||
#define DAC1 17
|
||||
#define DAC2 18
|
||||
#else
|
||||
#error Target CONFIG_IDF_TARGET is not supported
|
||||
#endif
|
||||
|
||||
void ARDUINO_ISR_ATTR __dacWrite(uint8_t pin, uint8_t value)
|
||||
{
|
||||
if(pin < DAC1 || pin > DAC2){
|
||||
@ -54,3 +59,5 @@ void ARDUINO_ISR_ATTR __dacWrite(uint8_t pin, uint8_t value)
|
||||
}
|
||||
|
||||
extern void dacWrite(uint8_t pin, uint8_t value) __attribute__ ((weak, alias("__dacWrite")));
|
||||
|
||||
#endif
|
||||
|
@ -20,23 +20,25 @@
|
||||
#include "soc/gpio_reg.h"
|
||||
#include "soc/io_mux_reg.h"
|
||||
#include "soc/gpio_struct.h"
|
||||
#include "soc/rtc_io_reg.h"
|
||||
|
||||
#include "driver/gpio.h"
|
||||
#include "esp_system.h"
|
||||
|
||||
#ifdef ESP_IDF_VERSION_MAJOR // IDF 4+
|
||||
#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
|
||||
#include "esp32/rom/ets_sys.h"
|
||||
#include "esp32/rom/gpio.h"
|
||||
#include "esp_intr_alloc.h"
|
||||
#include "soc/rtc_io_reg.h"
|
||||
#define GPIO_FUNC 2
|
||||
#elif CONFIG_IDF_TARGET_ESP32S2
|
||||
#include "esp32s2/rom/ets_sys.h"
|
||||
#include "esp32s2/rom/gpio.h"
|
||||
#include "esp_intr_alloc.h"
|
||||
#include "soc/periph_defs.h"
|
||||
#include "soc/rtc_io_reg.h"
|
||||
#define GPIO_FUNC 1
|
||||
#else
|
||||
#error Target CONFIG_IDF_TARGET is not supported
|
||||
#define USE_ESP_IDF_GPIO 1
|
||||
#endif
|
||||
#else // ESP32 Before IDF 4.0
|
||||
#include "rom/ets_sys.h"
|
||||
@ -157,7 +159,45 @@ static InterruptHandle_t __pinInterruptHandlers[SOC_GPIO_PIN_COUNT] = {0,};
|
||||
|
||||
extern void ARDUINO_ISR_ATTR __pinMode(uint8_t pin, uint8_t mode)
|
||||
{
|
||||
#if USE_ESP_IDF_GPIO
|
||||
if (!GPIO_IS_VALID_GPIO(pin)) {
|
||||
return;
|
||||
}
|
||||
gpio_config_t conf = {
|
||||
.pin_bit_mask = (1ULL<<pin), /*!< GPIO pin: set with bit mask, each bit maps to a GPIO */
|
||||
.mode = GPIO_MODE_DISABLE, /*!< GPIO mode: set input/output mode */
|
||||
.pull_up_en = GPIO_PULLUP_DISABLE, /*!< GPIO pull-up */
|
||||
.pull_down_en = GPIO_PULLDOWN_DISABLE, /*!< GPIO pull-down */
|
||||
.intr_type = GPIO_INTR_DISABLE /*!< GPIO interrupt type */
|
||||
};
|
||||
if (mode < 0x20) {//io
|
||||
conf.mode = mode & (INPUT | OUTPUT);
|
||||
if (mode & OPEN_DRAIN) {
|
||||
conf.mode |= GPIO_MODE_DEF_OD;
|
||||
}
|
||||
if (mode & PULLUP) {
|
||||
conf.pull_up_en = GPIO_PULLUP_ENABLE;
|
||||
}
|
||||
if (mode & PULLDOWN) {
|
||||
conf.pull_down_en = GPIO_PULLDOWN_ENABLE;
|
||||
}
|
||||
}
|
||||
gpio_config(&conf);
|
||||
|
||||
if(mode == SPECIAL){
|
||||
#if CONFIG_IDF_TARGET_ESP32
|
||||
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[pin], (uint32_t)(((pin)==RX||(pin)==TX)?0:1));
|
||||
#elif CONFIG_IDF_TARGET_ESP32S2
|
||||
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[pin], (uint32_t)(((pin)==RX||(pin)==TX)?0:2));
|
||||
#endif
|
||||
} else if(mode == ANALOG){
|
||||
#if !CONFIG_IDF_TARGET_ESP32C3
|
||||
//adc_gpio_init(ADC_UNIT_1, ADC_CHANNEL_0);
|
||||
#endif
|
||||
} else if(mode >= 0x20 && mode < ANALOG) {//function
|
||||
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[pin], mode >> 5);
|
||||
}
|
||||
#else
|
||||
if(!digitalPinIsValid(pin)) {
|
||||
return;
|
||||
}
|
||||
@ -228,11 +268,7 @@ extern void ARDUINO_ISR_ATTR __pinMode(uint8_t pin, uint8_t mode)
|
||||
pinFunction |= FUN_IE;//input enable but required for output as well?
|
||||
|
||||
if(mode & (INPUT | OUTPUT)) {
|
||||
#if CONFIG_IDF_TARGET_ESP32
|
||||
pinFunction |= ((uint32_t)2 << MCU_SEL_S);
|
||||
#elif CONFIG_IDF_TARGET_ESP32S2
|
||||
pinFunction |= ((uint32_t)1 << MCU_SEL_S);
|
||||
#endif
|
||||
pinFunction |= ((uint32_t)PIN_FUNC_GPIO << MCU_SEL_S);
|
||||
} else if(mode == SPECIAL) {
|
||||
#if CONFIG_IDF_TARGET_ESP32
|
||||
pinFunction |= ((uint32_t)(((pin)==RX||(pin)==TX)?0:1) << MCU_SEL_S);
|
||||
@ -250,10 +286,20 @@ extern void ARDUINO_ISR_ATTR __pinMode(uint8_t pin, uint8_t mode)
|
||||
}
|
||||
|
||||
GPIO.pin[pin].val = pinControl;
|
||||
#endif
|
||||
}
|
||||
|
||||
extern void ARDUINO_ISR_ATTR __digitalWrite(uint8_t pin, uint8_t val)
|
||||
{
|
||||
#if USE_ESP_IDF_GPIO
|
||||
gpio_set_level((gpio_num_t)pin, val);
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
if (val) {
|
||||
GPIO.out_w1ts.out_w1ts = (1 << pin);
|
||||
} else {
|
||||
GPIO.out_w1tc.out_w1tc = (1 << pin);
|
||||
}
|
||||
#else
|
||||
if(val) {
|
||||
if(pin < 32) {
|
||||
GPIO.out_w1ts = ((uint32_t)1 << pin);
|
||||
@ -267,18 +313,37 @@ extern void ARDUINO_ISR_ATTR __digitalWrite(uint8_t pin, uint8_t val)
|
||||
GPIO.out1_w1tc.val = ((uint32_t)1 << (pin - 32));
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
extern int ARDUINO_ISR_ATTR __digitalRead(uint8_t pin)
|
||||
{
|
||||
#if USE_ESP_IDF_GPIO
|
||||
return gpio_get_level((gpio_num_t)pin);
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
return (GPIO.in.data >> pin) & 0x1;
|
||||
#else
|
||||
if(pin < 32) {
|
||||
return (GPIO.in >> pin) & 0x1;
|
||||
} else if(pin < GPIO_PIN_COUNT) {
|
||||
return (GPIO.in1.val >> (pin - 32)) & 0x1;
|
||||
}
|
||||
return 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
#if USE_ESP_IDF_GPIO
|
||||
static void ARDUINO_ISR_ATTR __onPinInterrupt(void * arg) {
|
||||
InterruptHandle_t * isr = (InterruptHandle_t*)arg;
|
||||
if(isr->fn) {
|
||||
if(isr->arg){
|
||||
((voidFuncPtrArg)isr->fn)(isr->arg);
|
||||
} else {
|
||||
isr->fn();
|
||||
}
|
||||
}
|
||||
}
|
||||
#else
|
||||
static intr_handle_t gpio_intr_handle = NULL;
|
||||
|
||||
static void ARDUINO_ISR_ATTR __onPinInterrupt()
|
||||
@ -320,6 +385,7 @@ static void ARDUINO_ISR_ATTR __onPinInterrupt()
|
||||
} while(++pin<GPIO_PIN_COUNT);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
extern void cleanupFunctional(void* arg);
|
||||
|
||||
@ -328,8 +394,17 @@ extern void __attachInterruptFunctionalArg(uint8_t pin, voidFuncPtrArg userFunc,
|
||||
static bool interrupt_initialized = false;
|
||||
|
||||
if(!interrupt_initialized) {
|
||||
#if USE_ESP_IDF_GPIO
|
||||
esp_err_t err = gpio_install_isr_service((int)ARDUINO_ISR_FLAG);
|
||||
interrupt_initialized = (err == ESP_OK) || (err == ESP_ERR_INVALID_STATE);
|
||||
#else
|
||||
interrupt_initialized = true;
|
||||
esp_intr_alloc(ETS_GPIO_INTR_SOURCE, (int)ARDUINO_ISR_FLAG, __onPinInterrupt, NULL, &gpio_intr_handle);
|
||||
#endif
|
||||
}
|
||||
if(!interrupt_initialized) {
|
||||
log_e("GPIO ISR Service Failed To Start");
|
||||
return;
|
||||
}
|
||||
|
||||
// if new attach without detach remove old info
|
||||
@ -341,6 +416,14 @@ extern void __attachInterruptFunctionalArg(uint8_t pin, voidFuncPtrArg userFunc,
|
||||
__pinInterruptHandlers[pin].arg = arg;
|
||||
__pinInterruptHandlers[pin].functional = functional;
|
||||
|
||||
#if USE_ESP_IDF_GPIO
|
||||
gpio_set_intr_type((gpio_num_t)pin, (gpio_int_type_t)(intr_type & 0x7));
|
||||
if(intr_type & 0x8){
|
||||
gpio_wakeup_enable((gpio_num_t)pin, (gpio_int_type_t)(intr_type & 0x7));
|
||||
}
|
||||
gpio_isr_handler_add((gpio_num_t)pin, __onPinInterrupt, &__pinInterruptHandlers[pin]);
|
||||
gpio_intr_enable((gpio_num_t)pin);
|
||||
#else
|
||||
esp_intr_disable(gpio_intr_handle);
|
||||
#if CONFIG_IDF_TARGET_ESP32
|
||||
if(esp_intr_get_cpu(gpio_intr_handle)) { //APP_CPU
|
||||
@ -353,6 +436,7 @@ extern void __attachInterruptFunctionalArg(uint8_t pin, voidFuncPtrArg userFunc,
|
||||
#endif
|
||||
GPIO.pin[pin].int_type = intr_type;
|
||||
esp_intr_enable(gpio_intr_handle);
|
||||
#endif
|
||||
}
|
||||
|
||||
extern void __attachInterruptArg(uint8_t pin, voidFuncPtrArg userFunc, void * arg, int intr_type)
|
||||
@ -366,7 +450,13 @@ extern void __attachInterrupt(uint8_t pin, voidFuncPtr userFunc, int intr_type)
|
||||
|
||||
extern void __detachInterrupt(uint8_t pin)
|
||||
{
|
||||
#if USE_ESP_IDF_GPIO
|
||||
gpio_intr_disable((gpio_num_t)pin);
|
||||
gpio_isr_handler_remove((gpio_num_t)pin);
|
||||
gpio_wakeup_disable((gpio_num_t)pin);
|
||||
#else
|
||||
esp_intr_disable(gpio_intr_handle);
|
||||
#endif
|
||||
if (__pinInterruptHandlers[pin].functional && __pinInterruptHandlers[pin].arg)
|
||||
{
|
||||
cleanupFunctional(__pinInterruptHandlers[pin].arg);
|
||||
@ -375,9 +465,13 @@ extern void __detachInterrupt(uint8_t pin)
|
||||
__pinInterruptHandlers[pin].arg = NULL;
|
||||
__pinInterruptHandlers[pin].functional = false;
|
||||
|
||||
#if USE_ESP_IDF_GPIO
|
||||
gpio_set_intr_type((gpio_num_t)pin, GPIO_INTR_DISABLE);
|
||||
#else
|
||||
GPIO.pin[pin].int_ena = 0;
|
||||
GPIO.pin[pin].int_type = 0;
|
||||
esp_intr_enable(gpio_intr_handle);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
|
@ -21,16 +21,19 @@
|
||||
#include "driver/periph_ctrl.h"
|
||||
#include "soc/i2c_reg.h"
|
||||
#include "soc/i2c_struct.h"
|
||||
#include "soc/dport_reg.h"
|
||||
#include "esp_attr.h"
|
||||
#include "esp32-hal-cpu.h" // cpu clock change support 31DEC2018
|
||||
|
||||
#include "esp_system.h"
|
||||
#ifdef ESP_IDF_VERSION_MAJOR // IDF 4+
|
||||
#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
|
||||
#include "soc/dport_reg.h"
|
||||
#include "esp32/rom/ets_sys.h"
|
||||
#elif CONFIG_IDF_TARGET_ESP32S2
|
||||
#include "soc/dport_reg.h"
|
||||
#include "esp32s2/rom/ets_sys.h"
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
#include "esp32c3/rom/ets_sys.h"
|
||||
#else
|
||||
#error Target CONFIG_IDF_TARGET is not supported
|
||||
#endif
|
||||
@ -1795,7 +1798,7 @@ struct i2c_struct_t {
|
||||
static i2c_t * i2c_ports[2] = {NULL, NULL};
|
||||
|
||||
i2c_t * i2cInit(uint8_t i2c_num, int8_t sda, int8_t scl, uint32_t clk_speed){
|
||||
if(i2c_num >= 2){
|
||||
if(i2c_num >= SOC_I2C_NUM){
|
||||
return NULL;
|
||||
}
|
||||
if(!clk_speed){
|
||||
|
@ -17,19 +17,25 @@
|
||||
#include "freertos/task.h"
|
||||
#include "freertos/semphr.h"
|
||||
#include "esp32-hal-matrix.h"
|
||||
#include "soc/dport_reg.h"
|
||||
#include "soc/ledc_reg.h"
|
||||
#include "soc/ledc_struct.h"
|
||||
#include "driver/periph_ctrl.h"
|
||||
|
||||
#include "esp_system.h"
|
||||
#ifdef ESP_IDF_VERSION_MAJOR // IDF 4+
|
||||
#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
|
||||
#include "soc/dport_reg.h"
|
||||
#include "esp32/rom/ets_sys.h"
|
||||
#define LAST_CHAN (15)
|
||||
#elif CONFIG_IDF_TARGET_ESP32S2
|
||||
#include "soc/dport_reg.h"
|
||||
#include "esp32s2/rom/ets_sys.h"
|
||||
#define LAST_CHAN (7)
|
||||
#define LEDC_DIV_NUM_HSTIMER0_V LEDC_CLK_DIV_LSTIMER0_V
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
#include "esp32c3/rom/ets_sys.h"
|
||||
#define LAST_CHAN (7)
|
||||
#define LEDC_DIV_NUM_HSTIMER0_V LEDC_CLK_DIV_LSTIMER0_V
|
||||
#else
|
||||
#error Target CONFIG_IDF_TARGET is not supported
|
||||
#endif
|
||||
@ -111,8 +117,7 @@ static void _ledcSetupTimer(uint8_t chan, uint32_t div_num, uint8_t bit_num, boo
|
||||
static uint16_t _activeChannels = 0;
|
||||
if(!tHasStarted) {
|
||||
tHasStarted = true;
|
||||
DPORT_SET_PERI_REG_MASK(DPORT_PERIP_CLK_EN_REG, DPORT_LEDC_CLK_EN);
|
||||
DPORT_CLEAR_PERI_REG_MASK(DPORT_PERIP_RST_EN_REG, DPORT_LEDC_RST);
|
||||
periph_module_enable(PERIPH_LEDC_MODULE);
|
||||
LEDC.conf.apb_clk_sel = 1;//LS use apb clock
|
||||
addApbChangeCallback((void*)&_activeChannels, _on_apb_change);
|
||||
|
||||
@ -302,7 +307,7 @@ void ledcAttachPin(uint8_t pin, uint8_t chan)
|
||||
return;
|
||||
}
|
||||
pinMode(pin, OUTPUT);
|
||||
#if CONFIG_IDF_TARGET_ESP32S2
|
||||
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32C3
|
||||
pinMatrixOutAttach(pin, LEDC_LS_SIG_OUT0_IDX + chan, false, false);
|
||||
#else
|
||||
pinMatrixOutAttach(pin, ((chan/8)?LEDC_LS_SIG_OUT0_IDX:LEDC_HS_SIG_OUT0_IDX) + (chan%8), false, false);
|
||||
|
@ -21,6 +21,8 @@
|
||||
#include "esp32/rom/gpio.h"
|
||||
#elif CONFIG_IDF_TARGET_ESP32S2
|
||||
#include "esp32s2/rom/gpio.h"
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
#include "esp32c3/rom/gpio.h"
|
||||
#else
|
||||
#error Target CONFIG_IDF_TARGET is not supported
|
||||
#endif
|
||||
|
@ -40,6 +40,8 @@
|
||||
#include "esp32/rom/rtc.h"
|
||||
#elif CONFIG_IDF_TARGET_ESP32S2
|
||||
#include "esp32s2/rom/rtc.h"
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
#include "esp32c3/rom/rtc.h"
|
||||
#else
|
||||
#error Target CONFIG_IDF_TARGET is not supported
|
||||
#endif
|
||||
|
@ -28,15 +28,27 @@
|
||||
*/
|
||||
#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
|
||||
#define MAX_CHANNELS 8
|
||||
#define MAX_DATA_PER_CHANNEL 64
|
||||
#define MAX_DATA_PER_ITTERATION 62
|
||||
#elif CONFIG_IDF_TARGET_ESP32S2
|
||||
#define MAX_CHANNELS 4
|
||||
#define MAX_DATA_PER_CHANNEL 64
|
||||
#define MAX_DATA_PER_ITTERATION 62
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
#define MAX_CHANNELS 4
|
||||
#define MAX_DATA_PER_CHANNEL 48
|
||||
#define MAX_DATA_PER_ITTERATION 46
|
||||
#else
|
||||
#error Target CONFIG_IDF_TARGET is not supported
|
||||
#endif
|
||||
#define MAX_DATA_PER_CHANNEL 64
|
||||
#define MAX_DATA_PER_ITTERATION 62
|
||||
#define _ABS(a) (a>0?a:-a)
|
||||
#define _LIMIT(a,b) (a>b?b:a)
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
#define _INT_TX_END(channel) (1<<(channel))
|
||||
#define _INT_RX_END(channel) (4<<(channel))
|
||||
#define _INT_ERROR(channel) (16<<(channel))
|
||||
#define _INT_THR_EVNT(channel) (256<<(channel))
|
||||
#else
|
||||
#define __INT_TX_END (1)
|
||||
#define __INT_RX_END (2)
|
||||
#define __INT_ERROR (4)
|
||||
@ -46,6 +58,7 @@
|
||||
#define _INT_RX_END(channel) (__INT_RX_END<<(channel*3))
|
||||
#define _INT_ERROR(channel) (__INT_ERROR<<(channel*3))
|
||||
#define _INT_THR_EVNT(channel) ((__INT_THR_EVNT)<<(channel))
|
||||
#endif
|
||||
|
||||
#if CONFIG_DISABLE_HAL_LOCKS
|
||||
# define RMT_MUTEX_LOCK(channel)
|
||||
@ -55,7 +68,7 @@
|
||||
# define RMT_MUTEX_UNLOCK(channel) xSemaphoreGive(g_rmt_objlocks[channel])
|
||||
#endif /* CONFIG_DISABLE_HAL_LOCKS */
|
||||
|
||||
#define _RMT_INTERNAL_DEBUG
|
||||
//#define _RMT_INTERNAL_DEBUG
|
||||
#ifdef _RMT_INTERNAL_DEBUG
|
||||
# define DEBUG_INTERRUPT_START(pin) digitalWrite(pin, 1);
|
||||
# define DEBUG_INTERRUPT_END(pin) digitalWrite(pin, 0);
|
||||
@ -162,12 +175,17 @@ bool rmtSetCarrier(rmt_obj_t* rmt, bool carrier_en, bool carrier_level, uint32_t
|
||||
size_t channel = rmt->channel;
|
||||
|
||||
RMT_MUTEX_LOCK(channel);
|
||||
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMT.tx_carrier[channel].low = low;
|
||||
RMT.tx_carrier[channel].high = high;
|
||||
RMT.rx_conf[channel].conf0.carrier_en = carrier_en;
|
||||
RMT.rx_conf[channel].conf0.carrier_out_lv = carrier_level;
|
||||
#else
|
||||
RMT.carrier_duty_ch[channel].low = low;
|
||||
RMT.carrier_duty_ch[channel].high = high;
|
||||
RMT.conf_ch[channel].conf0.carrier_en = carrier_en;
|
||||
RMT.conf_ch[channel].conf0.carrier_out_lv = carrier_level;
|
||||
|
||||
#endif
|
||||
RMT_MUTEX_UNLOCK(channel);
|
||||
|
||||
return true;
|
||||
@ -183,8 +201,13 @@ bool rmtSetFilter(rmt_obj_t* rmt, bool filter_en, uint32_t filter_level)
|
||||
|
||||
RMT_MUTEX_LOCK(channel);
|
||||
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMT.rx_conf[channel].conf1.rx_filter_thres = filter_level;
|
||||
RMT.rx_conf[channel].conf1.rx_filter_en = filter_en;
|
||||
#else
|
||||
RMT.conf_ch[channel].conf1.rx_filter_thres = filter_level;
|
||||
RMT.conf_ch[channel].conf1.rx_filter_en = filter_en;
|
||||
#endif
|
||||
|
||||
RMT_MUTEX_UNLOCK(channel);
|
||||
|
||||
@ -200,7 +223,11 @@ bool rmtSetRxThreshold(rmt_obj_t* rmt, uint32_t value)
|
||||
size_t channel = rmt->channel;
|
||||
|
||||
RMT_MUTEX_LOCK(channel);
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMT.rx_conf[channel].conf0.idle_thres = value;
|
||||
#else
|
||||
RMT.conf_ch[channel].conf0.idle_thres = value;
|
||||
#endif
|
||||
RMT_MUTEX_UNLOCK(channel);
|
||||
|
||||
return true;
|
||||
@ -265,7 +292,7 @@ bool rmtWrite(rmt_obj_t* rmt, rmt_data_t* data, size_t size)
|
||||
int channel = rmt->channel;
|
||||
int allocated_size = MAX_DATA_PER_CHANNEL * rmt->buffers;
|
||||
|
||||
if (size > allocated_size) {
|
||||
if (size > (allocated_size - 1)) {
|
||||
|
||||
int half_tx_nr = MAX_DATA_PER_ITTERATION/2;
|
||||
RMT_MUTEX_LOCK(channel);
|
||||
@ -279,6 +306,18 @@ bool rmtWrite(rmt_obj_t* rmt, rmt_data_t* data, size_t size)
|
||||
rmt->intr_mode = E_TX_INTR | E_TXTHR_INTR;
|
||||
rmt->tx_state = E_SET_CONTI | E_FIRST_HALF;
|
||||
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
//uint32_t val = RMT.tx_conf[channel].val;
|
||||
// init the tx limit for interruption
|
||||
RMT.tx_lim[channel].limit = half_tx_nr+2;
|
||||
//RMT.tx_conf[channel].val = val;
|
||||
//RMT.tx_conf[channel].conf_update = 1;
|
||||
// reset memory pointer
|
||||
RMT.tx_conf[channel].mem_rst = 1;
|
||||
//RMT.tx_conf[channel].mem_rst = 0;
|
||||
RMT.tx_conf[channel].mem_rd_rst = 1;
|
||||
//RMT.tx_conf[channel].mem_rd_rst = 0;
|
||||
#else
|
||||
// init the tx limit for interruption
|
||||
RMT.tx_lim_ch[channel].limit = half_tx_nr+2;
|
||||
// reset memory pointer
|
||||
@ -288,9 +327,9 @@ bool rmtWrite(rmt_obj_t* rmt, rmt_data_t* data, size_t size)
|
||||
RMT.conf_ch[channel].conf1.mem_rd_rst = 0;
|
||||
RMT.conf_ch[channel].conf1.mem_wr_rst = 1;
|
||||
RMT.conf_ch[channel].conf1.mem_wr_rst = 0;
|
||||
|
||||
#endif
|
||||
// set the tx end mark
|
||||
RMTMEM.chan[channel].data32[MAX_DATA_PER_ITTERATION].val = 0;
|
||||
//RMTMEM.chan[channel].data32[MAX_DATA_PER_ITTERATION].val = 0;
|
||||
|
||||
// clear and enable both Tx completed and half tx event
|
||||
RMT.int_clr.val = _INT_TX_END(channel);
|
||||
@ -304,6 +343,7 @@ bool rmtWrite(rmt_obj_t* rmt, rmt_data_t* data, size_t size)
|
||||
RMT_MUTEX_UNLOCK(channel);
|
||||
|
||||
// start the transation
|
||||
//return _rmtSendOnce(rmt, data, MAX_DATA_PER_ITTERATION, true);
|
||||
return _rmtSendOnce(rmt, data, MAX_DATA_PER_ITTERATION, false);
|
||||
} else {
|
||||
// use one-go mode if data fits one buffer
|
||||
@ -342,10 +382,15 @@ bool rmtBeginReceive(rmt_obj_t* rmt)
|
||||
RMT.int_clr.val = _INT_ERROR(channel);
|
||||
RMT.int_ena.val |= _INT_ERROR(channel);
|
||||
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMT.rx_conf[channel].conf1.mem_owner = 1;
|
||||
RMT.rx_conf[channel].conf1.mem_wr_rst = 1;
|
||||
RMT.rx_conf[channel].conf1.rx_en = 1;
|
||||
#else
|
||||
RMT.conf_ch[channel].conf1.mem_owner = 1;
|
||||
RMT.conf_ch[channel].conf1.mem_wr_rst = 1;
|
||||
RMT.conf_ch[channel].conf1.rx_en = 1;
|
||||
|
||||
#endif
|
||||
return true;
|
||||
}
|
||||
|
||||
@ -384,17 +429,26 @@ bool rmtRead(rmt_obj_t* rmt, rmt_rx_data_cb_t cb, void * arg)
|
||||
rmt->data_alloc = true;
|
||||
}
|
||||
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMT.rx_conf[channel].conf1.mem_owner = 1;
|
||||
#else
|
||||
RMT.conf_ch[channel].conf1.mem_owner = 1;
|
||||
|
||||
#endif
|
||||
RMT.int_clr.val = _INT_RX_END(channel);
|
||||
RMT.int_clr.val = _INT_ERROR(channel);
|
||||
|
||||
RMT.int_ena.val |= _INT_RX_END(channel);
|
||||
RMT.int_ena.val |= _INT_ERROR(channel);
|
||||
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMT.rx_conf[channel].conf1.mem_wr_rst = 1;
|
||||
|
||||
RMT.rx_conf[channel].conf1.rx_en = 1;
|
||||
#else
|
||||
RMT.conf_ch[channel].conf1.mem_wr_rst = 1;
|
||||
|
||||
RMT.conf_ch[channel].conf1.rx_en = 1;
|
||||
#endif
|
||||
RMT_MUTEX_UNLOCK(channel);
|
||||
|
||||
return true;
|
||||
@ -407,7 +461,11 @@ bool rmtEnd(rmt_obj_t* rmt) {
|
||||
int channel = rmt->channel;
|
||||
|
||||
RMT_MUTEX_LOCK(channel);
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMT.rx_conf[channel].conf1.rx_en = 1;
|
||||
#else
|
||||
RMT.conf_ch[channel].conf1.rx_en = 1;
|
||||
#endif
|
||||
RMT_MUTEX_UNLOCK(channel);
|
||||
|
||||
return true;
|
||||
@ -437,7 +495,11 @@ bool rmtReadAsync(rmt_obj_t* rmt, rmt_data_t* data, size_t size, void* eventFlag
|
||||
RMT_MUTEX_LOCK(channel);
|
||||
rmt->intr_mode = E_RX_INTR;
|
||||
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMT.rx_conf[channel].conf1.mem_owner = 1;
|
||||
#else
|
||||
RMT.conf_ch[channel].conf1.mem_owner = 1;
|
||||
#endif
|
||||
|
||||
RMT.int_clr.val = _INT_RX_END(channel);
|
||||
RMT.int_clr.val = _INT_ERROR(channel);
|
||||
@ -445,9 +507,15 @@ bool rmtReadAsync(rmt_obj_t* rmt, rmt_data_t* data, size_t size, void* eventFlag
|
||||
RMT.int_ena.val |= _INT_RX_END(channel);
|
||||
RMT.int_ena.val |= _INT_ERROR(channel);
|
||||
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMT.rx_conf[channel].conf1.mem_wr_rst = 1;
|
||||
|
||||
RMT.rx_conf[channel].conf1.rx_en = 1;
|
||||
#else
|
||||
RMT.conf_ch[channel].conf1.mem_wr_rst = 1;
|
||||
|
||||
RMT.conf_ch[channel].conf1.rx_en = 1;
|
||||
#endif
|
||||
RMT_MUTEX_UNLOCK(channel);
|
||||
|
||||
// wait for data if requested so
|
||||
@ -474,14 +542,20 @@ float rmtSetTick(rmt_obj_t* rmt, float tick)
|
||||
* rmt tick for 1 MHz -> 1us (1x) div_cnt = 0x01
|
||||
256us (256x) div_cnt = 0x00
|
||||
*/
|
||||
int apb_div = _LIMIT(tick/12.5, 256);
|
||||
int ref_div = _LIMIT(tick/1000, 256);
|
||||
|
||||
float apb_tick = 12.5 * apb_div;
|
||||
float ref_tick = 1000.0 * ref_div;
|
||||
|
||||
size_t channel = rmt->channel;
|
||||
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
int apb_div = _LIMIT(tick/25.0, 256);
|
||||
float apb_tick = 25.0 * apb_div;
|
||||
RMT.tx_conf[channel].div_cnt = apb_div & 0xFF;
|
||||
RMT.tx_conf[channel].conf_update = 1;
|
||||
return apb_tick;
|
||||
#else
|
||||
int apb_div = _LIMIT(tick/12.5, 256);
|
||||
int ref_div = _LIMIT(tick/1000, 256);
|
||||
float apb_tick = 12.5 * apb_div;
|
||||
float ref_tick = 1000.0 * ref_div;
|
||||
if (_ABS(apb_tick - tick) < _ABS(ref_tick - tick)) {
|
||||
RMT.conf_ch[channel].conf0.div_cnt = apb_div & 0xFF;
|
||||
RMT.conf_ch[channel].conf1.ref_always_on = 1;
|
||||
@ -491,6 +565,7 @@ float rmtSetTick(rmt_obj_t* rmt, float tick)
|
||||
RMT.conf_ch[channel].conf1.ref_always_on = 0;
|
||||
return ref_tick;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
rmt_obj_t* rmtInit(int pin, bool tx_not_rx, rmt_reserve_memsize_t memsize)
|
||||
@ -553,6 +628,47 @@ rmt_obj_t* rmtInit(int pin, bool tx_not_rx, rmt_reserve_memsize_t memsize)
|
||||
// - no carrier, filter
|
||||
// - timebase tick of 1us
|
||||
// - idle threshold set to 0x8000 (max pulse width + 1)
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
|
||||
RMT.sys_conf.fifo_mask = 1;
|
||||
|
||||
if (tx_not_rx) {
|
||||
RMT.tx_lim[channel].limit = MAX_DATA_PER_ITTERATION/2 + 2;
|
||||
RMT.tx_conf[channel].val = 0;
|
||||
// RMT.tx_conf[channel].carrier_en = 0;
|
||||
// RMT.tx_conf[channel].carrier_out_lv = 0;
|
||||
// RMT.tx_conf[channel].tx_conti_mode = 0;
|
||||
// RMT.tx_conf[channel].idle_out_lv = 0; // signal level for idle
|
||||
// RMT.tx_conf[channel].tx_start = 0;
|
||||
// RMT.tx_conf[channel].tx_stop = 0;
|
||||
// RMT.tx_conf[channel].carrier_eff_en = 0;
|
||||
// RMT.tx_conf[channel].afifo_rst = 0;
|
||||
// RMT.tx_conf[channel].conf_update = 0;
|
||||
// RMT.tx_conf[channel].mem_tx_wrap_en = 0;
|
||||
// RMT.tx_conf[channel].mem_rst = 1;
|
||||
|
||||
RMT.tx_conf[channel].idle_out_en = 1; // enable idle
|
||||
RMT.tx_conf[channel].div_cnt = 1;
|
||||
RMT.tx_conf[channel].mem_size = buffers;
|
||||
RMT.tx_conf[channel].mem_rd_rst = 1;
|
||||
RMT.tx_conf[channel].conf_update = 1;
|
||||
} else {
|
||||
RMT.rx_conf[channel].conf0.div_cnt = 1;
|
||||
RMT.rx_conf[channel].conf0.mem_size = buffers;
|
||||
RMT.rx_conf[channel].conf0.carrier_en = 0;
|
||||
RMT.rx_conf[channel].conf0.carrier_out_lv = 0;
|
||||
RMT.rx_conf[channel].conf0.idle_thres = 0x80;
|
||||
RMT.rx_conf[channel].conf1.rx_filter_en = 0;
|
||||
RMT.rx_conf[channel].conf1.rx_filter_thres = 0;
|
||||
RMT.rx_conf[channel].conf1.mem_rst = 0;
|
||||
RMT.rx_conf[channel].conf1.mem_rx_wrap_en = 0;
|
||||
RMT.rx_conf[channel].conf1.afifo_rst = 0;
|
||||
RMT.rx_conf[channel].conf1.conf_update = 0;
|
||||
RMT.rx_conf[channel].conf1.rx_en = 1;
|
||||
RMT.rx_conf[channel].conf1.mem_owner = 1;
|
||||
RMT.rx_conf[channel].conf1.mem_wr_rst = 1;
|
||||
}
|
||||
#else
|
||||
RMT.conf_ch[channel].conf0.div_cnt = 1;
|
||||
RMT.conf_ch[channel].conf0.mem_size = buffers;
|
||||
RMT.conf_ch[channel].conf0.carrier_en = 0;
|
||||
@ -585,7 +701,7 @@ rmt_obj_t* rmtInit(int pin, bool tx_not_rx, rmt_reserve_memsize_t memsize)
|
||||
RMT.conf_ch[channel].conf1.mem_owner = 1;
|
||||
RMT.conf_ch[channel].conf1.mem_wr_rst = 1;
|
||||
}
|
||||
|
||||
#endif
|
||||
// install interrupt if at least one channel is active
|
||||
if (!intr_handle) {
|
||||
esp_intr_alloc(ETS_RMT_INTR_SOURCE, (int)ARDUINO_ISR_FLAG, _rmt_isr, NULL, &intr_handle);
|
||||
@ -604,7 +720,11 @@ bool _rmtSendOnce(rmt_obj_t* rmt, rmt_data_t* data, size_t size, bool continuous
|
||||
return false;
|
||||
}
|
||||
int channel = rmt->channel;
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMT.sys_conf.fifo_mask = 1;
|
||||
#else
|
||||
RMT.apb_conf.fifo_mask = 1;
|
||||
#endif
|
||||
if (data && size>0) {
|
||||
size_t i;
|
||||
volatile uint32_t* rmt_mem_ptr = &(RMTMEM.chan[channel].data32[0].val);
|
||||
@ -616,9 +736,15 @@ bool _rmtSendOnce(rmt_obj_t* rmt, rmt_data_t* data, size_t size, bool continuous
|
||||
}
|
||||
|
||||
RMT_MUTEX_LOCK(channel);
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMT.tx_conf[channel].tx_conti_mode = continuous;
|
||||
RMT.tx_conf[channel].mem_rd_rst = 1;
|
||||
RMT.tx_conf[channel].tx_start = 1;
|
||||
#else
|
||||
RMT.conf_ch[channel].conf1.tx_conti_mode = continuous;
|
||||
RMT.conf_ch[channel].conf1.mem_rd_rst = 1;
|
||||
RMT.conf_ch[channel].conf1.tx_start = 1;
|
||||
#endif
|
||||
RMT_MUTEX_UNLOCK(channel);
|
||||
|
||||
return true;
|
||||
@ -643,6 +769,7 @@ static void _initPin(int pin, int channel, bool tx_not_rx)
|
||||
{
|
||||
if (!periph_enabled) {
|
||||
periph_enabled = true;
|
||||
periph_module_reset( PERIPH_RMT_MODULE );
|
||||
periph_module_enable( PERIPH_RMT_MODULE );
|
||||
}
|
||||
if (tx_not_rx) {
|
||||
@ -658,6 +785,7 @@ static void _initPin(int pin, int channel, bool tx_not_rx)
|
||||
|
||||
static void ARDUINO_ISR_ATTR _rmt_isr(void* arg)
|
||||
{
|
||||
//DEBUG_INTERRUPT_START(4);
|
||||
int intr_val = RMT.int_st.val;
|
||||
size_t ch;
|
||||
for (ch = 0; ch < MAX_CHANNELS; ch++) {
|
||||
@ -692,9 +820,15 @@ static void ARDUINO_ISR_ATTR _rmt_isr(void* arg)
|
||||
(g_rmt_objects[ch].cb)(data_received, _rmt_get_mem_len(ch), g_rmt_objects[ch].arg);
|
||||
|
||||
// restart the reception
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMT.rx_conf[ch].conf1.mem_owner = 1;
|
||||
RMT.rx_conf[ch].conf1.mem_wr_rst = 1;
|
||||
RMT.rx_conf[ch].conf1.rx_en = 1;
|
||||
#else
|
||||
RMT.conf_ch[ch].conf1.mem_owner = 1;
|
||||
RMT.conf_ch[ch].conf1.mem_wr_rst = 1;
|
||||
RMT.conf_ch[ch].conf1.rx_en = 1;
|
||||
#endif
|
||||
RMT.int_ena.val |= _INT_RX_END(ch);
|
||||
} else {
|
||||
// if not callback provide, expect only one Rx
|
||||
@ -720,10 +854,17 @@ static void ARDUINO_ISR_ATTR _rmt_isr(void* arg)
|
||||
xEventGroupSetBits(g_rmt_objects[ch].events, RMT_FLAG_ERROR);
|
||||
}
|
||||
// reset memory
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMT.tx_conf[ch].mem_rd_rst = 1;
|
||||
RMT.tx_conf[ch].mem_rd_rst = 0;
|
||||
RMT.rx_conf[ch].conf1.mem_wr_rst = 1;
|
||||
RMT.rx_conf[ch].conf1.mem_wr_rst = 0;
|
||||
#else
|
||||
RMT.conf_ch[ch].conf1.mem_rd_rst = 1;
|
||||
RMT.conf_ch[ch].conf1.mem_rd_rst = 0;
|
||||
RMT.conf_ch[ch].conf1.mem_wr_rst = 1;
|
||||
RMT.conf_ch[ch].conf1.mem_wr_rst = 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
if (intr_val & _INT_TX_END(ch)) {
|
||||
@ -735,15 +876,24 @@ static void ARDUINO_ISR_ATTR _rmt_isr(void* arg)
|
||||
if (intr_val & _INT_THR_EVNT(ch)) {
|
||||
// clear the flag
|
||||
RMT.int_clr.val = _INT_THR_EVNT(ch);
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
//RMT.int_clr.val = _INT_TX_END(ch);
|
||||
//RMT.int_ena.val |= _INT_TX_END(ch);
|
||||
#endif
|
||||
|
||||
// initial setup of continuous mode
|
||||
if (g_rmt_objects[ch].tx_state & E_SET_CONTI) {
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMT.tx_conf[ch].tx_conti_mode = 1;
|
||||
#else
|
||||
RMT.conf_ch[ch].conf1.tx_conti_mode = 1;
|
||||
#endif
|
||||
g_rmt_objects[ch].intr_mode &= ~E_SET_CONTI;
|
||||
}
|
||||
_rmt_tx_mem_first(ch);
|
||||
}
|
||||
}
|
||||
//DEBUG_INTERRUPT_END(4);
|
||||
}
|
||||
|
||||
static void ARDUINO_ISR_ATTR _rmt_tx_mem_second(uint8_t ch)
|
||||
@ -753,14 +903,23 @@ static void ARDUINO_ISR_ATTR _rmt_tx_mem_second(uint8_t ch)
|
||||
int half_tx_nr = MAX_DATA_PER_ITTERATION/2;
|
||||
int i;
|
||||
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMT.tx_lim[ch].limit = half_tx_nr+2;
|
||||
#else
|
||||
RMT.tx_lim_ch[ch].limit = half_tx_nr+2;
|
||||
#endif
|
||||
RMT.int_clr.val = _INT_THR_EVNT(ch);
|
||||
RMT.int_ena.val |= _INT_THR_EVNT(ch);
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
//RMT.int_clr.val = _INT_TX_END(ch);
|
||||
//RMT.int_ena.val &= ~_INT_TX_END(ch);
|
||||
#endif
|
||||
|
||||
g_rmt_objects[ch].tx_state |= E_FIRST_HALF;
|
||||
|
||||
if (data) {
|
||||
int remaining_size = g_rmt_objects[ch].data_size;
|
||||
//ets_printf("RMT Tx[%d] %d\n", ch, remaining_size);
|
||||
// will the remaining data occupy the entire halfbuffer
|
||||
if (remaining_size > half_tx_nr) {
|
||||
for (i = 0; i < half_tx_nr; i++) {
|
||||
@ -779,17 +938,30 @@ static void ARDUINO_ISR_ATTR _rmt_tx_mem_second(uint8_t ch)
|
||||
g_rmt_objects[ch].data_ptr = NULL;
|
||||
|
||||
}
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMTMEM.chan[ch].data32[half_tx_nr+i].val = 0;
|
||||
RMT.tx_conf[ch].tx_start = 1;
|
||||
#endif
|
||||
} else if ((!(g_rmt_objects[ch].tx_state & E_LAST_DATA)) &&
|
||||
(!(g_rmt_objects[ch].tx_state & E_END_TRANS))) {
|
||||
//ets_printf("RMT Tx finishing %d!\n", ch);
|
||||
for (i = 0; i < half_tx_nr; i++) {
|
||||
RMTMEM.chan[ch].data32[half_tx_nr+i].val = 0x000F000F;
|
||||
}
|
||||
RMTMEM.chan[ch].data32[half_tx_nr+i].val = 0;
|
||||
g_rmt_objects[ch].tx_state |= E_LAST_DATA;
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMT.tx_conf[ch].tx_conti_mode = 0;
|
||||
#else
|
||||
RMT.conf_ch[ch].conf1.tx_conti_mode = 0;
|
||||
#endif
|
||||
} else {
|
||||
log_d("RMT Tx finished %d!\n", ch);
|
||||
//ets_printf("RMT Tx finished %d!\n", ch);
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMT.tx_conf[ch].tx_conti_mode = 0;
|
||||
#else
|
||||
RMT.conf_ch[ch].conf1.tx_conti_mode = 0;
|
||||
#endif
|
||||
RMT.int_ena.val &= ~_INT_TX_END(ch);
|
||||
RMT.int_ena.val &= ~_INT_THR_EVNT(ch);
|
||||
g_rmt_objects[ch].intr_mode = E_NO_INTR;
|
||||
@ -805,10 +977,15 @@ static void ARDUINO_ISR_ATTR _rmt_tx_mem_first(uint8_t ch)
|
||||
int half_tx_nr = MAX_DATA_PER_ITTERATION/2;
|
||||
int i;
|
||||
RMT.int_ena.val &= ~_INT_THR_EVNT(ch);
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMT.tx_lim[ch].limit = 0;
|
||||
#else
|
||||
RMT.tx_lim_ch[ch].limit = 0;
|
||||
#endif
|
||||
|
||||
if (data) {
|
||||
int remaining_size = g_rmt_objects[ch].data_size;
|
||||
//ets_printf("RMT TxF[%d] %d\n", ch, remaining_size);
|
||||
|
||||
// will the remaining data occupy the entire halfbuffer
|
||||
if (remaining_size > half_tx_nr) {
|
||||
@ -819,7 +996,11 @@ static void ARDUINO_ISR_ATTR _rmt_tx_mem_first(uint8_t ch)
|
||||
g_rmt_objects[ch].tx_state &= ~E_FIRST_HALF;
|
||||
// turn off the treshold interrupt
|
||||
RMT.int_ena.val &= ~_INT_THR_EVNT(ch);
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMT.tx_lim[ch].limit = 0;
|
||||
#else
|
||||
RMT.tx_lim_ch[ch].limit = 0;
|
||||
#endif
|
||||
g_rmt_objects[ch].data_size -= half_tx_nr;
|
||||
g_rmt_objects[ch].data_ptr += half_tx_nr;
|
||||
} else {
|
||||
@ -836,23 +1017,37 @@ static void ARDUINO_ISR_ATTR _rmt_tx_mem_first(uint8_t ch)
|
||||
g_rmt_objects[ch].data_ptr = NULL;
|
||||
}
|
||||
} else {
|
||||
//ets_printf("RMT TxF finished %d!\n", ch);
|
||||
for (i = 0; i < half_tx_nr; i++) {
|
||||
RMTMEM.chan[ch].data32[i].val = 0x000F000F;
|
||||
}
|
||||
RMTMEM.chan[ch].data32[i].val = 0;
|
||||
|
||||
g_rmt_objects[ch].tx_state &= ~E_FIRST_HALF;
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMT.tx_lim[ch].limit = 0;
|
||||
#else
|
||||
RMT.tx_lim_ch[ch].limit = 0;
|
||||
#endif
|
||||
g_rmt_objects[ch].tx_state |= E_LAST_DATA;
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
RMT.tx_conf[ch].tx_conti_mode = 0;
|
||||
#else
|
||||
RMT.conf_ch[ch].conf1.tx_conti_mode = 0;
|
||||
#endif
|
||||
}
|
||||
DEBUG_INTERRUPT_END(2);
|
||||
}
|
||||
|
||||
static int ARDUINO_ISR_ATTR _rmt_get_mem_len(uint8_t channel)
|
||||
{
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
int block_num = RMT.rx_conf[channel].conf0.mem_size;
|
||||
int item_block_len = block_num * 48;
|
||||
#else
|
||||
int block_num = RMT.conf_ch[channel].conf0.mem_size;
|
||||
int item_block_len = block_num * 64;
|
||||
#endif
|
||||
volatile rmt_item32_t* data = RMTMEM.chan[channel].data32;
|
||||
int idx;
|
||||
for(idx = 0; idx < item_block_len; idx++) {
|
||||
|
@ -26,6 +26,8 @@
|
||||
#include "esp32/rom/ets_sys.h"
|
||||
#elif CONFIG_IDF_TARGET_ESP32S2
|
||||
#include "esp32s2/rom/ets_sys.h"
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
#include "esp32c3/rom/ets_sys.h"
|
||||
#else
|
||||
#error Target CONFIG_IDF_TARGET is not supported
|
||||
#endif
|
||||
|
@ -22,19 +22,25 @@
|
||||
#include "soc/spi_struct.h"
|
||||
#include "soc/io_mux_reg.h"
|
||||
#include "soc/gpio_sig_map.h"
|
||||
#include "soc/dport_reg.h"
|
||||
#include "soc/rtc.h"
|
||||
#include "driver/periph_ctrl.h"
|
||||
|
||||
#include "esp_system.h"
|
||||
#ifdef ESP_IDF_VERSION_MAJOR // IDF 4+
|
||||
#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
|
||||
#include "soc/dport_reg.h"
|
||||
#include "esp32/rom/ets_sys.h"
|
||||
#include "esp32/rom/gpio.h"
|
||||
#include "esp_intr_alloc.h"
|
||||
#elif CONFIG_IDF_TARGET_ESP32S2
|
||||
#include "soc/dport_reg.h"
|
||||
#include "esp32s2/rom/ets_sys.h"
|
||||
#include "esp32s2/rom/gpio.h"
|
||||
#include "esp_intr_alloc.h"
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
#include "esp32c3/rom/ets_sys.h"
|
||||
#include "esp32c3/rom/gpio.h"
|
||||
#include "esp_intr_alloc.h"
|
||||
#else
|
||||
#error Target CONFIG_IDF_TARGET is not supported
|
||||
#endif
|
||||
@ -62,11 +68,24 @@ struct spi_struct_t {
|
||||
|
||||
#define SPI_SPI_SS_IDX(n) ((n==0)?SPICS0_OUT_IDX:((n==1)?SPICS1_OUT_IDX:0))
|
||||
#define SPI_HSPI_SS_IDX(n) ((n==0)?SPI3_CS0_OUT_IDX:((n==1)?SPI3_CS1_OUT_IDX:((n==2)?SPI3_CS2_OUT_IDX:SPI3_CS0_OUT_IDX)))
|
||||
#define SPI_FSPI_SS_IDX(n) ((n==0)?FSPICS0_OUT_IDX:((n==1)?FSPICS1_OUT_IDX:((n==2)?FSPICS2_OUT_IDX:VSPICS0_OUT_IDX)))
|
||||
#define SPI_FSPI_SS_IDX(n) ((n==0)?FSPICS0_OUT_IDX:((n==1)?FSPICS1_OUT_IDX:((n==2)?FSPICS2_OUT_IDX:FSPICS0_OUT_IDX)))
|
||||
#define SPI_SS_IDX(p, n) ((p==0)?SPI_SPI_SS_IDX(n):((p==1)?SPI_SPI_SS_IDX(n):((p==2)?SPI_HSPI_SS_IDX(n):0)))
|
||||
|
||||
#define SPI_INTR_SOURCE(u) ((u==0)?ETS_SPI1_INTR_SOURCE:((u==1)?ETS_SPI2_INTR_SOURCE:((u==2)?ETS_SPI3_INTR_SOURCE:0)))
|
||||
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
// ESP32S2
|
||||
#define SPI_COUNT (1)
|
||||
|
||||
#define SPI_CLK_IDX(p) FSPICLK_OUT_IDX
|
||||
#define SPI_MISO_IDX(p) FSPIQ_OUT_IDX
|
||||
#define SPI_MOSI_IDX(p) FSPID_IN_IDX
|
||||
|
||||
#define SPI_SPI_SS_IDX(n) ((n==0)?FSPICS0_OUT_IDX:((n==1)?FSPICS1_OUT_IDX:((n==2)?FSPICS2_OUT_IDX:FSPICS0_OUT_IDX)))
|
||||
#define SPI_SS_IDX(p, n) SPI_SPI_SS_IDX(n)
|
||||
|
||||
#define SPI_INTR_SOURCE(u) ETS_SPI2_INTR_SOURCE
|
||||
|
||||
#else
|
||||
// ESP32
|
||||
#define SPI_COUNT (4)
|
||||
@ -109,6 +128,8 @@ static spi_t _spi_bus_array[] = {
|
||||
{(volatile spi_dev_t *)(DR_REG_SPI1_BASE), NULL, 0},
|
||||
{(volatile spi_dev_t *)(DR_REG_SPI2_BASE), NULL, 1},
|
||||
{(volatile spi_dev_t *)(DR_REG_SPI3_BASE), NULL, 2}
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
{(volatile spi_dev_t *)(&GPSPI2), NULL, FSPI}
|
||||
#else
|
||||
{(volatile spi_dev_t *)(DR_REG_SPI0_BASE), NULL, 0},
|
||||
{(volatile spi_dev_t *)(DR_REG_SPI1_BASE), NULL, 1},
|
||||
@ -131,7 +152,7 @@ void spiAttachSCK(spi_t * spi, int8_t sck)
|
||||
log_e("HSPI Does not have default pins on ESP32S2!");
|
||||
return;
|
||||
}
|
||||
#else
|
||||
#elif CONFIG_IDF_TARGET_ESP32
|
||||
if(spi->num == HSPI) {
|
||||
sck = 14;
|
||||
} else if(spi->num == VSPI) {
|
||||
@ -139,6 +160,9 @@ void spiAttachSCK(spi_t * spi, int8_t sck)
|
||||
} else {
|
||||
sck = 6;
|
||||
}
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
log_e("SPI Does not have default pins on ESP32C3!");
|
||||
return;
|
||||
#endif
|
||||
}
|
||||
pinMode(sck, OUTPUT);
|
||||
@ -158,7 +182,7 @@ void spiAttachMISO(spi_t * spi, int8_t miso)
|
||||
log_e("HSPI Does not have default pins on ESP32S2!");
|
||||
return;
|
||||
}
|
||||
#else
|
||||
#elif CONFIG_IDF_TARGET_ESP32
|
||||
if(spi->num == HSPI) {
|
||||
miso = 12;
|
||||
} else if(spi->num == VSPI) {
|
||||
@ -166,6 +190,9 @@ void spiAttachMISO(spi_t * spi, int8_t miso)
|
||||
} else {
|
||||
miso = 7;
|
||||
}
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
log_e("SPI Does not have default pins on ESP32C3!");
|
||||
return;
|
||||
#endif
|
||||
}
|
||||
SPI_MUTEX_LOCK();
|
||||
@ -187,7 +214,7 @@ void spiAttachMOSI(spi_t * spi, int8_t mosi)
|
||||
log_e("HSPI Does not have default pins on ESP32S2!");
|
||||
return;
|
||||
}
|
||||
#else
|
||||
#elif CONFIG_IDF_TARGET_ESP32
|
||||
if(spi->num == HSPI) {
|
||||
mosi = 13;
|
||||
} else if(spi->num == VSPI) {
|
||||
@ -195,6 +222,9 @@ void spiAttachMOSI(spi_t * spi, int8_t mosi)
|
||||
} else {
|
||||
mosi = 8;
|
||||
}
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
log_e("SPI Does not have default pins on ESP32C3!");
|
||||
return;
|
||||
#endif
|
||||
}
|
||||
pinMode(mosi, OUTPUT);
|
||||
@ -214,7 +244,7 @@ void spiDetachSCK(spi_t * spi, int8_t sck)
|
||||
log_e("HSPI Does not have default pins on ESP32S2!");
|
||||
return;
|
||||
}
|
||||
#else
|
||||
#elif CONFIG_IDF_TARGET_ESP32
|
||||
if(spi->num == HSPI) {
|
||||
sck = 14;
|
||||
} else if(spi->num == VSPI) {
|
||||
@ -222,6 +252,9 @@ void spiDetachSCK(spi_t * spi, int8_t sck)
|
||||
} else {
|
||||
sck = 6;
|
||||
}
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
log_e("SPI Does not have default pins on ESP32C3!");
|
||||
return;
|
||||
#endif
|
||||
}
|
||||
pinMatrixOutDetach(sck, false, false);
|
||||
@ -241,7 +274,7 @@ void spiDetachMISO(spi_t * spi, int8_t miso)
|
||||
log_e("HSPI Does not have default pins on ESP32S2!");
|
||||
return;
|
||||
}
|
||||
#else
|
||||
#elif CONFIG_IDF_TARGET_ESP32
|
||||
if(spi->num == HSPI) {
|
||||
miso = 12;
|
||||
} else if(spi->num == VSPI) {
|
||||
@ -249,6 +282,9 @@ void spiDetachMISO(spi_t * spi, int8_t miso)
|
||||
} else {
|
||||
miso = 7;
|
||||
}
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
log_e("SPI Does not have default pins on ESP32C3!");
|
||||
return;
|
||||
#endif
|
||||
}
|
||||
pinMatrixInDetach(SPI_MISO_IDX(spi->num), false, false);
|
||||
@ -268,7 +304,7 @@ void spiDetachMOSI(spi_t * spi, int8_t mosi)
|
||||
log_e("HSPI Does not have default pins on ESP32S2!");
|
||||
return;
|
||||
}
|
||||
#else
|
||||
#elif CONFIG_IDF_TARGET_ESP32
|
||||
if(spi->num == HSPI) {
|
||||
mosi = 13;
|
||||
} else if(spi->num == VSPI) {
|
||||
@ -276,6 +312,9 @@ void spiDetachMOSI(spi_t * spi, int8_t mosi)
|
||||
} else {
|
||||
mosi = 8;
|
||||
}
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
log_e("SPI Does not have default pins on ESP32C3!");
|
||||
return;
|
||||
#endif
|
||||
}
|
||||
pinMatrixOutDetach(mosi, false, false);
|
||||
@ -299,7 +338,7 @@ void spiAttachSS(spi_t * spi, uint8_t cs_num, int8_t ss)
|
||||
log_e("HSPI Does not have default pins on ESP32S2!");
|
||||
return;
|
||||
}
|
||||
#else
|
||||
#elif CONFIG_IDF_TARGET_ESP32
|
||||
if(spi->num == HSPI) {
|
||||
ss = 15;
|
||||
} else if(spi->num == VSPI) {
|
||||
@ -307,6 +346,9 @@ void spiAttachSS(spi_t * spi, uint8_t cs_num, int8_t ss)
|
||||
} else {
|
||||
ss = 11;
|
||||
}
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
log_e("SPI Does not have default pins on ESP32C3!");
|
||||
return;
|
||||
#endif
|
||||
}
|
||||
pinMode(ss, OUTPUT);
|
||||
@ -327,7 +369,7 @@ void spiDetachSS(spi_t * spi, int8_t ss)
|
||||
log_e("HSPI Does not have default pins on ESP32S2!");
|
||||
return;
|
||||
}
|
||||
#else
|
||||
#elif CONFIG_IDF_TARGET_ESP32
|
||||
if(spi->num == HSPI) {
|
||||
ss = 15;
|
||||
} else if(spi->num == VSPI) {
|
||||
@ -335,6 +377,9 @@ void spiDetachSS(spi_t * spi, int8_t ss)
|
||||
} else {
|
||||
ss = 11;
|
||||
}
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
log_e("SPI Does not have default pins on ESP32C3!");
|
||||
return;
|
||||
#endif
|
||||
}
|
||||
pinMatrixOutDetach(ss, false, false);
|
||||
@ -347,7 +392,7 @@ void spiEnableSSPins(spi_t * spi, uint8_t cs_mask)
|
||||
return;
|
||||
}
|
||||
SPI_MUTEX_LOCK();
|
||||
#if CONFIG_IDF_TARGET_ESP32S2
|
||||
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->misc.val &= ~(cs_mask & SPI_CS_MASK_ALL);
|
||||
#else
|
||||
spi->dev->pin.val &= ~(cs_mask & SPI_CS_MASK_ALL);
|
||||
@ -361,7 +406,7 @@ void spiDisableSSPins(spi_t * spi, uint8_t cs_mask)
|
||||
return;
|
||||
}
|
||||
SPI_MUTEX_LOCK();
|
||||
#if CONFIG_IDF_TARGET_ESP32S2
|
||||
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->misc.val |= (cs_mask & SPI_CS_MASK_ALL);
|
||||
#else
|
||||
spi->dev->pin.val |= (cs_mask & SPI_CS_MASK_ALL);
|
||||
@ -397,7 +442,7 @@ void spiSSSet(spi_t * spi)
|
||||
return;
|
||||
}
|
||||
SPI_MUTEX_LOCK();
|
||||
#if CONFIG_IDF_TARGET_ESP32S2
|
||||
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->misc.cs_keep_active = 1;
|
||||
#else
|
||||
spi->dev->pin.cs_keep_active = 1;
|
||||
@ -411,7 +456,7 @@ void spiSSClear(spi_t * spi)
|
||||
return;
|
||||
}
|
||||
SPI_MUTEX_LOCK();
|
||||
#if CONFIG_IDF_TARGET_ESP32S2
|
||||
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->misc.cs_keep_active = 0;
|
||||
#else
|
||||
spi->dev->pin.cs_keep_active = 0;
|
||||
@ -442,7 +487,7 @@ uint8_t spiGetDataMode(spi_t * spi)
|
||||
if(!spi) {
|
||||
return 0;
|
||||
}
|
||||
#if CONFIG_IDF_TARGET_ESP32S2
|
||||
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32C3
|
||||
bool idleEdge = spi->dev->misc.ck_idle_edge;
|
||||
#else
|
||||
bool idleEdge = spi->dev->pin.ck_idle_edge;
|
||||
@ -468,7 +513,7 @@ void spiSetDataMode(spi_t * spi, uint8_t dataMode)
|
||||
SPI_MUTEX_LOCK();
|
||||
switch (dataMode) {
|
||||
case SPI_MODE1:
|
||||
#if CONFIG_IDF_TARGET_ESP32S2
|
||||
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->misc.ck_idle_edge = 0;
|
||||
#else
|
||||
spi->dev->pin.ck_idle_edge = 0;
|
||||
@ -476,7 +521,7 @@ void spiSetDataMode(spi_t * spi, uint8_t dataMode)
|
||||
spi->dev->user.ck_out_edge = 1;
|
||||
break;
|
||||
case SPI_MODE2:
|
||||
#if CONFIG_IDF_TARGET_ESP32S2
|
||||
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->misc.ck_idle_edge = 1;
|
||||
#else
|
||||
spi->dev->pin.ck_idle_edge = 1;
|
||||
@ -484,7 +529,7 @@ void spiSetDataMode(spi_t * spi, uint8_t dataMode)
|
||||
spi->dev->user.ck_out_edge = 1;
|
||||
break;
|
||||
case SPI_MODE3:
|
||||
#if CONFIG_IDF_TARGET_ESP32S2
|
||||
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->misc.ck_idle_edge = 1;
|
||||
#else
|
||||
spi->dev->pin.ck_idle_edge = 1;
|
||||
@ -493,7 +538,7 @@ void spiSetDataMode(spi_t * spi, uint8_t dataMode)
|
||||
break;
|
||||
case SPI_MODE0:
|
||||
default:
|
||||
#if CONFIG_IDF_TARGET_ESP32S2
|
||||
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->misc.ck_idle_edge = 0;
|
||||
#else
|
||||
spi->dev->pin.ck_idle_edge = 0;
|
||||
@ -542,9 +587,11 @@ static void _on_apb_change(void * arg, apb_change_ev_t ev_type, uint32_t old_apb
|
||||
|
||||
static void spiInitBus(spi_t * spi)
|
||||
{
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->slave.trans_done = 0;
|
||||
spi->dev->slave.slave_mode = 0;
|
||||
#if CONFIG_IDF_TARGET_ESP32S2
|
||||
#endif
|
||||
spi->dev->slave.val = 0;
|
||||
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->misc.val = 0;
|
||||
#else
|
||||
spi->dev->pin.val = 0;
|
||||
@ -552,8 +599,15 @@ static void spiInitBus(spi_t * spi)
|
||||
spi->dev->user.val = 0;
|
||||
spi->dev->user1.val = 0;
|
||||
spi->dev->ctrl.val = 0;
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->ctrl1.val = 0;
|
||||
spi->dev->ctrl2.val = 0;
|
||||
#else
|
||||
spi->dev->clk_gate.val = 0;
|
||||
spi->dev->dma_conf.val = 0;
|
||||
spi->dev->dma_conf.rx_afifo_rst = 1;
|
||||
spi->dev->dma_conf.buf_afifo_rst = 1;
|
||||
#endif
|
||||
spi->dev->clock.val = 0;
|
||||
}
|
||||
|
||||
@ -598,7 +652,7 @@ spi_t * spiStartBus(uint8_t spi_num, uint32_t clockDiv, uint8_t dataMode, uint8_
|
||||
DPORT_SET_PERI_REG_MASK(DPORT_PERIP_CLK_EN_REG, DPORT_SPI01_CLK_EN);
|
||||
DPORT_CLEAR_PERI_REG_MASK(DPORT_PERIP_RST_EN_REG, DPORT_SPI01_RST);
|
||||
}
|
||||
#else
|
||||
#elif CONFIG_IDF_TARGET_ESP32
|
||||
if(spi_num == HSPI) {
|
||||
DPORT_SET_PERI_REG_MASK(DPORT_PERIP_CLK_EN_REG, DPORT_SPI2_CLK_EN);
|
||||
DPORT_CLEAR_PERI_REG_MASK(DPORT_PERIP_RST_EN_REG, DPORT_SPI2_RST);
|
||||
@ -609,14 +663,24 @@ spi_t * spiStartBus(uint8_t spi_num, uint32_t clockDiv, uint8_t dataMode, uint8_
|
||||
DPORT_SET_PERI_REG_MASK(DPORT_PERIP_CLK_EN_REG, DPORT_SPI01_CLK_EN);
|
||||
DPORT_CLEAR_PERI_REG_MASK(DPORT_PERIP_RST_EN_REG, DPORT_SPI01_RST);
|
||||
}
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
periph_module_reset( PERIPH_SPI2_MODULE );
|
||||
periph_module_enable( PERIPH_SPI2_MODULE );
|
||||
#endif
|
||||
|
||||
SPI_MUTEX_LOCK();
|
||||
spiInitBus(spi);
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->clk_gate.clk_en = 1;
|
||||
spi->dev->clk_gate.mst_clk_sel = 1;
|
||||
spi->dev->clk_gate.mst_clk_active = 1;
|
||||
spi->dev->dma_conf.tx_seg_trans_clr_en = 1;
|
||||
spi->dev->dma_conf.rx_seg_trans_clr_en = 1;
|
||||
spi->dev->dma_conf.dma_seg_trans_en = 0;
|
||||
#endif
|
||||
spi->dev->user.usr_mosi = 1;
|
||||
spi->dev->user.usr_miso = 1;
|
||||
spi->dev->user.doutdin = 1;
|
||||
|
||||
int i;
|
||||
for(i=0; i<16; i++) {
|
||||
spi->dev->data_buf[i] = 0x00000000;
|
||||
@ -628,6 +692,7 @@ spi_t * spiStartBus(uint8_t spi_num, uint32_t clockDiv, uint8_t dataMode, uint8_
|
||||
spiSetClockDiv(spi, clockDiv);
|
||||
|
||||
addApbChangeCallback(spi, _on_apb_change);
|
||||
|
||||
return spi;
|
||||
}
|
||||
|
||||
@ -642,6 +707,11 @@ void spiWaitReady(spi_t * spi)
|
||||
#if CONFIG_IDF_TARGET_ESP32S2
|
||||
#define usr_mosi_dbitlen usr_mosi_bit_len
|
||||
#define usr_miso_dbitlen usr_miso_bit_len
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
#define usr_mosi_dbitlen ms_data_bitlen
|
||||
#define usr_miso_dbitlen ms_data_bitlen
|
||||
#define mosi_dlen ms_dlen
|
||||
#define miso_dlen ms_dlen
|
||||
#endif
|
||||
|
||||
void spiWrite(spi_t * spi, const uint32_t *data, uint8_t len)
|
||||
@ -655,10 +725,16 @@ void spiWrite(spi_t * spi, const uint32_t *data, uint8_t len)
|
||||
}
|
||||
SPI_MUTEX_LOCK();
|
||||
spi->dev->mosi_dlen.usr_mosi_dbitlen = (len * 32) - 1;
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->miso_dlen.usr_miso_dbitlen = 0;
|
||||
#endif
|
||||
for(i=0; i<len; i++) {
|
||||
spi->dev->data_buf[i] = data[i];
|
||||
}
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->cmd.update = 1;
|
||||
while (spi->dev->cmd.update);
|
||||
#endif
|
||||
spi->dev->cmd.usr = 1;
|
||||
while(spi->dev->cmd.usr);
|
||||
SPI_MUTEX_UNLOCK();
|
||||
@ -679,6 +755,10 @@ void spiTransfer(spi_t * spi, uint32_t *data, uint8_t len)
|
||||
for(i=0; i<len; i++) {
|
||||
spi->dev->data_buf[i] = data[i];
|
||||
}
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->cmd.update = 1;
|
||||
while (spi->dev->cmd.update);
|
||||
#endif
|
||||
spi->dev->cmd.usr = 1;
|
||||
while(spi->dev->cmd.usr);
|
||||
for(i=0; i<len; i++) {
|
||||
@ -694,8 +774,14 @@ void spiWriteByte(spi_t * spi, uint8_t data)
|
||||
}
|
||||
SPI_MUTEX_LOCK();
|
||||
spi->dev->mosi_dlen.usr_mosi_dbitlen = 7;
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->miso_dlen.usr_miso_dbitlen = 0;
|
||||
#endif
|
||||
spi->dev->data_buf[0] = data;
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->cmd.update = 1;
|
||||
while (spi->dev->cmd.update);
|
||||
#endif
|
||||
spi->dev->cmd.usr = 1;
|
||||
while(spi->dev->cmd.usr);
|
||||
SPI_MUTEX_UNLOCK();
|
||||
@ -710,6 +796,10 @@ uint8_t spiTransferByte(spi_t * spi, uint8_t data)
|
||||
spi->dev->mosi_dlen.usr_mosi_dbitlen = 7;
|
||||
spi->dev->miso_dlen.usr_miso_dbitlen = 7;
|
||||
spi->dev->data_buf[0] = data;
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->cmd.update = 1;
|
||||
while (spi->dev->cmd.update);
|
||||
#endif
|
||||
spi->dev->cmd.usr = 1;
|
||||
while(spi->dev->cmd.usr);
|
||||
data = spi->dev->data_buf[0] & 0xFF;
|
||||
@ -737,8 +827,14 @@ void spiWriteWord(spi_t * spi, uint16_t data)
|
||||
}
|
||||
SPI_MUTEX_LOCK();
|
||||
spi->dev->mosi_dlen.usr_mosi_dbitlen = 15;
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->miso_dlen.usr_miso_dbitlen = 0;
|
||||
#endif
|
||||
spi->dev->data_buf[0] = data;
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->cmd.update = 1;
|
||||
while (spi->dev->cmd.update);
|
||||
#endif
|
||||
spi->dev->cmd.usr = 1;
|
||||
while(spi->dev->cmd.usr);
|
||||
SPI_MUTEX_UNLOCK();
|
||||
@ -756,6 +852,10 @@ uint16_t spiTransferWord(spi_t * spi, uint16_t data)
|
||||
spi->dev->mosi_dlen.usr_mosi_dbitlen = 15;
|
||||
spi->dev->miso_dlen.usr_miso_dbitlen = 15;
|
||||
spi->dev->data_buf[0] = data;
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->cmd.update = 1;
|
||||
while (spi->dev->cmd.update);
|
||||
#endif
|
||||
spi->dev->cmd.usr = 1;
|
||||
while(spi->dev->cmd.usr);
|
||||
data = spi->dev->data_buf[0];
|
||||
@ -776,8 +876,14 @@ void spiWriteLong(spi_t * spi, uint32_t data)
|
||||
}
|
||||
SPI_MUTEX_LOCK();
|
||||
spi->dev->mosi_dlen.usr_mosi_dbitlen = 31;
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->miso_dlen.usr_miso_dbitlen = 0;
|
||||
#endif
|
||||
spi->dev->data_buf[0] = data;
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->cmd.update = 1;
|
||||
while (spi->dev->cmd.update);
|
||||
#endif
|
||||
spi->dev->cmd.usr = 1;
|
||||
while(spi->dev->cmd.usr);
|
||||
SPI_MUTEX_UNLOCK();
|
||||
@ -795,6 +901,10 @@ uint32_t spiTransferLong(spi_t * spi, uint32_t data)
|
||||
spi->dev->mosi_dlen.usr_mosi_dbitlen = 31;
|
||||
spi->dev->miso_dlen.usr_miso_dbitlen = 31;
|
||||
spi->dev->data_buf[0] = data;
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->cmd.update = 1;
|
||||
while (spi->dev->cmd.update);
|
||||
#endif
|
||||
spi->dev->cmd.usr = 1;
|
||||
while(spi->dev->cmd.usr);
|
||||
data = spi->dev->data_buf[0];
|
||||
@ -834,6 +944,10 @@ static void __spiTransferBytes(spi_t * spi, const uint8_t * data, uint8_t * out,
|
||||
spi->dev->data_buf[i] = wordsBuf[i]; //copy buffer to spi fifo
|
||||
}
|
||||
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->cmd.update = 1;
|
||||
while (spi->dev->cmd.update);
|
||||
#endif
|
||||
spi->dev->cmd.usr = 1;
|
||||
|
||||
while(spi->dev->cmd.usr);
|
||||
@ -898,7 +1012,7 @@ void spiTransaction(spi_t * spi, uint32_t clockDiv, uint8_t dataMode, uint8_t bi
|
||||
spi->dev->clock.val = clockDiv;
|
||||
switch (dataMode) {
|
||||
case SPI_MODE1:
|
||||
#if CONFIG_IDF_TARGET_ESP32S2
|
||||
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->misc.ck_idle_edge = 0;
|
||||
#else
|
||||
spi->dev->pin.ck_idle_edge = 0;
|
||||
@ -906,7 +1020,7 @@ void spiTransaction(spi_t * spi, uint32_t clockDiv, uint8_t dataMode, uint8_t bi
|
||||
spi->dev->user.ck_out_edge = 1;
|
||||
break;
|
||||
case SPI_MODE2:
|
||||
#if CONFIG_IDF_TARGET_ESP32S2
|
||||
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->misc.ck_idle_edge = 1;
|
||||
#else
|
||||
spi->dev->pin.ck_idle_edge = 1;
|
||||
@ -914,7 +1028,7 @@ void spiTransaction(spi_t * spi, uint32_t clockDiv, uint8_t dataMode, uint8_t bi
|
||||
spi->dev->user.ck_out_edge = 1;
|
||||
break;
|
||||
case SPI_MODE3:
|
||||
#if CONFIG_IDF_TARGET_ESP32S2
|
||||
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->misc.ck_idle_edge = 1;
|
||||
#else
|
||||
spi->dev->pin.ck_idle_edge = 1;
|
||||
@ -923,7 +1037,7 @@ void spiTransaction(spi_t * spi, uint32_t clockDiv, uint8_t dataMode, uint8_t bi
|
||||
break;
|
||||
case SPI_MODE0:
|
||||
default:
|
||||
#if CONFIG_IDF_TARGET_ESP32S2
|
||||
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->misc.ck_idle_edge = 0;
|
||||
#else
|
||||
spi->dev->pin.ck_idle_edge = 0;
|
||||
@ -962,8 +1076,14 @@ void ARDUINO_ISR_ATTR spiWriteByteNL(spi_t * spi, uint8_t data)
|
||||
return;
|
||||
}
|
||||
spi->dev->mosi_dlen.usr_mosi_dbitlen = 7;
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->miso_dlen.usr_miso_dbitlen = 0;
|
||||
#endif
|
||||
spi->dev->data_buf[0] = data;
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->cmd.update = 1;
|
||||
while (spi->dev->cmd.update);
|
||||
#endif
|
||||
spi->dev->cmd.usr = 1;
|
||||
while(spi->dev->cmd.usr);
|
||||
}
|
||||
@ -976,6 +1096,10 @@ uint8_t spiTransferByteNL(spi_t * spi, uint8_t data)
|
||||
spi->dev->mosi_dlen.usr_mosi_dbitlen = 7;
|
||||
spi->dev->miso_dlen.usr_miso_dbitlen = 7;
|
||||
spi->dev->data_buf[0] = data;
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->cmd.update = 1;
|
||||
while (spi->dev->cmd.update);
|
||||
#endif
|
||||
spi->dev->cmd.usr = 1;
|
||||
while(spi->dev->cmd.usr);
|
||||
data = spi->dev->data_buf[0] & 0xFF;
|
||||
@ -991,8 +1115,14 @@ void ARDUINO_ISR_ATTR spiWriteShortNL(spi_t * spi, uint16_t data)
|
||||
MSB_16_SET(data, data);
|
||||
}
|
||||
spi->dev->mosi_dlen.usr_mosi_dbitlen = 15;
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->miso_dlen.usr_miso_dbitlen = 0;
|
||||
#endif
|
||||
spi->dev->data_buf[0] = data;
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->cmd.update = 1;
|
||||
while (spi->dev->cmd.update);
|
||||
#endif
|
||||
spi->dev->cmd.usr = 1;
|
||||
while(spi->dev->cmd.usr);
|
||||
}
|
||||
@ -1008,6 +1138,10 @@ uint16_t spiTransferShortNL(spi_t * spi, uint16_t data)
|
||||
spi->dev->mosi_dlen.usr_mosi_dbitlen = 15;
|
||||
spi->dev->miso_dlen.usr_miso_dbitlen = 15;
|
||||
spi->dev->data_buf[0] = data;
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->cmd.update = 1;
|
||||
while (spi->dev->cmd.update);
|
||||
#endif
|
||||
spi->dev->cmd.usr = 1;
|
||||
while(spi->dev->cmd.usr);
|
||||
data = spi->dev->data_buf[0] & 0xFFFF;
|
||||
@ -1026,8 +1160,14 @@ void ARDUINO_ISR_ATTR spiWriteLongNL(spi_t * spi, uint32_t data)
|
||||
MSB_32_SET(data, data);
|
||||
}
|
||||
spi->dev->mosi_dlen.usr_mosi_dbitlen = 31;
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->miso_dlen.usr_miso_dbitlen = 0;
|
||||
#endif
|
||||
spi->dev->data_buf[0] = data;
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->cmd.update = 1;
|
||||
while (spi->dev->cmd.update);
|
||||
#endif
|
||||
spi->dev->cmd.usr = 1;
|
||||
while(spi->dev->cmd.usr);
|
||||
}
|
||||
@ -1043,6 +1183,10 @@ uint32_t spiTransferLongNL(spi_t * spi, uint32_t data)
|
||||
spi->dev->mosi_dlen.usr_mosi_dbitlen = 31;
|
||||
spi->dev->miso_dlen.usr_miso_dbitlen = 31;
|
||||
spi->dev->data_buf[0] = data;
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->cmd.update = 1;
|
||||
while (spi->dev->cmd.update);
|
||||
#endif
|
||||
spi->dev->cmd.usr = 1;
|
||||
while(spi->dev->cmd.usr);
|
||||
data = spi->dev->data_buf[0];
|
||||
@ -1053,6 +1197,9 @@ uint32_t spiTransferLongNL(spi_t * spi, uint32_t data)
|
||||
}
|
||||
|
||||
void spiWriteNL(spi_t * spi, const void * data_in, uint32_t len){
|
||||
if(!spi) {
|
||||
return;
|
||||
}
|
||||
size_t longs = len >> 2;
|
||||
if(len & 3){
|
||||
longs++;
|
||||
@ -1065,10 +1212,16 @@ void spiWriteNL(spi_t * spi, const void * data_in, uint32_t len){
|
||||
c_longs = (longs > 16)?16:longs;
|
||||
|
||||
spi->dev->mosi_dlen.usr_mosi_dbitlen = (c_len*8)-1;
|
||||
spi->dev->miso_dlen.usr_miso_dbitlen = 0;
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->miso_dlen.usr_miso_dbitlen = 0;
|
||||
#endif
|
||||
for (int i=0; i<c_longs; i++) {
|
||||
spi->dev->data_buf[i] = data[i];
|
||||
}
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->cmd.update = 1;
|
||||
while (spi->dev->cmd.update);
|
||||
#endif
|
||||
spi->dev->cmd.usr = 1;
|
||||
while(spi->dev->cmd.usr);
|
||||
|
||||
@ -1105,6 +1258,10 @@ void spiTransferBytesNL(spi_t * spi, const void * data_in, uint8_t * data_out, u
|
||||
spi->dev->data_buf[i] = 0xFFFFFFFF;
|
||||
}
|
||||
}
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->cmd.update = 1;
|
||||
while (spi->dev->cmd.update);
|
||||
#endif
|
||||
spi->dev->cmd.usr = 1;
|
||||
while(spi->dev->cmd.usr);
|
||||
if(result){
|
||||
@ -1160,6 +1317,10 @@ void spiTransferBitsNL(spi_t * spi, uint32_t data, uint32_t * out, uint8_t bits)
|
||||
spi->dev->mosi_dlen.usr_mosi_dbitlen = (bits - 1);
|
||||
spi->dev->miso_dlen.usr_miso_dbitlen = (bits - 1);
|
||||
spi->dev->data_buf[0] = data;
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->cmd.update = 1;
|
||||
while (spi->dev->cmd.update);
|
||||
#endif
|
||||
spi->dev->cmd.usr = 1;
|
||||
while(spi->dev->cmd.usr);
|
||||
data = spi->dev->data_buf[0];
|
||||
@ -1192,7 +1353,9 @@ void ARDUINO_ISR_ATTR spiWritePixelsNL(spi_t * spi, const void * data_in, uint32
|
||||
l_bytes = (c_len & 3);
|
||||
|
||||
spi->dev->mosi_dlen.usr_mosi_dbitlen = (c_len*8)-1;
|
||||
spi->dev->miso_dlen.usr_miso_dbitlen = 0;
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->miso_dlen.usr_miso_dbitlen = 0;
|
||||
#endif
|
||||
for (int i=0; i<c_longs; i++) {
|
||||
if(msb){
|
||||
if(l_bytes && i == (c_longs - 1)){
|
||||
@ -1208,6 +1371,10 @@ void ARDUINO_ISR_ATTR spiWritePixelsNL(spi_t * spi, const void * data_in, uint32
|
||||
spi->dev->data_buf[i] = data[i];
|
||||
}
|
||||
}
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
spi->dev->cmd.update = 1;
|
||||
while (spi->dev->cmd.update);
|
||||
#endif
|
||||
spi->dev->cmd.usr = 1;
|
||||
while(spi->dev->cmd.usr);
|
||||
|
||||
@ -1230,7 +1397,12 @@ typedef union {
|
||||
uint32_t clkcnt_l: 6; /*it must be equal to spi_clkcnt_N.*/
|
||||
uint32_t clkcnt_h: 6; /*it must be floor((spi_clkcnt_N+1)/2-1).*/
|
||||
uint32_t clkcnt_n: 6; /*it is the divider of spi_clk. So spi_clk frequency is system/(spi_clkdiv_pre+1)/(spi_clkcnt_N+1)*/
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
uint32_t clkdiv_pre: 4; /*it is pre-divider of spi_clk.*/
|
||||
uint32_t reserved: 9; /*reserved*/
|
||||
#else
|
||||
uint32_t clkdiv_pre: 13; /*it is pre-divider of spi_clk.*/
|
||||
#endif
|
||||
uint32_t clk_equ_sysclk: 1; /*1: spi_clk is eqaul to system 0: spi_clk is divided from system clock.*/
|
||||
};
|
||||
} spiClk_t;
|
||||
@ -1272,8 +1444,13 @@ uint32_t spiFrequencyToClockDiv(uint32_t freq)
|
||||
|
||||
while(calPreVari++ <= 1) {
|
||||
calPre = (((apb_freq / (reg.clkcnt_n + 1)) / freq) - 1) + calPreVari;
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
if(calPre > 0xF) {
|
||||
reg.clkdiv_pre = 0xF;
|
||||
#else
|
||||
if(calPre > 0x1FFF) {
|
||||
reg.clkdiv_pre = 0x1FFF;
|
||||
#endif
|
||||
} else if(calPre <= 0) {
|
||||
reg.clkdiv_pre = 0;
|
||||
} else {
|
||||
|
@ -25,11 +25,16 @@ extern "C" {
|
||||
|
||||
#define SPI_HAS_TRANSACTION
|
||||
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
#define FSPI 0
|
||||
#define HSPI 1
|
||||
#else
|
||||
#define FSPI 1 //SPI bus attached to the flash (can use the same data lines but different SS)
|
||||
#define HSPI 2 //SPI bus normally mapped to pins 12 - 15, but can be matrixed to any pins
|
||||
#if CONFIG_IDF_TARGET_ESP32
|
||||
#define VSPI 3 //SPI bus normally attached to pins 5, 18, 19 and 23, but can be matrixed to any pins
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// This defines are not representing the real Divider of the ESP32
|
||||
// the Defines match to an AVR Arduino on 16MHz for better compatibility
|
||||
|
@ -14,10 +14,12 @@
|
||||
|
||||
#include "esp32-hal-timer.h"
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32C3
|
||||
#include "freertos/xtensa_api.h"
|
||||
#include "soc/dport_reg.h"
|
||||
#endif
|
||||
#include "freertos/task.h"
|
||||
#include "soc/timer_group_struct.h"
|
||||
#include "soc/dport_reg.h"
|
||||
#include "esp_attr.h"
|
||||
#include "driver/periph_ctrl.h"
|
||||
|
||||
@ -30,6 +32,10 @@
|
||||
#include "esp32s2/rom/ets_sys.h"
|
||||
#include "esp_intr_alloc.h"
|
||||
#include "soc/periph_defs.h"
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
#include "esp32c3/rom/ets_sys.h"
|
||||
#include "esp_intr_alloc.h"
|
||||
#include "soc/periph_defs.h"
|
||||
#else
|
||||
#error Target CONFIG_IDF_TARGET is not supported
|
||||
#endif
|
||||
@ -296,12 +302,15 @@ void timerAttachInterrupt(hw_timer_t *timer, void (*fn)(void), bool edge){
|
||||
timer->dev->config.level_int_en = edge?0:1;//When set, an alarm will generate a level type interrupt.
|
||||
timer->dev->config.edge_int_en = edge?1:0;//When set, an alarm will generate an edge type interrupt.
|
||||
int intr_source = 0;
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32C3
|
||||
if(!edge){
|
||||
#endif
|
||||
if(timer->group){
|
||||
intr_source = ETS_TG1_T0_LEVEL_INTR_SOURCE + timer->timer;
|
||||
} else {
|
||||
intr_source = ETS_TG0_T0_LEVEL_INTR_SOURCE + timer->timer;
|
||||
}
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32C3
|
||||
} else {
|
||||
if(timer->group){
|
||||
intr_source = ETS_TG1_T0_EDGE_INTR_SOURCE + timer->timer;
|
||||
@ -309,6 +318,7 @@ void timerAttachInterrupt(hw_timer_t *timer, void (*fn)(void), bool edge){
|
||||
intr_source = ETS_TG0_T0_EDGE_INTR_SOURCE + timer->timer;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
if(!initialized){
|
||||
initialized = true;
|
||||
esp_intr_alloc(intr_source, (int)(ARDUINO_ISR_FLAG|ESP_INTR_FLAG_LOWMED), __timerISR, NULL, &intr_handle);
|
||||
|
@ -13,13 +13,14 @@
|
||||
// limitations under the License.
|
||||
|
||||
#include "esp32-hal-touch.h"
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32C3
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
#include "esp_attr.h"
|
||||
#include "soc/rtc_io_reg.h"
|
||||
#include "soc/rtc_cntl_reg.h"
|
||||
#include "soc/sens_reg.h"
|
||||
#include "soc/sens_struct.h"
|
||||
#include "soc/rtc_cntl_reg.h"
|
||||
#include "driver/touch_sensor.h"
|
||||
|
||||
#include "esp_system.h"
|
||||
@ -225,3 +226,4 @@ void __touchAttachInterrupt(uint8_t pin, void (*userFunc)(void), uint16_t thresh
|
||||
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")));
|
||||
#endif
|
||||
|
@ -23,19 +23,25 @@
|
||||
#include "soc/uart_struct.h"
|
||||
#include "soc/io_mux_reg.h"
|
||||
#include "soc/gpio_sig_map.h"
|
||||
#include "soc/dport_reg.h"
|
||||
#include "soc/rtc.h"
|
||||
#include "hal/uart_ll.h"
|
||||
#include "esp_intr_alloc.h"
|
||||
|
||||
#include "esp_system.h"
|
||||
#ifdef ESP_IDF_VERSION_MAJOR // IDF 4+
|
||||
#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
|
||||
#include "soc/dport_reg.h"
|
||||
#include "esp32/rom/ets_sys.h"
|
||||
#include "esp32/rom/uart.h"
|
||||
#elif CONFIG_IDF_TARGET_ESP32S2
|
||||
#include "soc/dport_reg.h"
|
||||
#include "esp32s2/rom/ets_sys.h"
|
||||
#include "esp32s2/rom/uart.h"
|
||||
#include "soc/periph_defs.h"
|
||||
#elif CONFIG_IDF_TARGET_ESP32C3
|
||||
#include "esp32c3/rom/ets_sys.h"
|
||||
#include "esp32c3/rom/uart.h"
|
||||
#include "soc/periph_defs.h"
|
||||
#else
|
||||
#error Target CONFIG_IDF_TARGET is not supported
|
||||
#endif
|
||||
@ -45,18 +51,24 @@
|
||||
#include "esp_intr.h"
|
||||
#endif
|
||||
|
||||
#if CONFIG_IDF_TARGET_ESP32S2
|
||||
#if CONFIG_IDF_TARGET_ESP32
|
||||
#define UART_PORTS_NUM 3
|
||||
#define UART_REG_BASE(u) ((u==0)?DR_REG_UART_BASE:( (u==1)?DR_REG_UART1_BASE:( (u==2)?DR_REG_UART2_BASE:0)))
|
||||
#define UART_RXD_IDX(u) ((u==0)?U0RXD_IN_IDX:( (u==1)?U1RXD_IN_IDX:( (u==2)?U2RXD_IN_IDX:0)))
|
||||
#define UART_TXD_IDX(u) ((u==0)?U0TXD_OUT_IDX:( (u==1)?U1TXD_OUT_IDX:( (u==2)?U2TXD_OUT_IDX:0)))
|
||||
#define UART_INTR_SOURCE(u) ((u==0)?ETS_UART0_INTR_SOURCE:( (u==1)?ETS_UART1_INTR_SOURCE:((u==2)?ETS_UART2_INTR_SOURCE:0)))
|
||||
#elif CONFIG_IDF_TARGET_ESP32S2
|
||||
#define UART_PORTS_NUM 2
|
||||
#define UART_REG_BASE(u) ((u==0)?DR_REG_UART_BASE:( (u==1)?DR_REG_UART1_BASE:0))
|
||||
#define UART_RXD_IDX(u) ((u==0)?U0RXD_IN_IDX:( (u==1)?U1RXD_IN_IDX:0))
|
||||
#define UART_TXD_IDX(u) ((u==0)?U0TXD_OUT_IDX:( (u==1)?U1TXD_OUT_IDX:0))
|
||||
#define UART_INTR_SOURCE(u) ((u==0)?ETS_UART0_INTR_SOURCE:( (u==1)?ETS_UART1_INTR_SOURCE:0))
|
||||
#else
|
||||
#define UART_PORTS_NUM 3
|
||||
#define UART_REG_BASE(u) ((u==0)?DR_REG_UART_BASE:( (u==1)?DR_REG_UART1_BASE:( (u==2)?DR_REG_UART2_BASE:0)))
|
||||
#define UART_RXD_IDX(u) ((u==0)?U0RXD_IN_IDX:( (u==1)?U1RXD_IN_IDX:( (u==2)?U2RXD_IN_IDX:0)))
|
||||
#define UART_TXD_IDX(u) ((u==0)?U0TXD_OUT_IDX:( (u==1)?U1TXD_OUT_IDX:( (u==2)?U2TXD_OUT_IDX:0)))
|
||||
#define UART_INTR_SOURCE(u) ((u==0)?ETS_UART0_INTR_SOURCE:( (u==1)?ETS_UART1_INTR_SOURCE:((u==2)?ETS_UART2_INTR_SOURCE:0)))
|
||||
#define UART_PORTS_NUM 2
|
||||
#define UART_REG_BASE(u) ((u==0)?DR_REG_UART_BASE:( (u==1)?DR_REG_UART1_BASE:0))
|
||||
#define UART_RXD_IDX(u) ((u==0)?U0RXD_IN_IDX:( (u==1)?U1RXD_IN_IDX:0))
|
||||
#define UART_TXD_IDX(u) ((u==0)?U0TXD_OUT_IDX:( (u==1)?U1TXD_OUT_IDX:0))
|
||||
#define UART_INTR_SOURCE(u) ((u==0)?ETS_UART0_INTR_SOURCE:( (u==1)?ETS_UART1_INTR_SOURCE:0))
|
||||
#endif
|
||||
|
||||
static int s_uart_debug_nr = 0;
|
||||
@ -225,6 +237,9 @@ uart_t* uartBegin(uint8_t uart_nr, uint32_t baudrate, uint32_t config, int8_t rx
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
#if CONFIG_IDF_TARGET_ESP32C3
|
||||
|
||||
#else
|
||||
if(uart_nr == 1){
|
||||
DPORT_SET_PERI_REG_MASK(DPORT_PERIP_CLK_EN_REG, DPORT_UART1_CLK_EN);
|
||||
DPORT_CLEAR_PERI_REG_MASK(DPORT_PERIP_RST_EN_REG, DPORT_UART1_RST);
|
||||
@ -237,6 +252,7 @@ uart_t* uartBegin(uint8_t uart_nr, uint32_t baudrate, uint32_t config, int8_t rx
|
||||
DPORT_SET_PERI_REG_MASK(DPORT_PERIP_CLK_EN_REG, DPORT_UART_CLK_EN);
|
||||
DPORT_CLEAR_PERI_REG_MASK(DPORT_PERIP_RST_EN_REG, DPORT_UART_RST);
|
||||
}
|
||||
#endif
|
||||
uartFlush(uart);
|
||||
uartSetBaudRate(uart, baudrate);
|
||||
UART_MUTEX_LOCK();
|
||||
@ -477,9 +493,7 @@ void uartSetBaudRate(uart_t* uart, uint32_t baud_rate)
|
||||
return;
|
||||
}
|
||||
UART_MUTEX_LOCK();
|
||||
uint32_t clk_div = ((getApbFrequency()<<4)/baud_rate);
|
||||
uart->dev->clk_div.div_int = clk_div>>4 ;
|
||||
uart->dev->clk_div.div_frag = clk_div & 0xf;
|
||||
uart_ll_set_baudrate(uart->dev, baud_rate);
|
||||
UART_MUTEX_UNLOCK();
|
||||
}
|
||||
|
||||
@ -676,15 +690,17 @@ unsigned long uartBaudrateDetect(uart_t *uart, bool flg)
|
||||
*/
|
||||
void uartStartDetectBaudrate(uart_t *uart) {
|
||||
if(!uart) return;
|
||||
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32C3
|
||||
uart->dev->auto_baud.glitch_filt = 0x08;
|
||||
uart->dev->auto_baud.en = 0;
|
||||
uart->dev->auto_baud.en = 1;
|
||||
#endif
|
||||
}
|
||||
|
||||
unsigned long
|
||||
uartDetectBaudrate(uart_t *uart)
|
||||
{
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32C3
|
||||
static bool uartStateDetectingBaudrate = false;
|
||||
|
||||
if(!uartStateDetectingBaudrate) {
|
||||
@ -719,6 +735,9 @@ uartDetectBaudrate(uart_t *uart)
|
||||
}
|
||||
|
||||
return default_rates[i];
|
||||
#else
|
||||
return 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
|
Reference in New Issue
Block a user