Browse Source

Cleanup following Pins Debug update

pull/1/head
Scott Lahteine 8 years ago
parent
commit
d4ce839351
  1. 41
      Marlin/Marlin_main.cpp
  2. 113
      Marlin/pinsDebug.h

41
Marlin/Marlin_main.cpp

@ -5317,25 +5317,17 @@ inline void gcode_M42() {
#include "pinsDebug.h"
inline void toggle_pins() {
int pin, j, start = 0, I_flag = 0, end = NUM_DIGITAL_PINS - 1, wait = 500, repeat = 1;
int pin, j;
if (code_seen('R'))
repeat = code_value_int();
bool I_flag = code_seen('I') ? code_value_bool() : false;
if (code_seen('S'))
start = code_value_int();
int repeat = code_seen('R') ? code_value_int() : 1,
start = code_seen('S') ? code_value_int() : 0,
end = code_seen('E') ? code_value_int() : NUM_DIGITAL_PINS - 1,
wait = code_seen('W') ? code_value_int() : 500;
if (code_seen('E'))
end = code_value_int();
if (code_seen('I') )
I_flag++;
if (code_seen('W'))
wait = code_value_int();
for(pin = start; pin <= end; pin++) {
if ( I_flag == 0 && pin_is_protected(pin)) {
for (pin = start; pin <= end; pin++) {
if (!I_flag && pin_is_protected(pin)) {
SERIAL_ECHOPAIR("Sensitive Pin: ", pin);
SERIAL_ECHOPGM(" untouched.\n");
}
@ -5344,22 +5336,17 @@ inline void gcode_M42() {
pinMode(pin, OUTPUT);
for(j = 0; j < repeat; j++) {
digitalWrite(pin, 0);
idle();
delay(wait);
safe_delay(wait);
digitalWrite(pin, 1);
idle();
delay(wait);
safe_delay(wait);
digitalWrite(pin, 0);
idle();
delay(wait);
safe_delay(wait);
}
}
SERIAL_ECHOPGM("\n");
}
SERIAL_ECHOPGM("Done\n");
return;
} // toggle pin(s)
} // toggle_pins
inline void servo_probe_test(){
#if !(NUM_SERVOS >= 1 && HAS_SERVO_0)
@ -5505,10 +5492,10 @@ inline void gcode_M42() {
if (first_pin > NUM_DIGITAL_PINS - 1) return;
}
bool ignore_protection = code_seen('I');
bool ignore_protection = code_seen('I') ? code_value_bool() : false;
// Watch until click, M108, or reset
if (code_seen('W')) { // watch digital pins
if (code_seen('W') && code_value_bool()) { // watch digital pins
SERIAL_PROTOCOLLNPGM("Watching pins");
byte pin_state[last_pin - first_pin + 1];
for (int8_t pin = first_pin; pin <= last_pin; pin++) {

113
Marlin/pinsDebug.h

@ -80,16 +80,16 @@ bool endstop_monitor_flag = false;
const char* const pin_array[][3] PROGMEM = {
/**
* [pin name] [pin number] [is digital or analog] 1 = digital, 0 = analog
* Each entry takes up 6 bytes in FLASH:
* 2 byte pointer to location of the name string
* 2 bytes containing the pin number
* analog pin numbers were convereted to digital when the array was created
* 2 bytes containing the digital/analog bool flag
*/
// manually add pins ...
/**
* [pin name] [pin number] [is digital or analog] 1 = digital, 0 = analog
* Each entry takes up 6 bytes in FLASH:
* 2 byte pointer to location of the name string
* 2 bytes containing the pin number
* analog pin numbers were convereted to digital when the array was created
* 2 bytes containing the digital/analog bool flag
*/
// manually add pins ...
#if SERIAL_PORT == 0
#if AVR_ATmega2560_FAMILY
{RXD_NAME, 0, 1},
@ -109,7 +109,8 @@ const char* const pin_array[][3] PROGMEM = {
#define n_array (sizeof (pin_array) / sizeof (const char *))/3
#if !defined(TIMER1B) // working with Teensyduino extension so need to re-define some things
#ifndef TIMER1B
// working with Teensyduino extension so need to re-define some things
#include "pinsDebug_Teensyduino.h"
#endif
@ -132,7 +133,7 @@ static bool pwm_status(uint8_t pin) {
switch(digitalPinToTimer(pin)) {
#if defined(TCCR0A) && defined(COM0A1)
#if defined (TIMER0A)
#ifdef TIMER0A
PWM_CASE(0,A);
#endif
PWM_CASE(0,B);
@ -141,7 +142,7 @@ static bool pwm_status(uint8_t pin) {
#if defined(TCCR1A) && defined(COM1A1)
PWM_CASE(1,A);
PWM_CASE(1,B);
#if defined(COM1C1) && defined (TIMER1C)
#if defined(COM1C1) && defined(TIMER1C)
PWM_CASE(1,C);
#endif
#endif
@ -200,13 +201,13 @@ const uint8_t* const PWM_other[][3] PROGMEM = {
const uint8_t* const PWM_OCR[][3] PROGMEM = {
#if defined (TIMER0A)
#ifdef TIMER0A
{&OCR0A,&OCR0B,0},
#else
{0,&OCR0B,0},
#endif
#if defined(COM1C1) && defined (TIMER1C)
#if defined(COM1C1) && defined(TIMER1C)
{ (const uint8_t*) &OCR1A, (const uint8_t*) &OCR1B, (const uint8_t*) &OCR1C},
#else
{ (const uint8_t*) &OCR1A, (const uint8_t*) &OCR1B,0},
@ -217,7 +218,7 @@ const uint8_t* const PWM_OCR[][3] PROGMEM = {
#endif
#if defined(TCCR3A) && defined(COM3A1)
#if defined(COM3C1)
#ifdef COM3C1
{ (const uint8_t*) &OCR3A, (const uint8_t*) &OCR3B, (const uint8_t*) &OCR3C},
#else
{ (const uint8_t*) &OCR3A, (const uint8_t*) &OCR3B,0},
@ -279,12 +280,12 @@ 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
uint8_t *TCCRB = (uint8_t*) TCCR_B(T);
uint8_t *TCCRA = (uint8_t*) TCCR_A(T);
uint8_t *TCCRB = (uint8_t*)TCCR_B(T);
uint8_t *TCCRA = (uint8_t*)TCCR_A(T);
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);
SERIAL_PROTOCOLPGM(" TIMER");
SERIAL_PROTOCOLCHAR(T + '0');
@ -323,18 +324,15 @@ void timer_prefix(uint8_t T, char L, uint8_t N){ // T - timer L - pwm n - W
if (TEST(*TMSK, TOIE)) err_prob_interrupt();
}
static void pwm_details(uint8_t pin) {
char buffer[20]; // for the sprintf statements
uint8_t WGM;
switch(digitalPinToTimer(pin)) {
#if defined(TCCR0A) && defined(COM0A1)
#if defined (TIMER0A)
#ifdef TIMER0A
case TIMER0A:
timer_prefix(0,'A',3);
break;
@ -351,7 +349,7 @@ static void pwm_details(uint8_t pin) {
case TIMER1B:
timer_prefix(1,'B',4);
break;
#if defined(COM1C1) && defined (TIMER1C)
#if defined(COM1C1) && defined(TIMER1C)
case TIMER1C:
timer_prefix(1,'C',4);
break;
@ -374,7 +372,7 @@ static void pwm_details(uint8_t pin) {
case TIMER3B:
timer_prefix(3,'B',4);
break;
#if defined(COM3C1)
#ifdef COM3C1
case TIMER3C:
timer_prefix(3,'C',4);
break;
@ -410,17 +408,15 @@ static void pwm_details(uint8_t pin) {
}
SERIAL_PROTOCOLPGM(" ");
// 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
// looking for port B7 - PWMs 0A and 1C
// looking for port B7 - PWMs 0A and 1C
if ( ('B' == digitalPinToPort(pin) + 64) && (0x80 == digitalPinToBitMask(pin))) {
#if !defined(TEENSYDUINO_IDE)
SERIAL_EOL;
SERIAL_PROTOCOLPGM (" . TIMER1C is also tied to this pin ");
#ifndef TEENSYDUINO_IDE
SERIAL_PROTOCOLPGM("\n . TIMER1C is also tied to this pin ");
timer_prefix(1,'C',4);
#else
SERIAL_EOL;
SERIAL_PROTOCOLPGM (" . TIMER0A is also tied to this pin ");
SERIAL_PROTOCOLPGM("\n . TIMER0A is also tied to this pin ");
timer_prefix(0,'A',3);
#endif
}
@ -429,7 +425,7 @@ static void pwm_details(uint8_t pin) {
bool get_pinMode(int8_t pin) { return *portModeRegister(digitalPinToPort(pin)) & digitalPinToBitMask(pin); }
#if !defined(digitalRead_mod) // use Teensyduino's version of digitalRead - it doesn't disable the PWMs
#ifndef digitalRead_mod // use Teensyduino's version of digitalRead - it doesn't disable the PWMs
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;
@ -437,34 +433,31 @@ bool get_pinMode(int8_t pin) { return *portModeRegister(digitalPinToPort(pin)) &
#endif
void print_port(int8_t pin) { // print port number
#if defined(digitalPinToPort)
#ifdef digitalPinToPort
SERIAL_PROTOCOLPGM(" Port: ");
uint8_t x = digitalPinToPort(pin) + 64;
SERIAL_CHAR(x);
uint8_t temp = digitalPinToBitMask(pin);
for (x = '0'; (x < '9' && !(temp == 1)); x++){
temp = temp >> 1;
}
for (x = '0'; x < '9' && temp != 1; x++) temp >>= 1;
SERIAL_CHAR(x);
#else
SERIAL_PROTOCOLPGM(" ")
SERIAL_PROTOCOLPGM(" ");
#endif
}
// pretty report with PWM info
inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = true) {
uint8_t temp_char;
char *name_mem_pointer;
char buffer[30]; // for the sprintf statements
bool found = false;
bool 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
if (pgm_read_byte(&pin_array[x][1]) == pin) {
if (found == true) multi_name_pin = true;
if (found) multi_name_pin = true;
found = true;
if (multi_name_pin == false) { // report digitial and analog pin number only on the first time through
sprintf(buffer, "PIN:% 3d ", pin); // digital pin number
if (!multi_name_pin) { // report digitial and analog pin number only on the first time through
sprintf(buffer, "PIN: %3d ", pin); // digital pin number
SERIAL_ECHO(buffer);
print_port(pin);
if (IS_ANALOG(pin)) {
@ -479,7 +472,7 @@ inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = t
temp_char = pgm_read_byte(name_mem_pointer + y);
if (temp_char != 0) MYSERIAL.write(temp_char);
else {
for (uint8_t i = 0; i < 28 - y; i++) MYSERIAL.write(" ");
for (uint8_t i = 0; i < 28 - y; i++) MYSERIAL.write(' ');
break;
}
}
@ -487,12 +480,12 @@ inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = t
SERIAL_ECHOPGM("protected ");
else {
if (!(pgm_read_byte(&pin_array[x][2]))) {
sprintf(buffer, "Analog in =% 5d", analogRead(pin - analogInputToDigitalPin(0)));
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 - stopped doing this
//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
SERIAL_PROTOCOLPAIR("Input = ", digitalRead_mod(pin));
@ -502,43 +495,41 @@ inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = t
}
else SERIAL_PROTOCOLPAIR("Output = ", digitalRead_mod(pin));
}
if (multi_name_pin == false && extended) pwm_details(pin); // report PWM capabilities only on the first pass & only if doing an extended report
if (!multi_name_pin && extended) pwm_details(pin); // report PWM capabilities only on the first pass & only if doing an extended report
}
SERIAL_EOL;
} // end of IF
} // end of for loop
if (found == false) {
sprintf(buffer, "PIN:% 3d ", pin);
if (!found) {
sprintf(buffer, "PIN: %3d ", pin);
SERIAL_ECHO(buffer);
print_port(pin);
if (IS_ANALOG(pin)) {
sprintf(buffer, " (A%2d) ", int(pin - analogInputToDigitalPin(0))); // analog pin number
SERIAL_ECHO(buffer);
}
else SERIAL_ECHOPGM(" "); // add padding if not an analog pin
else
SERIAL_ECHOPGM(" "); // add padding if not an analog pin
SERIAL_ECHOPGM("<unused/unknown>");
if (get_pinMode(pin)) {
if (get_pinMode(pin))
SERIAL_PROTOCOLPAIR(" Output = ", digitalRead_mod(pin));
}
else {
if (IS_ANALOG(pin)) {
sprintf(buffer, " Analog in =% 5d", analogRead(pin - analogInputToDigitalPin(0)));
sprintf(buffer, " Analog in = %5d", analogRead(pin - analogInputToDigitalPin(0)));
SERIAL_ECHO(buffer);
}
else {
else
SERIAL_ECHOPGM(" "); // add padding if not an analog pin
}
SERIAL_PROTOCOLPAIR(" Input = ", digitalRead_mod(pin));
}
// if (!pwm_status(pin)) SERIAL_ECHOPGM(" "); // add padding if it's not a PWM pin
}
//if (!pwm_status(pin)) SERIAL_ECHOCHAR(' '); // 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);
}

Loading…
Cancel
Save