mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2024-11-24 08:36:14 +01:00
compiles without error, nogo <1>
This commit is contained in:
parent
e816ef2b03
commit
70c1f1db2a
|
@ -194,19 +194,14 @@ void DCCTimer::reset() {
|
||||||
while(true){}
|
while(true){}
|
||||||
}*/
|
}*/
|
||||||
INTERRUPT_CALLBACK interruptHandler=0;
|
INTERRUPT_CALLBACK interruptHandler=0;
|
||||||
#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* _hwTimer = NULL;
|
//HardwareTimer* timer = NULL;
|
||||||
|
//HardwareTimer* timerAux = NULL;
|
||||||
|
HardwareTimer timer(TIM2);
|
||||||
|
HardwareTimer timerAux(TIM3);
|
||||||
|
static bool tim2ModeHA = false;
|
||||||
|
static bool tim3ModeHA = false;
|
||||||
|
|
||||||
void DCCTimer_Handler() __attribute__((interrupt));
|
void DCCTimer_Handler() __attribute__((interrupt));
|
||||||
|
|
||||||
void DCCTimer_Handler() {
|
void DCCTimer_Handler() {
|
||||||
|
@ -215,36 +210,66 @@ void DCCTimer_Handler() {
|
||||||
|
|
||||||
void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
|
void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
|
||||||
interruptHandler=callback;
|
interruptHandler=callback;
|
||||||
noInterrupts();
|
noInterrupts();
|
||||||
// Init timer TIM15
|
|
||||||
Portenta_H7_Timer ITimer0(TIM15);
|
// adc_set_sample_rate(ADC_SAMPLETIME_480CYCLES);
|
||||||
// Init timer TIM16
|
timer.pause();
|
||||||
Portenta_H7_Timer ITimer1(TIM16);
|
timerAux.pause();
|
||||||
_hwTimer->pause();
|
timer.setPrescaleFactor(1);
|
||||||
_hwTimer->setPrescaleFactor(1);
|
timer.setOverflow(DCC_SIGNAL_TIME, MICROSEC_FORMAT);
|
||||||
// timer.setOverflow(CLOCK_CYCLES * 2);
|
timer.attachInterrupt(DCCTimer_Handler);
|
||||||
_hwTimer->setOverflow(DCC_SIGNAL_TIME, MICROSEC_FORMAT);
|
timer.refresh();
|
||||||
// dcctimer.attachInterrupt(Timer11_Handler);
|
timerAux.setPrescaleFactor(1);
|
||||||
_hwTimer->attachInterrupt(DCCTimer_Handler);
|
timerAux.setOverflow(DCC_SIGNAL_TIME, MICROSEC_FORMAT);
|
||||||
_hwTimer->setInterruptPriority(0, 0); // Set highest preemptive priority!
|
timerAux.refresh();
|
||||||
_hwTimer->refresh();
|
|
||||||
_hwTimer->resume();
|
timer.resume();
|
||||||
interrupts();
|
timerAux.resume();
|
||||||
|
|
||||||
|
interrupts();
|
||||||
}
|
}
|
||||||
|
|
||||||
bool DCCTimer::isPWMPin(byte pin) {
|
bool DCCTimer::isPWMPin(byte pin) {
|
||||||
(void) pin;
|
switch (pin) {
|
||||||
return false; // TODO what are the relevant pins?
|
case 12:
|
||||||
|
return true;
|
||||||
|
case 13:
|
||||||
|
return true;
|
||||||
|
default:
|
||||||
|
return false;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void DCCTimer::setPWM(byte pin, bool high) {
|
void DCCTimer::setPWM(byte pin, bool high) {
|
||||||
(void) pin;
|
switch (pin) {
|
||||||
(void) high;
|
case 12:
|
||||||
// TODO what are the relevant pins?
|
if (!tim3ModeHA) {
|
||||||
|
timerAux.setMode(1, TIMER_OUTPUT_COMPARE_INACTIVE, D12);
|
||||||
|
tim3ModeHA = true;
|
||||||
|
}
|
||||||
|
if (high)
|
||||||
|
TIM3->CCMR1 = (TIM3->CCMR1 & ~TIM_CCMR1_OC1M_Msk) | TIM_CCMR1_OC1M_0;
|
||||||
|
else
|
||||||
|
TIM3->CCMR1 = (TIM3->CCMR1 & ~TIM_CCMR1_OC1M_Msk) | TIM_CCMR1_OC1M_1;
|
||||||
|
break;
|
||||||
|
case 13:
|
||||||
|
if (!tim2ModeHA) {
|
||||||
|
timer.setMode(1, TIMER_OUTPUT_COMPARE_INACTIVE, D13);
|
||||||
|
tim2ModeHA = true;
|
||||||
|
}
|
||||||
|
if (high)
|
||||||
|
TIM2->CCMR1 = (TIM2->CCMR1 & ~TIM_CCMR1_OC1M_Msk) | TIM_CCMR1_OC1M_0;
|
||||||
|
else
|
||||||
|
TIM2->CCMR1 = (TIM2->CCMR1 & ~TIM_CCMR1_OC1M_Msk) | TIM_CCMR1_OC1M_1;
|
||||||
|
break;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void DCCTimer::clearPWM() {
|
void DCCTimer::clearPWM() {
|
||||||
// Do nothing unless we implent HA
|
timer.setMode(1, TIMER_OUTPUT_COMPARE_INACTIVE, NC);
|
||||||
|
tim2ModeHA = false;
|
||||||
|
timerAux.setMode(1, TIMER_OUTPUT_COMPARE_INACTIVE, NC);
|
||||||
|
tim3ModeHA = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void DCCTimer::getSimulatedMacAddress(byte mac[6]) {
|
void DCCTimer::getSimulatedMacAddress(byte mac[6]) {
|
||||||
|
|
Loading…
Reference in New Issue
Block a user