Merge pull request #1606 from thinkyhead/cleanup_stepper

Cleanup of stepper.cpp
This commit is contained in:
Scott Lahteine 2015-03-15 06:05:08 -07:00
commit bb4cb1b15a
20 changed files with 640 additions and 852 deletions

View File

@ -32,6 +32,9 @@
#include "WProgram.h" #include "WProgram.h"
#endif #endif
#define BIT(b) (1<<(b))
#define TEST(n,b) ((n)&BIT(b)!=0)
// Arduino < 1.0.0 does not define this, so we need to do it ourselves // Arduino < 1.0.0 does not define this, so we need to do it ourselves
#ifndef analogInputToDigitalPin #ifndef analogInputToDigitalPin
#define analogInputToDigitalPin(p) ((p) + 0xA0) #define analogInputToDigitalPin(p) ((p) + 0xA0)

View File

@ -47,7 +47,7 @@
#endif #endif
#endif #endif
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1 #if HAS_DIGIPOTSS
#include <SPI.h> #include <SPI.h>
#endif #endif

View File

@ -47,7 +47,7 @@
#endif #endif
#endif #endif
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1 #if HAS_DIGIPOTSS
#include <SPI.h> #include <SPI.h>
#endif #endif

View File

@ -76,7 +76,7 @@ void MarlinSerial::begin(long baud) {
#endif #endif
if (useU2X) { if (useU2X) {
M_UCSRxA = 1 << M_U2Xx; M_UCSRxA = BIT(M_U2Xx);
baud_setting = (F_CPU / 4 / baud - 1) / 2; baud_setting = (F_CPU / 4 / baud - 1) / 2;
} else { } else {
M_UCSRxA = 0; M_UCSRxA = 0;

View File

@ -97,14 +97,14 @@ class MarlinSerial { //: public Stream
} }
FORCE_INLINE void write(uint8_t c) { FORCE_INLINE void write(uint8_t c) {
while (!((M_UCSRxA) & (1 << M_UDREx))) while (!TEST(M_UCSRxA, M_UDREx))
; ;
M_UDRx = c; M_UDRx = c;
} }
FORCE_INLINE void checkRx(void) { FORCE_INLINE void checkRx(void) {
if ((M_UCSRxA & (1<<M_RXCx)) != 0) { if (TEST(M_UCSRxA, M_RXCx)) {
unsigned char c = M_UDRx; unsigned char c = M_UDRx;
int i = (unsigned int)(rx_buffer.head + 1) % RX_BUFFER_SIZE; int i = (unsigned int)(rx_buffer.head + 1) % RX_BUFFER_SIZE;

View File

@ -62,7 +62,7 @@
#include "Servo.h" #include "Servo.h"
#endif #endif
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1 #if HAS_DIGIPOTSS
#include <SPI.h> #include <SPI.h>
#endif #endif
@ -4210,7 +4210,7 @@ inline void gcode_M503() {
* M907: Set digital trimpot motor current using axis codes X, Y, Z, E, B, S * M907: Set digital trimpot motor current using axis codes X, Y, Z, E, B, S
*/ */
inline void gcode_M907() { inline void gcode_M907() {
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1 #if HAS_DIGIPOTSS
for (int i=0;i<NUM_AXIS;i++) for (int i=0;i<NUM_AXIS;i++)
if (code_seen(axis_codes[i])) digipot_current(i, code_value()); if (code_seen(axis_codes[i])) digipot_current(i, code_value());
if (code_seen('B')) digipot_current(4, code_value()); if (code_seen('B')) digipot_current(4, code_value());
@ -4233,7 +4233,7 @@ inline void gcode_M907() {
#endif #endif
} }
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1 #if HAS_DIGIPOTSS
/** /**
* M908: Control digital trimpot directly (M908 P<pin> S<current>) * M908: Control digital trimpot directly (M908 P<pin> S<current>)
@ -4245,7 +4245,7 @@ inline void gcode_M907() {
); );
} }
#endif // DIGIPOTSS_PIN #endif // HAS_DIGIPOTSS
// M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers. // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers.
inline void gcode_M350() { inline void gcode_M350() {
@ -4832,11 +4832,11 @@ void process_commands() {
gcode_M907(); gcode_M907();
break; break;
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1 #if HAS_DIGIPOTSS
case 908: // M908 Control digital trimpot directly. case 908: // M908 Control digital trimpot directly.
gcode_M908(); gcode_M908();
break; break;
#endif // DIGIPOTSS_PIN #endif // HAS_DIGIPOTSS
case 350: // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers. case 350: // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers.
gcode_M350(); gcode_M350();

View File

@ -35,14 +35,14 @@
*/ */
static void spiInit(uint8_t spiRate) { static void spiInit(uint8_t spiRate) {
// See avr processor documentation // See avr processor documentation
SPCR = (1 << SPE) | (1 << MSTR) | (spiRate >> 1); SPCR = BIT(SPE) | BIT(MSTR) | (spiRate >> 1);
SPSR = spiRate & 1 || spiRate == 6 ? 0 : 1 << SPI2X; SPSR = spiRate & 1 || spiRate == 6 ? 0 : BIT(SPI2X);
} }
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
/** SPI receive a byte */ /** SPI receive a byte */
static uint8_t spiRec() { static uint8_t spiRec() {
SPDR = 0XFF; SPDR = 0XFF;
while (!(SPSR & (1 << SPIF))) { /* Intentionally left empty */ } while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
return SPDR; return SPDR;
} }
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
@ -52,18 +52,18 @@ void spiRead(uint8_t* buf, uint16_t nbyte) {
if (nbyte-- == 0) return; if (nbyte-- == 0) return;
SPDR = 0XFF; SPDR = 0XFF;
for (uint16_t i = 0; i < nbyte; i++) { for (uint16_t i = 0; i < nbyte; i++) {
while (!(SPSR & (1 << SPIF))) { /* Intentionally left empty */ } while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
buf[i] = SPDR; buf[i] = SPDR;
SPDR = 0XFF; SPDR = 0XFF;
} }
while (!(SPSR & (1 << SPIF))) { /* Intentionally left empty */ } while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
buf[nbyte] = SPDR; buf[nbyte] = SPDR;
} }
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
/** SPI send a byte */ /** SPI send a byte */
static void spiSend(uint8_t b) { static void spiSend(uint8_t b) {
SPDR = b; SPDR = b;
while (!(SPSR & (1 << SPIF))) { /* Intentionally left empty */ } while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
} }
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
/** SPI send block - only one call so force inline */ /** SPI send block - only one call so force inline */
@ -71,12 +71,12 @@ static inline __attribute__((always_inline))
void spiSendBlock(uint8_t token, const uint8_t* buf) { void spiSendBlock(uint8_t token, const uint8_t* buf) {
SPDR = token; SPDR = token;
for (uint16_t i = 0; i < 512; i += 2) { for (uint16_t i = 0; i < 512; i += 2) {
while (!(SPSR & (1 << SPIF))) { /* Intentionally left empty */ } while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
SPDR = buf[i]; SPDR = buf[i];
while (!(SPSR & (1 << SPIF))) { /* Intentionally left empty */ } while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
SPDR = buf[i + 1]; SPDR = buf[i + 1];
} }
while (!(SPSR & (1 << SPIF))) { /* Intentionally left empty */ } while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
} }
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
#else // SOFTWARE_SPI #else // SOFTWARE_SPI

View File

@ -334,9 +334,9 @@ static inline __attribute__((always_inline))
void setPinMode(uint8_t pin, uint8_t mode) { void setPinMode(uint8_t pin, uint8_t mode) {
if (__builtin_constant_p(pin) && pin < digitalPinCount) { if (__builtin_constant_p(pin) && pin < digitalPinCount) {
if (mode) { if (mode) {
*digitalPinMap[pin].ddr |= 1 << digitalPinMap[pin].bit; *digitalPinMap[pin].ddr |= BIT(digitalPinMap[pin].bit);
} else { } else {
*digitalPinMap[pin].ddr &= ~(1 << digitalPinMap[pin].bit); *digitalPinMap[pin].ddr &= ~BIT(digitalPinMap[pin].bit);
} }
} else { } else {
badPinNumber(); badPinNumber();
@ -354,9 +354,9 @@ static inline __attribute__((always_inline))
void fastDigitalWrite(uint8_t pin, uint8_t value) { void fastDigitalWrite(uint8_t pin, uint8_t value) {
if (__builtin_constant_p(pin) && pin < digitalPinCount) { if (__builtin_constant_p(pin) && pin < digitalPinCount) {
if (value) { if (value) {
*digitalPinMap[pin].port |= 1 << digitalPinMap[pin].bit; *digitalPinMap[pin].port |= BIT(digitalPinMap[pin].bit);
} else { } else {
*digitalPinMap[pin].port &= ~(1 << digitalPinMap[pin].bit); *digitalPinMap[pin].port &= ~BIT(digitalPinMap[pin].bit);
} }
} else { } else {
badPinNumber(); badPinNumber();

View File

@ -171,9 +171,9 @@ static inline uint8_t FAT_SECOND(uint16_t fatTime) {
return 2*(fatTime & 0X1F); return 2*(fatTime & 0X1F);
} }
/** Default date for file timestamps is 1 Jan 2000 */ /** Default date for file timestamps is 1 Jan 2000 */
uint16_t const FAT_DEFAULT_DATE = ((2000 - 1980) << 9) | (1 << 5) | 1; uint16_t const FAT_DEFAULT_DATE = ((2000 - 1980) << 9) | BIT(5) | 1;
/** Default time for file timestamp is 1 am */ /** Default time for file timestamp is 1 am */
uint16_t const FAT_DEFAULT_TIME = (1 << 11); uint16_t const FAT_DEFAULT_TIME = BIT(11);
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
/** /**
* \class SdBaseFile * \class SdBaseFile

View File

@ -360,7 +360,7 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) {
blocksPerCluster_ = fbs->sectorsPerCluster; blocksPerCluster_ = fbs->sectorsPerCluster;
// determine shift that is same as multiply by blocksPerCluster_ // determine shift that is same as multiply by blocksPerCluster_
clusterSizeShift_ = 0; clusterSizeShift_ = 0;
while (blocksPerCluster_ != (1 << clusterSizeShift_)) { while (blocksPerCluster_ != BIT(clusterSizeShift_)) {
// error if not power of 2 // error if not power of 2
if (clusterSizeShift_++ > 7) goto fail; if (clusterSizeShift_++ > 7) goto fail;
} }

View File

@ -24,9 +24,9 @@
#define BLEN_A 0 #define BLEN_A 0
#define BLEN_B 1 #define BLEN_B 1
#define BLEN_C 2 #define BLEN_C 2
#define EN_A (1<<BLEN_A) #define EN_A BIT(BLEN_A)
#define EN_B (1<<BLEN_B) #define EN_B BIT(BLEN_B)
#define EN_C (1<<BLEN_C) #define EN_C BIT(BLEN_C)
#define LCD_CLICKED (buttons&EN_C) #define LCD_CLICKED (buttons&EN_C)
#endif #endif

View File

@ -13,7 +13,6 @@
*/ */
#ifndef MASK #ifndef MASK
/// MASKING- returns \f$2^PIN\f$
#define MASK(PIN) (1 << PIN) #define MASK(PIN) (1 << PIN)
#endif #endif

View File

@ -184,4 +184,6 @@
analogInputToDigitalPin(TEMP_BED_PIN) \ analogInputToDigitalPin(TEMP_BED_PIN) \
} }
#define HAS_DIGIPOTSS (DIGIPOTSS_PIN >= 0)
#endif //__PINS_H #endif //__PINS_H

View File

@ -623,37 +623,37 @@ block->steps_y = labs((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-positi
#ifndef COREXY #ifndef COREXY
if (target[X_AXIS] < position[X_AXIS]) if (target[X_AXIS] < position[X_AXIS])
{ {
block->direction_bits |= (1<<X_AXIS); block->direction_bits |= BIT(X_AXIS);
} }
if (target[Y_AXIS] < position[Y_AXIS]) if (target[Y_AXIS] < position[Y_AXIS])
{ {
block->direction_bits |= (1<<Y_AXIS); block->direction_bits |= BIT(Y_AXIS);
} }
#else #else
if (target[X_AXIS] < position[X_AXIS]) if (target[X_AXIS] < position[X_AXIS])
{ {
block->direction_bits |= (1<<X_HEAD); //AlexBorro: Save the real Extruder (head) direction in X Axis block->direction_bits |= BIT(X_HEAD); //AlexBorro: Save the real Extruder (head) direction in X Axis
} }
if (target[Y_AXIS] < position[Y_AXIS]) if (target[Y_AXIS] < position[Y_AXIS])
{ {
block->direction_bits |= (1<<Y_HEAD); //AlexBorro: Save the real Extruder (head) direction in Y Axis block->direction_bits |= BIT(Y_HEAD); //AlexBorro: Save the real Extruder (head) direction in Y Axis
} }
if ((target[X_AXIS]-position[X_AXIS]) + (target[Y_AXIS]-position[Y_AXIS]) < 0) if ((target[X_AXIS]-position[X_AXIS]) + (target[Y_AXIS]-position[Y_AXIS]) < 0)
{ {
block->direction_bits |= (1<<X_AXIS); //AlexBorro: Motor A direction (Incorrectly implemented as X_AXIS) block->direction_bits |= BIT(X_AXIS); //AlexBorro: Motor A direction (Incorrectly implemented as X_AXIS)
} }
if ((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-position[Y_AXIS]) < 0) if ((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-position[Y_AXIS]) < 0)
{ {
block->direction_bits |= (1<<Y_AXIS); //AlexBorro: Motor B direction (Incorrectly implemented as Y_AXIS) block->direction_bits |= BIT(Y_AXIS); //AlexBorro: Motor B direction (Incorrectly implemented as Y_AXIS)
} }
#endif #endif
if (target[Z_AXIS] < position[Z_AXIS]) if (target[Z_AXIS] < position[Z_AXIS])
{ {
block->direction_bits |= (1<<Z_AXIS); block->direction_bits |= BIT(Z_AXIS);
} }
if (target[E_AXIS] < position[E_AXIS]) if (target[E_AXIS] < position[E_AXIS])
{ {
block->direction_bits |= (1<<E_AXIS); block->direction_bits |= BIT(E_AXIS);
} }
block->active_extruder = extruder; block->active_extruder = extruder;
@ -864,7 +864,7 @@ Having the real displacement of the head, we can calculate the total movement le
old_direction_bits = block->direction_bits; old_direction_bits = block->direction_bits;
segment_time = lround((float)segment_time / speed_factor); segment_time = lround((float)segment_time / speed_factor);
if((direction_change & (1<<X_AXIS)) == 0) if((direction_change & BIT(X_AXIS)) == 0)
{ {
x_segment_time[0] += segment_time; x_segment_time[0] += segment_time;
} }
@ -874,7 +874,7 @@ Having the real displacement of the head, we can calculate the total movement le
x_segment_time[1] = x_segment_time[0]; x_segment_time[1] = x_segment_time[0];
x_segment_time[0] = segment_time; x_segment_time[0] = segment_time;
} }
if((direction_change & (1<<Y_AXIS)) == 0) if((direction_change & BIT(Y_AXIS)) == 0)
{ {
y_segment_time[0] += segment_time; y_segment_time[0] += segment_time;
} }

File diff suppressed because it is too large Load Diff

View File

@ -25,26 +25,26 @@
#include "stepper_indirection.h" #include "stepper_indirection.h"
#if EXTRUDERS > 3 #if EXTRUDERS > 3
#define WRITE_E_STEP(v) { if(current_block->active_extruder == 3) { E3_STEP_WRITE(v); } else { if(current_block->active_extruder == 2) { E2_STEP_WRITE(v); } else { if(current_block->active_extruder == 1) { E1_STEP_WRITE(v); } else { E0_STEP_WRITE(v); }}}} #define E_STEP_WRITE(v) { if(current_block->active_extruder == 3) { E3_STEP_WRITE(v); } else { if(current_block->active_extruder == 2) { E2_STEP_WRITE(v); } else { if(current_block->active_extruder == 1) { E1_STEP_WRITE(v); } else { E0_STEP_WRITE(v); }}}}
#define NORM_E_DIR() { if(current_block->active_extruder == 3) { E3_DIR_WRITE( !INVERT_E3_DIR); } else { if(current_block->active_extruder == 2) { E2_DIR_WRITE(!INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { E1_DIR_WRITE(!INVERT_E1_DIR); } else { E0_DIR_WRITE(!INVERT_E0_DIR); }}}} #define NORM_E_DIR() { if(current_block->active_extruder == 3) { E3_DIR_WRITE( !INVERT_E3_DIR); } else { if(current_block->active_extruder == 2) { E2_DIR_WRITE(!INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { E1_DIR_WRITE(!INVERT_E1_DIR); } else { E0_DIR_WRITE(!INVERT_E0_DIR); }}}}
#define REV_E_DIR() { if(current_block->active_extruder == 3) { E3_DIR_WRITE(INVERT_E3_DIR); } else { if(current_block->active_extruder == 2) { E2_DIR_WRITE(INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { E1_DIR_WRITE(INVERT_E1_DIR); } else { E0_DIR_WRITE(INVERT_E0_DIR); }}}} #define REV_E_DIR() { if(current_block->active_extruder == 3) { E3_DIR_WRITE(INVERT_E3_DIR); } else { if(current_block->active_extruder == 2) { E2_DIR_WRITE(INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { E1_DIR_WRITE(INVERT_E1_DIR); } else { E0_DIR_WRITE(INVERT_E0_DIR); }}}}
#elif EXTRUDERS > 2 #elif EXTRUDERS > 2
#define WRITE_E_STEP(v) { if(current_block->active_extruder == 2) { E2_STEP_WRITE(v); } else { if(current_block->active_extruder == 1) { E1_STEP_WRITE(v); } else { E0_STEP_WRITE(v); }}} #define E_STEP_WRITE(v) { if(current_block->active_extruder == 2) { E2_STEP_WRITE(v); } else { if(current_block->active_extruder == 1) { E1_STEP_WRITE(v); } else { E0_STEP_WRITE(v); }}}
#define NORM_E_DIR() { if(current_block->active_extruder == 2) { E2_DIR_WRITE(!INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { E1_DIR_WRITE(!INVERT_E1_DIR); } else { E0_DIR_WRITE(!INVERT_E0_DIR); }}} #define NORM_E_DIR() { if(current_block->active_extruder == 2) { E2_DIR_WRITE(!INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { E1_DIR_WRITE(!INVERT_E1_DIR); } else { E0_DIR_WRITE(!INVERT_E0_DIR); }}}
#define REV_E_DIR() { if(current_block->active_extruder == 2) { E2_DIR_WRITE(INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { E1_DIR_WRITE(INVERT_E1_DIR); } else { E0_DIR_WRITE(INVERT_E0_DIR); }}} #define REV_E_DIR() { if(current_block->active_extruder == 2) { E2_DIR_WRITE(INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { E1_DIR_WRITE(INVERT_E1_DIR); } else { E0_DIR_WRITE(INVERT_E0_DIR); }}}
#elif EXTRUDERS > 1 #elif EXTRUDERS > 1
#ifndef DUAL_X_CARRIAGE #ifndef DUAL_X_CARRIAGE
#define WRITE_E_STEP(v) { if(current_block->active_extruder == 1) { E1_STEP_WRITE(v); } else { E0_STEP_WRITE(v); }} #define E_STEP_WRITE(v) { if(current_block->active_extruder == 1) { E1_STEP_WRITE(v); } else { E0_STEP_WRITE(v); }}
#define NORM_E_DIR() { if(current_block->active_extruder == 1) { E1_DIR_WRITE(!INVERT_E1_DIR); } else { E0_DIR_WRITE(!INVERT_E0_DIR); }} #define NORM_E_DIR() { if(current_block->active_extruder == 1) { E1_DIR_WRITE(!INVERT_E1_DIR); } else { E0_DIR_WRITE(!INVERT_E0_DIR); }}
#define REV_E_DIR() { if(current_block->active_extruder == 1) { E1_DIR_WRITE(INVERT_E1_DIR); } else { E0_DIR_WRITE(INVERT_E0_DIR); }} #define REV_E_DIR() { if(current_block->active_extruder == 1) { E1_DIR_WRITE(INVERT_E1_DIR); } else { E0_DIR_WRITE(INVERT_E0_DIR); }}
#else #else
extern bool extruder_duplication_enabled; extern bool extruder_duplication_enabled;
#define WRITE_E_STEP(v) { if(extruder_duplication_enabled) { E0_STEP_WRITE(v); E1_STEP_WRITE(v); } else if(current_block->active_extruder == 1) { E1_STEP_WRITE(v); } else { E0_STEP_WRITE(v); }} #define E_STEP_WRITE(v) { if(extruder_duplication_enabled) { E0_STEP_WRITE(v); E1_STEP_WRITE(v); } else if(current_block->active_extruder == 1) { E1_STEP_WRITE(v); } else { E0_STEP_WRITE(v); }}
#define NORM_E_DIR() { if(extruder_duplication_enabled) { E0_DIR_WRITE(!INVERT_E0_DIR); E1_DIR_WRITE(!INVERT_E1_DIR); } else if(current_block->active_extruder == 1) { E1_DIR_WRITE(!INVERT_E1_DIR); } else { E0_DIR_WRITE(!INVERT_E0_DIR); }} #define NORM_E_DIR() { if(extruder_duplication_enabled) { E0_DIR_WRITE(!INVERT_E0_DIR); E1_DIR_WRITE(!INVERT_E1_DIR); } else if(current_block->active_extruder == 1) { E1_DIR_WRITE(!INVERT_E1_DIR); } else { E0_DIR_WRITE(!INVERT_E0_DIR); }}
#define REV_E_DIR() { if(extruder_duplication_enabled) { E0_DIR_WRITE(INVERT_E0_DIR); E1_DIR_WRITE(INVERT_E1_DIR); } else if(current_block->active_extruder == 1) { E1_DIR_WRITE(INVERT_E1_DIR); } else { E0_DIR_WRITE(INVERT_E0_DIR); }} #define REV_E_DIR() { if(extruder_duplication_enabled) { E0_DIR_WRITE(INVERT_E0_DIR); E1_DIR_WRITE(INVERT_E1_DIR); } else if(current_block->active_extruder == 1) { E1_DIR_WRITE(INVERT_E1_DIR); } else { E0_DIR_WRITE(INVERT_E0_DIR); }}
#endif #endif
#else #else
#define WRITE_E_STEP(v) E0_STEP_WRITE(v) #define E_STEP_WRITE(v) E0_STEP_WRITE(v)
#define NORM_E_DIR() E0_DIR_WRITE(!INVERT_E0_DIR) #define NORM_E_DIR() E0_DIR_WRITE(!INVERT_E0_DIR)
#define REV_E_DIR() E0_DIR_WRITE(INVERT_E0_DIR) #define REV_E_DIR() E0_DIR_WRITE(INVERT_E0_DIR)
#endif #endif

View File

@ -882,8 +882,8 @@ void tp_init()
{ {
#if MB(RUMBA) && ((TEMP_SENSOR_0==-1)||(TEMP_SENSOR_1==-1)||(TEMP_SENSOR_2==-1)||(TEMP_SENSOR_BED==-1)) #if MB(RUMBA) && ((TEMP_SENSOR_0==-1)||(TEMP_SENSOR_1==-1)||(TEMP_SENSOR_2==-1)||(TEMP_SENSOR_BED==-1))
//disable RUMBA JTAG in case the thermocouple extension is plugged on top of JTAG connector //disable RUMBA JTAG in case the thermocouple extension is plugged on top of JTAG connector
MCUCR=(1<<JTD); MCUCR=BIT(JTD);
MCUCR=(1<<JTD); MCUCR=BIT(JTD);
#endif #endif
// Finish init of mult extruder arrays // Finish init of mult extruder arrays
@ -941,13 +941,13 @@ void tp_init()
#endif //HEATER_0_USES_MAX6675 #endif //HEATER_0_USES_MAX6675
#ifdef DIDR2 #ifdef DIDR2
#define ANALOG_SELECT(pin) do{ if (pin < 8) DIDR0 |= 1 << pin; else DIDR2 |= 1 << (pin - 8); }while(0) #define ANALOG_SELECT(pin) do{ if (pin < 8) DIDR0 |= BIT(pin); else DIDR2 |= BIT(pin - 8); }while(0)
#else #else
#define ANALOG_SELECT(pin) do{ DIDR0 |= 1 << pin; }while(0) #define ANALOG_SELECT(pin) do{ DIDR0 |= BIT(pin); }while(0)
#endif #endif
// Set analog inputs // Set analog inputs
ADCSRA = 1<<ADEN | 1<<ADSC | 1<<ADIF | 0x07; ADCSRA = BIT(ADEN) | BIT(ADSC) | BIT(ADIF) | 0x07;
DIDR0 = 0; DIDR0 = 0;
#ifdef DIDR2 #ifdef DIDR2
DIDR2 = 0; DIDR2 = 0;
@ -974,7 +974,7 @@ void tp_init()
// Use timer0 for temperature measurement // Use timer0 for temperature measurement
// Interleave temperature interrupt with millies interrupt // Interleave temperature interrupt with millies interrupt
OCR0B = 128; OCR0B = 128;
TIMSK0 |= (1<<OCIE0B); TIMSK0 |= BIT(OCIE0B);
// Wait for temperature measurement to settle // Wait for temperature measurement to settle
delay(250); delay(250);
@ -1178,12 +1178,12 @@ void disable_heater() {
max6675_temp = 0; max6675_temp = 0;
#ifdef PRR #ifdef PRR
PRR &= ~(1<<PRSPI); PRR &= ~BIT(PRSPI);
#elif defined(PRR0) #elif defined(PRR0)
PRR0 &= ~(1<<PRSPI); PRR0 &= ~BIT(PRSPI);
#endif #endif
SPCR = (1<<MSTR) | (1<<SPE) | (1<<SPR0); SPCR = BIT(MSTR) | BIT(SPE) | BIT(SPR0);
// enable TT_MAX6675 // enable TT_MAX6675
WRITE(MAX6675_SS, 0); WRITE(MAX6675_SS, 0);
@ -1194,13 +1194,13 @@ void disable_heater() {
// read MSB // read MSB
SPDR = 0; SPDR = 0;
for (;(SPSR & (1<<SPIF)) == 0;); for (;(SPSR & BIT(SPIF)) == 0;);
max6675_temp = SPDR; max6675_temp = SPDR;
max6675_temp <<= 8; max6675_temp <<= 8;
// read LSB // read LSB
SPDR = 0; SPDR = 0;
for (;(SPSR & (1<<SPIF)) == 0;); for (;(SPSR & BIT(SPIF)) == 0;);
max6675_temp |= SPDR; max6675_temp |= SPDR;
// disable TT_MAX6675 // disable TT_MAX6675
@ -1250,7 +1250,7 @@ ISR(TIMER0_COMPB_vect) {
static unsigned long raw_temp_3_value = 0; static unsigned long raw_temp_3_value = 0;
static unsigned long raw_temp_bed_value = 0; static unsigned long raw_temp_bed_value = 0;
static TempState temp_state = StartupDelay; static TempState temp_state = StartupDelay;
static unsigned char pwm_count = (1 << SOFT_PWM_SCALE); static unsigned char pwm_count = BIT(SOFT_PWM_SCALE);
// Static members for each heater // Static members for each heater
#ifdef SLOW_PWM_HEATERS #ifdef SLOW_PWM_HEATERS
@ -1335,7 +1335,7 @@ ISR(TIMER0_COMPB_vect) {
if (soft_pwm_fan < pwm_count) WRITE_FAN(0); if (soft_pwm_fan < pwm_count) WRITE_FAN(0);
#endif #endif
pwm_count += (1 << SOFT_PWM_SCALE); pwm_count += BIT(SOFT_PWM_SCALE);
pwm_count &= 0x7f; pwm_count &= 0x7f;
#else // SLOW_PWM_HEATERS #else // SLOW_PWM_HEATERS
@ -1416,7 +1416,7 @@ ISR(TIMER0_COMPB_vect) {
if (soft_pwm_fan < pwm_count) WRITE_FAN(0); if (soft_pwm_fan < pwm_count) WRITE_FAN(0);
#endif //FAN_SOFT_PWM #endif //FAN_SOFT_PWM
pwm_count += (1 << SOFT_PWM_SCALE); pwm_count += BIT(SOFT_PWM_SCALE);
pwm_count &= 0x7f; pwm_count &= 0x7f;
// increment slow_pwm_count only every 64 pwm_count circa 65.5ms // increment slow_pwm_count only every 64 pwm_count circa 65.5ms
@ -1442,9 +1442,9 @@ ISR(TIMER0_COMPB_vect) {
#endif // SLOW_PWM_HEATERS #endif // SLOW_PWM_HEATERS
#define SET_ADMUX_ADCSRA(pin) ADMUX = (1 << REFS0) | (pin & 0x07); ADCSRA |= 1<<ADSC #define SET_ADMUX_ADCSRA(pin) ADMUX = BIT(REFS0) | (pin & 0x07); ADCSRA |= BIT(ADSC)
#ifdef MUX5 #ifdef MUX5
#define START_ADC(pin) if (pin > 7) ADCSRB = 1 << MUX5; else ADCSRB = 0; SET_ADMUX_ADCSRA(pin) #define START_ADC(pin) if (pin > 7) ADCSRB = BIT(MUX5); else ADCSRB = 0; SET_ADMUX_ADCSRA(pin)
#else #else
#define START_ADC(pin) ADCSRB = 0; SET_ADMUX_ADCSRA(pin) #define START_ADC(pin) ADCSRB = 0; SET_ADMUX_ADCSRA(pin)
#endif #endif

View File

@ -1426,7 +1426,7 @@ void lcd_buttons_update() {
WRITE(SHIFT_LD, HIGH); WRITE(SHIFT_LD, HIGH);
for(int8_t i = 0; i < 8; i++) { for(int8_t i = 0; i < 8; i++) {
newbutton_reprapworld_keypad >>= 1; newbutton_reprapworld_keypad >>= 1;
if (READ(SHIFT_OUT)) newbutton_reprapworld_keypad |= (1 << 7); if (READ(SHIFT_OUT)) newbutton_reprapworld_keypad |= BIT(7);
WRITE(SHIFT_CLK, HIGH); WRITE(SHIFT_CLK, HIGH);
WRITE(SHIFT_CLK, LOW); WRITE(SHIFT_CLK, LOW);
} }
@ -1439,7 +1439,7 @@ void lcd_buttons_update() {
unsigned char tmp_buttons = 0; unsigned char tmp_buttons = 0;
for(int8_t i=0; i<8; i++) { for(int8_t i=0; i<8; i++) {
newbutton >>= 1; newbutton >>= 1;
if (READ(SHIFT_OUT)) newbutton |= (1 << 7); if (READ(SHIFT_OUT)) newbutton |= BIT(7);
WRITE(SHIFT_CLK, HIGH); WRITE(SHIFT_CLK, HIGH);
WRITE(SHIFT_CLK, LOW); WRITE(SHIFT_CLK, LOW);
} }

View File

@ -57,20 +57,20 @@
void lcd_ignore_click(bool b=true); void lcd_ignore_click(bool b=true);
#ifdef NEWPANEL #ifdef NEWPANEL
#define EN_C (1<<BLEN_C) #define EN_C BIT(BLEN_C)
#define EN_B (1<<BLEN_B) #define EN_B BIT(BLEN_B)
#define EN_A (1<<BLEN_A) #define EN_A BIT(BLEN_A)
#define LCD_CLICKED (buttons&EN_C) #define LCD_CLICKED (buttons&EN_C)
#ifdef REPRAPWORLD_KEYPAD #ifdef REPRAPWORLD_KEYPAD
#define EN_REPRAPWORLD_KEYPAD_F3 (1<<BLEN_REPRAPWORLD_KEYPAD_F3) #define EN_REPRAPWORLD_KEYPAD_F3 BIT(BLEN_REPRAPWORLD_KEYPAD_F3)
#define EN_REPRAPWORLD_KEYPAD_F2 (1<<BLEN_REPRAPWORLD_KEYPAD_F2) #define EN_REPRAPWORLD_KEYPAD_F2 BIT(BLEN_REPRAPWORLD_KEYPAD_F2)
#define EN_REPRAPWORLD_KEYPAD_F1 (1<<BLEN_REPRAPWORLD_KEYPAD_F1) #define EN_REPRAPWORLD_KEYPAD_F1 BIT(BLEN_REPRAPWORLD_KEYPAD_F1)
#define EN_REPRAPWORLD_KEYPAD_UP (1<<BLEN_REPRAPWORLD_KEYPAD_UP) #define EN_REPRAPWORLD_KEYPAD_UP BIT(BLEN_REPRAPWORLD_KEYPAD_UP)
#define EN_REPRAPWORLD_KEYPAD_RIGHT (1<<BLEN_REPRAPWORLD_KEYPAD_RIGHT) #define EN_REPRAPWORLD_KEYPAD_RIGHT BIT(BLEN_REPRAPWORLD_KEYPAD_RIGHT)
#define EN_REPRAPWORLD_KEYPAD_MIDDLE (1<<BLEN_REPRAPWORLD_KEYPAD_MIDDLE) #define EN_REPRAPWORLD_KEYPAD_MIDDLE BIT(BLEN_REPRAPWORLD_KEYPAD_MIDDLE)
#define EN_REPRAPWORLD_KEYPAD_DOWN (1<<BLEN_REPRAPWORLD_KEYPAD_DOWN) #define EN_REPRAPWORLD_KEYPAD_DOWN BIT(BLEN_REPRAPWORLD_KEYPAD_DOWN)
#define EN_REPRAPWORLD_KEYPAD_LEFT (1<<BLEN_REPRAPWORLD_KEYPAD_LEFT) #define EN_REPRAPWORLD_KEYPAD_LEFT BIT(BLEN_REPRAPWORLD_KEYPAD_LEFT)
#define LCD_CLICKED ((buttons&EN_C) || (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_F1)) #define LCD_CLICKED ((buttons&EN_C) || (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_F1))
#define REPRAPWORLD_KEYPAD_MOVE_Z_UP (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_F2) #define REPRAPWORLD_KEYPAD_MOVE_Z_UP (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_F2)
@ -83,14 +83,14 @@
#endif //REPRAPWORLD_KEYPAD #endif //REPRAPWORLD_KEYPAD
#else #else
//atomic, do not change //atomic, do not change
#define B_LE (1<<BL_LE) #define B_LE BIT(BL_LE)
#define B_UP (1<<BL_UP) #define B_UP BIT(BL_UP)
#define B_MI (1<<BL_MI) #define B_MI BIT(BL_MI)
#define B_DW (1<<BL_DW) #define B_DW BIT(BL_DW)
#define B_RI (1<<BL_RI) #define B_RI BIT(BL_RI)
#define B_ST (1<<BL_ST) #define B_ST BIT(BL_ST)
#define EN_B (1<<BLEN_B) #define EN_B BIT(BLEN_B)
#define EN_A (1<<BLEN_A) #define EN_A BIT(BLEN_A)
#define LCD_CLICKED ((buttons&B_MI)||(buttons&B_ST)) #define LCD_CLICKED ((buttons&B_MI)||(buttons&B_ST))
#endif//NEWPANEL #endif//NEWPANEL

View File

@ -24,13 +24,13 @@
#define BLEN_B 1 #define BLEN_B 1
#define BLEN_A 0 #define BLEN_A 0
#define EN_B (1<<BLEN_B) // The two encoder pins are connected through BTN_EN1 and BTN_EN2 #define EN_B BIT(BLEN_B) // The two encoder pins are connected through BTN_EN1 and BTN_EN2
#define EN_A (1<<BLEN_A) #define EN_A BIT(BLEN_A)
#if defined(BTN_ENC) && BTN_ENC > -1 #if defined(BTN_ENC) && BTN_ENC > -1
// encoder click is directly connected // encoder click is directly connected
#define BLEN_C 2 #define BLEN_C 2
#define EN_C (1<<BLEN_C) #define EN_C BIT(BLEN_C)
#endif #endif
// //
@ -85,14 +85,14 @@
#define REPRAPWORLD_BTN_OFFSET 3 // bit offset into buttons for shift register values #define REPRAPWORLD_BTN_OFFSET 3 // bit offset into buttons for shift register values
#define EN_REPRAPWORLD_KEYPAD_F3 (1<<(BLEN_REPRAPWORLD_KEYPAD_F3+REPRAPWORLD_BTN_OFFSET)) #define EN_REPRAPWORLD_KEYPAD_F3 BIT((BLEN_REPRAPWORLD_KEYPAD_F3+REPRAPWORLD_BTN_OFFSET))
#define EN_REPRAPWORLD_KEYPAD_F2 (1<<(BLEN_REPRAPWORLD_KEYPAD_F2+REPRAPWORLD_BTN_OFFSET)) #define EN_REPRAPWORLD_KEYPAD_F2 BIT((BLEN_REPRAPWORLD_KEYPAD_F2+REPRAPWORLD_BTN_OFFSET))
#define EN_REPRAPWORLD_KEYPAD_F1 (1<<(BLEN_REPRAPWORLD_KEYPAD_F1+REPRAPWORLD_BTN_OFFSET)) #define EN_REPRAPWORLD_KEYPAD_F1 BIT((BLEN_REPRAPWORLD_KEYPAD_F1+REPRAPWORLD_BTN_OFFSET))
#define EN_REPRAPWORLD_KEYPAD_UP (1<<(BLEN_REPRAPWORLD_KEYPAD_UP+REPRAPWORLD_BTN_OFFSET)) #define EN_REPRAPWORLD_KEYPAD_UP BIT((BLEN_REPRAPWORLD_KEYPAD_UP+REPRAPWORLD_BTN_OFFSET))
#define EN_REPRAPWORLD_KEYPAD_RIGHT (1<<(BLEN_REPRAPWORLD_KEYPAD_RIGHT+REPRAPWORLD_BTN_OFFSET)) #define EN_REPRAPWORLD_KEYPAD_RIGHT BIT((BLEN_REPRAPWORLD_KEYPAD_RIGHT+REPRAPWORLD_BTN_OFFSET))
#define EN_REPRAPWORLD_KEYPAD_MIDDLE (1<<(BLEN_REPRAPWORLD_KEYPAD_MIDDLE+REPRAPWORLD_BTN_OFFSET)) #define EN_REPRAPWORLD_KEYPAD_MIDDLE BIT((BLEN_REPRAPWORLD_KEYPAD_MIDDLE+REPRAPWORLD_BTN_OFFSET))
#define EN_REPRAPWORLD_KEYPAD_DOWN (1<<(BLEN_REPRAPWORLD_KEYPAD_DOWN+REPRAPWORLD_BTN_OFFSET)) #define EN_REPRAPWORLD_KEYPAD_DOWN BIT((BLEN_REPRAPWORLD_KEYPAD_DOWN+REPRAPWORLD_BTN_OFFSET))
#define EN_REPRAPWORLD_KEYPAD_LEFT (1<<(BLEN_REPRAPWORLD_KEYPAD_LEFT+REPRAPWORLD_BTN_OFFSET)) #define EN_REPRAPWORLD_KEYPAD_LEFT BIT((BLEN_REPRAPWORLD_KEYPAD_LEFT+REPRAPWORLD_BTN_OFFSET))
#define LCD_CLICKED ((buttons&EN_C) || (buttons&EN_REPRAPWORLD_KEYPAD_F1)) #define LCD_CLICKED ((buttons&EN_C) || (buttons&EN_REPRAPWORLD_KEYPAD_F1))
#define REPRAPWORLD_KEYPAD_MOVE_Y_DOWN (buttons&EN_REPRAPWORLD_KEYPAD_DOWN) #define REPRAPWORLD_KEYPAD_MOVE_Y_DOWN (buttons&EN_REPRAPWORLD_KEYPAD_DOWN)
@ -113,12 +113,12 @@
#define BL_ST 2 #define BL_ST 2
//automatic, do not change //automatic, do not change
#define B_LE (1<<BL_LE) #define B_LE BIT(BL_LE)
#define B_UP (1<<BL_UP) #define B_UP BIT(BL_UP)
#define B_MI (1<<BL_MI) #define B_MI BIT(BL_MI)
#define B_DW (1<<BL_DW) #define B_DW BIT(BL_DW)
#define B_RI (1<<BL_RI) #define B_RI BIT(BL_RI)
#define B_ST (1<<BL_ST) #define B_ST BIT(BL_ST)
#define LCD_CLICKED (buttons&(B_MI|B_ST)) #define LCD_CLICKED (buttons&(B_MI|B_ST))
#endif #endif