⚗️ Use pwm_set_duty over analogWrite to set PWM (#23048)
Co-authored-by: Scott Lahteine <thinkyhead@users.noreply.github.com>
This commit is contained in:
parent
b033da1782
commit
0d91b07797
|
@ -221,7 +221,7 @@ void set_pwm_frequency(const pin_t pin, int f_desired);
|
|||
|
||||
/**
|
||||
* set_pwm_duty
|
||||
* Sets the PWM duty cycle of the provided pin to the provided value
|
||||
* Set the PWM duty cycle of the provided pin to the provided value
|
||||
* Optionally allows inverting the duty cycle [default = false]
|
||||
* Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255]
|
||||
*/
|
||||
|
|
|
@ -22,11 +22,10 @@
|
|||
#ifdef __AVR__
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
#include "HAL.h"
|
||||
|
||||
#if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM
|
||||
|
||||
#include "HAL.h"
|
||||
|
||||
struct Timer {
|
||||
volatile uint8_t* TCCRnQ[3]; // max 3 TCCR registers per timer
|
||||
volatile uint16_t* OCRnQ[3]; // max 3 OCR registers per timer
|
||||
|
@ -153,7 +152,7 @@ Timer get_pwm_timer(const pin_t pin) {
|
|||
|
||||
void set_pwm_frequency(const pin_t pin, int f_desired) {
|
||||
Timer timer = get_pwm_timer(pin);
|
||||
if (timer.n == 0) return; // Don't proceed if protected timer or not recognised
|
||||
if (timer.n == 0) return; // Don't proceed if protected timer or not recognized
|
||||
uint16_t size;
|
||||
if (timer.n == 2) size = 255; else size = 65535;
|
||||
|
||||
|
@ -243,40 +242,39 @@ void set_pwm_frequency(const pin_t pin, int f_desired) {
|
|||
_SET_ICRn(timer.ICRn, res); // Set ICRn value (TOP) = res
|
||||
}
|
||||
|
||||
#endif // NEEDS_HARDWARE_PWM
|
||||
|
||||
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.
|
||||
// Note that digitalWrite also disables pwm output for us (sets COM bit to 0)
|
||||
if (v == 0)
|
||||
digitalWrite(pin, invert);
|
||||
else if (v == v_size)
|
||||
digitalWrite(pin, !invert);
|
||||
else {
|
||||
Timer timer = get_pwm_timer(pin);
|
||||
if (timer.n == 0) return; // Don't proceed if protected timer or not recognised
|
||||
// Set compare output mode to CLEAR -> SET or SET -> CLEAR (if inverted)
|
||||
_SET_COMnQ(timer.TCCRnQ, (timer.q
|
||||
#ifdef TCCR2
|
||||
+ (timer.q == 2) // COM20 is on bit 4 of TCCR2, thus requires q + 1 in the macro
|
||||
#endif
|
||||
), COM_CLEAR_SET + invert
|
||||
);
|
||||
#if NEEDS_HARDWARE_PWM
|
||||
|
||||
uint16_t top;
|
||||
if (timer.n == 2) { // if TIMER2
|
||||
top = (
|
||||
#if ENABLED(USE_OCR2A_AS_TOP)
|
||||
*timer.OCRnQ[0] // top = OCR2A
|
||||
#else
|
||||
255 // top = 0xFF (max)
|
||||
#endif
|
||||
// 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)
|
||||
if (v == 0)
|
||||
digitalWrite(pin, invert);
|
||||
else if (v == v_size)
|
||||
digitalWrite(pin, !invert);
|
||||
else {
|
||||
Timer timer = get_pwm_timer(pin);
|
||||
if (timer.n == 0) return; // Don't proceed if protected timer or not recognized
|
||||
// Set compare output mode to CLEAR -> SET or SET -> CLEAR (if inverted)
|
||||
_SET_COMnQ(timer.TCCRnQ, (timer.q
|
||||
#ifdef TCCR2
|
||||
+ (timer.q == 2) // COM20 is on bit 4 of TCCR2, thus requires q + 1 in the macro
|
||||
#endif
|
||||
), COM_CLEAR_SET + invert
|
||||
);
|
||||
}
|
||||
else
|
||||
top = *timer.ICRn; // top = ICRn
|
||||
|
||||
_SET_OCRnQ(timer.OCRnQ, timer.q, v * float(top) / float(v_size)); // Scale 8/16-bit v to top value
|
||||
}
|
||||
uint16_t top = (timer.n == 2) ? TERN(USE_OCR2A_AS_TOP, *timer.OCRnQ[0], 255) : *timer.ICRn;
|
||||
_SET_OCRnQ(timer.OCRnQ, timer.q, (v * top + v_size / 2) / v_size); // Scale 8/16-bit v to top value
|
||||
}
|
||||
|
||||
#else
|
||||
|
||||
analogWrite(pin, v);
|
||||
UNUSED(v_size);
|
||||
UNUSED(invert);
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // NEEDS_HARDWARE_PWM
|
||||
#endif // __AVR__
|
||||
|
|
|
@ -144,6 +144,11 @@ inline void HAL_adc_init() {}//todo
|
|||
void HAL_adc_start_conversion(const uint8_t ch);
|
||||
uint16_t HAL_adc_get_result();
|
||||
|
||||
//
|
||||
// PWM
|
||||
//
|
||||
inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
|
||||
|
||||
//
|
||||
// Pin Map
|
||||
//
|
||||
|
|
|
@ -129,6 +129,10 @@ void HAL_adc_init();
|
|||
|
||||
void HAL_adc_start_conversion(const uint8_t adc_pin);
|
||||
|
||||
// PWM
|
||||
inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
|
||||
|
||||
// Pin Map
|
||||
#define GET_PIN_MAP_PIN(index) index
|
||||
#define GET_PIN_MAP_INDEX(pin) pin
|
||||
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
|
||||
|
|
|
@ -101,6 +101,9 @@ void HAL_adc_enable_channel(const uint8_t ch);
|
|||
void HAL_adc_start_conversion(const uint8_t ch);
|
||||
uint16_t HAL_adc_get_result();
|
||||
|
||||
// PWM
|
||||
inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
|
||||
|
||||
// Reset source
|
||||
inline void HAL_clear_reset_source(void) {}
|
||||
inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; }
|
||||
|
|
|
@ -22,18 +22,18 @@
|
|||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM
|
||||
|
||||
#include <pwm.h>
|
||||
|
||||
void set_pwm_frequency(const pin_t pin, int f_desired) {
|
||||
LPC176x::pwm_set_frequency(pin, f_desired);
|
||||
}
|
||||
|
||||
void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
|
||||
LPC176x::pwm_write_ratio(pin, invert ? 1.0f - (float)v / v_size : (float)v / v_size);
|
||||
}
|
||||
|
||||
#endif // NEEDS_HARDWARE_PWM
|
||||
#if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM
|
||||
|
||||
void set_pwm_frequency(const pin_t pin, int f_desired) {
|
||||
LPC176x::pwm_set_frequency(pin, f_desired);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#endif // TARGET_LPC1768
|
||||
|
|
|
@ -133,6 +133,9 @@ void HAL_adc_enable_channel(const uint8_t ch);
|
|||
void HAL_adc_start_conversion(const uint8_t ch);
|
||||
uint16_t HAL_adc_get_result();
|
||||
|
||||
// PWM
|
||||
inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
|
||||
|
||||
// Reset source
|
||||
inline void HAL_clear_reset_source(void) {}
|
||||
inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; }
|
||||
|
|
|
@ -127,6 +127,11 @@ void HAL_adc_init();
|
|||
|
||||
void HAL_adc_start_conversion(const uint8_t adc_pin);
|
||||
|
||||
//
|
||||
// PWM
|
||||
//
|
||||
inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
|
||||
|
||||
//
|
||||
// Pin Map
|
||||
//
|
||||
|
|
|
@ -24,26 +24,9 @@
|
|||
|
||||
#ifdef HAL_STM32
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if NEEDS_HARDWARE_PWM
|
||||
|
||||
#include "HAL.h"
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "timers.h"
|
||||
|
||||
void set_pwm_frequency(const pin_t pin, int f_desired) {
|
||||
if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
|
||||
|
||||
PinName pin_name = digitalPinToPinName(pin);
|
||||
TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance
|
||||
|
||||
LOOP_S_L_N(i, 0, NUM_HARDWARE_TIMERS) // Protect used timers
|
||||
if (timer_instance[i] && timer_instance[i]->getHandle()->Instance == Instance)
|
||||
return;
|
||||
|
||||
pwm_start(pin_name, f_desired, 0, RESOLUTION_8B_COMPARE_FORMAT);
|
||||
}
|
||||
|
||||
void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
|
||||
PinName pin_name = digitalPinToPinName(pin);
|
||||
TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM);
|
||||
|
@ -58,5 +41,21 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255
|
|||
}
|
||||
}
|
||||
|
||||
#endif // NEEDS_HARDWARE_PWM
|
||||
#if NEEDS_HARDWARE_PWM
|
||||
|
||||
void set_pwm_frequency(const pin_t pin, int f_desired) {
|
||||
if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
|
||||
|
||||
PinName pin_name = digitalPinToPinName(pin);
|
||||
TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance
|
||||
|
||||
LOOP_S_L_N(i, 0, NUM_HARDWARE_TIMERS) // Protect used timers
|
||||
if (timer_instance[i] && timer_instance[i]->getHandle()->Instance == Instance)
|
||||
return;
|
||||
|
||||
pwm_start(pin_name, f_desired, 0, RESOLUTION_8B_COMPARE_FORMAT);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#endif // HAL_STM32
|
||||
|
|
|
@ -449,8 +449,7 @@ uint16_t analogRead(pin_t pin) {
|
|||
|
||||
// Wrapper to maple unprotected analogWrite
|
||||
void analogWrite(pin_t pin, int pwm_val8) {
|
||||
if (PWM_PIN(pin))
|
||||
analogWrite(uint8_t(pin), pwm_val8);
|
||||
if (PWM_PIN(pin)) analogWrite(uint8_t(pin), pwm_val8);
|
||||
}
|
||||
|
||||
void HAL_reboot() { nvic_sys_reset(); }
|
||||
|
|
|
@ -23,40 +23,10 @@
|
|||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if NEEDS_HARDWARE_PWM
|
||||
|
||||
#include <pwm.h>
|
||||
#include "HAL.h"
|
||||
#include "timers.h"
|
||||
|
||||
void set_pwm_frequency(const pin_t pin, int f_desired) {
|
||||
if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
|
||||
|
||||
timer_dev *timer = PIN_MAP[pin].timer_device;
|
||||
uint8_t channel = PIN_MAP[pin].timer_channel;
|
||||
|
||||
// Protect used timers
|
||||
if (timer == get_timer_dev(TEMP_TIMER_NUM)) return;
|
||||
if (timer == get_timer_dev(STEP_TIMER_NUM)) return;
|
||||
#if PULSE_TIMER_NUM != STEP_TIMER_NUM
|
||||
if (timer == get_timer_dev(PULSE_TIMER_NUM)) return;
|
||||
#endif
|
||||
|
||||
if (!(timer->regs.bas->SR & TIMER_CR1_CEN)) // Ensure the timer is enabled
|
||||
timer_init(timer);
|
||||
|
||||
timer_set_mode(timer, channel, TIMER_PWM);
|
||||
uint16_t preload = 255; // Lock 255 PWM resolution for high frequencies
|
||||
int32_t prescaler = (HAL_TIMER_RATE) / (preload + 1) / f_desired - 1;
|
||||
if (prescaler > 65535) { // For low frequencies increase prescaler
|
||||
prescaler = 65535;
|
||||
preload = (HAL_TIMER_RATE) / (prescaler + 1) / f_desired - 1;
|
||||
}
|
||||
if (prescaler < 0) return; // Too high frequency
|
||||
timer_set_reload(timer, preload);
|
||||
timer_set_prescaler(timer, prescaler);
|
||||
}
|
||||
|
||||
void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
|
||||
timer_dev *timer = PIN_MAP[pin].timer_device;
|
||||
uint16_t max_val = timer->regs.bas->ARR * v / v_size;
|
||||
|
@ -64,5 +34,35 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255
|
|||
pwmWrite(pin, max_val);
|
||||
}
|
||||
|
||||
#if NEEDS_HARDWARE_PWM
|
||||
|
||||
void set_pwm_frequency(const pin_t pin, int f_desired) {
|
||||
if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
|
||||
|
||||
timer_dev *timer = PIN_MAP[pin].timer_device;
|
||||
uint8_t channel = PIN_MAP[pin].timer_channel;
|
||||
|
||||
// Protect used timers
|
||||
if (timer == get_timer_dev(TEMP_TIMER_NUM)) return;
|
||||
if (timer == get_timer_dev(STEP_TIMER_NUM)) return;
|
||||
#if PULSE_TIMER_NUM != STEP_TIMER_NUM
|
||||
if (timer == get_timer_dev(PULSE_TIMER_NUM)) return;
|
||||
#endif
|
||||
|
||||
if (!(timer->regs.bas->SR & TIMER_CR1_CEN)) // Ensure the timer is enabled
|
||||
timer_init(timer);
|
||||
|
||||
timer_set_mode(timer, channel, TIMER_PWM);
|
||||
uint16_t preload = 255; // Lock 255 PWM resolution for high frequencies
|
||||
int32_t prescaler = (HAL_TIMER_RATE) / (preload + 1) / f_desired - 1;
|
||||
if (prescaler > 65535) { // For low frequencies increase prescaler
|
||||
prescaler = 65535;
|
||||
preload = (HAL_TIMER_RATE) / (prescaler + 1) / f_desired - 1;
|
||||
}
|
||||
if (prescaler < 0) return; // Too high frequency
|
||||
timer_set_reload(timer, preload);
|
||||
timer_set_prescaler(timer, prescaler);
|
||||
}
|
||||
|
||||
#endif // NEEDS_HARDWARE_PWM
|
||||
#endif // __STM32F1__
|
||||
|
|
|
@ -122,6 +122,12 @@ void HAL_adc_init();
|
|||
void HAL_adc_start_conversion(const uint8_t adc_pin);
|
||||
uint16_t HAL_adc_get_result();
|
||||
|
||||
// PWM
|
||||
|
||||
inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
|
||||
|
||||
// Pin Map
|
||||
|
||||
#define GET_PIN_MAP_PIN(index) index
|
||||
#define GET_PIN_MAP_INDEX(pin) pin
|
||||
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
|
||||
|
|
|
@ -129,6 +129,12 @@ void HAL_adc_init();
|
|||
void HAL_adc_start_conversion(const uint8_t adc_pin);
|
||||
uint16_t HAL_adc_get_result();
|
||||
|
||||
// PWM
|
||||
|
||||
inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
|
||||
|
||||
// Pin Map
|
||||
|
||||
#define GET_PIN_MAP_PIN(index) index
|
||||
#define GET_PIN_MAP_INDEX(pin) pin
|
||||
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
|
||||
|
|
|
@ -106,17 +106,17 @@ void HAL_adc_init() {
|
|||
void HAL_clear_reset_source() {
|
||||
uint32_t reset_source = SRC_SRSR;
|
||||
SRC_SRSR = reset_source;
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t HAL_get_reset_source() {
|
||||
switch (SRC_SRSR & 0xFF) {
|
||||
case 1: return RST_POWER_ON; break;
|
||||
case 2: return RST_SOFTWARE; break;
|
||||
case 4: return RST_EXTERNAL; break;
|
||||
// case 8: return RST_BROWN_OUT; break;
|
||||
//case 8: return RST_BROWN_OUT; break;
|
||||
case 16: return RST_WATCHDOG; break;
|
||||
case 64: return RST_JTAG; break;
|
||||
// case 128: return RST_OVERTEMP; break;
|
||||
case 64: return RST_JTAG; break;
|
||||
//case 128: return RST_OVERTEMP; break;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
@ -168,7 +168,7 @@ uint16_t HAL_adc_get_result() {
|
|||
return 0;
|
||||
}
|
||||
|
||||
bool is_output(uint8_t pin) {
|
||||
bool is_output(pin_t pin) {
|
||||
const struct digital_pin_bitband_and_config_table_struct *p;
|
||||
p = digital_pin_to_info_PGM + pin;
|
||||
return (*(p->reg + 1) & p->mask);
|
||||
|
|
|
@ -150,8 +150,14 @@ void HAL_adc_init();
|
|||
void HAL_adc_start_conversion(const uint8_t adc_pin);
|
||||
uint16_t HAL_adc_get_result();
|
||||
|
||||
// PWM
|
||||
|
||||
inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
|
||||
|
||||
// Pin Map
|
||||
|
||||
#define GET_PIN_MAP_PIN(index) index
|
||||
#define GET_PIN_MAP_INDEX(pin) pin
|
||||
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
|
||||
|
||||
bool is_output(uint8_t pin);
|
||||
bool is_output(pin_t pin);
|
||||
|
|
|
@ -70,7 +70,7 @@ void CaseLight::update(const bool sflag) {
|
|||
|
||||
#if CASELIGHT_USES_BRIGHTNESS
|
||||
if (pin_is_pwm())
|
||||
analogWrite(pin_t(CASE_LIGHT_PIN), (
|
||||
set_pwm_duty(pin_t(CASE_LIGHT_PIN), (
|
||||
#if CASE_LIGHT_MAX_PWM == 255
|
||||
n10ct
|
||||
#else
|
||||
|
|
|
@ -72,9 +72,10 @@ void ControllerFan::update() {
|
|||
? settings.active_speed : settings.idle_speed
|
||||
);
|
||||
|
||||
// Allow digital or PWM fan output (see M42 handling)
|
||||
WRITE(CONTROLLER_FAN_PIN, speed);
|
||||
analogWrite(pin_t(CONTROLLER_FAN_PIN), speed);
|
||||
if (PWM_PIN(CONTROLLER_FAN_PIN))
|
||||
set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed);
|
||||
else
|
||||
WRITE(CONTROLLER_FAN_PIN, speed);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -121,11 +121,11 @@ void LEDLights::set_color(const LEDColor &incol
|
|||
|
||||
// This variant uses 3-4 separate pins for the RGB(W) components.
|
||||
// If the pins can do PWM then their intensity will be set.
|
||||
#define _UPDATE_RGBW(C,c) do { \
|
||||
if (PWM_PIN(RGB_LED_##C##_PIN)) \
|
||||
analogWrite(pin_t(RGB_LED_##C##_PIN), c); \
|
||||
else \
|
||||
WRITE(RGB_LED_##C##_PIN, c ? HIGH : LOW); \
|
||||
#define _UPDATE_RGBW(C,c) do { \
|
||||
if (PWM_PIN(RGB_LED_##C##_PIN)) \
|
||||
set_pwm_duty(pin_t(RGB_LED_##C##_PIN), c); \
|
||||
else \
|
||||
WRITE(RGB_LED_##C##_PIN, c ? HIGH : LOW); \
|
||||
}while(0)
|
||||
#define UPDATE_RGBW(C,c) _UPDATE_RGBW(C, TERN1(CASE_LIGHT_USE_RGB_LED, caselight.on) ? incol.c : 0)
|
||||
UPDATE_RGBW(R,r); UPDATE_RGBW(G,g); UPDATE_RGBW(B,b);
|
||||
|
|
|
@ -66,7 +66,7 @@ void SpindleLaser::init() {
|
|||
#endif
|
||||
#if ENABLED(SPINDLE_LASER_USE_PWM)
|
||||
SET_PWM(SPINDLE_LASER_PWM_PIN);
|
||||
analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Set to lowest speed
|
||||
set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Set to lowest speed
|
||||
#endif
|
||||
#if ENABLED(HAL_CAN_SET_PWM_FREQ) && defined(SPINDLE_LASER_FREQUENCY)
|
||||
set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY);
|
||||
|
@ -92,10 +92,8 @@ void SpindleLaser::init() {
|
|||
void SpindleLaser::_set_ocr(const uint8_t ocr) {
|
||||
#if NEEDS_HARDWARE_PWM && SPINDLE_LASER_FREQUENCY
|
||||
set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), TERN(MARLIN_DEV_MODE, frequency, SPINDLE_LASER_FREQUENCY));
|
||||
set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF);
|
||||
#else
|
||||
analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF);
|
||||
#endif
|
||||
set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF);
|
||||
}
|
||||
|
||||
void SpindleLaser::set_ocr(const uint8_t ocr) {
|
||||
|
|
|
@ -126,10 +126,10 @@ void GcodeSuite::M42() {
|
|||
extDigitalWrite(pin, pin_status);
|
||||
|
||||
#ifdef ARDUINO_ARCH_STM32
|
||||
// A simple I/O will be set to 0 by analogWrite()
|
||||
// A simple I/O will be set to 0 by set_pwm_duty()
|
||||
if (pin_status <= 1 && !PWM_PIN(pin)) return;
|
||||
#endif
|
||||
analogWrite(pin, pin_status);
|
||||
set_pwm_duty(pin, pin_status);
|
||||
}
|
||||
|
||||
#endif // DIRECT_PIN_CONTROL
|
||||
|
|
|
@ -342,7 +342,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
|
|||
void MarlinUI::_set_brightness() {
|
||||
#if PIN_EXISTS(TFT_BACKLIGHT)
|
||||
if (PWM_PIN(TFT_BACKLIGHT_PIN))
|
||||
analogWrite(pin_t(TFT_BACKLIGHT_PIN), brightness);
|
||||
set_pwm_duty(pin_t(TFT_BACKLIGHT_PIN), brightness);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -213,7 +213,7 @@ void MarlinUI::clear_lcd() {
|
|||
void MarlinUI::_set_brightness() {
|
||||
#if PIN_EXISTS(TFT_BACKLIGHT)
|
||||
if (PWM_PIN(TFT_BACKLIGHT_PIN))
|
||||
analogWrite(pin_t(TFT_BACKLIGHT_PIN), brightness);
|
||||
set_pwm_duty(pin_t(TFT_BACKLIGHT_PIN), brightness);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -1342,7 +1342,7 @@ void Endstops::update() {
|
|||
ES_REPORT_CHANGE(K_MAX);
|
||||
#endif
|
||||
SERIAL_ECHOLNPGM("\n");
|
||||
analogWrite(pin_t(LED_PIN), local_LED_status);
|
||||
set_pwm_duty(pin_t(LED_PIN), local_LED_status);
|
||||
local_LED_status ^= 255;
|
||||
old_live_state_local = live_state_local;
|
||||
}
|
||||
|
|
|
@ -1270,7 +1270,7 @@ void Planner::recalculate() {
|
|||
#elif ENABLED(FAST_PWM_FAN)
|
||||
#define _FAN_SET(F) set_pwm_duty(FAN##F##_PIN, CALC_FAN_SPEED(F));
|
||||
#else
|
||||
#define _FAN_SET(F) analogWrite(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F));
|
||||
#define _FAN_SET(F) set_pwm_duty(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F));
|
||||
#endif
|
||||
#define FAN_SET(F) do{ kickstart_fan(fan_speed, ms, F); _FAN_SET(F); }while(0)
|
||||
|
||||
|
@ -1393,8 +1393,8 @@ void Planner::check_axes_activity() {
|
|||
TERN_(AUTOTEMP, autotemp_task());
|
||||
|
||||
#if ENABLED(BARICUDA)
|
||||
TERN_(HAS_HEATER_1, analogWrite(pin_t(HEATER_1_PIN), tail_valve_pressure));
|
||||
TERN_(HAS_HEATER_2, analogWrite(pin_t(HEATER_2_PIN), tail_e_to_p_pressure));
|
||||
TERN_(HAS_HEATER_1, set_pwm_duty(pin_t(HEATER_1_PIN), tail_valve_pressure));
|
||||
TERN_(HAS_HEATER_2, set_pwm_duty(pin_t(HEATER_2_PIN), tail_e_to_p_pressure));
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -3253,7 +3253,7 @@ void Stepper::report_positions() {
|
|||
|
||||
#elif HAS_MOTOR_CURRENT_PWM
|
||||
|
||||
#define _WRITE_CURRENT_PWM(P) analogWrite(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE))
|
||||
#define _WRITE_CURRENT_PWM(P) set_pwm_duty(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE))
|
||||
switch (driver) {
|
||||
case 0:
|
||||
#if PIN_EXISTS(MOTOR_CURRENT_PWM_X)
|
||||
|
|
|
@ -887,11 +887,11 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) {
|
|||
SBI(fanState, pgm_read_byte(&fanBit[COOLER_FAN_INDEX]));
|
||||
#endif
|
||||
|
||||
#define _UPDATE_AUTO_FAN(P,D,A) do{ \
|
||||
if (PWM_PIN(P##_AUTO_FAN_PIN) && A < 255) \
|
||||
analogWrite(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \
|
||||
else \
|
||||
WRITE(P##_AUTO_FAN_PIN, D); \
|
||||
#define _UPDATE_AUTO_FAN(P,D,A) do{ \
|
||||
if (PWM_PIN(P##_AUTO_FAN_PIN) && A < 255) \
|
||||
set_pwm_duty(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \
|
||||
else \
|
||||
WRITE(P##_AUTO_FAN_PIN, D); \
|
||||
}while(0)
|
||||
|
||||
uint8_t fanDone = 0;
|
||||
|
|
Loading…
Reference in a new issue