1
0
mirror of https://github.com/MarlinFirmware/Marlin.git synced 2024-11-27 13:56:24 +00:00

Misc cleanup, whitespace

This commit is contained in:
Scott Lahteine 2020-02-01 03:50:26 -06:00
parent e64b7a3ab2
commit 43d3463d5d
5 changed files with 10 additions and 11 deletions

View File

@ -20,7 +20,7 @@
*
*/
#include "../inc/MarlinConfig.h"
#include "../inc/MarlinConfigPre.h"
#if ENABLED(BARICUDA)

View File

@ -2460,10 +2460,10 @@ void Stepper::report_positions() {
#define BABYSTEP_AXIS(AXIS, INVERT, DIR) { \
const uint8_t old_dir = _READ_DIR(AXIS); \
_ENABLE_AXIS(AXIS); \
DELAY_NS(MINIMUM_STEPPER_PRE_DIR_DELAY); \
_ENABLE_AXIS(AXIS); \
DELAY_NS(MINIMUM_STEPPER_PRE_DIR_DELAY); \
_APPLY_DIR(AXIS, _INVERT_DIR(AXIS)^DIR^INVERT); \
DELAY_NS(MINIMUM_STEPPER_POST_DIR_DELAY); \
DELAY_NS(MINIMUM_STEPPER_POST_DIR_DELAY); \
_SAVE_START; \
_APPLY_STEP(AXIS)(!_INVERT_STEP_PIN(AXIS), true); \
_PULSE_WAIT; \

View File

@ -2608,9 +2608,8 @@ void Temperature::tick() {
#if ENABLED(FAN_SOFT_PWM)
#define _FAN_PWM(N) do{ \
uint8_t &spcf = soft_pwm_count_fan[N]; \
spcf = (spcf & pwm_mask) + (soft_pwm_amount_fan[N] >> 1); \
WRITE_FAN(N, spcf > pwm_mask ? HIGH : LOW); \
const uint8_t spcf = (soft_pwm_count_fan[N] & pwm_mask) + (soft_pwm_amount_fan[N] >> 1); \
WRITE_FAN(N, (spcf > pwm_mask)); \
}while(0)
#if HAS_FAN0
_FAN_PWM(0);

View File

@ -52,11 +52,11 @@
// Analog Inputs
//
#define TEMP_0_PIN 1
#define TEMP_1_PIN 2
#define TEMP_BED_PIN 4
#define TEMP_1_PIN 2
#define TEMP_BED_PIN 4
#ifndef TEMP_CHAMBER_PIN
#define TEMP_CHAMBER_PIN 5
#define TEMP_CHAMBER_PIN 5
#endif
//

View File

@ -292,7 +292,7 @@ int32_t SdVolume::freeClusterCount() {
if (cacheBuffer_.fat32[i] == 0) free++;
}
#ifdef ESP32
// Needed to reset the idle task watchdog timer on ESP32 as reading the complete FAT may easily
// Needed to reset the idle task watchdog timer on ESP32 as reading the complete FAT may easily
// block for 10+ seconds. yield() is insufficient since it blocks lower prio tasks (e.g., idle).
static millis_t nextTaskTime = 0;
const millis_t ms = millis();