aboutsummaryrefslogtreecommitdiff
path: root/Marlin/src/HAL/DUE/fastio
diff options
context:
space:
mode:
Diffstat (limited to 'Marlin/src/HAL/DUE/fastio')
-rw-r--r--Marlin/src/HAL/DUE/fastio/G2_PWM.cpp206
-rw-r--r--Marlin/src/HAL/DUE/fastio/G2_PWM.h78
-rw-r--r--Marlin/src/HAL/DUE/fastio/G2_pins.h278
3 files changed, 562 insertions, 0 deletions
diff --git a/Marlin/src/HAL/DUE/fastio/G2_PWM.cpp b/Marlin/src/HAL/DUE/fastio/G2_PWM.cpp
new file mode 100644
index 0000000..d9fbabc
--- /dev/null
+++ b/Marlin/src/HAL/DUE/fastio/G2_PWM.cpp
@@ -0,0 +1,206 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+
+/**
+ * The PWM module is only used to generate interrupts at specified times. It
+ * is NOT used to directly toggle pins. The ISR writes to the pin assigned to
+ * that interrupt.
+ *
+ * All PWMs use the same repetition rate. The G2 needs about 10KHz min in order to
+ * not have obvious ripple on the Vref signals.
+ *
+ * The data structures are setup to minimize the computation done by the ISR which
+ * minimizes ISR execution time. Execution times are 0.8 to 1.1 microseconds.
+ *
+ * FIve PWM interrupt sources are used. Channel 0 sets the base period. All Vref
+ * signals are set active when this counter overflows and resets to zero. The compare
+ * values in channels 1-4 are set to give the desired duty cycle for that Vref pin.
+ * When counter 0 matches the compare value then that channel generates an interrupt.
+ * The ISR checks the source of the interrupt and sets the corresponding pin inactive.
+ *
+ * Some jitter in the Vref signal is OK so the interrupt priority is left at its default value.
+ */
+
+#include "../../../inc/MarlinConfig.h"
+
+#if MB(PRINTRBOARD_G2)
+
+#include "G2_PWM.h"
+
+#if PIN_EXISTS(MOTOR_CURRENT_PWM_X)
+ #define G2_PWM_X 1
+#else
+ #define G2_PWM_X 0
+#endif
+#if PIN_EXISTS(MOTOR_CURRENT_PWM_Y)
+ #define G2_PWM_Y 1
+#else
+ #define G2_PWM_Y 0
+#endif
+#if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
+ #define G2_PWM_Z 1
+#else
+ #define G2_PWM_Z 0
+#endif
+#if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
+ #define G2_PWM_E 1
+#else
+ #define G2_PWM_E 0
+#endif
+#define G2_MASK_X(V) (G2_PWM_X * (V))
+#define G2_MASK_Y(V) (G2_PWM_Y * (V))
+#define G2_MASK_Z(V) (G2_PWM_Z * (V))
+#define G2_MASK_E(V) (G2_PWM_E * (V))
+
+volatile uint32_t *SODR_A = &PIOA->PIO_SODR,
+ *SODR_B = &PIOB->PIO_SODR,
+ *CODR_A = &PIOA->PIO_CODR,
+ *CODR_B = &PIOB->PIO_CODR;
+
+PWM_map ISR_table[NUM_PWMS] = PWM_MAP_INIT;
+
+void Stepper::digipot_init() {
+
+ #if PIN_EXISTS(MOTOR_CURRENT_PWM_X)
+ OUT_WRITE(MOTOR_CURRENT_PWM_X_PIN, 0); // init pins
+ #endif
+ #if PIN_EXISTS(MOTOR_CURRENT_PWM_Y)
+ OUT_WRITE(MOTOR_CURRENT_PWM_Y_PIN, 0);
+ #endif
+ #if G2_PWM_Z
+ OUT_WRITE(MOTOR_CURRENT_PWM_Z_PIN, 0);
+ #endif
+ #if G2_PWM_E
+ OUT_WRITE(MOTOR_CURRENT_PWM_E_PIN, 0);
+ #endif
+
+ #define WPKEY (0x50574D << 8) // “PWM” in ASCII
+ #define WPCMD_DIS_SW 0 // command to disable Write Protect SW
+ #define WPRG_ALL (PWM_WPCR_WPRG0 | PWM_WPCR_WPRG1 | PWM_WPCR_WPRG2 | PWM_WPCR_WPRG3 | PWM_WPCR_WPRG4 | PWM_WPCR_WPRG5) // all Write Protect Groups
+
+ #define PWM_CLOCK_F F_CPU / 1000000UL // set clock to 1MHz
+
+ PMC->PMC_PCER1 = PMC_PCER1_PID36; // enable PWM controller clock (disabled on power up)
+
+ PWM->PWM_WPCR = WPKEY | WPRG_ALL | WPCMD_DIS_SW; // enable setting of all PWM registers
+ PWM->PWM_CLK = PWM_CLOCK_F; // enable CLK_A and set it to 1MHz, leave CLK_B disabled
+ PWM->PWM_CH_NUM[0].PWM_CMR = 0b1011; // set channel 0 to Clock A input & to left aligned
+ if (G2_PWM_X) PWM->PWM_CH_NUM[1].PWM_CMR = 0b1011; // set channel 1 to Clock A input & to left aligned
+ if (G2_PWM_Y) PWM->PWM_CH_NUM[2].PWM_CMR = 0b1011; // set channel 2 to Clock A input & to left aligned
+ if (G2_PWM_Z) PWM->PWM_CH_NUM[3].PWM_CMR = 0b1011; // set channel 3 to Clock A input & to left aligned
+ if (G2_PWM_E) PWM->PWM_CH_NUM[4].PWM_CMR = 0b1011; // set channel 4 to Clock A input & to left aligned
+
+ PWM->PWM_CH_NUM[0].PWM_CPRD = PWM_PERIOD_US; // set channel 0 Period
+
+ PWM->PWM_IER2 = PWM_IER1_CHID0; // generate interrupt when counter0 overflows
+ PWM->PWM_IER2 = PWM_IER2_CMPM0
+ | G2_MASK_X(PWM_IER2_CMPM1)
+ | G2_MASK_Y(PWM_IER2_CMPM2)
+ | G2_MASK_Z(PWM_IER2_CMPM3)
+ | G2_MASK_E(PWM_IER2_CMPM4)
+ ; // generate interrupt on compare event
+
+ if (G2_PWM_X) PWM->PWM_CMP[1].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[0])); // interrupt when counter0 == CMPV - used to set Motor 1 PWM inactive
+ if (G2_PWM_Y) PWM->PWM_CMP[2].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[0])); // interrupt when counter0 == CMPV - used to set Motor 2 PWM inactive
+ if (G2_PWM_Z) PWM->PWM_CMP[3].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[1])); // interrupt when counter0 == CMPV - used to set Motor 3 PWM inactive
+ if (G2_PWM_E) PWM->PWM_CMP[4].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[2])); // interrupt when counter0 == CMPV - used to set Motor 4 PWM inactive
+
+ if (G2_PWM_X) PWM->PWM_CMP[1].PWM_CMPM = 0x0001; // enable compare event
+ if (G2_PWM_Y) PWM->PWM_CMP[2].PWM_CMPM = 0x0001; // enable compare event
+ if (G2_PWM_Z) PWM->PWM_CMP[3].PWM_CMPM = 0x0001; // enable compare event
+ if (G2_PWM_E) PWM->PWM_CMP[4].PWM_CMPM = 0x0001; // enable compare event
+
+ PWM->PWM_SCM = PWM_SCM_UPDM_MODE0 | PWM_SCM_SYNC0
+ | G2_MASK_X(PWM_SCM_SYNC1)
+ | G2_MASK_Y(PWM_SCM_SYNC2)
+ | G2_MASK_Z(PWM_SCM_SYNC3)
+ | G2_MASK_E(PWM_SCM_SYNC4)
+ ; // sync 1-4 with 0, use mode 0 for updates
+
+ PWM->PWM_ENA = PWM_ENA_CHID0
+ | G2_MASK_X(PWM_ENA_CHID1)
+ | G2_MASK_Y(PWM_ENA_CHID2)
+ | G2_MASK_Z(PWM_ENA_CHID3)
+ | G2_MASK_E(PWM_ENA_CHID4)
+ ; // enable channels used by G2
+
+ PWM->PWM_IER1 = PWM_IER1_CHID0
+ | G2_MASK_X(PWM_IER1_CHID1)
+ | G2_MASK_Y(PWM_IER1_CHID2)
+ | G2_MASK_Z(PWM_IER1_CHID3)
+ | G2_MASK_E(PWM_IER1_CHID4)
+ ; // enable interrupts for channels used by G2
+
+ NVIC_EnableIRQ(PWM_IRQn); // Enable interrupt handler
+ NVIC_SetPriority(PWM_IRQn, NVIC_EncodePriority(0, 10, 0)); // normal priority for PWM module (can stand some jitter on the Vref signals)
+}
+
+void Stepper::set_digipot_current(const uint8_t driver, const int16_t current) {
+
+ if (!(PWM->PWM_CH_NUM[0].PWM_CPRD == PWM_PERIOD_US)) digipot_init(); // Init PWM system if needed
+
+ switch (driver) {
+ case 0:
+ if (G2_PWM_X) PWM->PWM_CMP[1].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update X & Y
+ if (G2_PWM_Y) PWM->PWM_CMP[2].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current));
+ if (G2_PWM_X) PWM->PWM_CMP[1].PWM_CMPMUPD = 0x0001; // enable compare event
+ if (G2_PWM_Y) PWM->PWM_CMP[2].PWM_CMPMUPD = 0x0001; // enable compare event
+ if (G2_PWM_X || G2_PWM_Y) PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle
+ break;
+ case 1:
+ if (G2_PWM_Z) {
+ PWM->PWM_CMP[3].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update Z
+ PWM->PWM_CMP[3].PWM_CMPMUPD = 0x0001; // enable compare event
+ PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle
+ }
+ break;
+ default:
+ if (G2_PWM_E) {
+ PWM->PWM_CMP[4].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update E
+ PWM->PWM_CMP[4].PWM_CMPMUPD = 0x0001; // enable compare event
+ PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle
+ }
+ break;
+ }
+}
+
+volatile uint32_t PWM_ISR1_STATUS, PWM_ISR2_STATUS;
+
+void PWM_Handler() {
+ PWM_ISR1_STATUS = PWM->PWM_ISR1;
+ PWM_ISR2_STATUS = PWM->PWM_ISR2;
+ if (PWM_ISR1_STATUS & PWM_IER1_CHID0) { // CHAN_0 interrupt
+ if (G2_PWM_X) *ISR_table[0].set_register = ISR_table[0].write_mask; // set X to active
+ if (G2_PWM_Y) *ISR_table[1].set_register = ISR_table[1].write_mask; // set Y to active
+ if (G2_PWM_Z) *ISR_table[2].set_register = ISR_table[2].write_mask; // set Z to active
+ if (G2_PWM_E) *ISR_table[3].set_register = ISR_table[3].write_mask; // set E to active
+ }
+ else {
+ if (G2_PWM_X && (PWM_ISR2_STATUS & PWM_IER2_CMPM1)) *ISR_table[0].clr_register = ISR_table[0].write_mask; // set X to inactive
+ if (G2_PWM_Y && (PWM_ISR2_STATUS & PWM_IER2_CMPM2)) *ISR_table[1].clr_register = ISR_table[1].write_mask; // set Y to inactive
+ if (G2_PWM_Z && (PWM_ISR2_STATUS & PWM_IER2_CMPM3)) *ISR_table[2].clr_register = ISR_table[2].write_mask; // set Z to inactive
+ if (G2_PWM_E && (PWM_ISR2_STATUS & PWM_IER2_CMPM4)) *ISR_table[3].clr_register = ISR_table[3].write_mask; // set E to inactive
+ }
+ return;
+}
+
+#endif // PRINTRBOARD_G2
diff --git a/Marlin/src/HAL/DUE/fastio/G2_PWM.h b/Marlin/src/HAL/DUE/fastio/G2_PWM.h
new file mode 100644
index 0000000..dc4edff
--- /dev/null
+++ b/Marlin/src/HAL/DUE/fastio/G2_PWM.h
@@ -0,0 +1,78 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#pragma once
+
+/**
+ * This module is stripped down version of the LPC1768_PWM.h file from
+ * PR #7500. It is hardwired for the PRINTRBOARD_G2 Motor Current needs.
+ */
+
+#include "../../../inc/MarlinConfigPre.h"
+#include "../../../module/stepper.h"
+//C:\Users\bobku\Documents\GitHub\Marlin-Bob-2\Marlin\src\module\stepper.h
+//C:\Users\bobku\Documents\GitHub\Marlin-Bob-2\Marlin\src\HAL\HAL_DUE\G2_PWM.h
+
+#define PWM_PERIOD_US 100 // base repetition rate in micro seconds
+
+typedef struct { // holds the data needed by the ISR to control the Vref pin
+ volatile uint32_t* set_register;
+ volatile uint32_t* clr_register;
+ uint32_t write_mask;
+} PWM_map;
+
+#define G2_VREF(I) (uint32_t)(I * 5 * 0.15) // desired Vref * 1000 (scaled so don't loose accuracy in next step)
+
+#define G2_VREF_COUNT(Q) (uint32_t)map(constrain(Q, 500, 3.3 * 1000), 0, 3.3 * 1000, 0, PWM_PERIOD_US) // under 500 the results are very non-linear
+
+extern volatile uint32_t *SODR_A, *SODR_B, *CODR_A, *CODR_B;
+
+#define _PIN(IO) (DIO ## IO ## _PIN)
+
+#define PWM_MAP_INIT_ROW(IO,ZZ) { ZZ == 'A' ? SODR_A : SODR_B, ZZ == 'A' ? CODR_A : CODR_B, 1 << _PIN(IO) }
+
+
+#define PWM_MAP_INIT { PWM_MAP_INIT_ROW(MOTOR_CURRENT_PWM_X_PIN, 'B'), \
+ PWM_MAP_INIT_ROW(MOTOR_CURRENT_PWM_Y_PIN, 'B'), \
+ PWM_MAP_INIT_ROW(MOTOR_CURRENT_PWM_Z_PIN, 'B'), \
+ PWM_MAP_INIT_ROW(MOTOR_CURRENT_PWM_E_PIN, 'A'), \
+ };
+
+#define NUM_PWMS 4
+
+extern PWM_map ISR_table[NUM_PWMS];
+
+extern uint32_t motor_current_setting[3];
+
+#define IR_BIT(p) (WITHIN(p, 0, 3) ? (p) : (p) + 4)
+#define COPY_ACTIVE_TABLE() do{ LOOP_L_N(i, 6) work_table[i] = active_table[i]; }while(0)
+
+#define PWM_MR0 19999 // base repetition rate minus one count - 20mS
+#define PWM_PR 24 // prescaler value - prescaler divide by 24 + 1 - 1 MHz output
+#define PWM_PCLKSEL0 0x00 // select clock source for prescaler - defaults to 25MHz on power up
+ // 0: 25MHz, 1: 100MHz, 2: 50MHz, 3: 12.5MHZ to PWM1 prescaler
+#define MR0_MARGIN 200 // if channel value too close to MR0 the system locks up
+
+extern bool PWM_table_swap; // flag to tell the ISR that the tables have been swapped
+
+#define HAL_G2_PWM_ISR void PWM_Handler()
+
+extern volatile uint32_t PWM_ISR1_STATUS, PWM_ISR2_STATUS;
diff --git a/Marlin/src/HAL/DUE/fastio/G2_pins.h b/Marlin/src/HAL/DUE/fastio/G2_pins.h
new file mode 100644
index 0000000..80c87bd
--- /dev/null
+++ b/Marlin/src/HAL/DUE/fastio/G2_pins.h
@@ -0,0 +1,278 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#pragma once
+
+#include <stdint.h>
+
+/**
+ * This file contains the custom port/pin definitions for the PRINTRBOARD_G2
+ * motherboard. This motherboard uses the SAM3X8C which is a subset of the
+ * SAM3X8E used in the DUE board. It uses port/pin pairs that are not
+ * available using the DUE definitions.
+ *
+ * The first part is a copy of the pin descriptions in the
+ * "variants\arduino_due_x\variant.cpp" file but with pins 34-41 replaced by
+ * the G2 pins.
+ *
+ * The second part is the FASTIO port/pin definitions.
+ *
+ * THESE PINS CAN ONLY BE ACCESSED VIA FASTIO COMMANDS.
+ */
+
+/*
+ Copyright (c) 2011 Arduino. All right reserved.
+
+ This library is free software; you can redistribute it and/or
+ modify it under the terms of the GNU Lesser General Public
+ License as published by the Free Software Foundation; either
+ version 2.1 of the License, or (at your option) any later version.
+
+ This library is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+ See the GNU Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with this library; if not, write to the Free Software
+ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+*/
+
+typedef struct _G2_PinDescription {
+ Pio* pPort;
+ uint32_t ulPin;
+ uint32_t ulPeripheralId;
+ EPioType ulPinType;
+ uint32_t ulPinConfiguration;
+ uint32_t ulPinAttribute;
+ EAnalogChannel ulAnalogChannel; /* Analog pin in the Arduino context (label on the board) */
+ EAnalogChannel ulADCChannelNumber; /* ADC Channel number in the SAM device */
+ EPWMChannel ulPWMChannel;
+ ETCChannel ulTCChannel;
+} G2_PinDescription;
+
+/**
+ * This section is a copy of the pin descriptions in the "variants\arduino_due_x\variant.cpp" file
+ * with pins 34-41 replaced by the G2 pins.
+ */
+
+/**
+ * Pins descriptions
+ */
+const G2_PinDescription G2_g_APinDescription[] = {
+ // 0 .. 53 - Digital pins
+ // ----------------------
+ // 0/1 - UART (Serial)
+ { PIOA, PIO_PA8A_URXD, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // URXD
+ { PIOA, PIO_PA9A_UTXD, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // UTXD
+
+ // 2
+ { PIOB, PIO_PB25B_TIOA0, ID_PIOB, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC0_CHA0 }, // TIOA0
+ { PIOC, PIO_PC28B_TIOA7, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC2_CHA7 }, // TIOA7
+ { PIOC, PIO_PC26B_TIOB6, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC2_CHB6 }, // TIOB6
+
+ // 5
+ { PIOC, PIO_PC25B_TIOA6, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC2_CHA6 }, // TIOA6
+ { PIOC, PIO_PC24B_PWML7, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM), NO_ADC, NO_ADC, PWM_CH7, NOT_ON_TIMER }, // PWML7
+ { PIOC, PIO_PC23B_PWML6, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM), NO_ADC, NO_ADC, PWM_CH6, NOT_ON_TIMER }, // PWML6
+ { PIOC, PIO_PC22B_PWML5, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM), NO_ADC, NO_ADC, PWM_CH5, NOT_ON_TIMER }, // PWML5
+ { PIOC, PIO_PC21B_PWML4, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM), NO_ADC, NO_ADC, PWM_CH4, NOT_ON_TIMER }, // PWML4
+ // 10
+ { PIOC, PIO_PC29B_TIOB7, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC2_CHB7 }, // TIOB7
+ { PIOD, PIO_PD7B_TIOA8, ID_PIOD, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC2_CHA8 }, // TIOA8
+ { PIOD, PIO_PD8B_TIOB8, ID_PIOD, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC2_CHB8 }, // TIOB8
+
+ // 13 - AMBER LED
+ { PIOB, PIO_PB27B_TIOB0, ID_PIOB, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC0_CHB0 }, // TIOB0
+
+ // 14/15 - USART3 (Serial3)
+ { PIOD, PIO_PD4B_TXD3, ID_PIOD, PIO_PERIPH_B, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // TXD3
+ { PIOD, PIO_PD5B_RXD3, ID_PIOD, PIO_PERIPH_B, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // RXD3
+
+ // 16/17 - USART1 (Serial2)
+ { PIOA, PIO_PA13A_TXD1, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // TXD1
+ { PIOA, PIO_PA12A_RXD1, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // RXD1
+
+ // 18/19 - USART0 (Serial1)
+ { PIOA, PIO_PA11A_TXD0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // TXD0
+ { PIOA, PIO_PA10A_RXD0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // RXD0
+
+ // 20/21 - TWI1
+ { PIOB, PIO_PB12A_TWD1, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // TWD1 - SDA0
+ { PIOB, PIO_PB13A_TWCK1, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // TWCK1 - SCL0
+
+ // 22
+ { PIOB, PIO_PB26, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 22
+ { PIOA, PIO_PA14, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 23
+ { PIOA, PIO_PA15, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 24
+ { PIOD, PIO_PD0, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 25
+
+ // 26
+ { PIOD, PIO_PD1, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 26
+ { PIOD, PIO_PD2, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 27
+ { PIOD, PIO_PD3, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 28
+ { PIOD, PIO_PD6, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 29
+
+ // 30
+ { PIOD, PIO_PD9, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 30
+ { PIOA, PIO_PA7, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 31
+ { PIOD, PIO_PD10, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 32
+ { PIOC, PIO_PC1, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 33
+
+ // 34
+
+ // start of custom pins
+ { PIOA, PIO_PA29, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 34 Y_STEP_PIN
+ { PIOB, PIO_PB1, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 35 Y_DIR_PIN
+ { PIOB, PIO_PB0, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 36 Y_ENABLE_PIN
+ { PIOB, PIO_PB22, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 37 E0_ENABLE_PIN
+ { PIOB, PIO_PB11, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 38 E0_MS1_PIN
+ { PIOB, PIO_PB10, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 39 E0_MS3_PIN
+ { PIOA, PIO_PA5, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 40 HEATER_0_PIN
+ { PIOB, PIO_PB24, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 41 HEATER_BED_PIN
+ // end of custom pins
+
+ // 42
+ { PIOA, PIO_PA19, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 42
+ { PIOA, PIO_PA20, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 43
+ { PIOC, PIO_PC19, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 44
+ { PIOC, PIO_PC18, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 45
+
+ // 46
+ { PIOC, PIO_PC17, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 46
+ { PIOC, PIO_PC16, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 47
+ { PIOC, PIO_PC15, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 48
+ { PIOC, PIO_PC14, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 49
+
+ // 50
+ { PIOC, PIO_PC13, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 50
+ { PIOC, PIO_PC12, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 51
+ { PIOB, PIO_PB21, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 52
+ { PIOB, PIO_PB14, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 53
+
+
+ // 54 .. 65 - Analog pins
+ // ----------------------
+ { PIOA, PIO_PA16X1_AD7, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC0, ADC7, NOT_ON_PWM, NOT_ON_TIMER }, // AD0
+ { PIOA, PIO_PA24X1_AD6, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC1, ADC6, NOT_ON_PWM, NOT_ON_TIMER }, // AD1
+ { PIOA, PIO_PA23X1_AD5, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC2, ADC5, NOT_ON_PWM, NOT_ON_TIMER }, // AD2
+ { PIOA, PIO_PA22X1_AD4, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC3, ADC4, NOT_ON_PWM, NOT_ON_TIMER }, // AD3
+ // 58
+ { PIOA, PIO_PA6X1_AD3, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC4, ADC3, NOT_ON_PWM, TC0_CHB2 }, // AD4
+ { PIOA, PIO_PA4X1_AD2, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC5, ADC2, NOT_ON_PWM, NOT_ON_TIMER }, // AD5
+ { PIOA, PIO_PA3X1_AD1, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC6, ADC1, NOT_ON_PWM, TC0_CHB1 }, // AD6
+ { PIOA, PIO_PA2X1_AD0, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC7, ADC0, NOT_ON_PWM, TC0_CHA1 }, // AD7
+ // 62
+ { PIOB, PIO_PB17X1_AD10, ID_PIOB, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC8, ADC10, NOT_ON_PWM, NOT_ON_TIMER }, // AD8
+ { PIOB, PIO_PB18X1_AD11, ID_PIOB, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC9, ADC11, NOT_ON_PWM, NOT_ON_TIMER }, // AD9
+ { PIOB, PIO_PB19X1_AD12, ID_PIOB, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC10, ADC12, NOT_ON_PWM, NOT_ON_TIMER }, // AD10
+ { PIOB, PIO_PB20X1_AD13, ID_PIOB, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC11, ADC13, NOT_ON_PWM, NOT_ON_TIMER }, // AD11
+
+ // 66/67 - DAC0/DAC1
+ { PIOB, PIO_PB15X1_DAC0, ID_PIOB, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC12, DA0, NOT_ON_PWM, NOT_ON_TIMER }, // DAC0
+ { PIOB, PIO_PB16X1_DAC1, ID_PIOB, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC13, DA1, NOT_ON_PWM, NOT_ON_TIMER }, // DAC1
+
+ // 68/69 - CANRX0/CANTX0
+ { PIOA, PIO_PA1A_CANRX0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, ADC14, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // CANRX
+ { PIOA, PIO_PA0A_CANTX0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, ADC15, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // CANTX
+
+ // 70/71 - TWI0
+ { PIOA, PIO_PA17A_TWD0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // TWD0 - SDA1
+ { PIOA, PIO_PA18A_TWCK0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // TWCK0 - SCL1
+
+ // 72/73 - LEDs
+ { PIOC, PIO_PC30, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // LED AMBER RXL
+ { PIOA, PIO_PA21, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // LED AMBER TXL
+
+ // 74/75/76 - SPI
+ { PIOA, PIO_PA25A_SPI0_MISO,ID_PIOA,PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // MISO
+ { PIOA, PIO_PA26A_SPI0_MOSI,ID_PIOA,PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // MOSI
+ { PIOA, PIO_PA27A_SPI0_SPCK,ID_PIOA,PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // SPCK
+
+ // 77 - SPI CS0
+ { PIOA, PIO_PA28A_SPI0_NPCS0,ID_PIOA,PIO_PERIPH_A,PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // NPCS0
+
+ // 78 - SPI CS3 (unconnected)
+ { PIOB, PIO_PB23B_SPI0_NPCS3,ID_PIOB,PIO_PERIPH_B,PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // NPCS3
+
+ // 79 .. 84 - "All pins" masks
+
+ // 79 - TWI0 all pins
+ { PIOA, PIO_PA17A_TWD0|PIO_PA18A_TWCK0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER },
+ // 80 - TWI1 all pins
+ { PIOB, PIO_PB12A_TWD1|PIO_PB13A_TWCK1, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER },
+ // 81 - UART (Serial) all pins
+ { PIOA, PIO_PA8A_URXD|PIO_PA9A_UTXD, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER },
+ // 82 - USART0 (Serial1) all pins
+ { PIOA, PIO_PA11A_TXD0|PIO_PA10A_RXD0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER },
+ // 83 - USART1 (Serial2) all pins
+ { PIOA, PIO_PA13A_TXD1|PIO_PA12A_RXD1, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER },
+ // 84 - USART3 (Serial3) all pins
+ { PIOD, PIO_PD4B_TXD3|PIO_PD5B_RXD3, ID_PIOD, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER },
+
+ // 85 - USB
+ { PIOB, PIO_PB11A_UOTGID|PIO_PB10A_UOTGVBOF, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL,NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // ID - VBOF
+
+ // 86 - SPI CS2
+ { PIOB, PIO_PB21B_SPI0_NPCS2, ID_PIOB, PIO_PERIPH_B, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // NPCS2
+
+ // 87 - SPI CS1
+ { PIOA, PIO_PA29A_SPI0_NPCS1, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // NPCS1
+
+ // 88/89 - CANRX1/CANTX1 (same physical pin for 66/53)
+ { PIOB, PIO_PB15A_CANRX1, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // CANRX1
+ { PIOB, PIO_PB14A_CANTX1, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // CANTX1
+
+ // 90 .. 91 - "All CAN pins" masks
+ // 90 - CAN0 all pins
+ { PIOA, PIO_PA1A_CANRX0|PIO_PA0A_CANTX0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER },
+ // 91 - CAN1 all pins
+ { PIOB, PIO_PB15A_CANRX1|PIO_PB14A_CANTX1, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER },
+
+ // END
+ { nullptr, 0, 0, PIO_NOT_A_PIN, PIO_DEFAULT, 0, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }
+};
+
+// This section replaces the FASTIO definitions of pins 34-41
+
+#define DIO34_PIN 29
+#define DIO34_WPORT PIOA // only available via FASTIO // 34 PA29 - Y_STEP_PIN
+
+#define DIO35_PIN 1
+#define DIO35_WPORT PIOB // only available via FASTIO // 35 PAB1 - Y_DIR_PIN
+
+#define DIO36_PIN 0
+#define DIO36_WPORT PIOB // only available via FASTIO // 36 PB0 - Y_ENABLE_PIN
+
+#define DIO37_PIN 22
+#define DIO37_WPORT PIOB // only available via FASTIO // 37 PB22 - E0_ENABLE_PIN
+
+#define DIO38_PIN 11
+#define DIO38_WPORT PIOB // only available via FASTIO // 38 PB11 - E0_MS1_PIN
+
+#define DIO39_PIN 10
+#define DIO39_WPORT PIOB // only available via FASTIO // 39 PB10 - E0_MS3_PIN
+
+#define DIO40_PIN 5
+#define DIO40_WPORT PIOA // only available via FASTIO // 40 PA5 - HEATER_0_PIN
+
+#define DIO41_PIN 24
+#define DIO41_WPORT PIOB // only available via FASTIO // 41 PB24 - HEATER_BED_PIN