🧑💻 Adjust FastIO AVR timer enums, macros
This commit is contained in:
parent
67e5298a34
commit
c478ed08c8
|
@ -217,7 +217,7 @@ inline void HAL_adc_init() {
|
||||||
* NOTE that the frequency is applied to all pins on the timer (Ex OC3A, OC3B and OC3B)
|
* NOTE that the frequency is applied to all pins on the timer (Ex OC3A, OC3B and OC3B)
|
||||||
* NOTE that there are limitations, particularly if using TIMER2. (see Configuration_adv.h -> FAST FAN PWM Settings)
|
* NOTE that there are limitations, particularly if using TIMER2. (see Configuration_adv.h -> FAST FAN PWM Settings)
|
||||||
*/
|
*/
|
||||||
void set_pwm_frequency(const pin_t pin, int f_desired);
|
void set_pwm_frequency(const pin_t pin, const uint16_t f_desired);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* set_pwm_duty
|
* set_pwm_duty
|
||||||
|
|
|
@ -34,6 +34,24 @@ struct Timer {
|
||||||
uint8_t q; // the timer output [0->2] (A->C)
|
uint8_t q; // the timer output [0->2] (A->C)
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// Macros for the Timer structure
|
||||||
|
#define _SET_WGMnQ(TCCRnQ, V) do{ \
|
||||||
|
*(TCCRnQ)[0] = (*(TCCRnQ)[0] & ~(0x3 << 0)) | (( int(V) & 0x3) << 0); \
|
||||||
|
*(TCCRnQ)[1] = (*(TCCRnQ)[1] & ~(0x3 << 3)) | (((int(V) >> 2) & 0x3) << 3); \
|
||||||
|
}while(0)
|
||||||
|
|
||||||
|
// Set TCCR CS bits
|
||||||
|
#define _SET_CSn(TCCRnQ, V) (*(TCCRnQ)[1] = (*(TCCRnQ[1]) & ~(0x7 << 0)) | ((int(V) & 0x7) << 0))
|
||||||
|
|
||||||
|
// Set TCCR COM bits
|
||||||
|
#define _SET_COMnQ(TCCRnQ, Q, V) (*(TCCRnQ)[0] = (*(TCCRnQ)[0] & ~(0x3 << (6-2*(Q)))) | (int(V) << (6-2*(Q))))
|
||||||
|
|
||||||
|
// Set OCRnQ register
|
||||||
|
#define _SET_OCRnQ(OCRnQ, Q, V) (*(OCRnQ)[Q] = int(V) & 0xFFFF)
|
||||||
|
|
||||||
|
// Set ICRn register (one per timer)
|
||||||
|
#define _SET_ICRn(ICRn, V) (*(ICRn) = int(V) & 0xFFFF)
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* get_pwm_timer
|
* get_pwm_timer
|
||||||
* Get the timer information and register of the provided pin.
|
* Get the timer information and register of the provided pin.
|
||||||
|
@ -42,115 +60,119 @@ struct Timer {
|
||||||
*/
|
*/
|
||||||
Timer get_pwm_timer(const pin_t pin) {
|
Timer get_pwm_timer(const pin_t pin) {
|
||||||
uint8_t q = 0;
|
uint8_t q = 0;
|
||||||
|
|
||||||
switch (digitalPinToTimer(pin)) {
|
switch (digitalPinToTimer(pin)) {
|
||||||
// Protect reserved timers (TIMER0 & TIMER1)
|
// Protect reserved timers (TIMER0 & TIMER1)
|
||||||
#ifdef TCCR0A
|
#ifdef TCCR0A
|
||||||
#if !AVR_AT90USB1286_FAMILY
|
IF_DISABLED(AVR_AT90USB1286_FAMILY, case TIMER0A:)
|
||||||
case TIMER0A:
|
|
||||||
#endif
|
|
||||||
case TIMER0B:
|
case TIMER0B:
|
||||||
#endif
|
#endif
|
||||||
#ifdef TCCR1A
|
#ifdef TCCR1A
|
||||||
case TIMER1A: case TIMER1B:
|
case TIMER1A: case TIMER1B:
|
||||||
#endif
|
#endif
|
||||||
break;
|
|
||||||
#if HAS_TCCR2 || defined(TCCR2A)
|
break;
|
||||||
#if HAS_TCCR2
|
|
||||||
case TIMER2: {
|
#if HAS_TCCR2
|
||||||
|
case TIMER2: {
|
||||||
|
Timer timer = {
|
||||||
|
{ &TCCR2, nullptr, nullptr },
|
||||||
|
{ (uint16_t*)&OCR2, nullptr, nullptr },
|
||||||
|
nullptr,
|
||||||
|
2, 0
|
||||||
|
};
|
||||||
|
return timer;
|
||||||
|
}
|
||||||
|
#elif defined(TCCR2A)
|
||||||
|
#if ENABLED(USE_OCR2A_AS_TOP)
|
||||||
|
case TIMER2A: break; // protect TIMER2A
|
||||||
|
case TIMER2B: {
|
||||||
Timer timer = {
|
Timer timer = {
|
||||||
/*TCCRnQ*/ { &TCCR2, nullptr, nullptr },
|
{ &TCCR2A, &TCCR2B, nullptr },
|
||||||
/*OCRnQ*/ { (uint16_t*)&OCR2, nullptr, nullptr },
|
{ (uint16_t*)&OCR2A, (uint16_t*)&OCR2B, nullptr },
|
||||||
/*ICRn*/ nullptr,
|
nullptr,
|
||||||
/*n, q*/ 2, 0
|
2, 1
|
||||||
};
|
};
|
||||||
|
return timer;
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
case TIMER2B: ++q;
|
||||||
|
case TIMER2A: {
|
||||||
|
Timer timer = {
|
||||||
|
{ &TCCR2A, &TCCR2B, nullptr },
|
||||||
|
{ (uint16_t*)&OCR2A, (uint16_t*)&OCR2B, nullptr },
|
||||||
|
nullptr,
|
||||||
|
2, q
|
||||||
|
};
|
||||||
|
return timer;
|
||||||
}
|
}
|
||||||
#elif defined(TCCR2A)
|
|
||||||
#if ENABLED(USE_OCR2A_AS_TOP)
|
|
||||||
case TIMER2A: break; // protect TIMER2A
|
|
||||||
case TIMER2B: {
|
|
||||||
Timer timer = {
|
|
||||||
/*TCCRnQ*/ { &TCCR2A, &TCCR2B, nullptr },
|
|
||||||
/*OCRnQ*/ { (uint16_t*)&OCR2A, (uint16_t*)&OCR2B, nullptr },
|
|
||||||
/*ICRn*/ nullptr,
|
|
||||||
/*n, q*/ 2, 1
|
|
||||||
};
|
|
||||||
return timer;
|
|
||||||
}
|
|
||||||
#else
|
|
||||||
case TIMER2B: ++q;
|
|
||||||
case TIMER2A: {
|
|
||||||
Timer timer = {
|
|
||||||
/*TCCRnQ*/ { &TCCR2A, &TCCR2B, nullptr },
|
|
||||||
/*OCRnQ*/ { (uint16_t*)&OCR2A, (uint16_t*)&OCR2B, nullptr },
|
|
||||||
/*ICRn*/ nullptr,
|
|
||||||
2, q
|
|
||||||
};
|
|
||||||
return timer;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef OCR3C
|
#ifdef OCR3C
|
||||||
case TIMER3C: ++q;
|
case TIMER3C: ++q;
|
||||||
case TIMER3B: ++q;
|
case TIMER3B: ++q;
|
||||||
case TIMER3A: {
|
case TIMER3A: {
|
||||||
Timer timer = {
|
Timer timer = {
|
||||||
/*TCCRnQ*/ { &TCCR3A, &TCCR3B, &TCCR3C },
|
{ &TCCR3A, &TCCR3B, &TCCR3C },
|
||||||
/*OCRnQ*/ { &OCR3A, &OCR3B, &OCR3C },
|
{ &OCR3A, &OCR3B, &OCR3C },
|
||||||
/*ICRn*/ &ICR3,
|
&ICR3,
|
||||||
/*n, q*/ 3, q
|
3, q
|
||||||
};
|
};
|
||||||
return timer;
|
return timer;
|
||||||
}
|
}
|
||||||
#elif defined(OCR3B)
|
#elif defined(OCR3B)
|
||||||
case TIMER3B: ++q;
|
case TIMER3B: ++q;
|
||||||
case TIMER3A: {
|
case TIMER3A: {
|
||||||
Timer timer = {
|
Timer timer = {
|
||||||
/*TCCRnQ*/ { &TCCR3A, &TCCR3B, nullptr },
|
{ &TCCR3A, &TCCR3B, nullptr },
|
||||||
/*OCRnQ*/ { &OCR3A, &OCR3B, nullptr },
|
{ &OCR3A, &OCR3B, nullptr },
|
||||||
/*ICRn*/ &ICR3,
|
&ICR3,
|
||||||
/*n, q*/ 3, q
|
3, q
|
||||||
};
|
};
|
||||||
return timer;
|
return timer;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef TCCR4A
|
#ifdef TCCR4A
|
||||||
case TIMER4C: ++q;
|
case TIMER4C: ++q;
|
||||||
case TIMER4B: ++q;
|
case TIMER4B: ++q;
|
||||||
case TIMER4A: {
|
case TIMER4A: {
|
||||||
Timer timer = {
|
Timer timer = {
|
||||||
/*TCCRnQ*/ { &TCCR4A, &TCCR4B, &TCCR4C },
|
{ &TCCR4A, &TCCR4B, &TCCR4C },
|
||||||
/*OCRnQ*/ { &OCR4A, &OCR4B, &OCR4C },
|
{ &OCR4A, &OCR4B, &OCR4C },
|
||||||
/*ICRn*/ &ICR4,
|
&ICR4,
|
||||||
/*n, q*/ 4, q
|
4, q
|
||||||
};
|
};
|
||||||
return timer;
|
return timer;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef TCCR5A
|
#ifdef TCCR5A
|
||||||
case TIMER5C: ++q;
|
case TIMER5C: ++q;
|
||||||
case TIMER5B: ++q;
|
case TIMER5B: ++q;
|
||||||
case TIMER5A: {
|
case TIMER5A: {
|
||||||
Timer timer = {
|
Timer timer = {
|
||||||
/*TCCRnQ*/ { &TCCR5A, &TCCR5B, &TCCR5C },
|
{ &TCCR5A, &TCCR5B, &TCCR5C },
|
||||||
/*OCRnQ*/ { &OCR5A, &OCR5B, &OCR5C },
|
{ &OCR5A, &OCR5B, &OCR5C },
|
||||||
/*ICRn*/ &ICR5,
|
&ICR5,
|
||||||
/*n, q*/ 5, q
|
5, q
|
||||||
};
|
};
|
||||||
return timer;
|
return timer;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
Timer timer = {
|
Timer timer = {
|
||||||
/*TCCRnQ*/ { nullptr, nullptr, nullptr },
|
{ nullptr, nullptr, nullptr },
|
||||||
/*OCRnQ*/ { nullptr, nullptr, nullptr },
|
{ nullptr, nullptr, nullptr },
|
||||||
/*ICRn*/ nullptr,
|
nullptr,
|
||||||
0, 0
|
0, 0
|
||||||
};
|
};
|
||||||
return timer;
|
return timer;
|
||||||
}
|
}
|
||||||
|
|
||||||
void set_pwm_frequency(const pin_t pin, int f_desired) {
|
void set_pwm_frequency(const pin_t pin, const uint16_t f_desired) {
|
||||||
Timer timer = get_pwm_timer(pin);
|
Timer timer = get_pwm_timer(pin);
|
||||||
if (timer.n == 0) return; // Don't proceed if protected timer or not recognized
|
if (timer.n == 0) return; // Don't proceed if protected timer or not recognized
|
||||||
uint16_t size;
|
uint16_t size;
|
||||||
|
|
|
@ -118,7 +118,7 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// Waveform Generation Modes
|
// Waveform Generation Modes
|
||||||
enum WaveGenMode : char {
|
enum WaveGenMode : uint8_t {
|
||||||
WGM_NORMAL, // 0
|
WGM_NORMAL, // 0
|
||||||
WGM_PWM_PC_8, // 1
|
WGM_PWM_PC_8, // 1
|
||||||
WGM_PWM_PC_9, // 2
|
WGM_PWM_PC_9, // 2
|
||||||
|
@ -138,19 +138,19 @@ enum WaveGenMode : char {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Wavefore Generation Modes (Timer 2 only)
|
// Wavefore Generation Modes (Timer 2 only)
|
||||||
enum WaveGenMode2 : char {
|
enum WaveGenMode2 : uint8_t {
|
||||||
WGM2_NORMAL, // 0
|
WGM2_NORMAL, // 0
|
||||||
WGM2_PWM_PC, // 1
|
WGM2_PWM_PC, // 1
|
||||||
WGM2_CTC_OCR2A, // 2
|
WGM2_CTC_OCR2A, // 2
|
||||||
WGM2_FAST_PWM, // 3
|
WGM2_FAST_PWM, // 3
|
||||||
WGM2_reserved_1, // 4
|
WGM2_reserved_1, // 4
|
||||||
WGM2_PWM_PC_OCR2A, // 5
|
WGM2_PWM_PC_OCR2A, // 5
|
||||||
WGM2_reserved_2, // 6
|
WGM2_reserved_2, // 6
|
||||||
WGM2_FAST_PWM_OCR2A, // 7
|
WGM2_FAST_PWM_OCR2A, // 7
|
||||||
};
|
};
|
||||||
|
|
||||||
// Compare Modes
|
// Compare Modes
|
||||||
enum CompareMode : char {
|
enum CompareMode : uint8_t {
|
||||||
COM_NORMAL, // 0
|
COM_NORMAL, // 0
|
||||||
COM_TOGGLE, // 1 Non-PWM: OCnx ... Both PWM (WGM 9,11,14,15): OCnA only ... else NORMAL
|
COM_TOGGLE, // 1 Non-PWM: OCnx ... Both PWM (WGM 9,11,14,15): OCnA only ... else NORMAL
|
||||||
COM_CLEAR_SET, // 2 Non-PWM: OCnx ... Fast PWM: OCnx/Bottom ... PF-FC: OCnx Up/Down
|
COM_CLEAR_SET, // 2 Non-PWM: OCnx ... Fast PWM: OCnx/Bottom ... PF-FC: OCnx Up/Down
|
||||||
|
@ -158,7 +158,7 @@ enum CompareMode : char {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Clock Sources
|
// Clock Sources
|
||||||
enum ClockSource : char {
|
enum ClockSource : uint8_t {
|
||||||
CS_NONE, // 0
|
CS_NONE, // 0
|
||||||
CS_PRESCALER_1, // 1
|
CS_PRESCALER_1, // 1
|
||||||
CS_PRESCALER_8, // 2
|
CS_PRESCALER_8, // 2
|
||||||
|
@ -170,7 +170,7 @@ enum ClockSource : char {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Clock Sources (Timer 2 only)
|
// Clock Sources (Timer 2 only)
|
||||||
enum ClockSource2 : char {
|
enum ClockSource2 : uint8_t {
|
||||||
CS2_NONE, // 0
|
CS2_NONE, // 0
|
||||||
CS2_PRESCALER_1, // 1
|
CS2_PRESCALER_1, // 1
|
||||||
CS2_PRESCALER_8, // 2
|
CS2_PRESCALER_8, // 2
|
||||||
|
@ -203,11 +203,6 @@ enum ClockSource2 : char {
|
||||||
TCCR##T##B = (TCCR##T##B & ~(0x3 << WGM##T##2)) | (((int(V) >> 2) & 0x3) << WGM##T##2); \
|
TCCR##T##B = (TCCR##T##B & ~(0x3 << WGM##T##2)) | (((int(V) >> 2) & 0x3) << WGM##T##2); \
|
||||||
}while(0)
|
}while(0)
|
||||||
#define SET_WGM(T,V) _SET_WGM(T,WGM_##V)
|
#define SET_WGM(T,V) _SET_WGM(T,WGM_##V)
|
||||||
// Runtime (see set_pwm_frequency):
|
|
||||||
#define _SET_WGMnQ(TCCRnQ, V) do{ \
|
|
||||||
*(TCCRnQ)[0] = (*(TCCRnQ)[0] & ~(0x3 << 0)) | (( int(V) & 0x3) << 0); \
|
|
||||||
*(TCCRnQ)[1] = (*(TCCRnQ)[1] & ~(0x3 << 3)) | (((int(V) >> 2) & 0x3) << 3); \
|
|
||||||
}while(0)
|
|
||||||
|
|
||||||
// Set Clock Select bits
|
// Set Clock Select bits
|
||||||
// Ex: SET_CS3(PRESCALER_64);
|
// Ex: SET_CS3(PRESCALER_64);
|
||||||
|
@ -235,8 +230,6 @@ enum ClockSource2 : char {
|
||||||
#define SET_CS4(V) _SET_CS4(CS_##V)
|
#define SET_CS4(V) _SET_CS4(CS_##V)
|
||||||
#define SET_CS5(V) _SET_CS5(CS_##V)
|
#define SET_CS5(V) _SET_CS5(CS_##V)
|
||||||
#define SET_CS(T,V) SET_CS##T(V)
|
#define SET_CS(T,V) SET_CS##T(V)
|
||||||
// Runtime (see set_pwm_frequency)
|
|
||||||
#define _SET_CSn(TCCRnQ, V) (*(TCCRnQ)[1] = (*(TCCRnQ[1]) & ~(0x7 << 0)) | ((int(V) & 0x7) << 0))
|
|
||||||
|
|
||||||
// Set Compare Mode bits
|
// Set Compare Mode bits
|
||||||
// Ex: SET_COMS(4,CLEAR_SET,CLEAR_SET,CLEAR_SET);
|
// Ex: SET_COMS(4,CLEAR_SET,CLEAR_SET,CLEAR_SET);
|
||||||
|
@ -246,16 +239,6 @@ enum ClockSource2 : char {
|
||||||
#define SET_COMB(T,V) SET_COM(T,B,V)
|
#define SET_COMB(T,V) SET_COM(T,B,V)
|
||||||
#define SET_COMC(T,V) SET_COM(T,C,V)
|
#define SET_COMC(T,V) SET_COM(T,C,V)
|
||||||
#define SET_COMS(T,V1,V2,V3) do{ SET_COMA(T,V1); SET_COMB(T,V2); SET_COMC(T,V3); }while(0)
|
#define SET_COMS(T,V1,V2,V3) do{ SET_COMA(T,V1); SET_COMB(T,V2); SET_COMC(T,V3); }while(0)
|
||||||
// Runtime (see set_pwm_duty)
|
|
||||||
#define _SET_COMnQ(TCCRnQ, Q, V) (*(TCCRnQ)[0] = (*(TCCRnQ)[0] & ~(0x3 << (6-2*(Q)))) | (int(V) << (6-2*(Q))))
|
|
||||||
|
|
||||||
// Set OCRnQ register
|
|
||||||
// Runtime (see set_pwm_duty):
|
|
||||||
#define _SET_OCRnQ(OCRnQ, Q, V) (*(OCRnQ)[Q] = int(V) & 0xFFFF)
|
|
||||||
|
|
||||||
// Set ICRn register (one per timer)
|
|
||||||
// Runtime (see set_pwm_frequency)
|
|
||||||
#define _SET_ICRn(ICRn, V) (*(ICRn) = int(V) & 0xFFFF)
|
|
||||||
|
|
||||||
// Set Noise Canceler bit
|
// Set Noise Canceler bit
|
||||||
// Ex: SET_ICNC(2,1)
|
// Ex: SET_ICNC(2,1)
|
||||||
|
|
|
@ -206,7 +206,7 @@ void flashFirmware(const int16_t);
|
||||||
* All Hardware PWM pins run at the same frequency and all
|
* All Hardware PWM pins run at the same frequency and all
|
||||||
* Software PWM pins run at the same frequency
|
* Software PWM pins run at the same frequency
|
||||||
*/
|
*/
|
||||||
void set_pwm_frequency(const pin_t pin, int f_desired);
|
void set_pwm_frequency(const pin_t pin, const uint16_t f_desired);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* set_pwm_duty
|
* set_pwm_duty
|
||||||
|
|
|
@ -32,7 +32,7 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255
|
||||||
|
|
||||||
#if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM
|
#if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM
|
||||||
|
|
||||||
void set_pwm_frequency(const pin_t pin, int f_desired) {
|
void set_pwm_frequency(const pin_t pin, const uint16_t f_desired) {
|
||||||
LPC176x::pwm_set_frequency(pin, f_desired);
|
LPC176x::pwm_set_frequency(pin, f_desired);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -231,7 +231,7 @@ extern volatile uint32_t systick_uptime_millis;
|
||||||
* Set the frequency of the timer corresponding to the provided pin
|
* Set the frequency of the timer corresponding to the provided pin
|
||||||
* All Timer PWM pins run at the same frequency
|
* All Timer PWM pins run at the same frequency
|
||||||
*/
|
*/
|
||||||
void set_pwm_frequency(const pin_t pin, int f_desired);
|
void set_pwm_frequency(const pin_t pin, const uint16_t f_desired);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* set_pwm_duty
|
* set_pwm_duty
|
||||||
|
|
|
@ -56,7 +56,7 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255
|
||||||
if (previousMode != TIMER_OUTPUT_COMPARE_PWM1) HT->resume();
|
if (previousMode != TIMER_OUTPUT_COMPARE_PWM1) HT->resume();
|
||||||
}
|
}
|
||||||
|
|
||||||
void set_pwm_frequency(const pin_t pin, int f_desired) {
|
void set_pwm_frequency(const pin_t pin, const uint16_t f_desired) {
|
||||||
if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
|
if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
|
||||||
const PinName pin_name = digitalPinToPinName(pin);
|
const PinName pin_name = digitalPinToPinName(pin);
|
||||||
TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance
|
TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance
|
||||||
|
|
|
@ -274,7 +274,7 @@ void flashFirmware(const int16_t);
|
||||||
* Set the frequency of the timer corresponding to the provided pin
|
* Set the frequency of the timer corresponding to the provided pin
|
||||||
* All Timer PWM pins run at the same frequency
|
* All Timer PWM pins run at the same frequency
|
||||||
*/
|
*/
|
||||||
void set_pwm_frequency(const pin_t pin, int f_desired);
|
void set_pwm_frequency(const pin_t pin, const uint16_t f_desired);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* set_pwm_duty
|
* set_pwm_duty
|
||||||
|
|
|
@ -51,7 +51,7 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255
|
||||||
timer_set_mode(timer, channel, TIMER_PWM); // PWM Output Mode
|
timer_set_mode(timer, channel, TIMER_PWM); // PWM Output Mode
|
||||||
}
|
}
|
||||||
|
|
||||||
void set_pwm_frequency(const pin_t pin, int f_desired) {
|
void set_pwm_frequency(const pin_t pin, const uint16_t f_desired) {
|
||||||
if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
|
if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
|
||||||
|
|
||||||
timer_dev *timer; UNUSED(timer);
|
timer_dev *timer; UNUSED(timer);
|
||||||
|
|
Loading…
Reference in a new issue