diff --git a/CMakeLists.txt b/CMakeLists.txt index 00e9d3e3..fcbf4a69 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,9 +6,7 @@ set(CORE_SRCS cores/esp32/esp32-hal-ledc.c cores/esp32/esp32-hal-matrix.c cores/esp32/esp32-hal-misc.c - cores/esp32/esp32-hal-psram.c cores/esp32/esp32-hal-spi.c - cores/esp32/esp32-hal-rmt.c cores/esp32/FunctionalInterrupt.cpp cores/esp32/stdlib_noniso.c cores/esp32/wiring_pulse.c diff --git a/cores/esp32/esp32-hal-psram.c b/cores/esp32/esp32-hal-psram.c deleted file mode 100644 index 6735f05c..00000000 --- a/cores/esp32/esp32-hal-psram.c +++ /dev/null @@ -1,138 +0,0 @@ -// 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.h" - -#include -#include - -#if CONFIG_SPIRAM_SUPPORT || CONFIG_SPIRAM -#include "soc/efuse_reg.h" -#include "esp_heap_caps.h" - -#include "esp_system.h" -#ifdef ESP_IDF_VERSION_MAJOR // IDF 4+ -#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4 -#include "esp32/spiram.h" -#elif CONFIG_IDF_TARGET_ESP32S2 -#include "esp32s2/spiram.h" -#include "esp32s2/rom/cache.h" -#else -#error Target CONFIG_IDF_TARGET is not supported -#endif -#else // ESP32 Before IDF 4.0 -#include "esp_spiram.h" -#endif - -static volatile bool spiramDetected = false; -static volatile bool spiramFailed = false; - -bool psramInit(){ - if (spiramDetected) { - return true; - } -#ifndef CONFIG_SPIRAM_BOOT_INIT - if (spiramFailed) { - return false; - } -#if CONFIG_IDF_TARGET_ESP32 - uint32_t chip_ver = REG_GET_FIELD(EFUSE_BLK0_RDATA3_REG, EFUSE_RD_CHIP_VER_PKG); - uint32_t pkg_ver = chip_ver & 0x7; - if (pkg_ver == EFUSE_RD_CHIP_VER_PKG_ESP32D2WDQ5 || pkg_ver == EFUSE_RD_CHIP_VER_PKG_ESP32PICOD2) { - spiramFailed = true; - log_w("PSRAM not supported!"); - return false; - } -#elif CONFIG_IDF_TARGET_ESP32S2 - extern void esp_config_data_cache_mode(void); - esp_config_data_cache_mode(); - Cache_Enable_DCache(0); -#endif - if (esp_spiram_init() != ESP_OK) { - spiramFailed = true; - log_w("PSRAM init failed!"); -#if CONFIG_IDF_TARGET_ESP32 - pinMatrixOutDetach(16, false, false); - pinMatrixOutDetach(17, false, false); -#endif - return false; - } - esp_spiram_init_cache(); - if (!esp_spiram_test()) { - spiramFailed = true; - log_e("PSRAM test failed!"); - return false; - } - if (esp_spiram_add_to_heapalloc() != ESP_OK) { - spiramFailed = true; - log_e("PSRAM could not be added to the heap!"); - return false; - } -#if CONFIG_SPIRAM_MALLOC_ALWAYSINTERNAL && !CONFIG_ARDUINO_ISR_IRAM - heap_caps_malloc_extmem_enable(CONFIG_SPIRAM_MALLOC_ALWAYSINTERNAL); -#endif -#endif - spiramDetected = true; - log_d("PSRAM enabled"); - return true; -} - -bool ARDUINO_ISR_ATTR psramFound(){ - return spiramDetected; -} - -void ARDUINO_ISR_ATTR *ps_malloc(size_t size){ - if(!spiramDetected){ - return NULL; - } - return heap_caps_malloc(size, MALLOC_CAP_SPIRAM | MALLOC_CAP_8BIT); -} - -void ARDUINO_ISR_ATTR *ps_calloc(size_t n, size_t size){ - if(!spiramDetected){ - return NULL; - } - return heap_caps_calloc(n, size, MALLOC_CAP_SPIRAM | MALLOC_CAP_8BIT); -} - -void ARDUINO_ISR_ATTR *ps_realloc(void *ptr, size_t size){ - if(!spiramDetected){ - return NULL; - } - return heap_caps_realloc(ptr, size, MALLOC_CAP_SPIRAM | MALLOC_CAP_8BIT); -} - -#else - -bool psramInit(){ - return false; -} - -bool ARDUINO_ISR_ATTR psramFound(){ - return false; -} - -void ARDUINO_ISR_ATTR *ps_malloc(size_t size){ - return NULL; -} - -void ARDUINO_ISR_ATTR *ps_calloc(size_t n, size_t size){ - return NULL; -} - -void ARDUINO_ISR_ATTR *ps_realloc(void *ptr, size_t size){ - return NULL; -} - -#endif diff --git a/cores/esp32/esp32-hal-psram.h b/cores/esp32/esp32-hal-psram.h deleted file mode 100644 index 0ba6763c..00000000 --- a/cores/esp32/esp32-hal-psram.h +++ /dev/null @@ -1,44 +0,0 @@ -// 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 _ESP32_HAL_PSRAM_H_ -#define _ESP32_HAL_PSRAM_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "sdkconfig.h" - -#ifndef BOARD_HAS_PSRAM -#ifdef CONFIG_SPIRAM_SUPPORT -#undef CONFIG_SPIRAM_SUPPORT -#endif -#ifdef CONFIG_SPIRAM -#undef CONFIG_SPIRAM -#endif -#endif - -bool psramInit(); -bool psramFound(); - -void *ps_malloc(size_t size); -void *ps_calloc(size_t n, size_t size); -void *ps_realloc(void *ptr, size_t size); - -#ifdef __cplusplus -} -#endif - -#endif /* _ESP32_HAL_PSRAM_H_ */ diff --git a/cores/esp32/esp32-hal-rmt.c b/cores/esp32/esp32-hal-rmt.c deleted file mode 100644 index a3ddb3ce..00000000 --- a/cores/esp32/esp32-hal-rmt.c +++ /dev/null @@ -1,878 +0,0 @@ -// Copyright 2018 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 "freertos/FreeRTOS.h" -#include "freertos/event_groups.h" -#include "freertos/semphr.h" - -#include "esp32-hal.h" -#include "esp32-hal-log.h" -#include "esp8266-compat.h" -#include "soc/gpio_reg.h" -#include "soc/rmt_struct.h" -#include -#include "esp_intr_alloc.h" -#include "hal/rmt_ll.h" -#include "driver/rmt.h" -#include "esp32-hal-rmt.h" -#include "esp32-hal-gpio.h" -#include "esp32-hal-matrix.h" - -// RMTMEM address is declared in .peripherals.ld -extern rmt_mem_t RMTMEM; - -/** - * Internal macros - */ -#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4 -#define MAX_CHANNELS 8 -#elif CONFIG_IDF_TARGET_ESP32S2 -#define MAX_CHANNELS 4 -#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) -#define __INT_TX_END (1) -#define __INT_RX_END (2) -#define __INT_ERROR (4) -#define __INT_THR_EVNT (1<<24) - -#define _INT_TX_END(channel) (__INT_TX_END<<(channel*3)) -#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)) - -#if CONFIG_DISABLE_HAL_LOCKS -# define RMT_MUTEX_LOCK(channel) -# define RMT_MUTEX_UNLOCK(channel) -#else -# define RMT_MUTEX_LOCK(channel) do {} while (xSemaphoreTake(g_rmt_objlocks[channel], portMAX_DELAY) != pdPASS) -# define RMT_MUTEX_UNLOCK(channel) xSemaphoreGive(g_rmt_objlocks[channel]) -#endif /* CONFIG_DISABLE_HAL_LOCKS */ - -#define _RMT_INTERNAL_DEBUG -#ifdef _RMT_INTERNAL_DEBUG -# define DEBUG_INTERRUPT_START(pin) digitalWrite(pin, 1); -# define DEBUG_INTERRUPT_END(pin) digitalWrite(pin, 0); -#else -# define DEBUG_INTERRUPT_START(pin) -# define DEBUG_INTERRUPT_END(pin) -#endif /* _RMT_INTERNAL_DEBUG */ - -/** - * Typedefs for internal stuctures, enums - */ -typedef enum { - E_NO_INTR = 0, - E_TX_INTR = 1, - E_TXTHR_INTR = 2, - E_RX_INTR = 4, -} intr_mode_t; - -typedef enum { - E_INACTIVE = 0, - E_FIRST_HALF = 1, - E_LAST_DATA = 2, - E_END_TRANS = 4, - E_SET_CONTI = 8, -} transaction_state_t; - -struct rmt_obj_s -{ - bool allocated; - EventGroupHandle_t events; - int pin; - int channel; - bool tx_not_rx; - int buffers; - int data_size; - uint32_t* data_ptr; - intr_mode_t intr_mode; - transaction_state_t tx_state; - rmt_rx_data_cb_t cb; - bool data_alloc; - void * arg; -}; - -/** - * Internal variables for channel descriptors - */ -static SemaphoreHandle_t g_rmt_objlocks[MAX_CHANNELS] = { - NULL, NULL, NULL, NULL, -#if CONFIG_IDF_TARGET_ESP32 - NULL, NULL, NULL, NULL -#endif -}; - -static rmt_obj_t g_rmt_objects[MAX_CHANNELS] = { - { false, NULL, 0, 0, 0, 0, 0, NULL, E_NO_INTR, E_INACTIVE, NULL, false, NULL}, - { false, NULL, 0, 0, 0, 0, 0, NULL, E_NO_INTR, E_INACTIVE, NULL, false, NULL}, - { false, NULL, 0, 0, 0, 0, 0, NULL, E_NO_INTR, E_INACTIVE, NULL, false, NULL}, - { false, NULL, 0, 0, 0, 0, 0, NULL, E_NO_INTR, E_INACTIVE, NULL, false, NULL}, -#if CONFIG_IDF_TARGET_ESP32 - { false, NULL, 0, 0, 0, 0, 0, NULL, E_NO_INTR, E_INACTIVE, NULL, false, NULL}, - { false, NULL, 0, 0, 0, 0, 0, NULL, E_NO_INTR, E_INACTIVE, NULL, false, NULL}, - { false, NULL, 0, 0, 0, 0, 0, NULL, E_NO_INTR, E_INACTIVE, NULL, false, NULL}, - { false, NULL, 0, 0, 0, 0, 0, NULL, E_NO_INTR, E_INACTIVE, NULL, false, NULL}, -#endif -}; - -/** - * Internal variables for driver data - */ -static intr_handle_t intr_handle; - -static bool periph_enabled = false; - -static SemaphoreHandle_t g_rmt_block_lock = NULL; - -/** - * Internal method (private) declarations - */ -static void _initPin(int pin, int channel, bool tx_not_rx); - -static bool _rmtSendOnce(rmt_obj_t* rmt, rmt_data_t* data, size_t size, bool continuous); - -static void ARDUINO_ISR_ATTR _rmt_isr(void* arg); - -static rmt_obj_t* _rmtAllocate(int pin, int from, int size); - -static void _initPin(int pin, int channel, bool tx_not_rx); - -static int ARDUINO_ISR_ATTR _rmt_get_mem_len(uint8_t channel); - -static void ARDUINO_ISR_ATTR _rmt_tx_mem_first(uint8_t ch); - -static void ARDUINO_ISR_ATTR _rmt_tx_mem_second(uint8_t ch); - - -/** - * Public method definitions - */ -bool rmtSetCarrier(rmt_obj_t* rmt, bool carrier_en, bool carrier_level, uint32_t low, uint32_t high) -{ - if (!rmt || low > 0xFFFF || high > 0xFFFF) { - return false; - } - size_t channel = rmt->channel; - - RMT_MUTEX_LOCK(channel); - - 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; - - RMT_MUTEX_UNLOCK(channel); - - return true; - -} - -bool rmtSetFilter(rmt_obj_t* rmt, bool filter_en, uint32_t filter_level) -{ - if (!rmt || filter_level > 0xFF) { - return false; - } - size_t channel = rmt->channel; - - RMT_MUTEX_LOCK(channel); - - RMT.conf_ch[channel].conf1.rx_filter_thres = filter_level; - RMT.conf_ch[channel].conf1.rx_filter_en = filter_en; - - RMT_MUTEX_UNLOCK(channel); - - return true; - -} - -bool rmtSetRxThreshold(rmt_obj_t* rmt, uint32_t value) -{ - if (!rmt || value > 0xFFFF) { - return false; - } - size_t channel = rmt->channel; - - RMT_MUTEX_LOCK(channel); - RMT.conf_ch[channel].conf0.idle_thres = value; - RMT_MUTEX_UNLOCK(channel); - - return true; -} - - -bool rmtDeinit(rmt_obj_t *rmt) -{ - if (!rmt) { - return false; - } - - // sanity check - if (rmt != &(g_rmt_objects[rmt->channel])) { - return false; - } - - size_t from = rmt->channel; - size_t to = rmt->buffers + rmt->channel; - size_t i; - -#if !CONFIG_DISABLE_HAL_LOCKS - if(g_rmt_objlocks[from] != NULL) { - vSemaphoreDelete(g_rmt_objlocks[from]); - } -#endif - - if (g_rmt_objects[from].data_alloc) { - free(g_rmt_objects[from].data_ptr); - } - - for (i = from; i < to; i++) { - g_rmt_objects[i].allocated = false; - } - - g_rmt_objects[from].channel = 0; - g_rmt_objects[from].buffers = 0; - - return true; -} - -bool rmtLoop(rmt_obj_t* rmt, rmt_data_t* data, size_t size) -{ - if (!rmt) { - return false; - } - - int allocated_size = MAX_DATA_PER_CHANNEL * rmt->buffers; - - if (size > allocated_size) { - return false; - } - return _rmtSendOnce(rmt, data, size, true); -} - -bool rmtWrite(rmt_obj_t* rmt, rmt_data_t* data, size_t size) -{ - if (!rmt) { - return false; - } - - int channel = rmt->channel; - int allocated_size = MAX_DATA_PER_CHANNEL * rmt->buffers; - - if (size > allocated_size) { - - int half_tx_nr = MAX_DATA_PER_ITTERATION/2; - RMT_MUTEX_LOCK(channel); - // setup interrupt handler if not yet installed for half and full tx - if (!intr_handle) { - esp_intr_alloc(ETS_RMT_INTR_SOURCE, (int)ARDUINO_ISR_FLAG, _rmt_isr, NULL, &intr_handle); - } - - rmt->data_size = size - MAX_DATA_PER_ITTERATION; - rmt->data_ptr = ((uint32_t*)data) + MAX_DATA_PER_ITTERATION; - rmt->intr_mode = E_TX_INTR | E_TXTHR_INTR; - rmt->tx_state = E_SET_CONTI | E_FIRST_HALF; - - // init the tx limit for interruption - RMT.tx_lim_ch[channel].limit = half_tx_nr+2; - // reset memory pointer - RMT.conf_ch[channel].conf1.apb_mem_rst = 1; - RMT.conf_ch[channel].conf1.apb_mem_rst = 0; - RMT.conf_ch[channel].conf1.mem_rd_rst = 1; - 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; - - // set the tx end mark - 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); - RMT.int_clr.val = _INT_THR_EVNT(channel); - RMT.int_clr.val = _INT_ERROR(channel); - - RMT.int_ena.val |= _INT_TX_END(channel); - RMT.int_ena.val |= _INT_THR_EVNT(channel); - RMT.int_ena.val |= _INT_ERROR(channel); - - RMT_MUTEX_UNLOCK(channel); - - // start the transation - return _rmtSendOnce(rmt, data, MAX_DATA_PER_ITTERATION, false); - } else { - // use one-go mode if data fits one buffer - return _rmtSendOnce(rmt, data, size, false); - } -} - -bool rmtReadData(rmt_obj_t* rmt, uint32_t* data, size_t size) -{ - if (!rmt) { - return false; - } - int channel = rmt->channel; - - if (g_rmt_objects[channel].buffers < size/MAX_DATA_PER_CHANNEL) { - return false; - } - - size_t i; - volatile uint32_t* rmt_mem_ptr = &(RMTMEM.chan[channel].data32[0].val); - for (i=0; ichannel; - - RMT.int_clr.val = _INT_ERROR(channel); - RMT.int_ena.val |= _INT_ERROR(channel); - - 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; - - return true; -} - -bool rmtReceiveCompleted(rmt_obj_t* rmt) -{ - if (!rmt) { - return false; - } - int channel = rmt->channel; - - if (RMT.int_raw.val&_INT_RX_END(channel)) { - // RX end flag - RMT.int_clr.val = _INT_RX_END(channel); - return true; - } else { - return false; - } -} - -bool rmtRead(rmt_obj_t* rmt, rmt_rx_data_cb_t cb, void * arg) -{ - if (!rmt && !cb) { - return false; - } - int channel = rmt->channel; - - RMT_MUTEX_LOCK(channel); - rmt->arg = arg; - rmt->intr_mode = E_RX_INTR; - rmt->tx_state = E_FIRST_HALF; - rmt->cb = cb; - // allocate internally two buffers which would alternate - if (!rmt->data_alloc) { - rmt->data_ptr = (uint32_t*)malloc(2*MAX_DATA_PER_CHANNEL*(rmt->buffers)*sizeof(uint32_t)); - rmt->data_size = MAX_DATA_PER_CHANNEL*rmt->buffers; - rmt->data_alloc = true; - } - - RMT.conf_ch[channel].conf1.mem_owner = 1; - - 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); - - RMT.conf_ch[channel].conf1.mem_wr_rst = 1; - - RMT.conf_ch[channel].conf1.rx_en = 1; - RMT_MUTEX_UNLOCK(channel); - - return true; -} - -bool rmtEnd(rmt_obj_t* rmt) { - if (!rmt) { - return false; - } - int channel = rmt->channel; - - RMT_MUTEX_LOCK(channel); - RMT.conf_ch[channel].conf1.rx_en = 1; - RMT_MUTEX_UNLOCK(channel); - - return true; -} - -bool rmtReadAsync(rmt_obj_t* rmt, rmt_data_t* data, size_t size, void* eventFlag, bool waitForData, uint32_t timeout) -{ - if (!rmt) { - return false; - } - int channel = rmt->channel; - - if (g_rmt_objects[channel].buffers < size/MAX_DATA_PER_CHANNEL) { - return false; - } - - if (eventFlag) { - xEventGroupClearBits(eventFlag, RMT_FLAGS_ALL); - rmt->events = eventFlag; - } - - if (data && size>0) { - rmt->data_ptr = (uint32_t*)data; - rmt->data_size = size; - } - - RMT_MUTEX_LOCK(channel); - rmt->intr_mode = E_RX_INTR; - - RMT.conf_ch[channel].conf1.mem_owner = 1; - - 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); - - RMT.conf_ch[channel].conf1.mem_wr_rst = 1; - - RMT.conf_ch[channel].conf1.rx_en = 1; - RMT_MUTEX_UNLOCK(channel); - - // wait for data if requested so - if (waitForData && eventFlag) { - uint32_t flags = xEventGroupWaitBits(eventFlag, RMT_FLAGS_ALL, - pdTRUE /* clear on exit */, pdFALSE /* wait for all bits */, timeout); - if (flags & RMT_FLAG_ERROR) { - return false; - } - } - - return true; -} - -float rmtSetTick(rmt_obj_t* rmt, float tick) -{ - if (!rmt) { - return false; - } - /* - divider field span from 1 (smallest), 2, 3, ... , 0xFF, 0x00 (highest) - * rmt tick from 1/80M -> 12.5ns (1x) div_cnt = 0x01 - 3.2 us (256x) div_cnt = 0x00 - * 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 (_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; - return apb_tick; - } else { - RMT.conf_ch[channel].conf0.div_cnt = ref_div & 0xFF; - RMT.conf_ch[channel].conf1.ref_always_on = 0; - return ref_tick; - } -} - -rmt_obj_t* rmtInit(int pin, bool tx_not_rx, rmt_reserve_memsize_t memsize) -{ - int buffers = memsize; - rmt_obj_t* rmt; - size_t i; - size_t j; - - // create common block mutex for protecting allocs from multiple threads - if (!g_rmt_block_lock) { - g_rmt_block_lock = xSemaphoreCreateMutex(); - } - // lock - while (xSemaphoreTake(g_rmt_block_lock, portMAX_DELAY) != pdPASS) {} - - for (i=0; i MAX_CHANNELS || j != buffers) { - xSemaphoreGive(g_rmt_block_lock); - return NULL; - } - rmt = _rmtAllocate(pin, i, buffers); - - xSemaphoreGive(g_rmt_block_lock); - - size_t channel = i; - -#if !CONFIG_DISABLE_HAL_LOCKS - if(g_rmt_objlocks[channel] == NULL) { - g_rmt_objlocks[channel] = xSemaphoreCreateMutex(); - if(g_rmt_objlocks[channel] == NULL) { - return NULL; - } - } -#endif - - RMT_MUTEX_LOCK(channel); - - rmt->pin = pin; - rmt->tx_not_rx = tx_not_rx; - rmt->buffers =buffers; - rmt->channel = channel; - rmt->arg = NULL; - - _initPin(pin, channel, tx_not_rx); - - // Initialize the registers in default mode: - // - no carrier, filter - // - timebase tick of 1us - // - idle threshold set to 0x8000 (max pulse width + 1) - RMT.conf_ch[channel].conf0.div_cnt = 1; - RMT.conf_ch[channel].conf0.mem_size = buffers; - RMT.conf_ch[channel].conf0.carrier_en = 0; - RMT.conf_ch[channel].conf0.carrier_out_lv = 0; -#if CONFIG_IDF_TARGET_ESP32 - RMT.conf_ch[channel].conf0.mem_pd = 0; -#endif - RMT.conf_ch[channel].conf0.idle_thres = 0x80; - RMT.conf_ch[channel].conf1.rx_en = 0; - RMT.conf_ch[channel].conf1.tx_conti_mode = 0; -#if CONFIG_IDF_TARGET_ESP32 - RMT.conf_ch[channel].conf1.ref_cnt_rst = 0; -#else - RMT.conf_ch[channel].conf1.chk_rx_carrier_en = 0; -#endif - RMT.conf_ch[channel].conf1.rx_filter_en = 0; - RMT.conf_ch[channel].conf1.rx_filter_thres = 0; - RMT.conf_ch[channel].conf1.idle_out_lv = 0; // signal level for idle - RMT.conf_ch[channel].conf1.idle_out_en = 1; // enable idle - RMT.conf_ch[channel].conf1.ref_always_on = 0; // base clock - - RMT.apb_conf.fifo_mask = 1; - - if (tx_not_rx) { - // RMT.conf_ch[channel].conf1.rx_en = 0; - RMT.conf_ch[channel].conf1.mem_owner = 0; - RMT.conf_ch[channel].conf1.mem_rd_rst = 1; - } else { - // RMT.conf_ch[channel].conf1.rx_en = 1; - RMT.conf_ch[channel].conf1.mem_owner = 1; - RMT.conf_ch[channel].conf1.mem_wr_rst = 1; - } - - // 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); - } - RMT_MUTEX_UNLOCK(channel); - - return rmt; -} - -/** - * Private methods definitions - */ -bool _rmtSendOnce(rmt_obj_t* rmt, rmt_data_t* data, size_t size, bool continuous) -{ - if (!rmt) { - return false; - } - int channel = rmt->channel; - RMT.apb_conf.fifo_mask = 1; - if (data && size>0) { - size_t i; - volatile uint32_t* rmt_mem_ptr = &(RMTMEM.chan[channel].data32[0].val); - for (i = 0; i < size; i++) { - *rmt_mem_ptr++ = data[i].val; - } - // tx end mark - RMTMEM.chan[channel].data32[size].val = 0; - } - - RMT_MUTEX_LOCK(channel); - 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; - RMT_MUTEX_UNLOCK(channel); - - return true; -} - - -static rmt_obj_t* _rmtAllocate(int pin, int from, int size) -{ - size_t i; - // setup how many buffers shall we use - g_rmt_objects[from].buffers = size; - - for (i=0; i 0) { - size_t i; - uint32_t * data = g_rmt_objects[ch].data_ptr; - // in case of callback, provide switching between memories - if (g_rmt_objects[ch].cb) { - if (g_rmt_objects[ch].tx_state & E_FIRST_HALF) { - g_rmt_objects[ch].tx_state &= ~E_FIRST_HALF; - } else { - g_rmt_objects[ch].tx_state |= E_FIRST_HALF; - data += MAX_DATA_PER_CHANNEL*(g_rmt_objects[ch].buffers); - } - } - uint32_t *data_received = data; - for (i = 0; i < g_rmt_objects[ch].data_size; i++ ) { - *data++ = RMTMEM.chan[ch].data32[i].val; - } - if (g_rmt_objects[ch].cb) { - // actually received data ptr - (g_rmt_objects[ch].cb)(data_received, _rmt_get_mem_len(ch), g_rmt_objects[ch].arg); - - // restart the reception - 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; - RMT.int_ena.val |= _INT_RX_END(ch); - } else { - // if not callback provide, expect only one Rx - g_rmt_objects[ch].intr_mode &= ~E_RX_INTR; - } - } - } else { - // Report error and disable Rx interrupt - log_e("Unexpected Rx interrupt!\n"); // TODO: eplace messages with log_X - RMT.int_ena.val &= ~_INT_RX_END(ch); - } - - - } - - if (intr_val & _INT_ERROR(ch)) { - // clear the flag - RMT.int_clr.val = _INT_ERROR(ch); - RMT.int_ena.val &= ~_INT_ERROR(ch); - // report error - log_e("RMT Error %d!\n", ch); - if (g_rmt_objects[ch].events) { - xEventGroupSetBits(g_rmt_objects[ch].events, RMT_FLAG_ERROR); - } - // reset memory - 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; - } - - if (intr_val & _INT_TX_END(ch)) { - - RMT.int_clr.val = _INT_TX_END(ch); - _rmt_tx_mem_second(ch); - } - - if (intr_val & _INT_THR_EVNT(ch)) { - // clear the flag - RMT.int_clr.val = _INT_THR_EVNT(ch); - - // initial setup of continuous mode - if (g_rmt_objects[ch].tx_state & E_SET_CONTI) { - RMT.conf_ch[ch].conf1.tx_conti_mode = 1; - g_rmt_objects[ch].intr_mode &= ~E_SET_CONTI; - } - _rmt_tx_mem_first(ch); - } - } -} - -static void ARDUINO_ISR_ATTR _rmt_tx_mem_second(uint8_t ch) -{ - DEBUG_INTERRUPT_START(4) - uint32_t* data = g_rmt_objects[ch].data_ptr; - int half_tx_nr = MAX_DATA_PER_ITTERATION/2; - int i; - - RMT.tx_lim_ch[ch].limit = half_tx_nr+2; - RMT.int_clr.val = _INT_THR_EVNT(ch); - RMT.int_ena.val |= _INT_THR_EVNT(ch); - - g_rmt_objects[ch].tx_state |= E_FIRST_HALF; - - if (data) { - int remaining_size = g_rmt_objects[ch].data_size; - // will the remaining data occupy the entire halfbuffer - if (remaining_size > half_tx_nr) { - for (i = 0; i < half_tx_nr; i++) { - RMTMEM.chan[ch].data32[half_tx_nr+i].val = data[i]; - } - g_rmt_objects[ch].data_size -= half_tx_nr; - g_rmt_objects[ch].data_ptr += half_tx_nr; - } else { - for (i = 0; i < half_tx_nr; i++) { - if (i < remaining_size) { - RMTMEM.chan[ch].data32[half_tx_nr+i].val = data[i]; - } else { - RMTMEM.chan[ch].data32[half_tx_nr+i].val = 0x000F000F; - } - } - g_rmt_objects[ch].data_ptr = NULL; - - } - } else if ((!(g_rmt_objects[ch].tx_state & E_LAST_DATA)) && - (!(g_rmt_objects[ch].tx_state & E_END_TRANS))) { - 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; - RMT.conf_ch[ch].conf1.tx_conti_mode = 0; - } else { - log_d("RMT Tx finished %d!\n", ch); - RMT.conf_ch[ch].conf1.tx_conti_mode = 0; - 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; - g_rmt_objects[ch].tx_state = E_INACTIVE; - } - DEBUG_INTERRUPT_END(4); -} - -static void ARDUINO_ISR_ATTR _rmt_tx_mem_first(uint8_t ch) -{ - DEBUG_INTERRUPT_START(2); - uint32_t* data = g_rmt_objects[ch].data_ptr; - int half_tx_nr = MAX_DATA_PER_ITTERATION/2; - int i; - RMT.int_ena.val &= ~_INT_THR_EVNT(ch); - RMT.tx_lim_ch[ch].limit = 0; - - if (data) { - int remaining_size = g_rmt_objects[ch].data_size; - - // will the remaining data occupy the entire halfbuffer - if (remaining_size > half_tx_nr) { - RMTMEM.chan[ch].data32[0].val = data[0] - 1; - for (i = 1; i < half_tx_nr; i++) { - RMTMEM.chan[ch].data32[i].val = data[i]; - } - g_rmt_objects[ch].tx_state &= ~E_FIRST_HALF; - // turn off the treshold interrupt - RMT.int_ena.val &= ~_INT_THR_EVNT(ch); - RMT.tx_lim_ch[ch].limit = 0; - g_rmt_objects[ch].data_size -= half_tx_nr; - g_rmt_objects[ch].data_ptr += half_tx_nr; - } else { - RMTMEM.chan[ch].data32[0].val = data[0] - 1; - for (i = 1; i < half_tx_nr; i++) { - if (i < remaining_size) { - RMTMEM.chan[ch].data32[i].val = data[i]; - } else { - RMTMEM.chan[ch].data32[i].val = 0x000F000F; - } - } - - g_rmt_objects[ch].tx_state &= ~E_FIRST_HALF; - g_rmt_objects[ch].data_ptr = NULL; - } - } else { - 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; - RMT.tx_lim_ch[ch].limit = 0; - g_rmt_objects[ch].tx_state |= E_LAST_DATA; - RMT.conf_ch[ch].conf1.tx_conti_mode = 0; - } - DEBUG_INTERRUPT_END(2); -} - -static int ARDUINO_ISR_ATTR _rmt_get_mem_len(uint8_t channel) -{ - int block_num = RMT.conf_ch[channel].conf0.mem_size; - int item_block_len = block_num * 64; - volatile uint32_t* data = &RMTMEM.chan[channel].data32->val; - int idx; - for(idx = 0; idx < item_block_len; idx++) { - rmt_item32_t helper; - helper.val = data[idx]; - - if(helper.duration0 == 0) { - return idx; - } else if(helper.duration1 == 0) { - return idx + 1; - } - } - return idx; -} diff --git a/cores/esp32/esp32-hal-rmt.h b/cores/esp32/esp32-hal-rmt.h deleted file mode 100644 index cce6c8c8..00000000 --- a/cores/esp32/esp32-hal-rmt.h +++ /dev/null @@ -1,152 +0,0 @@ -// Copyright 2018 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 MAIN_ESP32_HAL_RMT_H_ -#define MAIN_ESP32_HAL_RMT_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// notification flags -#define RMT_FLAG_TX_DONE (1) -#define RMT_FLAG_RX_DONE (2) -#define RMT_FLAG_ERROR (4) -#define RMT_FLAGS_ALL (RMT_FLAG_TX_DONE | RMT_FLAG_RX_DONE | RMT_FLAG_ERROR) - -struct rmt_obj_s; - -typedef enum { - RMT_MEM_64 = 1, - RMT_MEM_128 = 2, - RMT_MEM_192 = 3, - RMT_MEM_256 = 4, - RMT_MEM_320 = 5, - RMT_MEM_384 = 6, - RMT_MEM_448 = 7, - RMT_MEM_512 = 8, -} rmt_reserve_memsize_t; - -typedef struct rmt_obj_s rmt_obj_t; - -typedef void (*rmt_rx_data_cb_t)(uint32_t *data, size_t len, void *arg); - -typedef struct { - union { - struct { - uint32_t duration0 :15; - uint32_t level0 :1; - uint32_t duration1 :15; - uint32_t level1 :1; - }; - uint32_t val; - }; -} rmt_data_t; - -/** -* Initialize the object -* -*/ -rmt_obj_t* rmtInit(int pin, bool tx_not_rx, rmt_reserve_memsize_t memsize); - -/** -* Sets the clock/divider of timebase the nearest tick to the supplied value in nanoseconds -* return the real actual tick value in ns -*/ -float rmtSetTick(rmt_obj_t* rmt, float tick); - -/** -* Sending data in one-go mode or continual mode -* (more data being send while updating buffers in interrupts) -* -*/ -bool rmtWrite(rmt_obj_t* rmt, rmt_data_t* data, size_t size); - -/** -* Loop data up to the reserved memsize continuously -* -*/ -bool rmtLoop(rmt_obj_t* rmt, rmt_data_t* data, size_t size); - -/** -* Initiates async receive, event flag indicates data received -* -*/ -bool rmtReadAsync(rmt_obj_t* rmt, rmt_data_t* data, size_t size, void* eventFlag, bool waitForData, uint32_t timeout); - -/** -* Initiates async receive with automatic buffering -* and callback with data from ISR -* -*/ -bool rmtRead(rmt_obj_t* rmt, rmt_rx_data_cb_t cb, void * arg); - -/*** - * Ends async receive started with rmtRead(); but does not - * rmtDeInit(). - */ -bool rmtEnd(rmt_obj_t* rmt); - -/* Additional interface */ - -/** -* Start reception -* -*/ -bool rmtBeginReceive(rmt_obj_t* rmt); - -/** -* Checks if reception completes -* -*/ -bool rmtReceiveCompleted(rmt_obj_t* rmt); - -/** -* Reads the data for particular channel -* -*/ -bool rmtReadData(rmt_obj_t* rmt, uint32_t* data, size_t size); - -/** - * Setting threshold for Rx completed - */ -bool rmtSetRxThreshold(rmt_obj_t* rmt, uint32_t value); - -/** - * Setting carrier - */ -bool rmtSetCarrier(rmt_obj_t* rmt, bool carrier_en, bool carrier_level, uint32_t low, uint32_t high); - -/** - * Setting input filter - */ -bool rmtSetFilter(rmt_obj_t* rmt, bool filter_en, uint32_t filter_level); - -/** - * Deinitialize the driver - */ -bool rmtDeinit(rmt_obj_t *rmt); - -// TODO: -// * uninstall interrupt when all channels are deinit -// * send only-conti mode with circular-buffer -// * put sanity checks to some macro or inlines -// * doxy comments -// * error reporting - -#ifdef __cplusplus -} -#endif - -#endif /* MAIN_ESP32_HAL_RMT_H_ */