🐛 Fix, improve PWM on AVR (#23520)
This commit is contained in:
parent
44249b1380
commit
01cb7c19f9
@ -61,7 +61,6 @@ Timer get_pwm_timer(const pin_t pin) {
|
|||||||
switch (digitalPinToTimer(pin)) {
|
switch (digitalPinToTimer(pin)) {
|
||||||
#ifdef TCCR0A
|
#ifdef TCCR0A
|
||||||
IF_DISABLED(AVR_AT90USB1286_FAMILY, case TIMER0A:)
|
IF_DISABLED(AVR_AT90USB1286_FAMILY, case TIMER0A:)
|
||||||
case TIMER0B:
|
|
||||||
#endif
|
#endif
|
||||||
#ifdef TCCR1A
|
#ifdef TCCR1A
|
||||||
case TIMER1A: case TIMER1B:
|
case TIMER1A: case TIMER1B:
|
||||||
@ -69,11 +68,16 @@ Timer get_pwm_timer(const pin_t pin) {
|
|||||||
|
|
||||||
break; // Protect reserved timers (TIMER0 & TIMER1)
|
break; // Protect reserved timers (TIMER0 & TIMER1)
|
||||||
|
|
||||||
|
#ifdef TCCR0A
|
||||||
|
case TIMER0B: // Protected timer, but allow setting the duty cycle on OCR0B for pin D4 only
|
||||||
|
return Timer({ { &TCCR0A, nullptr, nullptr }, { (uint16_t*)&OCR0B, nullptr, nullptr }, nullptr, 0, 0, true, true });
|
||||||
|
#endif
|
||||||
|
|
||||||
#if HAS_TCCR2
|
#if HAS_TCCR2
|
||||||
case TIMER2:
|
case TIMER2:
|
||||||
return Timer({ { &TCCR2, nullptr, nullptr }, { (uint16_t*)&OCR2, nullptr, nullptr }, nullptr, 2, 0, true, false });
|
return Timer({ { &TCCR2, nullptr, nullptr }, { (uint16_t*)&OCR2, nullptr, nullptr }, nullptr, 2, 0, true, false });
|
||||||
#elif ENABLED(USE_OCR2A_AS_TOP)
|
#elif ENABLED(USE_OCR2A_AS_TOP)
|
||||||
case TIMER2A: break; // protect TIMER2A since its OCR is used by TIMER2B
|
case TIMER2A: break; // Protect TIMER2A since its OCR is used by TIMER2B
|
||||||
case TIMER2B:
|
case TIMER2B:
|
||||||
return Timer({ { &TCCR2A, &TCCR2B, nullptr }, { (uint16_t*)&OCR2A, (uint16_t*)&OCR2B, nullptr }, nullptr, 2, 1, true, false });
|
return Timer({ { &TCCR2A, &TCCR2B, nullptr }, { (uint16_t*)&OCR2A, (uint16_t*)&OCR2B, nullptr }, nullptr, 2, 1, true, false });
|
||||||
#elif defined(TCCR2A)
|
#elif defined(TCCR2A)
|
||||||
@ -174,19 +178,24 @@ void set_pwm_frequency(const pin_t pin, const uint16_t f_desired) {
|
|||||||
|
|
||||||
void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
|
void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
|
||||||
// If v is 0 or v_size (max), digitalWrite to LOW or HIGH.
|
// If v is 0 or v_size (max), digitalWrite to LOW or HIGH.
|
||||||
// Note that digitalWrite also disables pwm output for us (sets COM bit to 0)
|
// Note that digitalWrite also disables PWM output for us (sets COM bit to 0)
|
||||||
if (v == 0)
|
if (v == 0)
|
||||||
digitalWrite(pin, invert);
|
digitalWrite(pin, invert);
|
||||||
else if (v == v_size)
|
else if (v == v_size)
|
||||||
digitalWrite(pin, !invert);
|
digitalWrite(pin, !invert);
|
||||||
else {
|
else {
|
||||||
Timer timer = get_pwm_timer(pin);
|
Timer timer = get_pwm_timer(pin);
|
||||||
if (timer.isProtected) return; // Leave protected timer unchanged
|
|
||||||
if (timer.isPWM) {
|
if (timer.isPWM) {
|
||||||
_SET_COMnQ(timer.TCCRnQ, SUM_TERN(HAS_TCCR2, timer.q, timer.q == 2), COM_CLEAR_SET + invert); // COM20 is on bit 4 of TCCR2, so +1 for q==2
|
if (timer.n == 0) {
|
||||||
|
TCCR0A |= _BV(COM0B1); // Only allow a TIMER0B select and OCR0B duty update for pin D4 outputs no frequency changes are permited.
|
||||||
|
OCR0B = v;
|
||||||
|
}
|
||||||
|
else if (!timer.isProtected) {
|
||||||
const uint16_t top = timer.n == 2 ? TERN(USE_OCR2A_AS_TOP, *timer.OCRnQ[0], 255) : *timer.ICRn;
|
const uint16_t top = timer.n == 2 ? TERN(USE_OCR2A_AS_TOP, *timer.OCRnQ[0], 255) : *timer.ICRn;
|
||||||
|
_SET_COMnQ(timer.TCCRnQ, SUM_TERN(HAS_TCCR2, timer.q, timer.q == 2), COM_CLEAR_SET + invert); // COM20 is on bit 4 of TCCR2, so +1 for q==2
|
||||||
_SET_OCRnQ(timer.OCRnQ, timer.q, uint16_t(uint32_t(v) * top / v_size)); // Scale 8/16-bit v to top value
|
_SET_OCRnQ(timer.OCRnQ, timer.q, uint16_t(uint32_t(v) * top / v_size)); // Scale 8/16-bit v to top value
|
||||||
}
|
}
|
||||||
|
}
|
||||||
else
|
else
|
||||||
digitalWrite(pin, v < 128 ? LOW : HIGH);
|
digitalWrite(pin, v < 128 ? LOW : HIGH);
|
||||||
}
|
}
|
||||||
|
@ -1244,10 +1244,6 @@ void Planner::recalculate() {
|
|||||||
recalculate_trapezoids();
|
recalculate_trapezoids();
|
||||||
}
|
}
|
||||||
|
|
||||||
#if HAS_FAN && DISABLED(LASER_SYNCHRONOUS_M106_M107)
|
|
||||||
#define HAS_TAIL_FAN_SPEED 1
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Apply fan speeds
|
* Apply fan speeds
|
||||||
*/
|
*/
|
||||||
@ -1308,8 +1304,9 @@ void Planner::check_axes_activity() {
|
|||||||
xyze_bool_t axis_active = { false };
|
xyze_bool_t axis_active = { false };
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAS_TAIL_FAN_SPEED
|
#if HAS_FAN && DISABLED(LASER_SYNCHRONOUS_M106_M107)
|
||||||
static uint8_t tail_fan_speed[FAN_COUNT] = ARRAY_N_1(FAN_COUNT, 255);
|
#define HAS_TAIL_FAN_SPEED 1
|
||||||
|
static uint8_t tail_fan_speed[FAN_COUNT] = ARRAY_N_1(FAN_COUNT, 128);
|
||||||
bool fans_need_update = false;
|
bool fans_need_update = false;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user