mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2024-12-23 21:01:25 +01:00
STM32 DCCEXanalogWrite for TrackManager PWM
This commit is contained in:
parent
624656ebc9
commit
ed0cfee091
@ -1,6 +1,6 @@
|
||||
/*
|
||||
* © 2023 Neil McKechnie
|
||||
* © 2022-23 Paul M. Antoine
|
||||
* © 2022-2023 Paul M. Antoine
|
||||
* © 2021 Mike S
|
||||
* © 2021, 2023 Harald Barth
|
||||
* © 2021 Fred Decker
|
||||
@ -154,13 +154,28 @@ HardwareSerial Serial6(PG9, PG14); // Rx=PG9, Tx=PG14 -- USART6
|
||||
///////////////////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
INTERRUPT_CALLBACK interruptHandler=0;
|
||||
// Let's use STM32's timer #11 until disabused of this notion
|
||||
// Timer #11 is used for "servo" library, but as DCC-EX is not using
|
||||
// this libary, we should be free and clear.
|
||||
HardwareTimer timer(TIM11);
|
||||
|
||||
// On STM32F4xx models that have them, Timers 6 and 7 have no PWM output capability,
|
||||
// so are good choices for general timer duties - they are used for tone and servo
|
||||
// in stm32duino so we shall usurp those as DCC-EX doesn't use tone or servo libs.
|
||||
// NB: the F401, F410 and F411 do **not** have Timer 6 or 7, so we use Timer 11
|
||||
#ifndef DCC_EX_TIMER
|
||||
#if defined(TIM6)
|
||||
#define DCC_EX_TIMER TIM6
|
||||
#elif defined(TIM7)
|
||||
#define DCC_EX_TIMER TIM7
|
||||
#elif defined(TIM11)
|
||||
#define DCC_EX_TIMER TIM11
|
||||
#else
|
||||
#warning This STM32F4XX variant does not have Timers 6,7 or 11!!
|
||||
#endif
|
||||
#endif // ifndef DCC_EX_TIMER
|
||||
|
||||
HardwareTimer dcctimer(DCC_EX_TIMER);
|
||||
void DCCTimer_Handler() __attribute__((interrupt));
|
||||
|
||||
// Timer IRQ handler
|
||||
void Timer11_Handler() {
|
||||
void DCCTimer_Handler() {
|
||||
interruptHandler();
|
||||
}
|
||||
|
||||
@ -168,22 +183,24 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
|
||||
interruptHandler=callback;
|
||||
noInterrupts();
|
||||
|
||||
// adc_set_sample_rate(ADC_SAMPLETIME_480CYCLES);
|
||||
timer.pause();
|
||||
timer.setPrescaleFactor(1);
|
||||
dcctimer.pause();
|
||||
dcctimer.setPrescaleFactor(1);
|
||||
// timer.setOverflow(CLOCK_CYCLES * 2);
|
||||
timer.setOverflow(DCC_SIGNAL_TIME, MICROSEC_FORMAT);
|
||||
timer.attachInterrupt(Timer11_Handler);
|
||||
timer.refresh();
|
||||
timer.resume();
|
||||
dcctimer.setOverflow(DCC_SIGNAL_TIME, MICROSEC_FORMAT);
|
||||
// dcctimer.attachInterrupt(Timer11_Handler);
|
||||
dcctimer.attachInterrupt(DCCTimer_Handler);
|
||||
dcctimer.setInterruptPriority(0, 0); // Set highest preemptive priority!
|
||||
dcctimer.refresh();
|
||||
dcctimer.resume();
|
||||
|
||||
interrupts();
|
||||
}
|
||||
|
||||
bool DCCTimer::isPWMPin(byte pin) {
|
||||
//TODO: SAMD whilst this call to digitalPinHasPWM will reveal which pins can do PWM,
|
||||
//TODO: STM32 whilst this call to digitalPinHasPWM will reveal which pins can do PWM,
|
||||
// there's no support yet for High Accuracy, so for now return false
|
||||
// return digitalPinHasPWM(pin);
|
||||
(void) pin;
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -235,6 +252,78 @@ void DCCTimer::reset() {
|
||||
while(true) {};
|
||||
}
|
||||
|
||||
// TODO: rationalise the size of these... could really use sparse arrays etc.
|
||||
static HardwareTimer * pin_timer[100] = {0};
|
||||
static uint32_t channel_frequency[100] = {0};
|
||||
static uint32_t pin_channel[100] = {0};
|
||||
|
||||
// Using the HardwareTimer library API included in stm32duino core to handle PWM duties
|
||||
// TODO: in order to use the HA code above which Neil kindly wrote, we may have to do something more
|
||||
// sophisticated about detecting any clash between the timer we'd like to use for PWM and the ones
|
||||
// currently used for HA so they don't interfere with one another. For now we'll just make PWM
|
||||
// work well... then work backwards to integrate with HA mode if we can.
|
||||
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency)
|
||||
{
|
||||
if (pin_timer[pin] == NULL) {
|
||||
// Automatically retrieve TIM instance and channel associated to pin
|
||||
// This is used to be compatible with all STM32 series automatically.
|
||||
TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pin), PinMap_PWM);
|
||||
if (Instance == NULL) {
|
||||
// We shouldn't get here (famous last words) as it ought to have been caught by brakeCanPWM()!
|
||||
DIAG(F("DCCEXanalogWriteFrequency::Pin %d has no PWM function!"), pin);
|
||||
return;
|
||||
}
|
||||
pin_channel[pin] = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pin), PinMap_PWM));
|
||||
|
||||
// Instantiate HardwareTimer object. Thanks to 'new' instantiation,
|
||||
// HardwareTimer is not destructed when setup function is finished.
|
||||
pin_timer[pin] = new HardwareTimer(Instance);
|
||||
// Configure and start PWM
|
||||
// MyTim->setPWM(channel, pin, 5, 10, NULL, NULL); // No callback required, we can simplify the function call
|
||||
if (pin_timer[pin] != NULL)
|
||||
{
|
||||
pin_timer[pin]->setPWM(pin_channel[pin], pin, frequency, 0); // set frequency in Hertz, 0% dutycycle
|
||||
DIAG(F("DCCEXanalogWriteFrequency::Pin %d on Timer %d, frequency %d"), pin, pin_channel[pin], frequency);
|
||||
}
|
||||
else
|
||||
DIAG(F("DCCEXanalogWriteFrequency::failed to allocate HardwareTimer instance!"));
|
||||
}
|
||||
else
|
||||
{
|
||||
// Frequency change request
|
||||
if (frequency != channel_frequency[pin])
|
||||
{
|
||||
pinmap_pinout(digitalPinToPinName(pin), PinMap_TIM); // ensure the pin has been configured!
|
||||
pin_timer[pin]->setOverflow(frequency, HERTZ_FORMAT); // Just change the frequency if it's already running!
|
||||
DIAG(F("DCCEXanalogWriteFrequency::setting frequency to %d"), frequency);
|
||||
}
|
||||
}
|
||||
channel_frequency[pin] = frequency;
|
||||
return;
|
||||
}
|
||||
|
||||
void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) {
|
||||
// Calculate percentage duty cycle from value given
|
||||
uint32_t duty_cycle = (value * 100 / 256) + 1;
|
||||
if (pin_timer[pin] != NULL) {
|
||||
if (duty_cycle == 100)
|
||||
{
|
||||
pin_timer[pin]->pauseChannel(pin_channel[pin]);
|
||||
DIAG(F("DCCEXanalogWrite::Pausing timer channel on pin %d"), pin);
|
||||
}
|
||||
else
|
||||
{
|
||||
pinmap_pinout(digitalPinToPinName(pin), PinMap_TIM); // ensure the pin has been configured!
|
||||
pin_timer[pin]->resumeChannel(pin_channel[pin]);
|
||||
pin_timer[pin]->setCaptureCompare(pin_channel[pin], duty_cycle, PERCENT_COMPARE_FORMAT); // DCC_EX_PWM_FREQ Hertz, duty_cycle% dutycycle
|
||||
DIAG(F("DCCEXanalogWrite::Pin %d, value %d, duty cycle %d"), pin, value, duty_cycle);
|
||||
}
|
||||
}
|
||||
else
|
||||
DIAG(F("DCCEXanalogWrite::Pin %d is not configured for PWM!"), pin);
|
||||
}
|
||||
|
||||
|
||||
// Now we can handle more ADCs, maybe this works!
|
||||
#define NUM_ADC_INPUTS NUM_ANALOG_INPUTS
|
||||
|
||||
|
@ -34,6 +34,11 @@ unsigned long MotorDriver::globalOverloadStart = 0;
|
||||
volatile portreg_t shadowPORTA;
|
||||
volatile portreg_t shadowPORTB;
|
||||
volatile portreg_t shadowPORTC;
|
||||
#if defined(ARDUINO_ARCH_STM32)
|
||||
volatile portreg_t shadowPORTD;
|
||||
volatile portreg_t shadowPORTE;
|
||||
volatile portreg_t shadowPORTF;
|
||||
#endif
|
||||
|
||||
MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, int16_t brake_pin,
|
||||
byte current_pin, float sense_factor, unsigned int trip_milliamps, int16_t fault_pin) {
|
||||
@ -68,6 +73,21 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
|
||||
fastSignalPin.shadowinout = fastSignalPin.inout;
|
||||
fastSignalPin.inout = &shadowPORTC;
|
||||
}
|
||||
if (HAVE_PORTD(fastSignalPin.inout == &PORTD)) {
|
||||
DIAG(F("Found PORTD pin %d"),signalPin);
|
||||
fastSignalPin.shadowinout = fastSignalPin.inout;
|
||||
fastSignalPin.inout = &shadowPORTD;
|
||||
}
|
||||
if (HAVE_PORTE(fastSignalPin.inout == &PORTE)) {
|
||||
DIAG(F("Found PORTE pin %d"),signalPin);
|
||||
fastSignalPin.shadowinout = fastSignalPin.inout;
|
||||
fastSignalPin.inout = &shadowPORTE;
|
||||
}
|
||||
if (HAVE_PORTF(fastSignalPin.inout == &PORTF)) {
|
||||
DIAG(F("Found PORTF pin %d"),signalPin);
|
||||
fastSignalPin.shadowinout = fastSignalPin.inout;
|
||||
fastSignalPin.inout = &shadowPORTF;
|
||||
}
|
||||
|
||||
signalPin2=signal_pin2;
|
||||
if (signalPin2!=UNUSED_PIN) {
|
||||
@ -91,6 +111,21 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
|
||||
fastSignalPin2.shadowinout = fastSignalPin2.inout;
|
||||
fastSignalPin2.inout = &shadowPORTC;
|
||||
}
|
||||
if (HAVE_PORTD(fastSignalPin2.inout == &PORTD)) {
|
||||
DIAG(F("Found PORTD pin %d"),signalPin2);
|
||||
fastSignalPin2.shadowinout = fastSignalPin2.inout;
|
||||
fastSignalPin2.inout = &shadowPORTD;
|
||||
}
|
||||
if (HAVE_PORTE(fastSignalPin2.inout == &PORTE)) {
|
||||
DIAG(F("Found PORTE pin %d"),signalPin2);
|
||||
fastSignalPin2.shadowinout = fastSignalPin2.inout;
|
||||
fastSignalPin2.inout = &shadowPORTE;
|
||||
}
|
||||
if (HAVE_PORTF(fastSignalPin2.inout == &PORTF)) {
|
||||
DIAG(F("Found PORTF pin %d"),signalPin2);
|
||||
fastSignalPin2.shadowinout = fastSignalPin2.inout;
|
||||
fastSignalPin2.inout = &shadowPORTF;
|
||||
}
|
||||
}
|
||||
else dualSignal=false;
|
||||
|
||||
@ -279,7 +314,7 @@ void MotorDriver::startCurrentFromHW() {
|
||||
#pragma GCC pop_options
|
||||
#endif //ANALOG_READ_INTERRUPT
|
||||
|
||||
#if defined(ARDUINO_ARCH_ESP32)
|
||||
#if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32)
|
||||
#ifdef VARIABLE_TONES
|
||||
uint16_t taurustones[28] = { 165, 175, 196, 220,
|
||||
247, 262, 294, 330,
|
||||
@ -330,7 +365,7 @@ void MotorDriver::setDCSignal(byte speedcode) {
|
||||
byte tSpeed=speedcode & 0x7F; // DCC Speed with 0,1 stop and speed steps 2 to 127
|
||||
byte tDir=speedcode & 0x80;
|
||||
byte brake;
|
||||
#if defined(ARDUINO_ARCH_ESP32)
|
||||
#if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32)
|
||||
{
|
||||
int f = 131;
|
||||
#ifdef VARIABLE_TONES
|
||||
@ -348,7 +383,7 @@ void MotorDriver::setDCSignal(byte speedcode) {
|
||||
else brake = 2 * (128-tSpeed);
|
||||
if (invertBrake)
|
||||
brake=255-brake;
|
||||
#if defined(ARDUINO_ARCH_ESP32)
|
||||
#if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32)
|
||||
DCCTimer::DCCEXanalogWrite(brakePin,brake);
|
||||
#else
|
||||
analogWrite(brakePin,brake);
|
||||
@ -372,6 +407,24 @@ void MotorDriver::setDCSignal(byte speedcode) {
|
||||
setSignal(tDir);
|
||||
HAVE_PORTC(PORTC=shadowPORTC);
|
||||
interrupts();
|
||||
} else if (HAVE_PORTD(fastSignalPin.shadowinout == &PORTD)) {
|
||||
noInterrupts();
|
||||
HAVE_PORTD(shadowPORTD=PORTD);
|
||||
setSignal(tDir);
|
||||
HAVE_PORTD(PORTD=shadowPORTD);
|
||||
interrupts();
|
||||
} else if (HAVE_PORTE(fastSignalPin.shadowinout == &PORTE)) {
|
||||
noInterrupts();
|
||||
HAVE_PORTE(shadowPORTE=PORTE);
|
||||
setSignal(tDir);
|
||||
HAVE_PORTE(PORTE=shadowPORTE);
|
||||
interrupts();
|
||||
} else if (HAVE_PORTF(fastSignalPin.shadowinout == &PORTF)) {
|
||||
noInterrupts();
|
||||
HAVE_PORTF(shadowPORTF=PORTF);
|
||||
setSignal(tDir);
|
||||
HAVE_PORTF(PORTF=shadowPORTF);
|
||||
interrupts();
|
||||
} else {
|
||||
noInterrupts();
|
||||
setSignal(tDir);
|
||||
@ -393,6 +446,13 @@ void MotorDriver::throttleInrush(bool on) {
|
||||
} else {
|
||||
ledcDetachPin(brakePin);
|
||||
}
|
||||
#elif defined(ARDUINO_ARCH_STM32)
|
||||
if(on) {
|
||||
DCCTimer::DCCEXanalogWriteFrequency(brakePin, 62500);
|
||||
DCCTimer::DCCEXanalogWrite(brakePin,duty);
|
||||
} else {
|
||||
pinMode(brakePin, OUTPUT);
|
||||
}
|
||||
#else
|
||||
if(on){
|
||||
switch(brakePin) {
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* © 2022 Paul M Antoine
|
||||
* © 2022-2023 Paul M. Antoine
|
||||
* © 2021 Mike S
|
||||
* © 2021 Fred Decker
|
||||
* © 2020 Chris Harlow
|
||||
@ -60,6 +60,16 @@ enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PRO
|
||||
#define HAVE_PORTB(X) X
|
||||
#define PORTC GPIOC->ODR
|
||||
#define HAVE_PORTC(X) X
|
||||
#define PORTD GPIOD->ODR
|
||||
#define HAVE_PORTD(X) X
|
||||
#if defined(GPIOE)
|
||||
#define PORTE GPIOE->ODR
|
||||
#define HAVE_PORTE(X) X
|
||||
#endif
|
||||
#if defined(GPIOF)
|
||||
#define PORTF GPIOF->ODR
|
||||
#define HAVE_PORTF(X) X
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// if macros not defined as pass-through we define
|
||||
@ -74,6 +84,15 @@ enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PRO
|
||||
#ifndef HAVE_PORTC
|
||||
#define HAVE_PORTC(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0
|
||||
#endif
|
||||
#ifndef HAVE_PORTD
|
||||
#define HAVE_PORTD(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0
|
||||
#endif
|
||||
#ifndef HAVE_PORTE
|
||||
#define HAVE_PORTE(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0
|
||||
#endif
|
||||
#ifndef HAVE_PORTF
|
||||
#define HAVE_PORTF(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0
|
||||
#endif
|
||||
|
||||
// Virtualised Motor shield 1-track hardware Interface
|
||||
|
||||
@ -110,6 +129,9 @@ struct FASTPIN {
|
||||
extern volatile portreg_t shadowPORTA;
|
||||
extern volatile portreg_t shadowPORTB;
|
||||
extern volatile portreg_t shadowPORTC;
|
||||
extern volatile portreg_t shadowPORTD;
|
||||
extern volatile portreg_t shadowPORTE;
|
||||
extern volatile portreg_t shadowPORTF;
|
||||
|
||||
enum class POWERMODE : byte { OFF, ON, OVERLOAD, ALERT };
|
||||
|
||||
@ -163,16 +185,16 @@ class MotorDriver {
|
||||
unsigned int raw2mA( int raw);
|
||||
unsigned int mA2raw( unsigned int mA);
|
||||
inline bool brakeCanPWM() {
|
||||
#if defined(ARDUINO_ARCH_ESP32) || defined(__arm__)
|
||||
// TODO: on ARM we can use digitalPinHasPWM, and may wish/need to
|
||||
return true;
|
||||
#else
|
||||
#ifdef digitalPinToTimer
|
||||
#if defined(ARDUINO_ARCH_ESP32)
|
||||
return (brakePin != UNUSED_PIN); // This was just (true) but we probably do need to check for UNUSED_PIN!
|
||||
#elif defined(__arm__)
|
||||
// On ARM we can use digitalPinHasPWM
|
||||
return ((brakePin!=UNUSED_PIN) && (digitalPinHasPWM(brakePin)));
|
||||
#elif defined(digitalPinToTimer)
|
||||
return ((brakePin!=UNUSED_PIN) && (digitalPinToTimer(brakePin)));
|
||||
#else
|
||||
return (brakePin<14 && brakePin >1);
|
||||
#endif //digitalPinToTimer
|
||||
#endif //ESP32/ARM
|
||||
#endif
|
||||
}
|
||||
inline int getRawCurrentTripValue() {
|
||||
return rawCurrentTripValue;
|
||||
|
@ -154,10 +154,16 @@ void TrackManager::setDCCSignal( bool on) {
|
||||
HAVE_PORTA(shadowPORTA=PORTA);
|
||||
HAVE_PORTB(shadowPORTB=PORTB);
|
||||
HAVE_PORTC(shadowPORTC=PORTC);
|
||||
HAVE_PORTD(shadowPORTD=PORTD);
|
||||
HAVE_PORTE(shadowPORTE=PORTE);
|
||||
HAVE_PORTF(shadowPORTF=PORTF);
|
||||
APPLY_BY_MODE(TRACK_MODE_MAIN,setSignal(on));
|
||||
HAVE_PORTA(PORTA=shadowPORTA);
|
||||
HAVE_PORTB(PORTB=shadowPORTB);
|
||||
HAVE_PORTC(PORTC=shadowPORTC);
|
||||
HAVE_PORTD(PORTD=shadowPORTD);
|
||||
HAVE_PORTE(PORTE=shadowPORTE);
|
||||
HAVE_PORTF(PORTF=shadowPORTF);
|
||||
}
|
||||
|
||||
void TrackManager::setCutout( bool on) {
|
||||
@ -172,10 +178,16 @@ void TrackManager::setPROGSignal( bool on) {
|
||||
HAVE_PORTA(shadowPORTA=PORTA);
|
||||
HAVE_PORTB(shadowPORTB=PORTB);
|
||||
HAVE_PORTC(shadowPORTC=PORTC);
|
||||
HAVE_PORTD(shadowPORTD=PORTD);
|
||||
HAVE_PORTE(shadowPORTE=PORTE);
|
||||
HAVE_PORTF(shadowPORTF=PORTF);
|
||||
APPLY_BY_MODE(TRACK_MODE_PROG,setSignal(on));
|
||||
HAVE_PORTA(PORTA=shadowPORTA);
|
||||
HAVE_PORTB(PORTB=shadowPORTB);
|
||||
HAVE_PORTC(PORTC=shadowPORTC);
|
||||
HAVE_PORTD(PORTD=shadowPORTD);
|
||||
HAVE_PORTE(PORTE=shadowPORTE);
|
||||
HAVE_PORTF(PORTF=shadowPORTF);
|
||||
}
|
||||
|
||||
// setDCSignal(), called from normal context
|
||||
|
@ -3,7 +3,12 @@
|
||||
|
||||
#include "StringFormatter.h"
|
||||
|
||||
#define VERSION "5.1.9"
|
||||
#define VERSION "5.1.10"
|
||||
// 5.1.10 - STM32F4xx DCCEXanalogWrite to handle PWM generation for TrackManager DC/DCX
|
||||
// - STM32F4xx DCC 58uS timer now using non-PWM output timers where possible
|
||||
// - ESP32 brakeCanPWM check now detects UNUSED_PIN
|
||||
// - ARM architecture brakeCanPWM now uses digitalPinHasPWM()
|
||||
// - STM32F4xx shadowpin extensions to handle pins on ports D, E and F
|
||||
// 5.1.9 - Fixed IO_PCA9555'h to work with PCA9548 mux, tested OK
|
||||
// 5.1.8 - STM32Fxx ADCee extension to support ADCs #2 and #3
|
||||
// 5.1.7 - Fix turntable broadcasts for non-movement activities and <JP> result
|
||||
|
Loading…
Reference in New Issue
Block a user