Merge pull request #5118 from thinkyhead/rc_expanded_M43

Enhancements to M43 pins debugging
master
Scott Lahteine 8 years ago committed by GitHub
commit fa6bf12697

@ -148,6 +148,7 @@
* The '#' is necessary when calling from within sd files, as it stops buffer prereading
* M33 - Get the longname version of a path. (Requires LONG_FILENAME_HOST_SUPPORT)
* M42 - Change pin status via gcode: M42 P<pin> S<value>. LED pin assumed if P is omitted.
* M43 - Monitor pins & report changes - report active pins
* M48 - Measure Z Probe repeatability: M48 P<points> X<pos> Y<pos> V<level> E<engage> L<legs>. (Requires Z_MIN_PROBE_REPEATABILITY_TEST)
* M75 - Start the print job timer.
* M76 - Pause the print job timer.
@ -4675,20 +4676,43 @@ inline void gcode_M42() {
/**
* M43: Pin report and debug
*
* P<pin> Will read/watch a single pin
* W Watch pins for changes until reboot
* E<bool> Enable / disable background endstop monitoring
* - Machine continues to operate
* - Reports changes to endstops
* - Toggles LED when an endstop changes
*
* or
*
* P<pin> Pin to read or watch. If omitted, read/watch all pins.
* W<bool> Watch pins -reporting changes- until reset, click, or M108.
* I<bool> Flag to ignore Marlin's pin protection.
*
*/
inline void gcode_M43() {
int first_pin = 0, last_pin = DIO_COUNT - 1;
// Enable or disable endstop monitoring
if (code_seen('E')) {
endstop_monitor_flag = code_value_bool();
SERIAL_PROTOCOLPGM("endstop monitor ");
SERIAL_PROTOCOL(endstop_monitor_flag ? "en" : "dis");
SERIAL_PROTOCOLLNPGM("abled");
return;
}
// Get the range of pins to test or watch
int first_pin = 0, last_pin = NUM_DIGITAL_PINS - 1;
if (code_seen('P')) {
first_pin = last_pin = code_value_byte();
if (first_pin > DIO_COUNT - 1) return;
if (first_pin > NUM_DIGITAL_PINS - 1) return;
}
bool ignore_protection = code_seen('I') ? code_value_bool() : false;
// Watch until click, M108, or reset
if (code_seen('W') && code_value_bool()) { // watch digital pins
byte pin_state[last_pin - first_pin + 1];
for (int8_t pin = first_pin; pin <= last_pin; pin++) {
if (pin_is_protected(pin)) continue;
if (pin_is_protected(pin) && !ignore_protection) continue;
pinMode(pin, INPUT_PULLUP);
// if (IS_ANALOG(pin))
// pin_state[pin - first_pin] = analogRead(pin - analogInputToDigitalPin(0)); // int16_t pin_state[...]
@ -4720,10 +4744,12 @@ inline void gcode_M42() {
safe_delay(500);
}
return;
}
else // single pins report
for (int8_t pin = first_pin; pin <= last_pin; pin++)
report_pin_state(pin);
// Report current state of selected pin(s)
for (uint8_t pin = first_pin; pin <= last_pin; pin++)
report_pin_state_extended(pin, ignore_protection);
}
#endif // PINS_DEBUGGING

@ -20,152 +20,155 @@
*
*/
// How many DIO pins are defined?
#if defined(DIO85_PIN)
#define DIO_COUNT 86
#elif defined(DIO53_PIN)
#define DIO_COUNT 54
#elif defined(DIO47_PIN)
#define DIO_COUNT 48
#elif defined(DIO31_PIN)
#define DIO_COUNT 32
#elif defined(DIO21_PIN)
#define DIO_COUNT 22
#endif
#define _PIN_SAY(NAME) { SERIAL_ECHOPGM(STRINGIFY(NAME)); return true; }
#define PIN_SAY(NAME) if (pin == NAME) _PIN_SAY(_##NAME##_);
#define ANALOG_PIN_SAY(NAME) if (pin == analogInputToDigitalPin(NAME)) _PIN_SAY(_##NAME##_);
bool endstop_monitor_flag = false;
#define NAME_FORMAT "%-28s" // one place to specify the format of all the sources of names
// "-" left justify, "28" minimum width of name, pad with blanks
#define _PIN_SAY(NAME) { sprintf(buffer, NAME_FORMAT, NAME); SERIAL_ECHO(buffer); return true; }
#define PIN_SAY(NAME) if (pin == NAME) _PIN_SAY(#NAME);
#define _ANALOG_PIN_SAY(NAME) { sprintf(buffer, NAME_FORMAT, NAME); SERIAL_ECHO(buffer); pin_is_analog = true; return true; }
#define ANALOG_PIN_SAY(NAME) if (pin == analogInputToDigitalPin(NAME)) _ANALOG_PIN_SAY(#NAME);
#define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(0) && ((P) <= analogInputToDigitalPin(15) || (P) <= analogInputToDigitalPin(5)))
// Report pin name for a given fastio digital pin index
static bool report_pin_name(int8_t pin) {
int digitalRead_mod(int8_t pin) { // same as digitalRead except the PWM stop section has been removed
uint8_t port = digitalPinToPort(pin);
return (port != NOT_A_PIN) && (*portInputRegister(port) & digitalPinToBitMask(pin)) ? HIGH : LOW;
}
SERIAL_ECHO((int)pin);
SERIAL_CHAR(' ');
/**
* Report pin name for a given fastio digital pin index
*/
static bool report_pin_name(int8_t pin, bool &pin_is_analog) {
char buffer[30]; // for the sprintf statements
pin_is_analog = false; // default to digital pin
if (IS_ANALOG(pin)) {
SERIAL_CHAR('('); SERIAL_CHAR('A');
SERIAL_ECHO(int(pin - analogInputToDigitalPin(0)));
SERIAL_CHAR(')'); SERIAL_CHAR(' ');
sprintf(buffer, "(A%2d) ", int(pin - analogInputToDigitalPin(0)));
SERIAL_ECHO(buffer);
}
else SERIAL_ECHOPGM(" ");
#if defined(RXD) && RXD > -1
if (pin == 0) { SERIAL_ECHOPGM("RXD"); return true; }
#if defined(RXD) && RXD >= 0
if (pin == 0) { sprintf(buffer, NAME_FORMAT, "RXD"); SERIAL_ECHO(buffer); return true; }
#endif
#if defined(TXD) && TXD > -1
if (pin == 1) { SERIAL_ECHOPGM("TXD"); return true; }
#if defined(TXD) && TXD >= 0
if (pin == 1) { sprintf(buffer, NAME_FORMAT, "TXD"); SERIAL_ECHO(buffer); return true; }
#endif
#if PIN_EXISTS(SERVO0)
PIN_SAY(SERVO0_PIN);
// Pin list updated from 7 OCT RCBugfix branch
#if defined(__FD) && __FD >= 0
PIN_SAY(__FD)
#endif
#if PIN_EXISTS(SERVO1)
PIN_SAY(SERVO1_PIN);
#if defined(__FS) && __FS >= 0
PIN_SAY(__FS)
#endif
#if PIN_EXISTS(SERVO2)
PIN_SAY(SERVO2_PIN);
#if defined(__GD) && __GD >= 0
PIN_SAY(__GD)
#endif
#if PIN_EXISTS(SERVO3)
PIN_SAY(SERVO3_PIN);
#if defined(__GS) && __GS >= 0
PIN_SAY(__GS)
#endif
#if PIN_EXISTS(X_MIN)
PIN_SAY(X_MIN_PIN);
#if PIN_EXISTS(AVR_MISO)
PIN_SAY(AVR_MISO_PIN);
#endif
#if PIN_EXISTS(X_MAX)
PIN_SAY(X_MAX_PIN);
#if PIN_EXISTS(AVR_MOSI)
PIN_SAY(AVR_MOSI_PIN);
#endif
#if PIN_EXISTS(Y_MIN)
PIN_SAY(Y_MIN_PIN);
#if PIN_EXISTS(AVR_SCK)
PIN_SAY(AVR_SCK_PIN);
#endif
#if PIN_EXISTS(Y_MAX)
PIN_SAY(Y_MAX_PIN);
#if PIN_EXISTS(AVR_SS)
PIN_SAY(AVR_SS_PIN);
#endif
#if PIN_EXISTS(Z_MIN)
PIN_SAY(Z_MIN_PIN);
#if PIN_EXISTS(BEEPER)
PIN_SAY(BEEPER_PIN);
#endif
#if PIN_EXISTS(Z_MAX)
PIN_SAY(Z_MAX_PIN);
#if defined(BTN_CENTER) && BTN_CENTER >= 0
PIN_SAY(BTN_CENTER);
#endif
#if PIN_EXISTS(Z_MIN_PROBE)
PIN_SAY(Z_MIN_PROBE_PIN);
#if defined(BTN_DOWN) && BTN_DOWN >= 0
PIN_SAY(BTN_DOWN);
#endif
#if PIN_EXISTS(X_STEP)
PIN_SAY(X_STEP_PIN);
#if defined(BTN_DWN) && BTN_DWN >= 0
PIN_SAY(BTN_DWN);
#endif
#if PIN_EXISTS(X_DIR)
PIN_SAY(X_DIR_PIN);
#if defined(BTN_EN1) && BTN_EN1 >= 0
PIN_SAY(BTN_EN1);
#endif
#if PIN_EXISTS(X_ENABLE)
PIN_SAY(X_ENABLE_PIN);
#if defined(BTN_EN2) && BTN_EN2 >= 0
PIN_SAY(BTN_EN2);
#endif
#if PIN_EXISTS(X_MS1)
PIN_SAY(X_MS1_PIN);
#if defined(BTN_ENC) && BTN_ENC >= 0
PIN_SAY(BTN_ENC);
#endif
#if PIN_EXISTS(X_MS2)
PIN_SAY(X_MS2_PIN);
#if defined(BTN_HOME) && BTN_HOME >= 0
PIN_SAY(BTN_HOME);
#endif
#if PIN_EXISTS(X2_STEP)
PIN_SAY(X2_STEP_PIN);
#if defined(BTN_LEFT) && BTN_LEFT >= 0
PIN_SAY(BTN_LEFT);
#endif
#if PIN_EXISTS(X2_DIR)
PIN_SAY(X2_DIR_PIN);
#if defined(BTN_LFT) && BTN_LFT >= 0
PIN_SAY(BTN_LFT);
#endif
#if PIN_EXISTS(X2_ENABLE)
PIN_SAY(X2_ENABLE_PIN);
#if defined(BTN_RIGHT) && BTN_RIGHT >= 0
PIN_SAY(BTN_RIGHT);
#endif
#if PIN_EXISTS(Y_STEP)
PIN_SAY(Y_STEP_PIN);
#if defined(BTN_RT) && BTN_RT >= 0
PIN_SAY(BTN_RT);
#endif
#if PIN_EXISTS(Y_DIR)
PIN_SAY(Y_DIR_PIN);
#if defined(BTN_UP) && BTN_UP >= 0
PIN_SAY(BTN_UP);
#endif
#if PIN_EXISTS(Y_ENABLE)
PIN_SAY(Y_ENABLE_PIN);
#if PIN_EXISTS(CONTROLLERFAN)
PIN_SAY(CONTROLLERFAN_PIN);
#endif
#if PIN_EXISTS(Y_MS1)
PIN_SAY(Y_MS1_PIN);
#if PIN_EXISTS(DAC_DISABLE)
PIN_SAY(DAC_DISABLE_PIN);
#endif
#if PIN_EXISTS(Y_MS2)
PIN_SAY(Y_MS2_PIN);
#if defined(DAC_STEPPER_GAIN) && DAC_STEPPER_GAIN >= 0
PIN_SAY(DAC_STEPPER_GAIN);
#endif
#if PIN_EXISTS(Y2_STEP)
PIN_SAY(Y2_STEP_PIN);
#if defined(DAC_STEPPER_VREF) && DAC_STEPPER_VREF >= 0
PIN_SAY(DAC_STEPPER_VREF);
#endif
#if PIN_EXISTS(Y2_DIR)
PIN_SAY(Y2_DIR_PIN);
#if PIN_EXISTS(DEBUG)
PIN_SAY(DEBUG_PIN);
#endif
#if PIN_EXISTS(Y2_ENABLE)
PIN_SAY(Y2_ENABLE_PIN);
#if PIN_EXISTS(DIGIPOTSS)
PIN_SAY(DIGIPOTSS_PIN);
#endif
#if PIN_EXISTS(Z_STEP)
PIN_SAY(Z_STEP_PIN);
#if defined(DOGLCD_A0) && DOGLCD_A0 >= 0
PIN_SAY(DOGLCD_A0);
#endif
#if PIN_EXISTS(Z_DIR)
PIN_SAY(Z_DIR_PIN);
#if defined(DOGLCD_CS) && DOGLCD_CS >= 0
PIN_SAY(DOGLCD_CS);
#endif
#if PIN_EXISTS(Z_ENABLE)
PIN_SAY(Z_ENABLE_PIN);
#if defined(DOGLCD_MOSI) && DOGLCD_MOSI >= 0
PIN_SAY(DOGLCD_MOSI);
#endif
#if PIN_EXISTS(Z_MS1)
PIN_SAY(Z_MS1_PIN);
#if defined(DOGLCD_SCK) && DOGLCD_SCK >= 0
PIN_SAY(DOGLCD_SCK);
#endif
#if PIN_EXISTS(Z_MS2)
PIN_SAY(Z_MS2_PIN);
#if PIN_EXISTS(E0_ATT)
PIN_SAY(E0_ATT_PIN);
#endif
#if PIN_EXISTS(Z2_STEP)
PIN_SAY(Z2_STEP_PIN);
#if PIN_EXISTS(E0_AUTO_FAN)
PIN_SAY(E0_AUTO_FAN_PIN);
#endif
#if PIN_EXISTS(Z2_DIR)
PIN_SAY(Z2_DIR_PIN);
#if PIN_EXISTS(E1_AUTO_FAN)
PIN_SAY(E1_AUTO_FAN_PIN);
#endif
#if PIN_EXISTS(Z2_ENABLE)
PIN_SAY(Z2_ENABLE_PIN);
#if PIN_EXISTS(E2_AUTO_FAN)
PIN_SAY(E2_AUTO_FAN_PIN);
#endif
#if PIN_EXISTS(E0_STEP)
PIN_SAY(E0_STEP_PIN);
#if PIN_EXISTS(E3_AUTO_FAN)
PIN_SAY(E3_AUTO_FAN_PIN);
#endif
#if PIN_EXISTS(E0_DIR)
PIN_SAY(E0_DIR_PIN);
@ -179,8 +182,8 @@ static bool report_pin_name(int8_t pin) {
#if PIN_EXISTS(E0_MS2)
PIN_SAY(E0_MS2_PIN);
#endif
#if PIN_EXISTS(E1_STEP)
PIN_SAY(E1_STEP_PIN);
#if PIN_EXISTS(E0_STEP)
PIN_SAY(E0_STEP_PIN);
#endif
#if PIN_EXISTS(E1_DIR)
PIN_SAY(E1_DIR_PIN);
@ -194,8 +197,8 @@ static bool report_pin_name(int8_t pin) {
#if PIN_EXISTS(E1_MS2)
PIN_SAY(E1_MS2_PIN);
#endif
#if PIN_EXISTS(E2_STEP)
PIN_SAY(E2_STEP_PIN);
#if PIN_EXISTS(E1_STEP)
PIN_SAY(E1_STEP_PIN);
#endif
#if PIN_EXISTS(E2_DIR)
PIN_SAY(E2_DIR_PIN);
@ -203,8 +206,8 @@ static bool report_pin_name(int8_t pin) {
#if PIN_EXISTS(E2_ENABLE)
PIN_SAY(E2_ENABLE_PIN);
#endif
#if PIN_EXISTS(E3_STEP)
PIN_SAY(E3_STEP_PIN);
#if PIN_EXISTS(E2_STEP)
PIN_SAY(E2_STEP_PIN);
#endif
#if PIN_EXISTS(E3_DIR)
PIN_SAY(E3_DIR_PIN);
@ -212,8 +215,8 @@ static bool report_pin_name(int8_t pin) {
#if PIN_EXISTS(E3_ENABLE)
PIN_SAY(E3_ENABLE_PIN);
#endif
#if PIN_EXISTS(E4_STEP)
PIN_SAY(E4_STEP_PIN);
#if PIN_EXISTS(E3_STEP)
PIN_SAY(E3_STEP_PIN);
#endif
#if PIN_EXISTS(E4_DIR)
PIN_SAY(E4_DIR_PIN);
@ -221,6 +224,57 @@ static bool report_pin_name(int8_t pin) {
#if PIN_EXISTS(E4_ENABLE)
PIN_SAY(E4_ENABLE_PIN);
#endif
#if PIN_EXISTS(E4_STEP)
PIN_SAY(E4_STEP_PIN);
#endif
#if defined(encrot1) && encrot1 >= 0
PIN_SAY(encrot1);
#endif
#if defined(encrot2) && encrot2 >= 0
PIN_SAY(encrot2);
#endif
#if defined(encrot3) && encrot3 >= 0
PIN_SAY(encrot3);
#endif
#if defined(EXT_AUX_A0_IO) && EXT_AUX_A0_IO >= 0
PIN_SAY(EXT_AUX_A0_IO);
#endif
#if defined(EXT_AUX_A1) && EXT_AUX_A1 >= 0
PIN_SAY(EXT_AUX_A1);
#endif
#if defined(EXT_AUX_A1_IO) && EXT_AUX_A1_IO >= 0
PIN_SAY(EXT_AUX_A1_IO);
#endif
#if defined(EXT_AUX_A2) && EXT_AUX_A2 >= 0
PIN_SAY(EXT_AUX_A2);
#endif
#if defined(EXT_AUX_A2_IO) && EXT_AUX_A2_IO >= 0
PIN_SAY(EXT_AUX_A2_IO);
#endif
#if defined(EXT_AUX_A3) && EXT_AUX_A3 >= 0
PIN_SAY(EXT_AUX_A3);
#endif
#if defined(EXT_AUX_A3_IO) && EXT_AUX_A3_IO >= 0
PIN_SAY(EXT_AUX_A3_IO);
#endif
#if defined(EXT_AUX_A4) && EXT_AUX_A4 >= 0
PIN_SAY(EXT_AUX_A4);
#endif
#if defined(EXT_AUX_A4_IO) && EXT_AUX_A4_IO >= 0
PIN_SAY(EXT_AUX_A4_IO);
#endif
#if defined(EXT_AUX_PWM_D24) && EXT_AUX_PWM_D24 >= 0
PIN_SAY(EXT_AUX_PWM_D24);
#endif
#if defined(EXT_AUX_RX1_D2) && EXT_AUX_RX1_D2 >= 0
PIN_SAY(EXT_AUX_RX1_D2);
#endif
#if defined(EXT_AUX_SDA_D1) && EXT_AUX_SDA_D1 >= 0
PIN_SAY(EXT_AUX_SDA_D1);
#endif
#if defined(EXT_AUX_TX1_D3) && EXT_AUX_TX1_D3 >= 0
PIN_SAY(EXT_AUX_TX1_D3);
#endif
#if PIN_EXISTS(FAN)
PIN_SAY(FAN_PIN);
@ -231,20 +285,14 @@ static bool report_pin_name(int8_t pin) {
#if PIN_EXISTS(FAN2)
PIN_SAY(FAN2_PIN);
#endif
#if PIN_EXISTS(CONTROLLERFAN)
PIN_SAY(CONTROLLERFAN_PIN);
#endif
#if PIN_EXISTS(E0_AUTO_FAN)
PIN_SAY(E0_AUTO_FAN_PIN);
#endif
#if PIN_EXISTS(E1_AUTO_FAN)
PIN_SAY(E1_AUTO_FAN_PIN);
#if PIN_EXISTS(FIL_RUNOUT)
PIN_SAY(FIL_RUNOUT_PIN);
#endif
#if PIN_EXISTS(E2_AUTO_FAN)
PIN_SAY(E2_AUTO_FAN_PIN);
#if PIN_EXISTS(FILWIDTH)
ANALOG_PIN_SAY(FILWIDTH_PIN);
#endif
#if PIN_EXISTS(E3_AUTO_FAN)
PIN_SAY(E3_AUTO_FAN_PIN);
#if defined(GEN7_VERSION) && GEN7_VERSION >= 0
PIN_SAY(GEN7_VERSION);
#endif
#if PIN_EXISTS(HEATER_0)
PIN_SAY(HEATER_0_PIN);
@ -258,178 +306,594 @@ static bool report_pin_name(int8_t pin) {
#if PIN_EXISTS(HEATER_3)
PIN_SAY(HEATER_3_PIN);
#endif
#if PIN_EXISTS(HEATER_4)
PIN_SAY(HEATER_4_PIN);
#endif
#if PIN_EXISTS(HEATER_5)
PIN_SAY(HEATER_5_PIN);
#endif
#if PIN_EXISTS(HEATER_6)
PIN_SAY(HEATER_6_PIN);
#endif
#if PIN_EXISTS(HEATER_7)
PIN_SAY(HEATER_7_PIN);
#endif
#if PIN_EXISTS(HEATER_BED)
PIN_SAY(HEATER_BED_PIN);
#endif
#if PIN_EXISTS(X_ATT)
PIN_SAY(X_ATT_PIN);
#endif
#if PIN_EXISTS(Y_ATT)
PIN_SAY(Y_ATT_PIN);
#if defined(I2C_SCL) && I2C_SCL >= 0
PIN_SAY(I2C_SCL);
#endif
#if PIN_EXISTS(Z_ATT)
PIN_SAY(Z_ATT_PIN);
#if defined(I2C_SDA) && I2C_SDA >= 0
PIN_SAY(I2C_SDA);
#endif
#if PIN_EXISTS(E0_ATT)
PIN_SAY(E0_ATT_PIN);
#if PIN_EXISTS(KILL)
PIN_SAY(KILL_PIN);
#endif
#if PIN_EXISTS(TEMP_0)
ANALOG_PIN_SAY(TEMP_0_PIN);
#if PIN_EXISTS(LCD_BACKLIGHT)
PIN_SAY(LCD_BACKLIGHT_PIN);
#endif
#if PIN_EXISTS(TEMP_1)
ANALOG_PIN_SAY(TEMP_1_PIN);
#if defined(LCD_CONTRAST) && LCD_CONTRAST >= 0
PIN_SAY(LCD_CONTRAST);
#endif
#if PIN_EXISTS(TEMP_2)
ANALOG_PIN_SAY(TEMP_2_PIN);
#if defined(LCD_PINS_D4) && LCD_PINS_D4 >= 0
PIN_SAY(LCD_PINS_D4);
#endif
#if PIN_EXISTS(TEMP_3)
ANALOG_PIN_SAY(TEMP_3_PIN);
#if defined(LCD_PINS_D5) && LCD_PINS_D5 >= 0
PIN_SAY(LCD_PINS_D5);
#endif
#if PIN_EXISTS(TEMP_BED)
ANALOG_PIN_SAY(TEMP_BED_PIN);
#if defined(LCD_PINS_D6) && LCD_PINS_D6 >= 0
PIN_SAY(LCD_PINS_D6);
#endif
#if PIN_EXISTS(FILWIDTH)
ANALOG_PIN_SAY(FILWIDTH_PIN);
#if defined(LCD_PINS_D7) && LCD_PINS_D7 >= 0
PIN_SAY(LCD_PINS_D7);
#endif
#if PIN_EXISTS(BEEPER)
PIN_SAY(BEEPER_PIN);
#if defined(LCD_PINS_ENABLE) && LCD_PINS_ENABLE >= 0
PIN_SAY(LCD_PINS_ENABLE);
#endif
#if PIN_EXISTS(SLED)
PIN_SAY(SLED_PIN);
#if defined(LCD_PINS_RS) && LCD_PINS_RS >= 0
PIN_SAY(LCD_PINS_RS);
#endif
#if PIN_EXISTS(FIL_RUNOUT)
PIN_SAY(FIL_RUNOUT_PIN);
#if defined(LCD_SDSS) && LCD_SDSS >= 0
PIN_SAY(LCD_SDSS);
#endif
#if PIN_EXISTS(LED)
PIN_SAY(LED_PIN);
#endif
// #if defined(DEBUG_LED) && DEBUG_LED > -1
// PIN_SAY(DEBUG_LED);
// #endif
#if PIN_EXISTS(STAT_LED_RED)
PIN_SAY(STAT_LED_RED_PIN);
#endif
#if PIN_EXISTS(STAT_LED_BLUE)
PIN_SAY(STAT_LED_BLUE_PIN);
#endif
#if PIN_EXISTS(DIGIPOTSS)
PIN_SAY(DIGIPOTSS_PIN);
#if PIN_EXISTS(MAIN_VOLTAGE_MEASURE)
PIN_SAY(MAIN_VOLTAGE_MEASURE_PIN);
#endif
#if PIN_EXISTS(SCK)
PIN_SAY(SCK_PIN);
#if defined(MAX6675_SS) && MAX6675_SS >= 0
PIN_SAY(MAX6675_SS);
#endif
#if PIN_EXISTS(MISO)
PIN_SAY(MISO_PIN);
#endif
#if PIN_EXISTS(MOSFET_D)
PIN_SAY(MOSFET_D_PIN);
#endif
#if PIN_EXISTS(MOSI)
PIN_SAY(MOSI_PIN);
#endif
#if PIN_EXISTS(SS)
PIN_SAY(SS_PIN);
#if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
PIN_SAY(MOTOR_CURRENT_PWM_E_PIN);
#endif
#if PIN_EXISTS(MOTOR_CURRENT_PWM_XY)
PIN_SAY(MOTOR_CURRENT_PWM_XY_PIN);
#endif
#if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
PIN_SAY(MOTOR_CURRENT_PWM_Z_PIN);
#endif
#if defined(NUM_TLCS) && NUM_TLCS >= 0
PIN_SAY(NUM_TLCS);
#endif
#if PIN_EXISTS(PHOTOGRAPH)
PIN_SAY(PHOTOGRAPH_PIN);
#endif
#if PIN_EXISTS(PS_ON)
PIN_SAY(PS_ON_PIN);
#endif
#if PIN_EXISTS(RAMPS_D10)
PIN_SAY(RAMPS_D10_PIN);
#endif
#if PIN_EXISTS(RAMPS_D8)
PIN_SAY(RAMPS_D8_PIN);
#endif
#if PIN_EXISTS(RAMPS_D9)
PIN_SAY(RAMPS_D9_PIN);
#endif
#if PIN_EXISTS(RX_ENABLE)
PIN_SAY(RX_ENABLE_PIN);
#endif
#if PIN_EXISTS(SAFETY_TRIGGERED)
PIN_SAY(SAFETY_TRIGGERED_PIN);
#endif
#if PIN_EXISTS(SCK)
PIN_SAY(SCK_PIN);
#endif
#if defined(SCL) && SCL >= 0
PIN_SAY(SCL);
#endif
#if PIN_EXISTS(SD_DETECT)
PIN_SAY(SD_DETECT_PIN);
#endif
#if defined(SDPOWER) && SDPOWER > -1
#if defined(SDA) && SDA >= 0
PIN_SAY(SDA);
#endif
#if defined(SDPOWER) && SDPOWER >= 0
PIN_SAY(SDPOWER);
#endif
#if defined(SDSS) && SDSS > -1
#if defined(SDSS) && SDSS >= 0
PIN_SAY(SDSS);
#endif
#if defined(I2C_SCL) && I2C_SCL > -1
PIN_SAY(I2C_SCL);
#if PIN_EXISTS(SERVO0)
PIN_SAY(SERVO0_PIN);
#endif
#if defined(I2C_SDA) && I2C_SDA > -1
PIN_SAY(I2C_SDA);
#if PIN_EXISTS(SERVO1)
PIN_SAY(SERVO1_PIN);
#endif
#if defined(SCL) && SCL > -1
PIN_SAY(SCL);
#if PIN_EXISTS(SERVO2)
PIN_SAY(SERVO2_PIN);
#endif
#if defined(SDA) && SDA > -1
PIN_SAY(SDA);
#if PIN_EXISTS(SERVO3)
PIN_SAY(SERVO3_PIN);
#endif
#if PIN_EXISTS(PS_ON)
PIN_SAY(PS_ON_PIN);
#if defined(SHIFT_CLK) && SHIFT_CLK >= 0
PIN_SAY(SHIFT_CLK);
#endif
#if PIN_EXISTS(KILL)
PIN_SAY(KILL_PIN);
#if defined(SHIFT_EN) && SHIFT_EN >= 0
PIN_SAY(SHIFT_EN);
#endif
#if defined(SHIFT_LD) && SHIFT_LD >= 0
PIN_SAY(SHIFT_LD);
#endif
#if defined(SHIFT_OUT) && SHIFT_OUT >= 0
PIN_SAY(SHIFT_OUT);
#endif
#if PIN_EXISTS(SLED)
PIN_SAY(SLED_PIN);
#endif
#if PIN_EXISTS(SLEEP_WAKE)
PIN_SAY(SLEEP_WAKE_PIN);
#endif
#if PIN_EXISTS(SOL1)
PIN_SAY(SOL1_PIN);
#endif
#if PIN_EXISTS(SOL2)
PIN_SAY(SOL2_PIN);
#endif
#if PIN_EXISTS(SPINDLE_ENABLE)
PIN_SAY(SPINDLE_ENABLE_PIN);
#endif
#if PIN_EXISTS(SPINDLE_SPEED)
PIN_SAY(SPINDLE_SPEED_PIN);
#endif
#if PIN_EXISTS(SS)
PIN_SAY(SS_PIN);
#endif
#if PIN_EXISTS(STAT_LED_BLUE)
PIN_SAY(STAT_LED_BLUE_PIN);
#endif
#if PIN_EXISTS(STAT_LED_RED)
PIN_SAY(STAT_LED_RED_PIN);
#endif
#if PIN_EXISTS(STEPPER_RESET)
PIN_SAY(STEPPER_RESET_PIN);
#endif
#if PIN_EXISTS(SUICIDE)
PIN_SAY(SUICIDE_PIN);
#endif
#if PIN_EXISTS(DEBUG)
PIN_SAY(DEBUG_PIN);
#if defined(TC1) && TC1 >= 0
ANALOG_PIN_SAY(TC1);
#endif
#if PIN_EXISTS(PHOTOGRAPH)
PIN_SAY(PHOTOGRAPH_PIN);
#if defined(TC2) && TC2 >= 0
ANALOG_PIN_SAY(TC2);
#endif
#if PIN_EXISTS(BEEPER)
PIN_SAY(BEEPER_PIN);
#if PIN_EXISTS(TEMP_0)
ANALOG_PIN_SAY(TEMP_0_PIN);
#endif
#if defined(BTN_EN1) && BTN_EN1 > -1
PIN_SAY(BTN_EN1);
#if PIN_EXISTS(TEMP_1)
ANALOG_PIN_SAY(TEMP_1_PIN);
#endif
#if defined(BTN_EN2) && BTN_EN2 > -1
PIN_SAY(BTN_EN2);
#if PIN_EXISTS(TEMP_2)
ANALOG_PIN_SAY(TEMP_2_PIN);
#endif
#if defined(BTN_ENC) && BTN_ENC > -1
PIN_SAY(BTN_ENC);
#if PIN_EXISTS(TEMP_3)
ANALOG_PIN_SAY(TEMP_3_PIN);
#endif
#if defined(LCD_PINS_RS) && LCD_PINS_RS > -1
PIN_SAY(LCD_PINS_RS);
#if PIN_EXISTS(TEMP_4)
ANALOG_PIN_SAY(TEMP_4_PIN);
#endif
#if defined(LCD_PINS_ENABLE) && LCD_PINS_ENABLE > -1
PIN_SAY(LCD_PINS_ENABLE);
#if PIN_EXISTS(TEMP_BED)
ANALOG_PIN_SAY(TEMP_BED_PIN);
#endif
#if defined(LCD_PINS_D4) && LCD_PINS_D4 > -1
PIN_SAY(LCD_PINS_D4);
#if PIN_EXISTS(TEMP_X)
ANALOG_PIN_SAY(TEMP_X_PIN);
#endif
#if defined(LCD_PINS_D5) && LCD_PINS_D5 > -1
PIN_SAY(LCD_PINS_D5);
#if defined(TLC_BLANK_BIT) && TLC_BLANK_BIT >= 0
PIN_SAY(TLC_BLANK_BIT);
#endif
#if defined(LCD_PINS_D6) && LCD_PINS_D6 > -1
PIN_SAY(LCD_PINS_D6);
#if PIN_EXISTS(TLC_BLANK)
PIN_SAY(TLC_BLANK_PIN);
#endif
#if defined(LCD_PINS_D7) && LCD_PINS_D7 > -1
PIN_SAY(LCD_PINS_D7);
#if defined(TLC_CLOCK_BIT) && TLC_CLOCK_BIT >= 0
PIN_SAY(TLC_CLOCK_BIT);
#endif
#if PIN_EXISTS(RAMPS_D8)
PIN_SAY(RAMPS_D8_PIN);
#if PIN_EXISTS(TLC_CLOCK)
PIN_SAY(TLC_CLOCK_PIN);
#endif
#if PIN_EXISTS(RAMPS_D9)
PIN_SAY(RAMPS_D9_PIN);
#if defined(TLC_DATA_BIT) && TLC_DATA_BIT >= 0
PIN_SAY(TLC_DATA_BIT);
#endif
#if PIN_EXISTS(RAMPS_D10)
PIN_SAY(RAMPS_D10_PIN);
#if PIN_EXISTS(TLC_DATA)
PIN_SAY(TLC_DATA_PIN);
#endif
#if PIN_EXISTS(MOSFET_D)
PIN_SAY(MOSFET_D_PIN);
#if PIN_EXISTS(TLC_XLAT)
PIN_SAY(TLC_XLAT_PIN);
#endif
#if PIN_EXISTS(TX_ENABLE)
PIN_SAY(TX_ENABLE_PIN);
#endif
#if PIN_EXISTS(RX_ENABLE)
PIN_SAY(RX_ENABLE_PIN);
#if defined(UNUSED_PWM) && UNUSED_PWM >= 0
PIN_SAY(UNUSED_PWM);
#endif
#if PIN_EXISTS(X_ATT)
PIN_SAY(X_ATT_PIN);
#endif
#if PIN_EXISTS(X_DIR)
PIN_SAY(X_DIR_PIN);
#endif
#if PIN_EXISTS(X_ENABLE)
PIN_SAY(X_ENABLE_PIN);
#endif
#if PIN_EXISTS(X_MAX)
PIN_SAY(X_MAX_PIN);
#endif
#if PIN_EXISTS(X_MIN)
PIN_SAY(X_MIN_PIN);
#endif
#if PIN_EXISTS(X_MS1)
PIN_SAY(X_MS1_PIN);
#endif
#if PIN_EXISTS(X_MS2)
PIN_SAY(X_MS2_PIN);
#endif
#if PIN_EXISTS(X_STEP)
PIN_SAY(X_STEP_PIN);
#endif
#if PIN_EXISTS(X_STOP)
PIN_SAY(X_STOP_PIN);
#endif
#if PIN_EXISTS(X2_DIR)
PIN_SAY(X2_DIR_PIN);
#endif
#if PIN_EXISTS(X2_ENABLE)
PIN_SAY(X2_ENABLE_PIN);
#endif
#if PIN_EXISTS(X2_STEP)
PIN_SAY(X2_STEP_PIN);
#endif
#if PIN_EXISTS(Y_ATT)
PIN_SAY(Y_ATT_PIN);
#endif
#if PIN_EXISTS(Y_DIR)
PIN_SAY(Y_DIR_PIN);
#endif
#if PIN_EXISTS(Y_ENABLE)
PIN_SAY(Y_ENABLE_PIN);
#endif
#if PIN_EXISTS(Y_MAX)
PIN_SAY(Y_MAX_PIN);
#endif
#if PIN_EXISTS(Y_MIN)
PIN_SAY(Y_MIN_PIN);
#endif
#if PIN_EXISTS(Y_MS1)
PIN_SAY(Y_MS1_PIN);
#endif
#if PIN_EXISTS(Y_MS2)
PIN_SAY(Y_MS2_PIN);
#endif
#if PIN_EXISTS(Y_STEP)
PIN_SAY(Y_STEP_PIN);
#endif
#if PIN_EXISTS(Y_STOP)
PIN_SAY(Y_STOP_PIN);
#endif
#if PIN_EXISTS(Y2_DIR)
PIN_SAY(Y2_DIR_PIN);
#endif
#if PIN_EXISTS(Y2_ENABLE)
PIN_SAY(Y2_ENABLE_PIN);
#endif
#if PIN_EXISTS(Y2_STEP)
PIN_SAY(Y2_STEP_PIN);
#endif
#if PIN_EXISTS(Z_ATT)
PIN_SAY(Z_ATT_PIN);
#endif
#if PIN_EXISTS(Z_DIR)
PIN_SAY(Z_DIR_PIN);
#endif
#if PIN_EXISTS(Z_ENABLE)
PIN_SAY(Z_ENABLE_PIN);
#endif
#if PIN_EXISTS(Z_MAX)
PIN_SAY(Z_MAX_PIN);
#endif
#if PIN_EXISTS(Z_MIN)
PIN_SAY(Z_MIN_PIN);
#endif
#if PIN_EXISTS(Z_MIN_PROBE)
PIN_SAY(Z_MIN_PROBE_PIN);
#endif
#if PIN_EXISTS(Z_MS1)
PIN_SAY(Z_MS1_PIN);
#endif
#if PIN_EXISTS(Z_MS2)
PIN_SAY(Z_MS2_PIN);
#endif
#if PIN_EXISTS(Z_STEP)
PIN_SAY(Z_STEP_PIN);
#endif
#if PIN_EXISTS(Z_STOP)
PIN_SAY(Z_STOP_PIN);
#endif
#if PIN_EXISTS(Z2_DIR)
PIN_SAY(Z2_DIR_PIN);
#endif
#if PIN_EXISTS(Z2_ENABLE)
PIN_SAY(Z2_ENABLE_PIN);
#endif
#if PIN_EXISTS(Z2_STEP)
PIN_SAY(Z2_STEP_PIN);
#endif
sprintf(buffer, NAME_FORMAT, "<unused> ");
SERIAL_ECHO(buffer);
SERIAL_ECHOPGM("<unused>");
return false;
} // report_pin_name
#define PWM_PRINT(V) do{ sprintf(buffer, "PWM: %4d", V); SERIAL_ECHO(buffer); }while(0)
#define PWM_CASE(N) \
case TIMER##N: \
if (TCCR##N & (_BV(COM## N ##1) | _BV(COM## N ##0))) { \
PWM_PRINT(OCR##N); \
return true; \
} else return false
/**
* Print a pin's PWM status.
* Return true if it's currently a PWM pin.
*/
static bool PWM_status(uint8_t pin) {
char buffer[20]; // for the sprintf statements
switch(digitalPinToTimer(pin)) {
#if defined(TCCR0A) && defined(COM0A1)
PWM_CASE(0A);
PWM_CASE(0B);
#endif
#if defined(TCCR1A) && defined(COM1A1)
PWM_CASE(1A);
PWM_CASE(1B);
PWM_CASE(1C);
#endif
#if defined(TCCR2A) && defined(COM2A1)
PWM_CASE(2A);
PWM_CASE(2B);
#endif
#if defined(TCCR3A) && defined(COM3A1)
PWM_CASE(3A);
PWM_CASE(3B);
PWM_CASE(3C);
#endif
#ifdef TCCR4A
PWM_CASE(4A);
PWM_CASE(4B);
PWM_CASE(4C);
#endif
#if defined(TCCR5A) && defined(COM5A1)
PWM_CASE(5A);
PWM_CASE(5B);
PWM_CASE(5C);
#endif
case NOT_ON_TIMER:
default:
return false;
}
SERIAL_PROTOCOLPGM(" ");
} //PWM_status
#define WGM_MAKE3(N) ((TEST(TCCR##N##B, WGM##N##2) >> 1) | (TCCR##N##A & (_BV(WGM##N##0) | _BV(WGM##N##1))))
#define WGM_MAKE4(N) (WGM_MAKE3(N) | (TEST(TCCR##N##B, WGM##N##3) >> 1))
#define TIMER_PREFIX(T,L,N) do{ \
WGM = WGM_MAKE##N(T); \
SERIAL_PROTOCOLPGM(" TIMER"); \
SERIAL_PROTOCOLPGM(STRINGIFY(T) STRINGIFY(L)); \
SERIAL_PROTOCOLPAIR(" WGM: ", WGM); \
SERIAL_PROTOCOLPAIR(" TIMSK" STRINGIFY(T) ": ", TIMSK##T); \
}while(0)
#define WGM_TEST1 (WGM == 0 || WGM == 2 || WGM == 4 || WGM == 6)
#define WGM_TEST2 (WGM == 0 || WGM == 4 || WGM == 12 || WGM == 13)
static void err_is_counter() {
SERIAL_PROTOCOLPGM(" Can't ");
SERIAL_PROTOCOLPGM("be used as a PWM because ");
SERIAL_PROTOCOLPGM("of counter mode");
}
static void err_is_interrupt() {
SERIAL_PROTOCOLPGM(" Can't ");
SERIAL_PROTOCOLPGM("be used as a PWM because ");
SERIAL_PROTOCOLPGM("it's ");
SERIAL_PROTOCOLPGM("being used as an interrupt");
}
static void err_prob_interrupt() {
SERIAL_PROTOCOLPGM(" Probably can't ");
SERIAL_PROTOCOLPGM("be used as a PWM because ");
SERIAL_PROTOCOLPGM("counter/timer is ");
SERIAL_PROTOCOLPGM("being used as an interrupt");
}
static void can_be_used() { SERIAL_PROTOCOLPGM(" can be used as PWM "); }
static void PWM_details(uint8_t pin) {
uint8_t WGM;
switch(digitalPinToTimer(pin)) {
#if defined(TCCR0A) && defined(COM0A1)
case TIMER0A:
TIMER_PREFIX(0,A,3);
if (WGM_TEST1) err_is_counter();
else if (TEST(TIMSK0, OCIE0A)) err_is_interrupt();
else if (TEST(TIMSK0, TOIE0)) err_prob_interrupt();
else can_be_used();
break;
case TIMER0B:
TIMER_PREFIX(0,B,3);
if (WGM_TEST1) err_is_counter();
else if (TEST(TIMSK0, OCIE0B)) err_is_interrupt();
else if (TEST(TIMSK0, TOIE0)) err_prob_interrupt();
else can_be_used();
break;
#endif
#if defined(TCCR1A) && defined(COM1A1)
case TIMER1A:
TIMER_PREFIX(1,A,4);
if (WGM_TEST2) err_is_counter();
else if (TEST(TIMSK1, OCIE1A)) err_is_interrupt();
else if (TIMSK1 & (_BV(TOIE1) | _BV(ICIE1))) err_prob_interrupt();
else can_be_used();
break;
case TIMER1B:
TIMER_PREFIX(1,B,4);
if (WGM_TEST2) err_is_counter();
else if (TEST(TIMSK1, OCIE1B)) err_is_interrupt();
else if (TIMSK1 & (_BV(TOIE1) | _BV(ICIE1))) err_prob_interrupt();
else can_be_used();
break;
case TIMER1C:
TIMER_PREFIX(1,C,4);
if (WGM_TEST2) err_is_counter();
else if (TEST(TIMSK1, OCIE1C)) err_is_interrupt();
else if (TIMSK1 & (_BV(TOIE1) | _BV(ICIE1))) err_prob_interrupt();
else can_be_used();
break;
#endif
#if defined(TCCR2A) && defined(COM2A1)
case TIMER2A:
TIMER_PREFIX(2,A,3);
if (WGM_TEST1) err_is_counter();
else if (TIMSK2 & (_BV(TOIE2) | _BV(OCIE2A))) err_is_interrupt();
else if (TEST(TIMSK2, TOIE2)) err_prob_interrupt();
else can_be_used();
break;
case TIMER2B:
TIMER_PREFIX(2,B,3);
if (WGM_TEST1) err_is_counter();
else if (TEST(TIMSK2, OCIE2B)) err_is_interrupt();
else if (TEST(TIMSK2, TOIE2)) err_prob_interrupt();
else can_be_used();
break;
#endif
#if defined(TCCR3A) && defined(COM3A1)
case TIMER3A:
TIMER_PREFIX(3,A,3);
if (WGM_TEST2) err_is_counter();
else if (TEST(TIMSK3, OCIE3A)) err_is_interrupt();
else if (TIMSK3 & (_BV(TOIE3) | _BV(ICIE3))) err_prob_interrupt();
else can_be_used();
break;
case TIMER3B:
TIMER_PREFIX(3,B,3);
if (WGM_TEST2) err_is_counter();
else if (TEST(TIMSK3, OCIE3B)) err_is_interrupt();
else if (TIMSK3 & (_BV(TOIE3) | _BV(ICIE3))) err_prob_interrupt();
else can_be_used();
break;
case TIMER3C:
TIMER_PREFIX(3,C,3);
if (WGM_TEST2) err_is_counter();
else if (TEST(TIMSK3, OCIE3C)) err_is_interrupt();
else if (TIMSK3 & (_BV(TOIE3) | _BV(ICIE3))) err_prob_interrupt();
else can_be_used();
break;
#endif
#ifdef TCCR4A
case TIMER4A:
TIMER_PREFIX(4,A,4);
if (WGM_TEST2) err_is_counter();
else if (TEST(TIMSK4, OCIE4A)) err_is_interrupt();
else if (TIMSK4 & (_BV(TOIE4) | _BV(ICIE4))) err_prob_interrupt();
else can_be_used();
break;
case TIMER4B:
TIMER_PREFIX(4,B,4);
if (WGM_TEST2) err_is_counter();
else if (TEST(TIMSK4, OCIE4B)) err_is_interrupt();
else if (TIMSK4 & (_BV(TOIE4) | _BV(ICIE4))) err_prob_interrupt();
else can_be_used();
break;
case TIMER4C:
TIMER_PREFIX(4,C,4);
if (WGM_TEST2) err_is_counter();
else if (TEST(TIMSK4, OCIE4C)) err_is_interrupt();
else if (TIMSK4 & (_BV(TOIE4) | _BV(ICIE4))) err_prob_interrupt();
else can_be_used();
break;
#endif
#if defined(TCCR5A) && defined(COM5A1)
case TIMER5A:
TIMER_PREFIX(5,A,4);
if (WGM_TEST2) err_is_counter();
else if (TEST(TIMSK5, OCIE5A)) err_is_interrupt();
else if (TIMSK5 & (_BV(TOIE5) | _BV(ICIE5))) err_prob_interrupt();
else can_be_used();
break;
case TIMER5B:
TIMER_PREFIX(5,B,4);
if (WGM_TEST2) err_is_counter();
else if (TEST(TIMSK5, OCIE5B)) err_is_interrupt();
else if (TIMSK5 & (_BV(TOIE5) | _BV(ICIE5))) err_prob_interrupt();
else can_be_used();
break;
case TIMER5C:
TIMER_PREFIX(5,C,4);
if (WGM_TEST2) err_is_counter();
else if (TEST(TIMSK5, OCIE5C)) err_is_interrupt();
else if (TIMSK5 & (_BV(TOIE5) | _BV(ICIE5))) err_prob_interrupt();
else can_be_used();
break;
#endif
case NOT_ON_TIMER: break;
}
SERIAL_PROTOCOLPGM(" ");
} // PWM_details
inline void report_pin_state(int8_t pin) {
if (report_pin_name(pin)) {
SERIAL_ECHO((int)pin);
SERIAL_CHAR(' ');
bool dummy;
if (report_pin_name(pin, dummy)) {
if (pin_is_protected(pin))
SERIAL_ECHOPGM(" (protected)");
else {
@ -445,3 +909,44 @@ inline void report_pin_state(int8_t pin) {
}
SERIAL_EOL;
}
bool get_pinMode(int8_t pin) { return *portModeRegister(digitalPinToPort(pin)) & digitalPinToBitMask(pin); }
// pretty report with PWM info
inline void report_pin_state_extended(int8_t pin, bool ignore) {
char buffer[30]; // for the sprintf statements
// report pin number
sprintf(buffer, "PIN:% 3d ", pin);
SERIAL_ECHO(buffer);
// report pin name
bool analog_pin;
report_pin_name(pin, analog_pin);
// report pin state
if (pin_is_protected(pin) && !ignore)
SERIAL_ECHOPGM("protected ");
else {
if (analog_pin) {
sprintf(buffer, "Analog in =% 5d", analogRead(pin - analogInputToDigitalPin(0)));
SERIAL_ECHO(buffer);
}
else {
if (!get_pinMode(pin)) {
pinMode(pin, INPUT_PULLUP); // make sure input isn't floating
SERIAL_PROTOCOLPAIR("Input = ", digitalRead_mod(pin));
}
else if (PWM_status(pin)) {
// do nothing
}
else SERIAL_PROTOCOLPAIR("Output = ", digitalRead_mod(pin));
}
}
// report PWM capabilities
PWM_details(pin);
SERIAL_EOL;
}

@ -115,8 +115,8 @@
#define HEATER_BED_PIN 3
#define FAN_PIN 8
#define FAN0_PIN 6
#define FAN1_PIN 2
#define FAN1_PIN 6
#define FAN2_PIN 2
//
// Misc. Functions

@ -462,12 +462,12 @@ int Temperature::getHeaterPower(int heater) {
AUTO_3_IS_0 ? 0 : AUTO_3_IS_1 ? 1 : AUTO_3_IS_2 ? 2 : 3
};
uint8_t fanState = 0;
HOTEND_LOOP() {
if (current_temperature[e] > EXTRUDER_AUTO_FAN_TEMPERATURE)
SBI(fanState, fanBit[e]);
}
uint8_t fanDone = 0;
for (uint8_t f = 0; f < COUNT(fanPin); f++) {
int8_t pin = fanPin[f];
@ -1393,6 +1393,87 @@ void Temperature::set_current_temp_raw() {
temp_meas_ready = true;
}
#if ENABLED(PINS_DEBUGGING)
/**
* monitors endstops & Z probe for changes
*
* If a change is detected then the LED is toggled and
* a message is sent out the serial port
*
* Yes, we could miss a rapid back & forth change but
* that won't matter because this is all manual.
*
*/
void endstop_monitor() {
static uint16_t old_endstop_bits_local = 0;
static uint8_t local_LED_status = 0;
uint16_t current_endstop_bits_local = 0;
#if HAS_X_MIN
if (READ(X_MIN_PIN)) SBI(current_endstop_bits_local, X_MIN);
#endif
#if HAS_X_MAX
if (READ(X_MAX_PIN)) SBI(current_endstop_bits_local, X_MAX);
#endif
#if HAS_Y_MIN
if (READ(Y_MIN_PIN)) SBI(current_endstop_bits_local, Y_MIN);
#endif
#if HAS_Y_MAX
if (READ(Y_MAX_PIN)) SBI(current_endstop_bits_local, Y_MAX);
#endif
#if HAS_Z_MIN
if (READ(Z_MIN_PIN)) SBI(current_endstop_bits_local, Z_MIN);
#endif
#if HAS_Z_MAX
if (READ(Z_MAX_PIN)) SBI(current_endstop_bits_local, Z_MAX);
#endif
#if HAS_Z_MIN_PROBE_PIN
if (READ(Z_MIN_PROBE_PIN)) SBI(current_endstop_bits_local, Z_MIN_PROBE);
#endif
#if HAS_Z2_MIN
if (READ(Z2_MIN_PIN)) SBI(current_endstop_bits_local, Z2_MIN);
#endif
#if HAS_Z2_MAX
if (READ(Z2_MAX_PIN)) SBI(current_endstop_bits_local, Z2_MAX);
#endif
uint16_t endstop_change = current_endstop_bits_local ^ old_endstop_bits_local;
if (endstop_change) {
#if HAS_X_MIN
if (TEST(endstop_change, X_MIN)) SERIAL_PROTOCOLPAIR("X_MIN:", !!TEST(current_endstop_bits_local, X_MIN));
#endif
#if HAS_X_MAX
if (TEST(endstop_change, X_MAX)) SERIAL_PROTOCOLPAIR(" X_MAX:", !!TEST(current_endstop_bits_local, X_MAX));
#endif
#if HAS_Y_MIN
if (TEST(endstop_change, Y_MIN)) SERIAL_PROTOCOLPAIR(" Y_MIN:", !!TEST(current_endstop_bits_local, Y_MIN));
#endif
#if HAS_Y_MAX
if (TEST(endstop_change, Y_MAX)) SERIAL_PROTOCOLPAIR(" Y_MAX:", !!TEST(current_endstop_bits_local, Y_MAX));
#endif
#if HAS_Z_MIN
if (TEST(endstop_change, Z_MIN)) SERIAL_PROTOCOLPAIR(" Z_MIN:", !!TEST(current_endstop_bits_local, Z_MIN));
#endif
#if HAS_Z_MAX
if (TEST(endstop_change, Z_MAX)) SERIAL_PROTOCOLPAIR(" Z_MAX:", !!TEST(current_endstop_bits_local, Z_MAX));
#endif
#if HAS_Z_MIN_PROBE_PIN
if (TEST(endstop_change, Z_MIN_PROBE)) SERIAL_PROTOCOLPAIR(" PROBE:", !!TEST(current_endstop_bits_local, Z_MIN_PROBE));
#endif
#if HAS_Z2_MIN
if (TEST(endstop_change, Z2_MIN)) SERIAL_PROTOCOLPAIR(" Z2_MIN:", !!TEST(current_endstop_bits_local, Z2_MIN));
#endif
#if HAS_Z2_MAX
if (TEST(endstop_change, Z2_MAX)) SERIAL_PROTOCOLPAIR(" Z2_MAX:", !!TEST(current_endstop_bits_local, Z2_MAX));
#endif
SERIAL_PROTOCOLPGM("\n\n");
analogWrite(LED_PIN, local_LED_status);
local_LED_status ^= 255;
old_endstop_bits_local = current_endstop_bits_local;
}
}
#endif // PINS_DEBUGGING
/**
* Timer 0 is shared with millies so don't change the prescaler.
*
@ -1848,4 +1929,15 @@ void Temperature::isr() {
}
}
#endif //BABYSTEPPING
#if ENABLED(PINS_DEBUGGING)
extern bool endstop_monitor_flag;
// run the endstop monitor at 15Hz
static uint8_t endstop_monitor_count = 16; // offset this check from the others
if (endstop_monitor_flag) {
endstop_monitor_count += _BV(1); // 15 Hz
endstop_monitor_count &= 0x7F;
if (!endstop_monitor_count) endstop_monitor(); // report changes in endstop status
}
#endif
}

Loading…
Cancel
Save