Fix analogWrite ambiguity

This commit is contained in:
Scott Lahteine 2019-07-02 04:04:49 -05:00
parent d6265df962
commit d4415dcf59
8 changed files with 16 additions and 16 deletions

View file

@ -192,7 +192,7 @@ void HAL_adc_start_conversion(uint8_t adc_pin) {
HAL_adc_result = mv*1023.0/3300.0; HAL_adc_result = mv*1023.0/3300.0;
} }
void analogWrite(int pin, int value) { void analogWrite(pin_t pin, int value) {
if (!PWM_PIN(pin)) return; if (!PWM_PIN(pin)) return;

View file

@ -98,7 +98,7 @@ void _delay_ms(int delay);
int freeMemory(void); int freeMemory(void);
void analogWrite(int pin, int value); void analogWrite(pin_t pin, int value);
// EEPROM // EEPROM
void eeprom_write_byte(uint8_t *pos, unsigned char value); void eeprom_write_byte(uint8_t *pos, unsigned char value);

View file

@ -71,7 +71,7 @@ void update_case_light() {
#if DISABLED(CASE_LIGHT_NO_BRIGHTNESS) #if DISABLED(CASE_LIGHT_NO_BRIGHTNESS)
if (PWM_PIN(CASE_LIGHT_PIN)) if (PWM_PIN(CASE_LIGHT_PIN))
analogWrite(CASE_LIGHT_PIN, n10ct); analogWrite(pin_t(CASE_LIGHT_PIN), n10ct);
else else
#endif #endif
{ {

View file

@ -81,7 +81,7 @@ void controllerfan_update() {
// allows digital or PWM fan output to be used (see M42 handling) // allows digital or PWM fan output to be used (see M42 handling)
WRITE(CONTROLLER_FAN_PIN, speed); WRITE(CONTROLLER_FAN_PIN, speed);
analogWrite(CONTROLLER_FAN_PIN, speed); analogWrite(pin_t(CONTROLLER_FAN_PIN), speed);
} }
} }

View file

@ -41,7 +41,7 @@ void SpindleLaser::init() {
#endif #endif
#if ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM) #if ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)
SET_PWM(SPINDLE_LASER_PWM_PIN); SET_PWM(SPINDLE_LASER_PWM_PIN);
analogWrite(SPINDLE_LASER_PWM_PIN, SPINDLE_LASER_PWM_INVERT ? 255 : 0); // set to lowest speed analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_INVERT ? 255 : 0); // set to lowest speed
#endif #endif
} }
@ -55,7 +55,7 @@ void SpindleLaser::init() {
void SpindleLaser::set_ocr(const uint8_t ocr) { void SpindleLaser::set_ocr(const uint8_t ocr) {
WRITE(SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_ACTIVE_HIGH); // turn spindle on (active low) WRITE(SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_ACTIVE_HIGH); // turn spindle on (active low)
#if ENABLED(SPINDLE_LASER_PWM) #if ENABLED(SPINDLE_LASER_PWM)
analogWrite(SPINDLE_LASER_PWM_PIN, (SPINDLE_LASER_PWM_INVERT) ? 255 - ocr : ocr); analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), (SPINDLE_LASER_PWM_INVERT) ? 255 - ocr : ocr);
#endif #endif
} }
@ -76,7 +76,7 @@ void SpindleLaser::update_output() {
} }
else { // Convert RPM to PWM duty cycle else { // Convert RPM to PWM duty cycle
WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_HIGH); // Turn spindle off (active low) WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_HIGH); // Turn spindle off (active low)
analogWrite(SPINDLE_LASER_PWM_PIN, SPINDLE_LASER_PWM_INVERT ? 255 : 0); // Only write low byte analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_INVERT ? 255 : 0); // Only write low byte
} }
#else #else
WRITE(SPINDLE_LASER_ENA_PIN, ena ? SPINDLE_LASER_ACTIVE_HIGH : !SPINDLE_LASER_ACTIVE_HIGH); WRITE(SPINDLE_LASER_ENA_PIN, ena ? SPINDLE_LASER_ACTIVE_HIGH : !SPINDLE_LASER_ACTIVE_HIGH);

View file

@ -1289,10 +1289,10 @@ void Planner::check_axes_activity() {
#if ENABLED(BARICUDA) #if ENABLED(BARICUDA)
#if HAS_HEATER_1 #if HAS_HEATER_1
analogWrite(HEATER_1_PIN, tail_valve_pressure); analogWrite(pin_t(HEATER_1_PIN), tail_valve_pressure);
#endif #endif
#if HAS_HEATER_2 #if HAS_HEATER_2
analogWrite(HEATER_2_PIN, tail_e_to_p_pressure); analogWrite(pin_t(HEATER_2_PIN), tail_e_to_p_pressure);
#endif #endif
#endif #endif
} }

View file

@ -2502,7 +2502,7 @@ void Stepper::report_positions() {
if (WITHIN(driver, 0, COUNT(motor_current_setting) - 1)) if (WITHIN(driver, 0, COUNT(motor_current_setting) - 1))
motor_current_setting[driver] = current; // update motor_current_setting motor_current_setting[driver] = current; // update motor_current_setting
#define _WRITE_CURRENT_PWM(P) analogWrite(MOTOR_CURRENT_PWM_## P ##_PIN, 255L * current / (MOTOR_CURRENT_PWM_RANGE)) #define _WRITE_CURRENT_PWM(P) analogWrite(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE))
switch (driver) { switch (driver) {
case 0: case 0:
#if PIN_EXISTS(MOTOR_CURRENT_PWM_X) #if PIN_EXISTS(MOTOR_CURRENT_PWM_X)

View file

@ -701,7 +701,7 @@ int16_t Temperature::getHeaterPower(const int8_t heater) {
#define _UPDATE_AUTO_FAN(P,D,A) do{ \ #define _UPDATE_AUTO_FAN(P,D,A) do{ \
if (PWM_PIN(P##_AUTO_FAN_PIN) && A < 255) \ if (PWM_PIN(P##_AUTO_FAN_PIN) && A < 255) \
analogWrite(P##_AUTO_FAN_PIN, D ? A : 0); \ analogWrite(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \
else \ else \
WRITE(P##_AUTO_FAN_PIN, D); \ WRITE(P##_AUTO_FAN_PIN, D); \
}while(0) }while(0)