1
0
mirror of https://github.com/DCC-EX/CommandStation-EX.git synced 2024-11-22 23:56:13 +01:00

Merge ESP32-fixes into DCCTimerESP

This commit is contained in:
pmantoine 2023-04-16 15:40:27 +08:00
parent 75f274e3b7
commit d2cc60812d
5 changed files with 48 additions and 97 deletions

View File

@ -1,7 +1,7 @@
/* /*
* © 2022 Paul M. Antoine * © 2022-2023 Paul M. Antoine
* © 2021 Mike S * © 2021 Mike S
* © 2021-2022 Harald Barth * © 2021-2023 Harald Barth
* © 2021 Fred Decker * © 2021 Fred Decker
* All rights reserved. * All rights reserved.
* *
@ -62,6 +62,9 @@ class DCCTimer {
static bool isPWMPin(byte pin); static bool isPWMPin(byte pin);
static void setPWM(byte pin, bool high); static void setPWM(byte pin, bool high);
static void clearPWM(); static void clearPWM();
static void DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency);
static void DCCEXanalogWrite(uint8_t pin, int value);
// Update low ram level. Allow for extra bytes to be specified // Update low ram level. Allow for extra bytes to be specified
// by estimation or inspection, that may be used by other // by estimation or inspection, that may be used by other
// called subroutines. Must be called with interrupts disabled. // called subroutines. Must be called with interrupts disabled.

View File

@ -150,6 +150,45 @@ int DCCTimer::freeMemory() {
void DCCTimer::reset() { void DCCTimer::reset() {
ESP.restart(); ESP.restart();
} }
#include "esp32-hal.h"
#include "soc/soc_caps.h"
#ifdef SOC_LEDC_SUPPORT_HS_MODE
#define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM<<1)
#else
#define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM)
#endif
static int8_t pin_to_channel[SOC_GPIO_PIN_COUNT] = { 0 };
static int cnt_channel = LEDC_CHANNELS;
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency) {
if (pin < SOC_GPIO_PIN_COUNT) {
if (pin_to_channel[pin] != 0) {
ledcSetup(pin_to_channel[pin], frequency, 8);
}
}
}
void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) {
if (pin < SOC_GPIO_PIN_COUNT) {
if (pin_to_channel[pin] == 0) {
if (!cnt_channel) {
log_e("No more PWM channels available! All %u already used", LEDC_CHANNELS);
return;
}
pin_to_channel[pin] = --cnt_channel;
ledcAttachPin(pin, cnt_channel);
ledcSetup(cnt_channel, 1000, 8);
} else {
ledcAttachPin(pin, pin_to_channel[pin]);
}
ledcWrite(pin_to_channel[pin], value);
}
}
int ADCee::init(uint8_t pin) { int ADCee::init(uint8_t pin) {
pinMode(pin, ANALOG); pinMode(pin, ANALOG);
adc1_config_width(ADC_WIDTH_BIT_12); adc1_config_width(ADC_WIDTH_BIT_12);

View File

@ -1,61 +0,0 @@
/*
* © 2022 Harald Barth
* All rights reserved.
*
* This file is part of CommandStation-EX
*
* This is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* It 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
*/
#ifdef ARDUINO_ARCH_ESP32
#include <Arduino.h>
#include "ESP32-fixes.h"
#include "esp32-hal.h"
#include "soc/soc_caps.h"
#ifdef SOC_LEDC_SUPPORT_HS_MODE
#define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM<<1)
#else
#define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM)
#endif
static int8_t pin_to_channel[SOC_GPIO_PIN_COUNT] = { 0 };
static int cnt_channel = LEDC_CHANNELS;
void DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency) {
if (pin < SOC_GPIO_PIN_COUNT) {
if (pin_to_channel[pin] != 0) {
ledcSetup(pin_to_channel[pin], frequency, 8);
}
}
}
void DCCEXanalogWrite(uint8_t pin, int value) {
if (pin < SOC_GPIO_PIN_COUNT) {
if (pin_to_channel[pin] == 0) {
if (!cnt_channel) {
log_e("No more PWM channels available! All %u already used", LEDC_CHANNELS);
return;
}
pin_to_channel[pin] = --cnt_channel;
ledcAttachPin(pin, cnt_channel);
ledcSetup(cnt_channel, 1000, 8);
} else {
ledcAttachPin(pin, pin_to_channel[pin]);
}
ledcWrite(pin_to_channel[pin], value);
}
}
#endif

View File

@ -1,26 +0,0 @@
/*
* © 2022 Harald Barth
* All rights reserved.
*
* This file is part of CommandStation-EX
*
* This is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* It 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
*/
#ifdef ARDUINO_ARCH_ESP32
#pragma once
#include <Arduino.h>
void DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency);
void DCCEXanalogWrite(uint8_t pin, int value);
#endif

View File

@ -1,8 +1,8 @@
/* /*
* © 2022 Paul M Antoine * © 2022-2023 Paul M Antoine
* © 2021 Mike S * © 2021 Mike S
* © 2021 Fred Decker * © 2021 Fred Decker
* © 2020-2022 Harald Barth * © 2020-2023 Harald Barth
* © 2020-2021 Chris Harlow * © 2020-2021 Chris Harlow
* All rights reserved. * All rights reserved.
* *
@ -27,10 +27,6 @@
#include "DCCTimer.h" #include "DCCTimer.h"
#include "DIAG.h" #include "DIAG.h"
#if defined(ARDUINO_ARCH_ESP32)
#include "ESP32-fixes.h"
#endif
bool MotorDriver::commonFaultPin=false; bool MotorDriver::commonFaultPin=false;
volatile portreg_t shadowPORTA; volatile portreg_t shadowPORTA;
@ -286,7 +282,7 @@ void MotorDriver::setDCSignal(byte speedcode) {
f = taurustones[ (tSpeed-2)/2 ] ; f = taurustones[ (tSpeed-2)/2 ] ;
} }
} }
DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency to 100Hz XXX May move to setup DCCTimer::DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency to 100Hz XXX May move to setup
} }
#endif #endif
if (tSpeed <= 1) brake = 255; if (tSpeed <= 1) brake = 255;
@ -295,7 +291,7 @@ void MotorDriver::setDCSignal(byte speedcode) {
if (invertBrake) if (invertBrake)
brake=255-brake; brake=255-brake;
#if defined(ARDUINO_ARCH_ESP32) #if defined(ARDUINO_ARCH_ESP32)
DCCEXanalogWrite(brakePin,brake); DCCTimer::DCCEXanalogWrite(brakePin,brake);
#else #else
analogWrite(brakePin,brake); analogWrite(brakePin,brake);
#endif #endif