@@ -161,30 +161,8 @@ int _configureComplementaryPair(const int pinH,const int pinL, long frequency) {
161
161
// set 32kHz frequency if requested freq is higher than the middle of the range (14kHz)
162
162
// else set the 4kHz
163
163
if (frequency >= 0.5 *(_PWM_FREQUENCY_MAX-_PWM_FREQUENCY_MIN)) high_fq=true ;
164
- // High PWM frequency
165
- // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-ATmega2560
166
- // https://forum.arduino.cc/index.php?topic=72092.0
167
- if (pin == 13 || pin == 4 ) {
168
- TCCR0A = ((TCCR0A & 0b11111100 ) | 0x01 ); // configure the pwm phase-corrected mode
169
- if (high_fq) TCCR0B = ((TCCR0B & 0b11110000 ) | 0x01 ); // set prescaler to 1 - 32kHz
170
- else TCCR0B = ((TCCR0B & 0b11110000 ) | 0x02 ); // set prescaler to 2 - 4kHz
171
- }
172
- else if (pin == 12 || pin == 11 )
173
- if (high_fq) TCCR1B = ((TCCR1B & 0b11110000 ) | 0x01 ); // set prescaler to 1 - 32kHz
174
- else TCCR1B = ((TCCR1B & 0b11110000 ) | 0x02 ); // set prescaler to 2 - 4kHz
175
- else if (pin == 10 || pin == 9 )
176
- if (high_fq) TCCR2B = ((TCCR2B & 0b11110000 ) | 0x01 ); // set prescaler to 1 - 32kHz
177
- else TCCR2B = ((TCCR2B & 0b11110000 ) | 0x02 ); // set prescaler to 2 - 4kHz
178
- else if (pin == 5 || pin == 3 || pin == 2 )
179
- if (high_fq) TCCR3B = ((TCCR3B & 0b11110000 ) | 0x01 ); // set prescaler to 1 - 32kHz
180
- else TCCR3B = ((TCCR3B & 0b11110000 ) | 0x02 ); // set prescaler to 2 - 4kHz
181
- else if (pin == 8 || pin == 7 || pin == 6 )
182
- if (high_fq) TCCR4B = ((TCCR4B & 0b11110000 ) | 0x01 ); // set prescaler to 1 - 32kHz
183
- else TCCR4B = ((TCCR4B & 0b11110000 ) | 0x02 ); // set prescaler to 2 - 4kHz
184
- else if (pin == 44 || pin == 45 || pin == 46 )
185
- if (high_fq) TCCR5B = ((TCCR5B & 0b11110000 ) | 0x01 ); // set prescaler to 1 - 32kHz
186
- else TCCR5B = ((TCCR5B & 0b11110000 ) | 0x02 ); // set prescaler to 2 - 4kHz
187
164
165
+ // configure pin pairs
188
166
if ( (pinH == 4 && pinL == 13 ) || (pinH == 13 && pinL == 4 ) ){
189
167
// configure the pwm phase-corrected mode
190
168
TCCR0A = ((TCCR0A & 0b11111100 ) | 0x01 );
0 commit comments