mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2024-12-23 12:51:24 +01:00
less debug diag
This commit is contained in:
parent
19efa749b8
commit
9ebb1c5fb1
4
DCC.cpp
4
DCC.cpp
@ -163,8 +163,8 @@ uint8_t DCC::getThrottleFrequency(int cab) {
|
||||
if (reg<0)
|
||||
return 0; // use default frequency
|
||||
uint8_t res = (uint8_t)(speedTable[reg].functions >>30);
|
||||
DIAG(F("Speed table %d functions %l shifted %d"), reg, speedTable[reg].functions, res);
|
||||
return res; // shift out first 29 bits so we have the "frequency bits" left
|
||||
//DIAG(F("Speed table %d functions %l shifted %d"), reg, speedTable[reg].functions, res);
|
||||
return res; // shift out first 30 bits so we have the "frequency bits" left
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -157,7 +157,7 @@ void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) {
|
||||
|
||||
TCCR2A = (TCCR2A & B11111100) | abits; // set WGM0 and WGM1
|
||||
TCCR2B = (TCCR2B & B11110000) | bbits; // set WGM2 and 3 bits of prescaler
|
||||
DIAG(F("Timer 2 A=%x B=%x"), TCCR2A, TCCR2B);
|
||||
//DIAG(F("Timer 2 A=%x B=%x"), TCCR2A, TCCR2B);
|
||||
|
||||
} else { // not timer 9 or 10
|
||||
abits = B01;
|
||||
@ -179,7 +179,7 @@ void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) {
|
||||
// Timer4
|
||||
TCCR4A = (TCCR4A & B11111100) | abits; // set WGM0 and WGM1
|
||||
TCCR4B = (TCCR4B & B11100000) | bbits; // set WGM2 and WGM3 and divisor
|
||||
DIAG(F("Timer 4 A=%x B=%x"), TCCR4A, TCCR4B);
|
||||
//DIAG(F("Timer 4 A=%x B=%x"), TCCR4A, TCCR4B);
|
||||
break;
|
||||
case 46:
|
||||
case 45:
|
||||
@ -187,7 +187,7 @@ void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) {
|
||||
// Timer5
|
||||
TCCR5A = (TCCR5A & B11111100) | abits; // set WGM0 and WGM1
|
||||
TCCR5B = (TCCR5B & B11100000) | bbits; // set WGM2 and WGM3 and divisor
|
||||
DIAG(F("Timer 5 A=%x B=%x"), TCCR5A, TCCR5B);
|
||||
//DIAG(F("Timer 5 A=%x B=%x"), TCCR5A, TCCR5B);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
|
@ -349,7 +349,7 @@ void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/)
|
||||
}
|
||||
}
|
||||
#endif
|
||||
DIAG(F("Brake %d freqency %d"), brakePin, f);
|
||||
//DIAG(F("Brake pin %d freqency %d"), brakePin, f);
|
||||
DCCTimer::DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency to 100Hz XXX May move to setup
|
||||
DCCTimer::DCCEXanalogWrite(brakePin,brake);
|
||||
#else // all AVR here
|
||||
|
Loading…
Reference in New Issue
Block a user