Browse Source

Fix analogWrite ambiguity

Scott Lahteine 5 years ago
parent
commit
d4415dcf59

+ 1
- 1
Marlin/src/HAL/HAL_ESP32/HAL.cpp View File

192
   HAL_adc_result = mv*1023.0/3300.0;
192
   HAL_adc_result = mv*1023.0/3300.0;
193
 }
193
 }
194
 
194
 
195
-void analogWrite(int pin, int value) {
195
+void analogWrite(pin_t pin, int value) {
196
 
196
 
197
   if (!PWM_PIN(pin)) return;
197
   if (!PWM_PIN(pin)) return;
198
 
198
 

+ 1
- 1
Marlin/src/HAL/HAL_ESP32/HAL.h View File

98
 
98
 
99
 int freeMemory(void);
99
 int freeMemory(void);
100
 
100
 
101
-void analogWrite(int pin, int value);
101
+void analogWrite(pin_t pin, int value);
102
 
102
 
103
 // EEPROM
103
 // EEPROM
104
 void eeprom_write_byte(uint8_t *pos, unsigned char value);
104
 void eeprom_write_byte(uint8_t *pos, unsigned char value);

+ 1
- 1
Marlin/src/feature/caselight.cpp View File

71
 
71
 
72
     #if DISABLED(CASE_LIGHT_NO_BRIGHTNESS)
72
     #if DISABLED(CASE_LIGHT_NO_BRIGHTNESS)
73
       if (PWM_PIN(CASE_LIGHT_PIN))
73
       if (PWM_PIN(CASE_LIGHT_PIN))
74
-        analogWrite(CASE_LIGHT_PIN, n10ct);
74
+        analogWrite(pin_t(CASE_LIGHT_PIN), n10ct);
75
       else
75
       else
76
     #endif
76
     #endif
77
       {
77
       {

+ 1
- 1
Marlin/src/feature/controllerfan.cpp View File

81
 
81
 
82
     // allows digital or PWM fan output to be used (see M42 handling)
82
     // allows digital or PWM fan output to be used (see M42 handling)
83
     WRITE(CONTROLLER_FAN_PIN, speed);
83
     WRITE(CONTROLLER_FAN_PIN, speed);
84
-    analogWrite(CONTROLLER_FAN_PIN, speed);
84
+    analogWrite(pin_t(CONTROLLER_FAN_PIN), speed);
85
   }
85
   }
86
 }
86
 }
87
 
87
 

+ 4
- 4
Marlin/src/feature/spindle_laser.cpp View File

41
   #endif
41
   #endif
42
   #if ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)
42
   #if ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)
43
     SET_PWM(SPINDLE_LASER_PWM_PIN);
43
     SET_PWM(SPINDLE_LASER_PWM_PIN);
44
-    analogWrite(SPINDLE_LASER_PWM_PIN, SPINDLE_LASER_PWM_INVERT ? 255 : 0);  // set to lowest speed
44
+    analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_INVERT ? 255 : 0);  // set to lowest speed
45
   #endif
45
   #endif
46
 }
46
 }
47
 
47
 
55
   void SpindleLaser::set_ocr(const uint8_t ocr) {
55
   void SpindleLaser::set_ocr(const uint8_t ocr) {
56
     WRITE(SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_ACTIVE_HIGH); // turn spindle on (active low)
56
     WRITE(SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_ACTIVE_HIGH); // turn spindle on (active low)
57
     #if ENABLED(SPINDLE_LASER_PWM)
57
     #if ENABLED(SPINDLE_LASER_PWM)
58
-      analogWrite(SPINDLE_LASER_PWM_PIN, (SPINDLE_LASER_PWM_INVERT) ? 255 - ocr : ocr);
58
+      analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), (SPINDLE_LASER_PWM_INVERT) ? 255 - ocr : ocr);
59
     #endif
59
     #endif
60
   }
60
   }
61
 
61
 
75
       set_ocr(ocr_val & 0xFF);                                                            // ...limited to Atmel PWM max
75
       set_ocr(ocr_val & 0xFF);                                                            // ...limited to Atmel PWM max
76
     }
76
     }
77
     else {                                                                                // Convert RPM to PWM duty cycle
77
     else {                                                                                // Convert RPM to PWM duty cycle
78
-      WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_HIGH);                         // Turn spindle off (active low)
79
-      analogWrite(SPINDLE_LASER_PWM_PIN, SPINDLE_LASER_PWM_INVERT ? 255 : 0);             // Only write low byte
78
+      WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_HIGH);                           // Turn spindle off (active low)
79
+      analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_INVERT ? 255 : 0);      // Only write low byte
80
     }
80
     }
81
   #else
81
   #else
82
     WRITE(SPINDLE_LASER_ENA_PIN, ena ? SPINDLE_LASER_ACTIVE_HIGH : !SPINDLE_LASER_ACTIVE_HIGH);
82
     WRITE(SPINDLE_LASER_ENA_PIN, ena ? SPINDLE_LASER_ACTIVE_HIGH : !SPINDLE_LASER_ACTIVE_HIGH);

+ 2
- 2
Marlin/src/module/planner.cpp View File

1289
 
1289
 
1290
   #if ENABLED(BARICUDA)
1290
   #if ENABLED(BARICUDA)
1291
     #if HAS_HEATER_1
1291
     #if HAS_HEATER_1
1292
-      analogWrite(HEATER_1_PIN, tail_valve_pressure);
1292
+      analogWrite(pin_t(HEATER_1_PIN), tail_valve_pressure);
1293
     #endif
1293
     #endif
1294
     #if HAS_HEATER_2
1294
     #if HAS_HEATER_2
1295
-      analogWrite(HEATER_2_PIN, tail_e_to_p_pressure);
1295
+      analogWrite(pin_t(HEATER_2_PIN), tail_e_to_p_pressure);
1296
     #endif
1296
     #endif
1297
   #endif
1297
   #endif
1298
 }
1298
 }

+ 1
- 1
Marlin/src/module/stepper.cpp View File

2502
         if (WITHIN(driver, 0, COUNT(motor_current_setting) - 1))
2502
         if (WITHIN(driver, 0, COUNT(motor_current_setting) - 1))
2503
           motor_current_setting[driver] = current; // update motor_current_setting
2503
           motor_current_setting[driver] = current; // update motor_current_setting
2504
 
2504
 
2505
-        #define _WRITE_CURRENT_PWM(P) analogWrite(MOTOR_CURRENT_PWM_## P ##_PIN, 255L * current / (MOTOR_CURRENT_PWM_RANGE))
2505
+        #define _WRITE_CURRENT_PWM(P) analogWrite(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE))
2506
         switch (driver) {
2506
         switch (driver) {
2507
           case 0:
2507
           case 0:
2508
             #if PIN_EXISTS(MOTOR_CURRENT_PWM_X)
2508
             #if PIN_EXISTS(MOTOR_CURRENT_PWM_X)

+ 5
- 5
Marlin/src/module/temperature.cpp View File

699
         SBI(fanState, pgm_read_byte(&fanBit[CHAMBER_FAN_INDEX]));
699
         SBI(fanState, pgm_read_byte(&fanBit[CHAMBER_FAN_INDEX]));
700
     #endif
700
     #endif
701
 
701
 
702
-    #define _UPDATE_AUTO_FAN(P,D,A) do{             \
703
-      if (PWM_PIN(P##_AUTO_FAN_PIN) && A < 255)     \
704
-        analogWrite(P##_AUTO_FAN_PIN, D ? A : 0);   \
705
-      else                                          \
706
-        WRITE(P##_AUTO_FAN_PIN, D);                 \
702
+    #define _UPDATE_AUTO_FAN(P,D,A) do{                  \
703
+      if (PWM_PIN(P##_AUTO_FAN_PIN) && A < 255)          \
704
+        analogWrite(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \
705
+      else                                               \
706
+        WRITE(P##_AUTO_FAN_PIN, D);                      \
707
     }while(0)
707
     }while(0)
708
 
708
 
709
     uint8_t fanDone = 0;
709
     uint8_t fanDone = 0;

Loading…
Cancel
Save