Unify AVR90USB: pinsDebug changes
This commit is contained in:
parent
5426fc1735
commit
748bf32388
@ -732,9 +732,7 @@ void report_current_position_detail();
|
|||||||
SERIAL_ECHOPAIR(", ", y);
|
SERIAL_ECHOPAIR(", ", y);
|
||||||
SERIAL_ECHOPAIR(", ", z);
|
SERIAL_ECHOPAIR(", ", z);
|
||||||
SERIAL_CHAR(')');
|
SERIAL_CHAR(')');
|
||||||
|
if (suffix) serialprintPGM(suffix); else SERIAL_EOL();
|
||||||
if (suffix) {serialprintPGM(suffix);} //won't compile for Teensy with the previous construction
|
|
||||||
else SERIAL_EOL();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void print_xyz(const char* prefix, const char* suffix, const float xyz[]) {
|
void print_xyz(const char* prefix, const char* suffix, const float xyz[]) {
|
||||||
@ -6366,23 +6364,44 @@ inline void gcode_M42() {
|
|||||||
wait = parser.seen('W') ? parser.value_int() : 500;
|
wait = parser.seen('W') ? parser.value_int() : 500;
|
||||||
|
|
||||||
for (uint8_t pin = start; pin <= end; pin++) {
|
for (uint8_t pin = start; pin <= end; pin++) {
|
||||||
|
//report_pin_state_extended(pin, I_flag, false);
|
||||||
|
|
||||||
if (!I_flag && pin_is_protected(pin)) {
|
if (!I_flag && pin_is_protected(pin)) {
|
||||||
SERIAL_ECHOPAIR("Sensitive Pin: ", pin);
|
report_pin_state_extended(pin, I_flag, true, "Untouched ");
|
||||||
SERIAL_ECHOLNPGM(" untouched.");
|
SERIAL_EOL();
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
SERIAL_ECHOPAIR("Pulsing Pin: ", pin);
|
report_pin_state_extended(pin, I_flag, true, "Pulsing ");
|
||||||
pinMode(pin, OUTPUT);
|
#ifdef AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO
|
||||||
for (int16_t j = 0; j < repeat; j++) {
|
if (pin == 46) {
|
||||||
digitalWrite(pin, 0);
|
SET_OUTPUT(46);
|
||||||
safe_delay(wait);
|
for (int16_t j = 0; j < repeat; j++) {
|
||||||
digitalWrite(pin, 1);
|
WRITE(46, 0); safe_delay(wait);
|
||||||
safe_delay(wait);
|
WRITE(46, 1); safe_delay(wait);
|
||||||
digitalWrite(pin, 0);
|
WRITE(46, 0); safe_delay(wait);
|
||||||
safe_delay(wait);
|
}
|
||||||
|
}
|
||||||
|
else if (pin == 47) {
|
||||||
|
SET_OUTPUT(47);
|
||||||
|
for (int16_t j = 0; j < repeat; j++) {
|
||||||
|
WRITE(47, 0); safe_delay(wait);
|
||||||
|
WRITE(47, 1); safe_delay(wait);
|
||||||
|
WRITE(47, 0); safe_delay(wait);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
#endif
|
||||||
|
{
|
||||||
|
pinMode(pin, OUTPUT);
|
||||||
|
for (int16_t j = 0; j < repeat; j++) {
|
||||||
|
digitalWrite(pin, 0); safe_delay(wait);
|
||||||
|
digitalWrite(pin, 1); safe_delay(wait);
|
||||||
|
digitalWrite(pin, 0); safe_delay(wait);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
SERIAL_CHAR('\n');
|
SERIAL_EOL();
|
||||||
}
|
}
|
||||||
SERIAL_ECHOLNPGM("Done.");
|
SERIAL_ECHOLNPGM("Done.");
|
||||||
|
|
||||||
@ -6527,13 +6546,13 @@ inline void gcode_M42() {
|
|||||||
* M43 E<bool> - Enable / disable background endstop monitoring
|
* M43 E<bool> - Enable / disable background endstop monitoring
|
||||||
* - Machine continues to operate
|
* - Machine continues to operate
|
||||||
* - Reports changes to endstops
|
* - Reports changes to endstops
|
||||||
* - Toggles LED when an endstop changes
|
* - Toggles LED_PIN when an endstop changes
|
||||||
* - Can not reliably catch the 5mS pulse from BLTouch type probes
|
* - Can not reliably catch the 5mS pulse from BLTouch type probes
|
||||||
*
|
*
|
||||||
* M43 T - Toggle pin(s) and report which pin is being toggled
|
* M43 T - Toggle pin(s) and report which pin is being toggled
|
||||||
* S<pin> - Start Pin number. If not given, will default to 0
|
* S<pin> - Start Pin number. If not given, will default to 0
|
||||||
* L<pin> - End Pin number. If not given, will default to last pin defined for this board
|
* L<pin> - End Pin number. If not given, will default to last pin defined for this board
|
||||||
* I - Flag to ignore Marlin's pin protection. Use with caution!!!!
|
* I<bool> - Flag to ignore Marlin's pin protection. Use with caution!!!!
|
||||||
* R - Repeat pulses on each pin this number of times before continueing to next pin
|
* R - Repeat pulses on each pin this number of times before continueing to next pin
|
||||||
* W - Wait time (in miliseconds) between pulses. If not given will default to 500
|
* W - Wait time (in miliseconds) between pulses. If not given will default to 500
|
||||||
*
|
*
|
||||||
@ -6542,7 +6561,7 @@ inline void gcode_M42() {
|
|||||||
*/
|
*/
|
||||||
inline void gcode_M43() {
|
inline void gcode_M43() {
|
||||||
|
|
||||||
if (parser.seen('T')) { // must be first ot else it's "S" and "E" parameters will execute endstop or servo test
|
if (parser.seen('T')) { // must be first or else it's "S" and "E" parameters will execute endstop or servo test
|
||||||
toggle_pins();
|
toggle_pins();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -6576,6 +6595,7 @@ inline void gcode_M42() {
|
|||||||
for (int8_t pin = first_pin; pin <= last_pin; pin++) {
|
for (int8_t pin = first_pin; pin <= last_pin; pin++) {
|
||||||
if (pin_is_protected(pin) && !ignore_protection) continue;
|
if (pin_is_protected(pin) && !ignore_protection) continue;
|
||||||
pinMode(pin, INPUT_PULLUP);
|
pinMode(pin, INPUT_PULLUP);
|
||||||
|
delay(1);
|
||||||
/*
|
/*
|
||||||
if (IS_ANALOG(pin))
|
if (IS_ANALOG(pin))
|
||||||
pin_state[pin - first_pin] = analogRead(pin - analogInputToDigitalPin(0)); // int16_t pin_state[...]
|
pin_state[pin - first_pin] = analogRead(pin - analogInputToDigitalPin(0)); // int16_t pin_state[...]
|
||||||
@ -6591,7 +6611,7 @@ inline void gcode_M42() {
|
|||||||
|
|
||||||
for (;;) {
|
for (;;) {
|
||||||
for (int8_t pin = first_pin; pin <= last_pin; pin++) {
|
for (int8_t pin = first_pin; pin <= last_pin; pin++) {
|
||||||
if (pin_is_protected(pin)) continue;
|
if (pin_is_protected(pin) && !ignore_protection) continue;
|
||||||
const byte val =
|
const byte val =
|
||||||
/*
|
/*
|
||||||
IS_ANALOG(pin)
|
IS_ANALOG(pin)
|
||||||
@ -6600,7 +6620,7 @@ inline void gcode_M42() {
|
|||||||
//*/
|
//*/
|
||||||
digitalRead(pin);
|
digitalRead(pin);
|
||||||
if (val != pin_state[pin - first_pin]) {
|
if (val != pin_state[pin - first_pin]) {
|
||||||
report_pin_state(pin);
|
report_pin_state_extended(pin, ignore_protection, false);
|
||||||
pin_state[pin - first_pin] = val;
|
pin_state[pin - first_pin] = val;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -6612,14 +6632,14 @@ inline void gcode_M42() {
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
safe_delay(500);
|
safe_delay(200);
|
||||||
}
|
}
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Report current state of selected pin(s)
|
// Report current state of selected pin(s)
|
||||||
for (uint8_t pin = first_pin; pin <= last_pin; pin++)
|
for (uint8_t pin = first_pin; pin <= last_pin; pin++)
|
||||||
report_pin_state_extended(pin, ignore_protection);
|
report_pin_state_extended(pin, ignore_protection, true);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // PINS_DEBUGGING
|
#endif // PINS_DEBUGGING
|
||||||
@ -12164,7 +12184,9 @@ void prepare_move_to_destination() {
|
|||||||
val &= 0x07;
|
val &= 0x07;
|
||||||
switch (digitalPinToTimer(pin)) {
|
switch (digitalPinToTimer(pin)) {
|
||||||
#ifdef TCCR0A
|
#ifdef TCCR0A
|
||||||
case TIMER0A:
|
#if !AVR_AT90USB1286_FAMILY
|
||||||
|
case TIMER0A:
|
||||||
|
#endif
|
||||||
case TIMER0B:
|
case TIMER0B:
|
||||||
//_SET_CS(0, val);
|
//_SET_CS(0, val);
|
||||||
break;
|
break;
|
||||||
|
@ -20,18 +20,13 @@
|
|||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
bool endstop_monitor_flag = false;
|
bool endstop_monitor_flag = false;
|
||||||
|
|
||||||
#define NAME_FORMAT "%-28s" // one place to specify the format of all the sources of names
|
#define NAME_FORMAT "%-35s" // one place to specify the format of all the sources of names
|
||||||
// "-" left justify, "28" minimum width of name, pad with blanks
|
// "-" left justify, "28" minimum width of name, pad with blanks
|
||||||
|
|
||||||
#define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(0) && ((P) <= analogInputToDigitalPin(15) || (P) <= analogInputToDigitalPin(7)))
|
#define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(0) && ((P) <= analogInputToDigitalPin(15) || (P) <= analogInputToDigitalPin(7)))
|
||||||
|
|
||||||
#define AVR_ATmega2560_FAMILY (defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__) || defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__))
|
|
||||||
#define AVR_AT90USB1286_FAMILY (defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB1286P__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB646P__) || defined(__AVR_AT90USB647__))
|
|
||||||
#define AVR_ATmega1284_FAMILY (defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__))
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* This routine minimizes RAM usage by creating a FLASH resident array to
|
* This routine minimizes RAM usage by creating a FLASH resident array to
|
||||||
* store the pin names, pin numbers and analog/digital flag.
|
* store the pin names, pin numbers and analog/digital flag.
|
||||||
@ -52,7 +47,7 @@ bool endstop_monitor_flag = false;
|
|||||||
#define REPORT_NAME_ANALOG(NAME, COUNTER) _ADD_PIN(#NAME, COUNTER)
|
#define REPORT_NAME_ANALOG(NAME, COUNTER) _ADD_PIN(#NAME, COUNTER)
|
||||||
|
|
||||||
#include "pinsDebug_list.h"
|
#include "pinsDebug_list.h"
|
||||||
#line 56
|
#line 51
|
||||||
|
|
||||||
// manually add pins that have names that are macros which don't play well with these macros
|
// manually add pins that have names that are macros which don't play well with these macros
|
||||||
#if SERIAL_PORT == 0 && (AVR_ATmega2560_FAMILY || AVR_ATmega1284_FAMILY)
|
#if SERIAL_PORT == 0 && (AVR_ATmega2560_FAMILY || AVR_ATmega1284_FAMILY)
|
||||||
@ -88,27 +83,34 @@ const char* const pin_array[][3] PROGMEM = {
|
|||||||
// manually add pins ...
|
// manually add pins ...
|
||||||
#if SERIAL_PORT == 0
|
#if SERIAL_PORT == 0
|
||||||
#if AVR_ATmega2560_FAMILY
|
#if AVR_ATmega2560_FAMILY
|
||||||
{ RXD_NAME, "0", "1" },
|
{ RXD_NAME, 0, 1 },
|
||||||
{ TXD_NAME, "1", "1" },
|
{ TXD_NAME, 1, 1 },
|
||||||
#elif AVR_ATmega1284_FAMILY
|
#elif AVR_ATmega1284_FAMILY
|
||||||
{ RXD_NAME, "8", "1" },
|
{ RXD_NAME, 8, 1 },
|
||||||
{ TXD_NAME, "9", "1" },
|
{ TXD_NAME, 9, 1 },
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "pinsDebug_list.h"
|
#include "pinsDebug_list.h"
|
||||||
#line 101
|
#line 96
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#define n_array (sizeof(pin_array) / sizeof(char*)) / 3
|
#define n_array (sizeof(pin_array) / sizeof(char*)) / 3
|
||||||
|
|
||||||
#ifndef TIMER1B
|
#if AVR_AT90USB1286_FAMILY
|
||||||
// working with Teensyduino extension so need to re-define some things
|
// Working with Teensyduino extension so need to re-define some things
|
||||||
#include "pinsDebug_Teensyduino.h"
|
#include "pinsDebug_Teensyduino.h"
|
||||||
|
// Can't use the "digitalPinToPort" function from the Teensyduino type IDEs
|
||||||
|
// portModeRegister takes a different argument
|
||||||
|
#define digitalPinToPort_DEBUG(p) digitalPinToPort_Teensy(p)
|
||||||
|
#define get_pinMode(pin) (*portModeRegister(pin) & digitalPinToBitMask(pin))
|
||||||
|
#else
|
||||||
|
#define digitalPinToPort_DEBUG(p) digitalPinToPort(p)
|
||||||
|
bool get_pinMode(int8_t pin) {return *portModeRegister(digitalPinToPort_DEBUG(pin)) & digitalPinToBitMask(pin); }
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define PWM_PRINT(V) do{ sprintf(buffer, "PWM: %4d", V); SERIAL_ECHO(buffer); }while(0)
|
#define PWM_PRINT(V) do{ sprintf_P(buffer, PSTR("PWM: %4d"), V); SERIAL_ECHO(buffer); }while(0)
|
||||||
#define PWM_CASE(N,Z) \
|
#define PWM_CASE(N,Z) \
|
||||||
case TIMER##N##Z: \
|
case TIMER##N##Z: \
|
||||||
if (TCCR##N##A & (_BV(COM##N##Z##1) | _BV(COM##N##Z##0))) { \
|
if (TCCR##N##A & (_BV(COM##N##Z##1) | _BV(COM##N##Z##0))) { \
|
||||||
@ -127,7 +129,9 @@ static bool pwm_status(uint8_t pin) {
|
|||||||
|
|
||||||
#if defined(TCCR0A) && defined(COM0A1)
|
#if defined(TCCR0A) && defined(COM0A1)
|
||||||
#ifdef TIMER0A
|
#ifdef TIMER0A
|
||||||
PWM_CASE(0, A);
|
#if !AVR_AT90USB1286_FAMILY // not available in Teensyduino type IDEs
|
||||||
|
PWM_CASE(0, A);
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
PWM_CASE(0, B);
|
PWM_CASE(0, B);
|
||||||
#endif
|
#endif
|
||||||
@ -244,9 +248,10 @@ const volatile uint8_t* const PWM_OCR[][3] PROGMEM = {
|
|||||||
static void err_is_counter() { SERIAL_PROTOCOLPGM(" non-standard PWM mode"); }
|
static void err_is_counter() { SERIAL_PROTOCOLPGM(" non-standard PWM mode"); }
|
||||||
static void err_is_interrupt() { SERIAL_PROTOCOLPGM(" compare interrupt enabled"); }
|
static void err_is_interrupt() { SERIAL_PROTOCOLPGM(" compare interrupt enabled"); }
|
||||||
static void err_prob_interrupt() { SERIAL_PROTOCOLPGM(" overflow interrupt enabled"); }
|
static void err_prob_interrupt() { SERIAL_PROTOCOLPGM(" overflow interrupt enabled"); }
|
||||||
|
static void print_is_also_tied() { SERIAL_PROTOCOLPGM(" is also tied to this pin"); SERIAL_PROTOCOL_SP(14); }
|
||||||
|
|
||||||
void com_print(uint8_t N, uint8_t Z) {
|
void com_print(uint8_t N, uint8_t Z) {
|
||||||
uint8_t *TCCRA = (uint8_t*)TCCR_A(N);
|
const uint8_t *TCCRA = (uint8_t*)TCCR_A(N);
|
||||||
SERIAL_PROTOCOLPGM(" COM");
|
SERIAL_PROTOCOLPGM(" COM");
|
||||||
SERIAL_PROTOCOLCHAR(N + '0');
|
SERIAL_PROTOCOLCHAR(N + '0');
|
||||||
switch (Z) {
|
switch (Z) {
|
||||||
@ -264,8 +269,8 @@ void com_print(uint8_t N, uint8_t Z) {
|
|||||||
|
|
||||||
void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N - WGM bit layout
|
void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N - WGM bit layout
|
||||||
char buffer[20]; // for the sprintf statements
|
char buffer[20]; // for the sprintf statements
|
||||||
uint8_t *TCCRB = (uint8_t*)TCCR_B(T);
|
const uint8_t *TCCRB = (uint8_t*)TCCR_B(T),
|
||||||
uint8_t *TCCRA = (uint8_t*)TCCR_A(T);
|
*TCCRA = (uint8_t*)TCCR_A(T);
|
||||||
uint8_t WGM = (((*TCCRB & _BV(WGM_2)) >> 1) | (*TCCRA & (_BV(WGM_0) | _BV(WGM_1))));
|
uint8_t WGM = (((*TCCRB & _BV(WGM_2)) >> 1) | (*TCCRA & (_BV(WGM_0) | _BV(WGM_1))));
|
||||||
if (N == 4) WGM |= ((*TCCRB & _BV(WGM_3)) >> 1);
|
if (N == 4) WGM |= ((*TCCRB & _BV(WGM_3)) >> 1);
|
||||||
|
|
||||||
@ -275,11 +280,11 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N -
|
|||||||
SERIAL_PROTOCOL_SP(3);
|
SERIAL_PROTOCOL_SP(3);
|
||||||
|
|
||||||
if (N == 3) {
|
if (N == 3) {
|
||||||
uint8_t *OCRVAL8 = (uint8_t*)OCR_VAL(T, L - 'A');
|
const uint8_t *OCRVAL8 = (uint8_t*)OCR_VAL(T, L - 'A');
|
||||||
PWM_PRINT(*OCRVAL8);
|
PWM_PRINT(*OCRVAL8);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
uint16_t *OCRVAL16 = (uint16_t*)OCR_VAL(T, L - 'A');
|
const uint16_t *OCRVAL16 = (uint16_t*)OCR_VAL(T, L - 'A');
|
||||||
PWM_PRINT(*OCRVAL16);
|
PWM_PRINT(*OCRVAL16);
|
||||||
}
|
}
|
||||||
SERIAL_PROTOCOLPAIR(" WGM: ", WGM);
|
SERIAL_PROTOCOLPAIR(" WGM: ", WGM);
|
||||||
@ -294,12 +299,12 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N -
|
|||||||
SERIAL_PROTOCOLCHAR(T + '0');
|
SERIAL_PROTOCOLCHAR(T + '0');
|
||||||
SERIAL_PROTOCOLPAIR("B: ", *TCCRB);
|
SERIAL_PROTOCOLPAIR("B: ", *TCCRB);
|
||||||
|
|
||||||
uint8_t *TMSK = (uint8_t*)TIMSK(T);
|
const uint8_t *TMSK = (uint8_t*)TIMSK(T);
|
||||||
SERIAL_PROTOCOLPGM(" TIMSK");
|
SERIAL_PROTOCOLPGM(" TIMSK");
|
||||||
SERIAL_PROTOCOLCHAR(T + '0');
|
SERIAL_PROTOCOLCHAR(T + '0');
|
||||||
SERIAL_PROTOCOLPAIR(": ", *TMSK);
|
SERIAL_PROTOCOLPAIR(": ", *TMSK);
|
||||||
|
|
||||||
uint8_t OCIE = L - 'A' + 1;
|
const uint8_t OCIE = L - 'A' + 1;
|
||||||
if (N == 3) { if (WGM == 0 || WGM == 2 || WGM == 4 || WGM == 6) err_is_counter(); }
|
if (N == 3) { if (WGM == 0 || WGM == 2 || WGM == 4 || WGM == 6) err_is_counter(); }
|
||||||
else { if (WGM == 0 || WGM == 4 || WGM == 12 || WGM == 13) err_is_counter(); }
|
else { if (WGM == 0 || WGM == 4 || WGM == 12 || WGM == 13) err_is_counter(); }
|
||||||
if (TEST(*TMSK, OCIE)) err_is_interrupt();
|
if (TEST(*TMSK, OCIE)) err_is_interrupt();
|
||||||
@ -311,7 +316,9 @@ static void pwm_details(uint8_t pin) {
|
|||||||
|
|
||||||
#if defined(TCCR0A) && defined(COM0A1)
|
#if defined(TCCR0A) && defined(COM0A1)
|
||||||
#ifdef TIMER0A
|
#ifdef TIMER0A
|
||||||
case TIMER0A: timer_prefix(0, 'A', 3); break;
|
#if !AVR_AT90USB1286_FAMILY // not available in Teensyduino type IDEs
|
||||||
|
case TIMER0A: timer_prefix(0, 'A', 3); break;
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
case TIMER0B: timer_prefix(0, 'B', 3); break;
|
case TIMER0B: timer_prefix(0, 'B', 3); break;
|
||||||
#endif
|
#endif
|
||||||
@ -357,136 +364,192 @@ static void pwm_details(uint8_t pin) {
|
|||||||
// on pins that have two PWMs, print info on second PWM
|
// on pins that have two PWMs, print info on second PWM
|
||||||
#if AVR_ATmega2560_FAMILY || AVR_AT90USB1286_FAMILY
|
#if AVR_ATmega2560_FAMILY || AVR_AT90USB1286_FAMILY
|
||||||
// looking for port B7 - PWMs 0A and 1C
|
// looking for port B7 - PWMs 0A and 1C
|
||||||
if (digitalPinToPort(pin) == 2 && digitalPinToBitMask(pin) == 0x80) {
|
if (digitalPinToPort_DEBUG(pin) == 'B' - 64 && 0x80 == digitalPinToBitMask(pin)) {
|
||||||
#ifndef TEENSYDUINO_IDE
|
#if !AVR_AT90USB1286_FAMILY
|
||||||
SERIAL_PROTOCOLPGM("\n .");
|
SERIAL_PROTOCOLPGM("\n .");
|
||||||
SERIAL_PROTOCOL_SP(18);
|
SERIAL_PROTOCOL_SP(18);
|
||||||
SERIAL_PROTOCOLPGM("TIMER1C is also tied to this pin");
|
SERIAL_PROTOCOLPGM("TIMER1C");
|
||||||
SERIAL_PROTOCOL_SP(13);
|
print_is_also_tied();
|
||||||
timer_prefix(1, 'C', 4);
|
timer_prefix(1, 'C', 4);
|
||||||
#else
|
#else
|
||||||
SERIAL_PROTOCOLPGM("\n .");
|
SERIAL_PROTOCOLPGM("\n .");
|
||||||
SERIAL_PROTOCOL_SP(18);
|
SERIAL_PROTOCOL_SP(18);
|
||||||
SERIAL_PROTOCOLPGM("TIMER0A is also tied to this pin");
|
SERIAL_PROTOCOLPGM("TIMER0A");
|
||||||
SERIAL_PROTOCOL_SP(13);
|
print_is_also_tied();
|
||||||
timer_prefix(0, 'A', 3);
|
timer_prefix(0, 'A', 3);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
} // pwm_details
|
} // pwm_details
|
||||||
|
|
||||||
bool get_pinMode(int8_t pin) { return *portModeRegister(digitalPinToPort(pin)) & digitalPinToBitMask(pin); }
|
#ifndef digitalRead_mod // Use Teensyduino's version of digitalRead - it doesn't disable the PWMs
|
||||||
|
int digitalRead_mod(const int8_t pin) { // same as digitalRead except the PWM stop section has been removed
|
||||||
#ifndef digitalRead_mod // use Teensyduino's version of digitalRead - it doesn't disable the PWMs
|
const uint8_t port = digitalPinToPort_DEBUG(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;
|
return (port != NOT_A_PIN) && (*portInputRegister(port) & digitalPinToBitMask(pin)) ? HIGH : LOW;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void print_port(int8_t pin) { // print port number
|
void print_port(int8_t pin) { // print port number
|
||||||
#ifdef digitalPinToPort
|
#ifdef digitalPinToPort_DEBUG
|
||||||
|
uint8_t x;
|
||||||
SERIAL_PROTOCOLPGM(" Port: ");
|
SERIAL_PROTOCOLPGM(" Port: ");
|
||||||
uint8_t x = digitalPinToPort(pin) + 64;
|
#if AVR_AT90USB1286_FAMILY
|
||||||
|
x = (pin == 46 || pin == 47) ? 'E' : digitalPinToPort_DEBUG(pin) + 64;
|
||||||
|
#else
|
||||||
|
x = digitalPinToPort_DEBUG(pin) + 64;
|
||||||
|
#endif
|
||||||
SERIAL_CHAR(x);
|
SERIAL_CHAR(x);
|
||||||
uint8_t temp = digitalPinToBitMask(pin);
|
|
||||||
for (x = '0'; x < '9' && temp != 1; x++) temp >>= 1;
|
#if AVR_AT90USB1286_FAMILY
|
||||||
|
if (pin == 46)
|
||||||
|
x = '2';
|
||||||
|
else if (pin == 47)
|
||||||
|
x = '3';
|
||||||
|
else {
|
||||||
|
uint8_t temp = digitalPinToBitMask(pin);
|
||||||
|
for (x = '0'; x < '9' && temp != 1; x++) temp >>= 1;
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
uint8_t temp = digitalPinToBitMask(pin);
|
||||||
|
for (x = '0'; x < '9' && temp != 1; x++) temp >>= 1;
|
||||||
|
#endif
|
||||||
SERIAL_CHAR(x);
|
SERIAL_CHAR(x);
|
||||||
#else
|
#else
|
||||||
SERIAL_PROTOCOL_SP(10);
|
SERIAL_PROTOCOL_SP(10);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static void print_input_or_output(const bool isout) {
|
||||||
|
serialprintPGM(isout ? PSTR("Output = ") : PSTR("Input = "));
|
||||||
|
}
|
||||||
|
|
||||||
// pretty report with PWM info
|
// pretty report with PWM info
|
||||||
inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = true) {
|
inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = false,const char *start_string = "") {
|
||||||
uint8_t temp_char;
|
uint8_t temp_char;
|
||||||
char *name_mem_pointer;
|
char *name_mem_pointer, buffer[30]; // for the sprintf statements
|
||||||
char buffer[30]; // for the sprintf statements
|
bool found = false, multi_name_pin = false;
|
||||||
bool found = false,
|
|
||||||
multi_name_pin = false;
|
|
||||||
for (uint8_t x = 0; x < n_array; x++) { // scan entire array and report all instances of this pin
|
for (uint8_t x = 0; x < n_array; x++) { // scan entire array and report all instances of this pin
|
||||||
if (pgm_read_byte(&pin_array[x][1]) == pin) {
|
if (pgm_read_byte(&pin_array[x][1]) == pin) {
|
||||||
if (found) multi_name_pin = true;
|
if (found) multi_name_pin = true;
|
||||||
found = true;
|
found = true;
|
||||||
if (!multi_name_pin) { // report digitial and analog pin number only on the first time through
|
if (!multi_name_pin) { // report digitial and analog pin number only on the first time through
|
||||||
sprintf(buffer, "PIN: %3d ", pin); // digital pin number
|
sprintf_P(buffer, PSTR("%sPIN: %3d "), start_string, pin); // digital pin number
|
||||||
SERIAL_ECHO(buffer);
|
SERIAL_ECHO(buffer);
|
||||||
print_port(pin);
|
print_port(pin);
|
||||||
if (IS_ANALOG(pin)) {
|
if (IS_ANALOG(pin)) {
|
||||||
sprintf(buffer, " (A%2d) ", int(pin - analogInputToDigitalPin(0))); // analog pin number
|
sprintf_P(buffer, PSTR(" (A%2d) "), int(pin - analogInputToDigitalPin(0))); // analog pin number
|
||||||
SERIAL_ECHO(buffer);
|
SERIAL_ECHO(buffer);
|
||||||
}
|
}
|
||||||
else SERIAL_ECHO_SP(8); // add padding if not an analog pin
|
else SERIAL_ECHO_SP(8); // add padding if not an analog pin
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
SERIAL_CHAR('.');
|
SERIAL_CHAR('.');
|
||||||
SERIAL_ECHO_SP(25); // add padding if not the first instance found
|
SERIAL_ECHO_SP(26 + strlen(start_string)); // add padding if not the first instance found
|
||||||
}
|
}
|
||||||
name_mem_pointer = (char*)pgm_read_word(&pin_array[x][0]);
|
name_mem_pointer = (char*)pgm_read_word(&pin_array[x][0]);
|
||||||
for (uint8_t y = 0; y < 28; y++) { // always print pin name
|
for (uint8_t y = 0; y < 28; y++) { // always print pin name
|
||||||
temp_char = pgm_read_byte(name_mem_pointer + y);
|
temp_char = pgm_read_byte(name_mem_pointer + y);
|
||||||
if (temp_char != 0) MYSERIAL.write(temp_char);
|
if (temp_char != 0)
|
||||||
|
MYSERIAL.write(temp_char);
|
||||||
else {
|
else {
|
||||||
for (uint8_t i = 0; i < 28 - y; i++) MYSERIAL.write(' ');
|
for (uint8_t i = 0; i < 28 - y; i++) MYSERIAL.write(' ');
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (pin_is_protected(pin) && !ignore)
|
if (extended) {
|
||||||
SERIAL_ECHOPGM("protected ");
|
if (pin_is_protected(pin) && !ignore)
|
||||||
else {
|
SERIAL_ECHOPGM("protected ");
|
||||||
if (!(pgm_read_byte(&pin_array[x][2]))) {
|
|
||||||
sprintf(buffer, "Analog in = %5d", analogRead(pin - analogInputToDigitalPin(0)));
|
|
||||||
SERIAL_ECHO(buffer);
|
|
||||||
}
|
|
||||||
else {
|
else {
|
||||||
if (!get_pinMode(pin)) {
|
#ifdef AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO
|
||||||
//pinMode(pin, INPUT_PULLUP); // make sure input isn't floating - stopped doing this
|
if (pin == 46) {
|
||||||
// because this could interfere with inductive/capacitive
|
print_input_or_output(GET_OUTPUT(46));
|
||||||
// sensors (high impedance voltage divider) and with PT100 amplifier
|
SERIAL_PROTOCOL(READ(46));
|
||||||
SERIAL_PROTOCOLPAIR("Input = ", digitalRead_mod(pin));
|
}
|
||||||
|
else if (pin == 47)
|
||||||
|
print_input_or_output(GET_OUTPUT(47));
|
||||||
|
SERIAL_PROTOCOL(READ(47));
|
||||||
|
}
|
||||||
|
else
|
||||||
|
#endif
|
||||||
|
{
|
||||||
|
if (!(pgm_read_byte(&pin_array[x][2]))) {
|
||||||
|
sprintf_P(buffer, PSTR("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 - stopped doing this
|
||||||
|
// because this could interfere with inductive/capacitive
|
||||||
|
// sensors (high impedance voltage divider) and with PT100 amplifier
|
||||||
|
print_input_or_output(false);
|
||||||
|
SERIAL_PROTOCOL(digitalRead_mod(pin));
|
||||||
|
}
|
||||||
|
else if (pwm_status(pin)) {
|
||||||
|
// do nothing
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
print_input_or_output(true);
|
||||||
|
SERIAL_PROTOCOL(digitalRead_mod(pin));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (!multi_name_pin && extended) pwm_details(pin); // report PWM capabilities only on the first pass & only if doing an extended report
|
||||||
}
|
}
|
||||||
else if (pwm_status(pin)) {
|
|
||||||
// do nothing
|
|
||||||
}
|
|
||||||
else SERIAL_PROTOCOLPAIR("Output = ", digitalRead_mod(pin));
|
|
||||||
}
|
}
|
||||||
if (!multi_name_pin && extended) pwm_details(pin); // report PWM capabilities only on the first pass & only if doing an extended report
|
|
||||||
}
|
}
|
||||||
SERIAL_EOL();
|
SERIAL_EOL();
|
||||||
} // end of IF
|
} // end of IF
|
||||||
} // end of for loop
|
} // end of for loop
|
||||||
|
|
||||||
if (!found) {
|
if (!found) {
|
||||||
sprintf(buffer, "PIN: %3d ", pin);
|
sprintf_P(buffer, PSTR("%sPIN: %3d "), start_string, pin);
|
||||||
SERIAL_ECHO(buffer);
|
SERIAL_ECHO(buffer);
|
||||||
print_port(pin);
|
print_port(pin);
|
||||||
if (IS_ANALOG(pin)) {
|
if (IS_ANALOG(pin)) {
|
||||||
sprintf(buffer, " (A%2d) ", int(pin - analogInputToDigitalPin(0))); // analog pin number
|
sprintf_P(buffer, PSTR(" (A%2d) "), int(pin - analogInputToDigitalPin(0))); // analog pin number
|
||||||
SERIAL_ECHO(buffer);
|
SERIAL_ECHO(buffer);
|
||||||
}
|
}
|
||||||
else
|
|
||||||
SERIAL_ECHO_SP(8); // add padding if not an analog pin
|
|
||||||
SERIAL_ECHOPGM("<unused/unknown>");
|
|
||||||
if (get_pinMode(pin)) {
|
|
||||||
SERIAL_PROTOCOL_SP(12);
|
|
||||||
SERIAL_PROTOCOLPAIR("Output = ", digitalRead_mod(pin));
|
|
||||||
}
|
|
||||||
else {
|
else {
|
||||||
if (IS_ANALOG(pin)) {
|
SERIAL_ECHO_SP(8); // add padding if not an analog pin
|
||||||
sprintf(buffer, " Analog in = %5d", analogRead(pin - analogInputToDigitalPin(0)));
|
SERIAL_ECHOPGM("<unused/unknown>");
|
||||||
SERIAL_ECHO(buffer);
|
if (extended) {
|
||||||
}
|
#ifdef AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO
|
||||||
else
|
if (pin == 46 || pin == 47) {
|
||||||
SERIAL_ECHO_SP(9); // add padding if not an analog pin
|
SERIAL_PROTOCOL_SP(12);
|
||||||
|
if (pin == 46) {
|
||||||
|
print_input_or_output(GET_OUTPUT(46));
|
||||||
|
SERIAL_PROTOCOL(READ(46));
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
print_input_or_output(GET_OUTPUT(47));
|
||||||
|
SERIAL_PROTOCOL(READ(47));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
#endif
|
||||||
|
{
|
||||||
|
if (get_pinMode(pin)) {
|
||||||
|
SERIAL_PROTOCOL_SP(12);
|
||||||
|
print_input_or_output(true);
|
||||||
|
SERIAL_PROTOCOL(digitalRead_mod(pin));
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
if (IS_ANALOG(pin)) {
|
||||||
|
sprintf_P(buffer, PSTR(" Analog in = %5d"), analogRead(pin - analogInputToDigitalPin(0)));
|
||||||
|
SERIAL_ECHO(buffer);
|
||||||
|
SERIAL_ECHOPGM(" ");
|
||||||
|
}
|
||||||
|
else
|
||||||
|
SERIAL_ECHO_SP(12); // add padding if not an analog pin
|
||||||
|
|
||||||
SERIAL_PROTOCOLPAIR(" Input = ", digitalRead_mod(pin));
|
print_input_or_output(false);
|
||||||
|
SERIAL_PROTOCOL(digitalRead_mod(pin));
|
||||||
|
}
|
||||||
|
//if (!pwm_status(pin)) SERIAL_CHAR(' '); // add padding if it's not a PWM pin
|
||||||
|
if (extended) pwm_details(pin); // report PWM capabilities only if doing an extended report
|
||||||
|
}
|
||||||
|
}
|
||||||
|
SERIAL_EOL();
|
||||||
}
|
}
|
||||||
//if (!pwm_status(pin)) SERIAL_CHAR(' '); // add padding if it's not a PWM pin
|
|
||||||
if (extended) pwm_details(pin); // report PWM capabilities only if doing an extended report
|
|
||||||
SERIAL_EOL();
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
inline void report_pin_state(int8_t pin) {
|
|
||||||
report_pin_state_extended(pin, false, false);
|
|
||||||
}
|
|
||||||
|
@ -25,21 +25,16 @@
|
|||||||
// do not function the same as the other Arduino extensions
|
// do not function the same as the other Arduino extensions
|
||||||
//
|
//
|
||||||
|
|
||||||
|
#ifndef __PINSDEBUG_TEENSYDUINO_H__
|
||||||
|
#define __PINSDEBUG_TEENSYDUINO_H__
|
||||||
|
|
||||||
#define TEENSYDUINO_IDE
|
#undef NUM_DIGITAL_PINS
|
||||||
|
#define NUM_DIGITAL_PINS 48 // Teensy says 46 but FASTIO is 48
|
||||||
|
|
||||||
//digitalPinToTimer(pin) function works like Arduino but Timers are not defined
|
// "digitalPinToPort" function just returns the pin number so need to create our own.
|
||||||
#define TIMER0B 1
|
// Can't use the name "digitalPinToPort" for our own because it interferes with the
|
||||||
#define TIMER1A 7
|
// FAST_PWM_FAN function if we do
|
||||||
#define TIMER1B 8
|
|
||||||
#define TIMER1C 9
|
|
||||||
#define TIMER2A 6
|
|
||||||
#define TIMER2B 2
|
|
||||||
#define TIMER3A 5
|
|
||||||
#define TIMER3B 4
|
|
||||||
#define TIMER3C 3
|
|
||||||
|
|
||||||
// digitalPinToPort function just returns the pin number so need to create our own
|
|
||||||
#define PA 1
|
#define PA 1
|
||||||
#define PB 2
|
#define PB 2
|
||||||
#define PC 3
|
#define PC 3
|
||||||
@ -47,9 +42,8 @@
|
|||||||
#define PE 5
|
#define PE 5
|
||||||
#define PF 6
|
#define PF 6
|
||||||
|
|
||||||
#undef digitalPinToPort
|
|
||||||
|
|
||||||
const uint8_t PROGMEM digital_pin_to_port_PGM[] = {
|
const uint8_t PROGMEM digital_pin_to_port_PGM_Teensy[] = {
|
||||||
PD, // 0 - PD0 - INT0 - PWM
|
PD, // 0 - PD0 - INT0 - PWM
|
||||||
PD, // 1 - PD1 - INT1 - PWM
|
PD, // 1 - PD1 - INT1 - PWM
|
||||||
PD, // 2 - PD2 - INT2 - RX
|
PD, // 2 - PD2 - INT2 - RX
|
||||||
@ -100,7 +94,7 @@ const uint8_t PROGMEM digital_pin_to_port_PGM[] = {
|
|||||||
PE, // 47 - PE3 (not defined in teensyduino)
|
PE, // 47 - PE3 (not defined in teensyduino)
|
||||||
};
|
};
|
||||||
|
|
||||||
#define digitalPinToPort(P) ( pgm_read_byte( digital_pin_to_port_PGM + (P) ) )
|
#define digitalPinToPort_Teensy(P) ( pgm_read_byte( digital_pin_to_port_PGM_Teensy + (P) ) )
|
||||||
|
|
||||||
// digitalPinToBitMask(pin) is OK
|
// digitalPinToBitMask(pin) is OK
|
||||||
|
|
||||||
@ -108,3 +102,5 @@ const uint8_t PROGMEM digital_pin_to_port_PGM[] = {
|
|||||||
// disable the PWMs so we can use it as is
|
// disable the PWMs so we can use it as is
|
||||||
|
|
||||||
// portModeRegister(pin) is OK
|
// portModeRegister(pin) is OK
|
||||||
|
|
||||||
|
#endif // __PINSDEBUG_TEENSYDUINO_H__
|
||||||
|
@ -353,22 +353,22 @@
|
|||||||
#if defined(LCD_CONTRAST) && LCD_CONTRAST >= 0
|
#if defined(LCD_CONTRAST) && LCD_CONTRAST >= 0
|
||||||
REPORT_NAME_DIGITAL(LCD_CONTRAST, __LINE__ )
|
REPORT_NAME_DIGITAL(LCD_CONTRAST, __LINE__ )
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(LCD)
|
#if defined(LCD_PINS_D4) && LCD_PINS_D4 >= 0
|
||||||
REPORT_NAME_DIGITAL(LCD_PINS_D4, __LINE__ )
|
REPORT_NAME_DIGITAL(LCD_PINS_D4, __LINE__ )
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(LCD)
|
#if defined(LCD_PINS_D5) && LCD_PINS_D5 >= 0
|
||||||
REPORT_NAME_DIGITAL(LCD_PINS_D5, __LINE__ )
|
REPORT_NAME_DIGITAL(LCD_PINS_D5, __LINE__ )
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(LCD)
|
#if defined(LCD_PINS_D6) && LCD_PINS_D6 >= 0
|
||||||
REPORT_NAME_DIGITAL(LCD_PINS_D6, __LINE__ )
|
REPORT_NAME_DIGITAL(LCD_PINS_D6, __LINE__ )
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(LCD)
|
#if defined(LCD_PINS_D7) && LCD_PINS_D7 >= 0
|
||||||
REPORT_NAME_DIGITAL(LCD_PINS_D7, __LINE__ )
|
REPORT_NAME_DIGITAL(LCD_PINS_D7, __LINE__ )
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(LCD)
|
#if defined(LCD_PINS_ENABLE) && LCD_PINS_ENABLE >= 0
|
||||||
REPORT_NAME_DIGITAL(LCD_PINS_ENABLE, __LINE__ )
|
REPORT_NAME_DIGITAL(LCD_PINS_ENABLE, __LINE__ )
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(LCD)
|
#if defined(LCD_PINS_RS) && LCD_PINS_RS >= 0
|
||||||
REPORT_NAME_DIGITAL(LCD_PINS_RS, __LINE__ )
|
REPORT_NAME_DIGITAL(LCD_PINS_RS, __LINE__ )
|
||||||
#endif
|
#endif
|
||||||
#if defined(LCD_SDSS) && LCD_SDSS >= 0
|
#if defined(LCD_SDSS) && LCD_SDSS >= 0
|
||||||
@ -446,6 +446,18 @@
|
|||||||
#if PIN_EXISTS(RAMPS_D9)
|
#if PIN_EXISTS(RAMPS_D9)
|
||||||
REPORT_NAME_DIGITAL(RAMPS_D9_PIN, __LINE__ )
|
REPORT_NAME_DIGITAL(RAMPS_D9_PIN, __LINE__ )
|
||||||
#endif
|
#endif
|
||||||
|
#if PIN_EXISTS(RGB_LED_R)
|
||||||
|
REPORT_NAME_DIGITAL(RGB_LED_R_PIN, __LINE__ )
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(RGB_LED_G)
|
||||||
|
REPORT_NAME_DIGITAL(RGB_LED_G_PIN, __LINE__ )
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(RGB_LED_B)
|
||||||
|
REPORT_NAME_DIGITAL(RGB_LED_B_PIN, __LINE__ )
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(RGB_LED_W)
|
||||||
|
REPORT_NAME_DIGITAL(RGB_LED_W_PIN, __LINE__ )
|
||||||
|
#endif
|
||||||
#if PIN_EXISTS(RX_ENABLE)
|
#if PIN_EXISTS(RX_ENABLE)
|
||||||
REPORT_NAME_DIGITAL(RX_ENABLE_PIN, __LINE__ )
|
REPORT_NAME_DIGITAL(RX_ENABLE_PIN, __LINE__ )
|
||||||
#endif
|
#endif
|
||||||
@ -500,12 +512,21 @@
|
|||||||
#if PIN_EXISTS(SLEEP_WAKE)
|
#if PIN_EXISTS(SLEEP_WAKE)
|
||||||
REPORT_NAME_DIGITAL(SLEEP_WAKE_PIN, __LINE__ )
|
REPORT_NAME_DIGITAL(SLEEP_WAKE_PIN, __LINE__ )
|
||||||
#endif
|
#endif
|
||||||
|
#if PIN_EXISTS(SOL0)
|
||||||
|
REPORT_NAME_DIGITAL(SOL0_PIN, __LINE__ )
|
||||||
|
#endif
|
||||||
#if PIN_EXISTS(SOL1)
|
#if PIN_EXISTS(SOL1)
|
||||||
REPORT_NAME_DIGITAL(SOL1_PIN, __LINE__ )
|
REPORT_NAME_DIGITAL(SOL1_PIN, __LINE__ )
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(SOL2)
|
#if PIN_EXISTS(SOL2)
|
||||||
REPORT_NAME_DIGITAL(SOL2_PIN, __LINE__ )
|
REPORT_NAME_DIGITAL(SOL2_PIN, __LINE__ )
|
||||||
#endif
|
#endif
|
||||||
|
#if PIN_EXISTS(SOL3)
|
||||||
|
REPORT_NAME_DIGITAL(SOL3_PIN, __LINE__ )
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(SOL4)
|
||||||
|
REPORT_NAME_DIGITAL(SOL4_PIN, __LINE__ )
|
||||||
|
#endif
|
||||||
#if defined(SPARE_IO) && SPARE_IO >= 0
|
#if defined(SPARE_IO) && SPARE_IO >= 0
|
||||||
REPORT_NAME_DIGITAL(SPARE_IO, __LINE__ )
|
REPORT_NAME_DIGITAL(SPARE_IO, __LINE__ )
|
||||||
#endif
|
#endif
|
||||||
@ -749,3 +770,4 @@
|
|||||||
#if PIN_EXISTS(Z2_STEP)
|
#if PIN_EXISTS(Z2_STEP)
|
||||||
REPORT_NAME_DIGITAL(Z2_STEP_PIN, __LINE__ )
|
REPORT_NAME_DIGITAL(Z2_STEP_PIN, __LINE__ )
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user