From 3fc82c0d345718cf0d780645aca981083d4961c0 Mon Sep 17 00:00:00 2001 From: 0xFEEDC0DE64 Date: Wed, 29 Mar 2023 16:00:35 +0200 Subject: [PATCH] Removed again lots of arduino bullshit --- CMakeLists.txt | 7 - cores/esp32/FunctionalInterrupt.cpp | 44 ---- cores/esp32/FunctionalInterrupt.h | 20 -- cores/esp32/WMath.cpp | 46 ---- cores/esp32/esp32-hal-dac.c | 57 ----- cores/esp32/esp32-hal-dac.h | 33 --- cores/esp32/esp32-hal-gpio.c | 63 ------ cores/esp32/esp32-hal-gpio.h | 4 - cores/esp32/esp32-hal-ledc.c | 319 ---------------------------- cores/esp32/esp32-hal-ledc.h | 44 ---- cores/esp32/esp32-hal-misc.c | 16 -- cores/esp32/stdlib_noniso.c | 161 -------------- cores/esp32/stdlib_noniso.h | 49 ----- cores/esp32/wiring_pulse.c | 50 ----- cores/esp32/wiring_shift.c | 53 ----- cores/esp32/wiring_shift.h | 9 - 16 files changed, 975 deletions(-) delete mode 100644 cores/esp32/FunctionalInterrupt.cpp delete mode 100644 cores/esp32/FunctionalInterrupt.h delete mode 100644 cores/esp32/WMath.cpp delete mode 100644 cores/esp32/esp32-hal-dac.c delete mode 100644 cores/esp32/esp32-hal-dac.h delete mode 100644 cores/esp32/esp32-hal-ledc.c delete mode 100644 cores/esp32/esp32-hal-ledc.h delete mode 100644 cores/esp32/stdlib_noniso.c delete mode 100644 cores/esp32/stdlib_noniso.h delete mode 100644 cores/esp32/wiring_pulse.c delete mode 100644 cores/esp32/wiring_shift.c delete mode 100644 cores/esp32/wiring_shift.h diff --git a/CMakeLists.txt b/CMakeLists.txt index fcbf4a69..719461c6 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,17 +1,10 @@ set(CORE_SRCS cores/esp32/esp32-hal-cpu.c - cores/esp32/esp32-hal-dac.c cores/esp32/esp32-hal-gpio.c cores/esp32/esp32-hal-i2c.c - cores/esp32/esp32-hal-ledc.c cores/esp32/esp32-hal-matrix.c cores/esp32/esp32-hal-misc.c cores/esp32/esp32-hal-spi.c - cores/esp32/FunctionalInterrupt.cpp - cores/esp32/stdlib_noniso.c - cores/esp32/wiring_pulse.c - cores/esp32/wiring_shift.c - cores/esp32/WMath.cpp ) set(LIBRARY_SRCS diff --git a/cores/esp32/FunctionalInterrupt.cpp b/cores/esp32/FunctionalInterrupt.cpp deleted file mode 100644 index a8f5518e..00000000 --- a/cores/esp32/FunctionalInterrupt.cpp +++ /dev/null @@ -1,44 +0,0 @@ -/* - * FunctionalInterrupt.cpp - * - * Created on: 8 jul. 2018 - * Author: Herman - */ - -#include "FunctionalInterrupt.h" -#include "esp32-hal.h" - -typedef void (*voidFuncPtr)(void); -typedef void (*voidFuncPtrArg)(void*); - -extern "C" -{ - extern void __attachInterruptFunctionalArg(uint8_t pin, voidFuncPtrArg userFunc, void * arg, int intr_type, bool functional); -} - -void ARDUINO_ISR_ATTR interruptFunctional(void* arg) -{ - InterruptArgStructure* localArg = (InterruptArgStructure*)arg; - if (localArg->interruptFunction) - { - localArg->interruptFunction(); - } -} - -void attachInterrupt(uint8_t pin, std::function intRoutine, int mode) -{ - // use the local interrupt routine which takes the ArgStructure as argument - __attachInterruptFunctionalArg (pin, (voidFuncPtrArg)interruptFunctional, new InterruptArgStructure{intRoutine}, mode, true); -} - -extern "C" -{ - void cleanupFunctional(void* arg) - { - delete (InterruptArgStructure*)arg; - } -} - - - - diff --git a/cores/esp32/FunctionalInterrupt.h b/cores/esp32/FunctionalInterrupt.h deleted file mode 100644 index b5e3181f..00000000 --- a/cores/esp32/FunctionalInterrupt.h +++ /dev/null @@ -1,20 +0,0 @@ -/* - * FunctionalInterrupt.h - * - * Created on: 8 jul. 2018 - * Author: Herman - */ - -#ifndef CORE_CORE_FUNCTIONALINTERRUPT_H_ -#define CORE_CORE_FUNCTIONALINTERRUPT_H_ - -#include - -struct InterruptArgStructure { - std::function interruptFunction; -}; - -void attachInterrupt(uint8_t pin, std::function intRoutine, int mode); - - -#endif /* CORE_CORE_FUNCTIONALINTERRUPT_H_ */ diff --git a/cores/esp32/WMath.cpp b/cores/esp32/WMath.cpp deleted file mode 100644 index c3701706..00000000 --- a/cores/esp32/WMath.cpp +++ /dev/null @@ -1,46 +0,0 @@ -/* -*- mode: jde; c-basic-offset: 2; indent-tabs-mode: nil -*- */ - -/* - Part of the Wiring project - http://wiring.org.co - Copyright (c) 2004-06 Hernando Barragan - Modified 13 August 2006, David A. Mellis for Arduino - http://www.arduino.cc/ - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General - Public License along with this library; if not, write to the - Free Software Foundation, Inc., 59 Temple Place, Suite 330, - Boston, MA 02111-1307 USA - - $Id$ - */ - -extern "C" { -#include "esp_system.h" -} - -//long map(long x, long in_min, long in_max, long out_min, long out_max) { -// const long dividend = out_max - out_min; -// const long divisor = in_max - in_min; -// const long delta = x - in_min; - -// return (delta * dividend + (divisor / 2)) / divisor + out_min; -//} - -//unsigned int makeWord(unsigned int w) -//{ -// return w; -//} - -//unsigned int makeWord(unsigned char h, unsigned char l) -//{ -// return (h << 8) | l; -//} diff --git a/cores/esp32/esp32-hal-dac.c b/cores/esp32/esp32-hal-dac.c deleted file mode 100644 index 19fd2f64..00000000 --- a/cores/esp32/esp32-hal-dac.c +++ /dev/null @@ -1,57 +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 "esp_attr.h" -#include "soc/rtc_io_reg.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" -#include "esp32-hal-gpio.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){ - return;//not dac pin - } - pinMode(pin, ANALOG); - uint8_t channel = pin - DAC1; -#if CONFIG_IDF_TARGET_ESP32 - CLEAR_PERI_REG_MASK(SENS_SAR_DAC_CTRL1_REG, SENS_SW_TONE_EN); -#elif CONFIG_IDF_TARGET_ESP32S2 - SENS.sar_dac_ctrl1.dac_clkgate_en = 1; -#endif - RTCIO.pad_dac[channel].dac_xpd_force = 1; - RTCIO.pad_dac[channel].xpd_dac = 1; - if (channel == 0) { - SENS.sar_dac_ctrl2.dac_cw_en1 = 0; - } else if (channel == 1) { - SENS.sar_dac_ctrl2.dac_cw_en2 = 0; - } - RTCIO.pad_dac[channel].dac = value; -} - -extern void dacWrite(uint8_t pin, uint8_t value) __attribute__ ((weak, alias("__dacWrite"))); diff --git a/cores/esp32/esp32-hal-dac.h b/cores/esp32/esp32-hal-dac.h deleted file mode 100644 index cfd7d798..00000000 --- a/cores/esp32/esp32-hal-dac.h +++ /dev/null @@ -1,33 +0,0 @@ -/* - Arduino.h - Main include file for the Arduino SDK - Copyright (c) 2005-2013 Arduino Team. All right reserved. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA - */ - -#ifndef MAIN_ESP32_HAL_DAC_H_ -#define MAIN_ESP32_HAL_DAC_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -void dacWrite(uint8_t pin, uint8_t value); - -#ifdef __cplusplus -} -#endif - -#endif /* MAIN_ESP32_HAL_DAC_H_ */ diff --git a/cores/esp32/esp32-hal-gpio.c b/cores/esp32/esp32-hal-gpio.c index d66e943a..bcacb531 100644 --- a/cores/esp32/esp32-hal-gpio.c +++ b/cores/esp32/esp32-hal-gpio.c @@ -323,70 +323,7 @@ static void ARDUINO_ISR_ATTR __onPinInterrupt() } } -extern void cleanupFunctional(void* arg); - -extern void __attachInterruptFunctionalArg(uint8_t pin, voidFuncPtrArg userFunc, void * arg, int intr_type, bool functional) -{ - static bool interrupt_initialized = false; - - if(!interrupt_initialized) { - interrupt_initialized = true; - esp_intr_alloc(ETS_GPIO_INTR_SOURCE, (int)ARDUINO_ISR_FLAG, __onPinInterrupt, NULL, &gpio_intr_handle); - } - - // if new attach without detach remove old info - if (__pinInterruptHandlers[pin].functional && __pinInterruptHandlers[pin].arg) - { - cleanupFunctional(__pinInterruptHandlers[pin].arg); - } - __pinInterruptHandlers[pin].fn = (voidFuncPtr)userFunc; - __pinInterruptHandlers[pin].arg = arg; - __pinInterruptHandlers[pin].functional = functional; - - esp_intr_disable(gpio_intr_handle); -#if CONFIG_IDF_TARGET_ESP32 - if(esp_intr_get_cpu(gpio_intr_handle)) { //APP_CPU -#endif - GPIO.pin[pin].int_ena = 1; -#if CONFIG_IDF_TARGET_ESP32 - } else { //PRO_CPU - GPIO.pin[pin].int_ena = 4; - } -#endif - GPIO.pin[pin].int_type = intr_type; - esp_intr_enable(gpio_intr_handle); -} - -extern void __attachInterruptArg(uint8_t pin, voidFuncPtrArg userFunc, void * arg, int intr_type) -{ - __attachInterruptFunctionalArg(pin, userFunc, arg, intr_type, false); -} - -extern void __attachInterrupt(uint8_t pin, voidFuncPtr userFunc, int intr_type) { - __attachInterruptFunctionalArg(pin, (voidFuncPtrArg)userFunc, NULL, intr_type, false); -} - -extern void __detachInterrupt(uint8_t pin) -{ - esp_intr_disable(gpio_intr_handle); - if (__pinInterruptHandlers[pin].functional && __pinInterruptHandlers[pin].arg) - { - cleanupFunctional(__pinInterruptHandlers[pin].arg); - } - __pinInterruptHandlers[pin].fn = NULL; - __pinInterruptHandlers[pin].arg = NULL; - __pinInterruptHandlers[pin].functional = false; - - GPIO.pin[pin].int_ena = 0; - GPIO.pin[pin].int_type = 0; - esp_intr_enable(gpio_intr_handle); -} - - extern void pinMode(uint8_t pin, uint8_t mode) __attribute__ ((weak, alias("__pinMode"))); extern void digitalWrite(uint8_t pin, uint8_t val) __attribute__ ((weak, alias("__digitalWrite"))); extern int digitalRead(uint8_t pin) __attribute__ ((weak, alias("__digitalRead"))); -extern void attachInterrupt(uint8_t pin, voidFuncPtr handler, int mode) __attribute__ ((weak, alias("__attachInterrupt"))); -extern void attachInterruptArg(uint8_t pin, voidFuncPtrArg handler, void * arg, int mode) __attribute__ ((weak, alias("__attachInterruptArg"))); -extern void detachInterrupt(uint8_t pin) __attribute__ ((weak, alias("__detachInterrupt"))); diff --git a/cores/esp32/esp32-hal-gpio.h b/cores/esp32/esp32-hal-gpio.h index 7620629e..ca43e67a 100644 --- a/cores/esp32/esp32-hal-gpio.h +++ b/cores/esp32/esp32-hal-gpio.h @@ -89,10 +89,6 @@ void pinMode(uint8_t pin, uint8_t mode); void digitalWrite(uint8_t pin, uint8_t val); int digitalRead(uint8_t pin); -void attachInterrupt(uint8_t pin, void (*)(void), int mode); -void attachInterruptArg(uint8_t pin, void (*)(void*), void * arg, int mode); -void detachInterrupt(uint8_t pin); - #ifdef __cplusplus } #endif diff --git a/cores/esp32/esp32-hal-ledc.c b/cores/esp32/esp32-hal-ledc.c deleted file mode 100644 index ceda0956..00000000 --- a/cores/esp32/esp32-hal-ledc.c +++ /dev/null @@ -1,319 +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 "freertos/FreeRTOS.h" -#include "freertos/task.h" -#include "freertos/semphr.h" -#include "esp32-hal-matrix.h" -#include "esp32-hal-log.h" -#include "soc/dport_reg.h" -#include "soc/ledc_reg.h" -#include "soc/ledc_struct.h" -#include "esp32-hal-cpu.h" -#include "esp32-hal-gpio.h" -#include "esp32-hal-ledc.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" -#define LAST_CHAN (15) -#elif CONFIG_IDF_TARGET_ESP32S2 -#include "esp32s2/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 -#else // ESP32 Before IDF 4.0 -#include "rom/ets_sys.h" -#endif - -#if CONFIG_DISABLE_HAL_LOCKS -#define LEDC_MUTEX_LOCK() -#define LEDC_MUTEX_UNLOCK() -#else -#define LEDC_MUTEX_LOCK() do {} while (xSemaphoreTake(_ledc_sys_lock, portMAX_DELAY) != pdPASS) -#define LEDC_MUTEX_UNLOCK() xSemaphoreGive(_ledc_sys_lock) -SemaphoreHandle_t _ledc_sys_lock = NULL; -#endif - -/* - * LEDC Chan to Group/Channel/Timer Mapping -** ledc: 0 => Group: 0, Channel: 0, Timer: 0 -** ledc: 1 => Group: 0, Channel: 1, Timer: 0 -** ledc: 2 => Group: 0, Channel: 2, Timer: 1 -** ledc: 3 => Group: 0, Channel: 3, Timer: 1 -** ledc: 4 => Group: 0, Channel: 4, Timer: 2 -** ledc: 5 => Group: 0, Channel: 5, Timer: 2 -** ledc: 6 => Group: 0, Channel: 6, Timer: 3 -** ledc: 7 => Group: 0, Channel: 7, Timer: 3 -** ledc: 8 => Group: 1, Channel: 0, Timer: 0 -** ledc: 9 => Group: 1, Channel: 1, Timer: 0 -** ledc: 10 => Group: 1, Channel: 2, Timer: 1 -** ledc: 11 => Group: 1, Channel: 3, Timer: 1 -** ledc: 12 => Group: 1, Channel: 4, Timer: 2 -** ledc: 13 => Group: 1, Channel: 5, Timer: 2 -** ledc: 14 => Group: 1, Channel: 6, Timer: 3 -** ledc: 15 => Group: 1, Channel: 7, Timer: 3 -*/ -#define LEDC_CHAN(g,c) LEDC.channel_group[(g)].channel[(c)] -#define LEDC_TIMER(g,t) LEDC.timer_group[(g)].timer[(t)] - -static void _on_apb_change(void * arg, apb_change_ev_t ev_type, uint32_t old_apb, uint32_t new_apb){ - if(ev_type == APB_AFTER_CHANGE && old_apb != new_apb){ - uint16_t iarg = *(uint16_t*)arg; - uint8_t chan = 0; - old_apb /= 1000000; - new_apb /= 1000000; - while(iarg){ // run though all active channels, adjusting timing configurations - if(iarg & 1) {// this channel is active - uint8_t group=(chan/8), timer=((chan/2)%4); - if(LEDC_TIMER(group, timer).conf.tick_sel){ - LEDC_MUTEX_LOCK(); - uint32_t old_div = LEDC_TIMER(group, timer).conf.clock_divider; - uint32_t div_num = (new_apb * old_div) / old_apb; - if(div_num > LEDC_DIV_NUM_HSTIMER0_V){ - div_num = ((REF_CLK_FREQ /1000000) * old_div) / old_apb; - if(div_num > LEDC_DIV_NUM_HSTIMER0_V) { - div_num = LEDC_DIV_NUM_HSTIMER0_V;//lowest clock possible - } - LEDC_TIMER(group, timer).conf.tick_sel = 0; - } else if(div_num < 256) { - div_num = 256;//highest clock possible - } - LEDC_TIMER(group, timer).conf.clock_divider = div_num; - LEDC_MUTEX_UNLOCK(); - } - else { - log_d("using REF_CLK chan=%d",chan); - } - } - iarg = iarg >> 1; - chan++; - } - } -} - -//uint32_t frequency = (80MHz or 1MHz)/((div_num / 256.0)*(1 << bit_num)); -static void _ledcSetupTimer(uint8_t chan, uint32_t div_num, uint8_t bit_num, bool apb_clk) -{ - uint8_t group=(chan/8), timer=((chan/2)%4); - static bool tHasStarted = false; - 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); - LEDC.conf.apb_clk_sel = 1;//LS use apb clock - addApbChangeCallback((void*)&_activeChannels, _on_apb_change); - -#if !CONFIG_DISABLE_HAL_LOCKS - _ledc_sys_lock = xSemaphoreCreateMutex(); -#endif - } - LEDC_MUTEX_LOCK(); - LEDC_TIMER(group, timer).conf.clock_divider = div_num;//18 bit (10.8) This register is used to configure parameter for divider in timer the least significant eight bits represent the decimal part. - LEDC_TIMER(group, timer).conf.duty_resolution = bit_num;//5 bit This register controls the range of the counter in timer. the counter range is [0 2**bit_num] the max bit width for counter is 20. - LEDC_TIMER(group, timer).conf.tick_sel = apb_clk;//apb clock -#if CONFIG_IDF_TARGET_ESP32 - if(group) { -#endif - LEDC_TIMER(group, timer).conf.low_speed_update = 1;//This bit is only useful for low speed timer channels, reserved for high speed timers -#if CONFIG_IDF_TARGET_ESP32 - } -#endif - LEDC_TIMER(group, timer).conf.pause = 0; - LEDC_TIMER(group, timer).conf.rst = 1;//This bit is used to reset timer the counter will be 0 after reset. - LEDC_TIMER(group, timer).conf.rst = 0; - LEDC_MUTEX_UNLOCK(); - _activeChannels |= (1 << chan); // mark as active for APB callback -} - -//max div_num 0x3FFFF (262143) -//max bit_num 0x1F (31) -static double _ledcSetupTimerFreq(uint8_t chan, double freq, uint8_t bit_num) -{ - uint64_t clk_freq = getApbFrequency(); - clk_freq <<= 8;//div_num is 8 bit decimal - uint32_t div_num = (clk_freq >> bit_num) / freq; - bool apb_clk = true; - if(div_num > LEDC_DIV_NUM_HSTIMER0_V) { - clk_freq /= 80; - div_num = (clk_freq >> bit_num) / freq; - if(div_num > LEDC_DIV_NUM_HSTIMER0_V) { - div_num = LEDC_DIV_NUM_HSTIMER0_V;//lowest clock possible - } - apb_clk = false; - } else if(div_num < 256) { - div_num = 256;//highest clock possible - } - _ledcSetupTimer(chan, div_num, bit_num, apb_clk); - //log_i("Fin: %f, Fclk: %uMhz, bits: %u, DIV: %u, Fout: %f", - // freq, apb_clk?80:1, bit_num, div_num, (clk_freq >> bit_num) / (double)div_num); - return (clk_freq >> bit_num) / (double)div_num; -} - -static double _ledcTimerRead(uint8_t chan) -{ - uint32_t div_num; - uint8_t bit_num; - bool apb_clk; - uint8_t group=(chan/8), timer=((chan/2)%4); - LEDC_MUTEX_LOCK(); - div_num = LEDC_TIMER(group, timer).conf.clock_divider;//18 bit (10.8) This register is used to configure parameter for divider in timer the least significant eight bits represent the decimal part. - bit_num = LEDC_TIMER(group, timer).conf.duty_resolution;//5 bit This register controls the range of the counter in timer. the counter range is [0 2**bit_num] the max bit width for counter is 20. - apb_clk = LEDC_TIMER(group, timer).conf.tick_sel;//apb clock - LEDC_MUTEX_UNLOCK(); - uint64_t clk_freq = 1000000; - if(apb_clk) { - clk_freq = getApbFrequency(); - } - clk_freq <<= 8;//div_num is 8 bit decimal - return (clk_freq >> bit_num) / (double)div_num; -} - -static void _ledcSetupChannel(uint8_t chan, uint8_t idle_level) -{ - uint8_t group=(chan/8), channel=(chan%8), timer=((chan/2)%4); - LEDC_MUTEX_LOCK(); - LEDC_CHAN(group, channel).conf0.timer_sel = timer;//2 bit Selects the timer to attach 0-3 - LEDC_CHAN(group, channel).conf0.idle_lv = idle_level;//1 bit This bit is used to control the output value when channel is off. - LEDC_CHAN(group, channel).hpoint.hpoint = 0;//20 bit The output value changes to high when timer selected by channel has reached hpoint - LEDC_CHAN(group, channel).conf1.duty_inc = 1;//1 bit This register is used to increase the duty of output signal or decrease the duty of output signal for high speed channel - LEDC_CHAN(group, channel).conf1.duty_num = 1;//10 bit This register is used to control the number of increased or decreased times for channel - LEDC_CHAN(group, channel).conf1.duty_cycle = 1;//10 bit This register is used to increase or decrease the duty every duty_cycle cycles for channel - LEDC_CHAN(group, channel).conf1.duty_scale = 0;//10 bit This register controls the increase or decrease step scale for channel. - LEDC_CHAN(group, channel).duty.duty = 0; - LEDC_CHAN(group, channel).conf0.sig_out_en = 0;//This is the output enable control bit for channel - LEDC_CHAN(group, channel).conf1.duty_start = 0;//When duty_num duty_cycle and duty_scale has been configured. these register won't take effect until set duty_start. this bit is automatically cleared by hardware. -#if CONFIG_IDF_TARGET_ESP32 - if(group) { -#endif - LEDC_CHAN(group, channel).conf0.low_speed_update = 1; -#if CONFIG_IDF_TARGET_ESP32 - } else { - LEDC_CHAN(group, channel).conf0.clk_en = 0; - } -#endif - LEDC_MUTEX_UNLOCK(); -} - -double ledcSetup(uint8_t chan, double freq, uint8_t bit_num) -{ - if(chan > LAST_CHAN) { - return 0; - } - double res_freq = _ledcSetupTimerFreq(chan, freq, bit_num); - _ledcSetupChannel(chan, LOW); - return res_freq; -} - -void ledcWrite(uint8_t chan, uint32_t duty) -{ - if(chan > LAST_CHAN) { - return; - } - uint8_t group=(chan/8), channel=(chan%8); - LEDC_MUTEX_LOCK(); - LEDC_CHAN(group, channel).duty.duty = duty << 4;//25 bit (21.4) - if(duty) { - LEDC_CHAN(group, channel).conf0.sig_out_en = 1;//This is the output enable control bit for channel - LEDC_CHAN(group, channel).conf1.duty_start = 1;//When duty_num duty_cycle and duty_scale has been configured. these register won't take effect until set duty_start. this bit is automatically cleared by hardware. -#if CONFIG_IDF_TARGET_ESP32 - if(group) { -#endif - LEDC_CHAN(group, channel).conf0.low_speed_update = 1; -#if CONFIG_IDF_TARGET_ESP32 - } else { - LEDC_CHAN(group, channel).conf0.clk_en = 1; - } -#endif - } else { - LEDC_CHAN(group, channel).conf0.sig_out_en = 0;//This is the output enable control bit for channel - LEDC_CHAN(group, channel).conf1.duty_start = 0;//When duty_num duty_cycle and duty_scale has been configured. these register won't take effect until set duty_start. this bit is automatically cleared by hardware. -#if CONFIG_IDF_TARGET_ESP32 - if(group) { -#endif - LEDC_CHAN(group, channel).conf0.low_speed_update = 1; -#if CONFIG_IDF_TARGET_ESP32 - } else { - LEDC_CHAN(group, channel).conf0.clk_en = 0; - } -#endif - } - LEDC_MUTEX_UNLOCK(); -} - -uint32_t ledcRead(uint8_t chan) -{ - if(chan > LAST_CHAN) { - return 0; - } - return LEDC.channel_group[chan/8].channel[chan%8].duty.duty >> 4; -} - -double ledcReadFreq(uint8_t chan) -{ - if(!ledcRead(chan)){ - return 0; - } - return _ledcTimerRead(chan); -} - -double ledcWriteTone(uint8_t chan, double freq) -{ - if(chan > LAST_CHAN) { - return 0; - } - if(!freq) { - ledcWrite(chan, 0); - return 0; - } - double res_freq = _ledcSetupTimerFreq(chan, freq, 10); - ledcWrite(chan, 0x1FF); - return res_freq; -} - -double ledcWriteNote(uint8_t chan, note_t note, uint8_t octave){ - const uint16_t noteFrequencyBase[12] = { - // C C# D Eb E F F# G G# A Bb B - 4186, 4435, 4699, 4978, 5274, 5588, 5920, 6272, 6645, 7040, 7459, 7902 - }; - - if(octave > 8 || note >= NOTE_MAX){ - return 0; - } - double noteFreq = (double)noteFrequencyBase[note] / (double)(1 << (8-octave)); - return ledcWriteTone(chan, noteFreq); -} - -void ledcAttachPin(uint8_t pin, uint8_t chan) -{ - if(chan > LAST_CHAN) { - return; - } - pinMode(pin, OUTPUT); -#if CONFIG_IDF_TARGET_ESP32S2 - 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); -#endif -} - -void ledcDetachPin(uint8_t pin) -{ - pinMatrixOutDetach(pin, false, false); -} diff --git a/cores/esp32/esp32-hal-ledc.h b/cores/esp32/esp32-hal-ledc.h deleted file mode 100644 index 159f98d5..00000000 --- a/cores/esp32/esp32-hal-ledc.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_LEDC_H_ -#define _ESP32_HAL_LEDC_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include -#include - -typedef enum { - NOTE_C, NOTE_Cs, NOTE_D, NOTE_Eb, NOTE_E, NOTE_F, NOTE_Fs, NOTE_G, NOTE_Gs, NOTE_A, NOTE_Bb, NOTE_B, NOTE_MAX -} note_t; - -//channel 0-15 resolution 1-16bits freq limits depend on resolution -double ledcSetup(uint8_t channel, double freq, uint8_t resolution_bits); -void ledcWrite(uint8_t channel, uint32_t duty); -double ledcWriteTone(uint8_t channel, double freq); -double ledcWriteNote(uint8_t channel, note_t note, uint8_t octave); -uint32_t ledcRead(uint8_t channel); -double ledcReadFreq(uint8_t channel); -void ledcAttachPin(uint8_t pin, uint8_t channel); -void ledcDetachPin(uint8_t pin); - - -#ifdef __cplusplus -} -#endif - -#endif /* _ESP32_HAL_LEDC_H_ */ diff --git a/cores/esp32/esp32-hal-misc.c b/cores/esp32/esp32-hal-misc.c index dcca7c33..19248361 100644 --- a/cores/esp32/esp32-hal-misc.c +++ b/cores/esp32/esp32-hal-misc.c @@ -45,22 +45,6 @@ #include "rom/rtc.h" #endif -//Undocumented!!! Get chip temperature in Farenheit -//Source: https://github.com/pcbreflux/espressif/blob/master/esp32/arduino/sketchbook/ESP32_int_temp_sensor/ESP32_int_temp_sensor.ino -uint8_t temprature_sens_read(); - -float temperatureRead() -{ - return (temprature_sens_read() - 32) / 1.8; -} - -void __yield() -{ - vPortYield(); -} - -void yield() __attribute__ ((weak, alias("__yield"))); - unsigned long ARDUINO_ISR_ATTR micros() { return (unsigned long) (esp_timer_get_time()); diff --git a/cores/esp32/stdlib_noniso.c b/cores/esp32/stdlib_noniso.c deleted file mode 100644 index e7920489..00000000 --- a/cores/esp32/stdlib_noniso.c +++ /dev/null @@ -1,161 +0,0 @@ -/* - core_esp8266_noniso.c - nonstandard (but usefull) conversion functions - - Copyright (c) 2014 Ivan Grokhotkov. All rights reserved. - This file is part of the esp8266 core for Arduino environment. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA - - Modified 03 April 2015 by Markus Sattler - - */ - -#include -#include -#include -#include -#include -#include "stdlib_noniso.h" - -void reverse(char* begin, char* end) { - char *is = begin; - char *ie = end - 1; - while(is < ie) { - char tmp = *ie; - *ie = *is; - *is = tmp; - ++is; - --ie; - } -} - -char* ltoa(long value, char* result, int base) { - if(base < 2 || base > 16) { - *result = 0; - return result; - } - - char* out = result; - long quotient = abs(value); - - do { - const long tmp = quotient / base; - *out = "0123456789abcdef"[quotient - (tmp * base)]; - ++out; - quotient = tmp; - } while(quotient); - - // Apply negative sign - if(value < 0) - *out++ = '-'; - - reverse(result, out); - *out = 0; - return result; -} - -char* ultoa(unsigned long value, char* result, int base) { - if(base < 2 || base > 16) { - *result = 0; - return result; - } - - char* out = result; - unsigned long quotient = value; - - do { - const unsigned long tmp = quotient / base; - *out = "0123456789abcdef"[quotient - (tmp * base)]; - ++out; - quotient = tmp; - } while(quotient); - - reverse(result, out); - *out = 0; - return result; -} - -char * dtostrf(double number, signed char width, unsigned char prec, char *s) { - bool negative = false; - - if (isnan(number)) { - strcpy(s, "nan"); - return s; - } - if (isinf(number)) { - strcpy(s, "inf"); - return s; - } - - char* out = s; - - int fillme = width; // how many cells to fill for the integer part - if (prec > 0) { - fillme -= (prec+1); - } - - // Handle negative numbers - if (number < 0.0) { - negative = true; - fillme--; - number = -number; - } - - // Round correctly so that print(1.999, 2) prints as "2.00" - // I optimized out most of the divisions - double rounding = 2.0; - for (uint8_t i = 0; i < prec; ++i) - rounding *= 10.0; - rounding = 1.0 / rounding; - - number += rounding; - - // Figure out how big our number really is - double tenpow = 1.0; - int digitcount = 1; - while (number >= 10.0 * tenpow) { - tenpow *= 10.0; - digitcount++; - } - - number /= tenpow; - fillme -= digitcount; - - // Pad unused cells with spaces - while (fillme-- > 0) { - *out++ = ' '; - } - - // Handle negative sign - if (negative) *out++ = '-'; - - // Print the digits, and if necessary, the decimal point - digitcount += prec; - int8_t digit = 0; - while (digitcount-- > 0) { - digit = (int8_t)number; - if (digit > 9) digit = 9; // insurance - *out++ = (char)('0' | digit); - if ((digitcount == prec) && (prec > 0)) { - *out++ = '.'; - } - number -= digit; - number *= 10.0; - } - - // make sure the string is terminated - *out = 0; - return s; -} diff --git a/cores/esp32/stdlib_noniso.h b/cores/esp32/stdlib_noniso.h deleted file mode 100644 index 3df2cc2a..00000000 --- a/cores/esp32/stdlib_noniso.h +++ /dev/null @@ -1,49 +0,0 @@ -/* - stdlib_noniso.h - nonstandard (but usefull) conversion functions - - Copyright (c) 2014 Ivan Grokhotkov. All rights reserved. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef STDLIB_NONISO_H -#define STDLIB_NONISO_H - -#ifdef __cplusplus -extern "C" { -#endif - -int atoi(const char *s); - -long atol(const char* s); - -double atof(const char* s); - -char* itoa (int val, char *s, int radix); - -char* ltoa (long val, char *s, int radix); - -char* utoa (unsigned int val, char *s, int radix); - -char* ultoa (unsigned long val, char *s, int radix); - -char* dtostrf (double val, signed char width, unsigned char prec, char *s); - -#ifdef __cplusplus -} // extern "C" -#endif - - -#endif diff --git a/cores/esp32/wiring_pulse.c b/cores/esp32/wiring_pulse.c deleted file mode 100644 index d56e7e16..00000000 --- a/cores/esp32/wiring_pulse.c +++ /dev/null @@ -1,50 +0,0 @@ -/* - pulse.c - wiring pulseIn implementation for esp8266 - Copyright (c) 2015 Hristo Gochkov. All rights reserved. - This file is part of the esp8266 core for Arduino environment. - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ -//#include -#include "wiring_private.h" -#include "pins_arduino.h" - - -extern uint32_t xthal_get_ccount(); - -#define WAIT_FOR_PIN_STATE(state) \ - while (digitalRead(pin) != (state)) { \ - if (xthal_get_ccount() - start_cycle_count > timeout_cycles) { \ - return 0; \ - } \ - } - -// max timeout is 27 seconds at 160MHz clock and 54 seconds at 80MHz clock -//unsigned long pulseIn(uint8_t pin, uint8_t state, unsigned long timeout) -//{ -// const uint32_t max_timeout_us = clockCyclesToMicroseconds(UINT_MAX); -// if (timeout > max_timeout_us) { -// timeout = max_timeout_us; -// } -// const uint32_t timeout_cycles = microsecondsToClockCycles(timeout); -// const uint32_t start_cycle_count = xthal_get_ccount(); -// WAIT_FOR_PIN_STATE(!state); -// WAIT_FOR_PIN_STATE(state); -// const uint32_t pulse_start_cycle_count = xthal_get_ccount(); -// WAIT_FOR_PIN_STATE(!state); -// return clockCyclesToMicroseconds(xthal_get_ccount() - pulse_start_cycle_count); -//} - -//unsigned long pulseInLong(uint8_t pin, uint8_t state, unsigned long timeout) -//{ -// return pulseIn(pin, state, timeout); -//} diff --git a/cores/esp32/wiring_shift.c b/cores/esp32/wiring_shift.c deleted file mode 100644 index d6658150..00000000 --- a/cores/esp32/wiring_shift.c +++ /dev/null @@ -1,53 +0,0 @@ -/* - wiring_shift.c - shiftOut() function - Part of Arduino - http://www.arduino.cc/ - Copyright (c) 2005-2006 David A. Mellis - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - You should have received a copy of the GNU Lesser General - Public License along with this library; if not, write to the - Free Software Foundation, Inc., 59 Temple Place, Suite 330, - Boston, MA 02111-1307 USA - $Id: wiring.c 248 2007-02-03 15:36:30Z mellis $ - */ - -#include "wiring_shift.h" -#include "esp32-hal.h" -#include "wiring_private.h" -#include "esp32-hal-gpio.h" - -uint8_t shiftIn(uint8_t dataPin, uint8_t clockPin, uint8_t bitOrder) { - uint8_t value = 0; - uint8_t i; - - for(i = 0; i < 8; ++i) { - //digitalWrite(clockPin, HIGH); - if(bitOrder == LSBFIRST) - value |= digitalRead(dataPin) << i; - else - value |= digitalRead(dataPin) << (7 - i); - digitalWrite(clockPin, HIGH); - digitalWrite(clockPin, LOW); - } - return value; -} - -void shiftOut(uint8_t dataPin, uint8_t clockPin, uint8_t bitOrder, uint8_t val) { - uint8_t i; - - for(i = 0; i < 8; i++) { - if(bitOrder == LSBFIRST) - digitalWrite(dataPin, !!(val & (1 << i))); - else - digitalWrite(dataPin, !!(val & (1 << (7 - i)))); - - digitalWrite(clockPin, HIGH); - digitalWrite(clockPin, LOW); - } -} diff --git a/cores/esp32/wiring_shift.h b/cores/esp32/wiring_shift.h deleted file mode 100644 index c5652640..00000000 --- a/cores/esp32/wiring_shift.h +++ /dev/null @@ -1,9 +0,0 @@ -#pragma once - -#define LSBFIRST 0 -#define MSBFIRST 1 - -#include - -uint8_t shiftIn(uint8_t dataPin, uint8_t clockPin, uint8_t bitOrder); -void shiftOut(uint8_t dataPin, uint8_t clockPin, uint8_t bitOrder, uint8_t val);