Skip to content

Commit 1ead45e

Browse files
ellenspLCh-77
authored andcommitted
🐛 Fix STM32 Pins Debugging (MarlinFirmware#22896)
1 parent b6f40ce commit 1ead45e

File tree

5 files changed

+40
-30
lines changed

5 files changed

+40
-30
lines changed

Marlin/src/HAL/DUE/pinsDebug.h

-1
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,6 @@ bool GET_PINMODE(int8_t pin) { // 1: output, 0: input
8686
|| pwm_status(pin));
8787
}
8888

89-
9089
void pwm_details(int32_t pin) {
9190
if (pwm_status(pin)) {
9291
uint32_t chan = g_APinDescription[pin].ulPWMChannel;

Marlin/src/HAL/STM32/pinsDebug.h

+29-18
Original file line numberDiff line numberDiff line change
@@ -79,7 +79,6 @@
7979
// make a list of the Arduino pin numbers in the Port/Pin order
8080
//
8181

82-
#define _PIN_ADD_2(NAME_ALPHA, ARDUINO_NUM) { {NAME_ALPHA}, ARDUINO_NUM },
8382
#define _PIN_ADD(NAME_ALPHA, ARDUINO_NUM) { NAME_ALPHA, ARDUINO_NUM },
8483
#define PIN_ADD(NAME) _PIN_ADD(#NAME, NAME)
8584

@@ -108,7 +107,11 @@ const XrefInfo pin_xref[] PROGMEM = {
108107
/**
109108
* Translation of routines & variables used by pinsDebug.h
110109
*/
111-
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
110+
111+
#if PA0 >= NUM_DIGITAL_PINS
112+
#define HAS_HIGH_ANALOG_PINS 1
113+
#endif
114+
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS + TERN0(HAS_HIGH_ANALOG_PINS, NUM_ANALOG_INPUTS)
112115
#define VALID_PIN(ANUM) ((ANUM) >= 0 && (ANUM) < NUMBER_PINS_TOTAL)
113116
#define digitalRead_mod(Ard_num) extDigitalRead(Ard_num) // must use Arduino pin numbers when doing reads
114117
#define PRINT_PIN(Q)
@@ -164,17 +167,20 @@ bool GET_PINMODE(const pin_t Ard_num) {
164167
return pin_mode == MODE_PIN_OUTPUT || pin_mode == MODE_PIN_ALT; // assume all alt definitions are PWM
165168
}
166169

167-
int8_t digital_pin_to_analog_pin(pin_t Ard_num) {
168-
Ard_num -= NUM_ANALOG_FIRST;
169-
return (Ard_num >= 0 && Ard_num < NUM_ANALOG_INPUTS) ? Ard_num : -1;
170+
int8_t digital_pin_to_analog_pin(const pin_t Ard_num) {
171+
if (WITHIN(Ard_num, NUM_ANALOG_FIRST, NUM_ANALOG_FIRST + NUM_ANALOG_INPUTS - 1))
172+
return Ard_num - NUM_ANALOG_FIRST;
173+
174+
const uint32_t ind = digitalPinToAnalogInput(Ard_num);
175+
return (ind < NUM_ANALOG_INPUTS) ? ind : -1;
170176
}
171177

172178
bool IS_ANALOG(const pin_t Ard_num) {
173179
return get_pin_mode(Ard_num) == MODE_PIN_ANALOG;
174180
}
175181

176-
bool is_digital(const pin_t x) {
177-
const uint8_t pin_mode = get_pin_mode(pin_array[x].pin);
182+
bool is_digital(const pin_t Ard_num) {
183+
const uint8_t pin_mode = get_pin_mode(pin_array[Ard_num].pin);
178184
return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT;
179185
}
180186

@@ -200,10 +206,15 @@ void port_print(const pin_t Ard_num) {
200206
SERIAL_ECHO_SP(7);
201207

202208
// Print number to be used with M42
203-
sprintf_P(buffer, PSTR(" M42 P%d "), Ard_num);
204-
SERIAL_ECHO(buffer);
205-
if (Ard_num < 10) SERIAL_CHAR(' ');
206-
if (Ard_num < 100) SERIAL_CHAR(' ');
209+
int calc_p = Ard_num % (NUM_DIGITAL_PINS + 1);
210+
if (Ard_num > NUM_DIGITAL_PINS && calc_p > 7) calc_p += 8;
211+
SERIAL_ECHOPGM(" M42 P", calc_p);
212+
SERIAL_CHAR(' ');
213+
if (calc_p < 100) {
214+
SERIAL_CHAR(' ');
215+
if (calc_p < 10)
216+
SERIAL_CHAR(' ');
217+
}
207218
}
208219

209220
bool pwm_status(const pin_t Ard_num) {
@@ -225,19 +236,19 @@ void pwm_details(const pin_t Ard_num) {
225236
case 'D' : alt_all = GPIOD->AFR[ind]; break;
226237
#ifdef PE_0
227238
case 'E' : alt_all = GPIOE->AFR[ind]; break;
228-
#elif defined (PF_0)
239+
#elif defined(PF_0)
229240
case 'F' : alt_all = GPIOF->AFR[ind]; break;
230-
#elif defined (PG_0)
241+
#elif defined(PG_0)
231242
case 'G' : alt_all = GPIOG->AFR[ind]; break;
232-
#elif defined (PH_0)
243+
#elif defined(PH_0)
233244
case 'H' : alt_all = GPIOH->AFR[ind]; break;
234-
#elif defined (PI_0)
245+
#elif defined(PI_0)
235246
case 'I' : alt_all = GPIOI->AFR[ind]; break;
236-
#elif defined (PJ_0)
247+
#elif defined(PJ_0)
237248
case 'J' : alt_all = GPIOJ->AFR[ind]; break;
238-
#elif defined (PK_0)
249+
#elif defined(PK_0)
239250
case 'K' : alt_all = GPIOK->AFR[ind]; break;
240-
#elif defined (PL_0)
251+
#elif defined(PL_0)
241252
case 'L' : alt_all = GPIOL->AFR[ind]; break;
242253
#endif
243254
}

Marlin/src/gcode/config/M43.cpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -313,7 +313,7 @@ void GcodeSuite::M43() {
313313

314314
// 'P' Get the range of pins to test or watch
315315
uint8_t first_pin = PARSED_PIN_INDEX('P', 0),
316-
last_pin = parser.seenval('P') ? first_pin : NUMBER_PINS_TOTAL - 1;
316+
last_pin = parser.seenval('P') ? first_pin : TERN(HAS_HIGH_ANALOG_PINS, NUM_DIGITAL_PINS, NUMBER_PINS_TOTAL) - 1;
317317

318318
if (first_pin > last_pin) return;
319319

@@ -333,12 +333,12 @@ void GcodeSuite::M43() {
333333
if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) continue;
334334
pinMode(pin, INPUT_PULLUP);
335335
delay(1);
336-
/*
337-
if (IS_ANALOG(pin))
338-
pin_state[pin - first_pin] = analogRead(DIGITAL_PIN_TO_ANALOG_PIN(pin)); // int16_t pin_state[...]
339-
else
340-
//*/
341-
pin_state[i - first_pin] = extDigitalRead(pin);
336+
/*
337+
if (IS_ANALOG(pin))
338+
pin_state[pin - first_pin] = analogRead(DIGITAL_PIN_TO_ANALOG_PIN(pin)); // int16_t pin_state[...]
339+
else
340+
//*/
341+
pin_state[i - first_pin] = extDigitalRead(pin);
342342
}
343343

344344
#if HAS_RESUME_CONTINUE

buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_PRO_V1_F429/variant.h

+2-2
Original file line numberDiff line numberDiff line change
@@ -141,10 +141,10 @@ extern "C" {
141141
#define PG15 111 //D79
142142

143143
// This must be a literal with the same value as PEND
144-
#define NUM_DIGITAL_PINS 125
144+
#define NUM_DIGITAL_PINS 112
145145
// This must be a literal with a value less than or equal to to MAX_ANALOG_INPUTS
146146
#define NUM_ANALOG_INPUTS 13
147-
#define NUM_ANALOG_FIRST 112
147+
#define NUM_ANALOG_FIRST NUM_DIGITAL_PINS
148148

149149
//#define ADC_RESOLUTION 12
150150

buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.h

+2-2
Original file line numberDiff line numberDiff line change
@@ -141,10 +141,10 @@ extern "C" {
141141
#define PG15 111 //D79
142142

143143
// This must be a literal with the same value as PEND
144-
#define NUM_DIGITAL_PINS 125
144+
#define NUM_DIGITAL_PINS 112
145145
// This must be a literal with a value less than or equal to to MAX_ANALOG_INPUTS
146146
#define NUM_ANALOG_INPUTS 13
147-
#define NUM_ANALOG_FIRST 112
147+
#define NUM_ANALOG_FIRST NUM_DIGITAL_PINS
148148

149149
//#define ADC_RESOLUTION 12
150150

0 commit comments

Comments
 (0)