|
@@ -10468,12 +10468,17 @@ inline void gcode_M907() {
|
10468
|
10468
|
void update_case_light() {
|
10469
|
10469
|
pinMode(CASE_LIGHT_PIN, OUTPUT); // digitalWrite doesn't set the port mode
|
10470
|
10470
|
if (case_light_on) {
|
10471
|
|
- if (USEABLE_HARDWARE_PWM(CASE_LIGHT_PIN)) {
|
|
10471
|
+ if (USEABLE_HARDWARE_PWM(CASE_LIGHT_PIN))
|
10472
|
10472
|
analogWrite(CASE_LIGHT_PIN, INVERT_CASE_LIGHT ? 255 - case_light_brightness : case_light_brightness);
|
10473
|
|
- }
|
10474
|
|
- else WRITE(CASE_LIGHT_PIN, INVERT_CASE_LIGHT ? LOW : HIGH);
|
|
10473
|
+ else
|
|
10474
|
+ WRITE(CASE_LIGHT_PIN, INVERT_CASE_LIGHT ? LOW : HIGH);
|
|
10475
|
+ }
|
|
10476
|
+ else {
|
|
10477
|
+ if (USEABLE_HARDWARE_PWM(CASE_LIGHT_PIN))
|
|
10478
|
+ analogWrite(CASE_LIGHT_PIN, INVERT_CASE_LIGHT ? 255 : 0);
|
|
10479
|
+ else
|
|
10480
|
+ WRITE(CASE_LIGHT_PIN, INVERT_CASE_LIGHT ? HIGH : LOW);
|
10475
|
10481
|
}
|
10476
|
|
- else WRITE(CASE_LIGHT_PIN, INVERT_CASE_LIGHT ? HIGH : LOW);
|
10477
|
10482
|
}
|
10478
|
10483
|
#endif // HAS_CASE_LIGHT
|
10479
|
10484
|
|