0
0
Fork 0
mirror of https://github.com/MarlinFirmware/Marlin.git synced 2025-03-15 10:46:18 +00:00

🧑‍💻 HAL Patches

This commit is contained in:
Scott Lahteine 2023-12-16 02:40:51 -06:00
parent 550a30300d
commit 875301521b
90 changed files with 1557 additions and 1072 deletions

View file

@ -63,18 +63,23 @@ void save_reset_reason() {
void MarlinHAL::init() {
// Init Servo Pins
#define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW)
#if HAS_SERVO_0
INIT_SERVO(0);
OUT_WRITE(SERVO0_PIN, LOW);
#endif
#if HAS_SERVO_1
INIT_SERVO(1);
OUT_WRITE(SERVO1_PIN, LOW);
#endif
#if HAS_SERVO_2
INIT_SERVO(2);
OUT_WRITE(SERVO2_PIN, LOW);
#endif
#if HAS_SERVO_3
INIT_SERVO(3);
OUT_WRITE(SERVO3_PIN, LOW);
#endif
#if HAS_SERVO_4
OUT_WRITE(SERVO4_PIN, LOW);
#endif
#if HAS_SERVO_5
OUT_WRITE(SERVO5_PIN, LOW);
#endif
init_pwm_timers(); // Init user timers to default frequency - 1000HZ

View file

@ -142,15 +142,15 @@ typedef Servo hal_servo_t;
#endif
#define LCD_SERIAL lcdSerial
#if HAS_DGUS_LCD
#define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.get_tx_buffer_free()
#define LCD_SERIAL_TX_BUFFER_FREE() LCD_SERIAL.get_tx_buffer_free()
#endif
#endif
//
// ADC
//
#define HAL_ADC_VREF 5.0
#define HAL_ADC_RESOLUTION 10
#define HAL_ADC_VREF_MV 5000
#define HAL_ADC_RESOLUTION 10
//
// Pin Mapping for M42, M43, M226

View file

@ -34,12 +34,9 @@
#include <WString.h>
#include "../../inc/MarlinConfigPre.h"
#include "../../core/types.h"
#include "../../core/serial_hook.h"
#ifndef SERIAL_PORT
#define SERIAL_PORT 0
#endif
#ifndef USBCON
// The presence of the UBRRH register is used to detect a UART.
@ -138,10 +135,6 @@
#define BYTE 0
// Templated type selector
template<bool b, typename T, typename F> struct TypeSelector { typedef T type;} ;
template<typename T, typename F> struct TypeSelector<false, T, F> { typedef F type; };
template<typename Cfg>
class MarlinSerial {
protected:
@ -164,7 +157,7 @@
static constexpr B_U2Xx<Cfg::PORT> B_U2X = 0;
// Base size of type on buffer size
typedef typename TypeSelector<(Cfg::RX_SIZE>256), uint16_t, uint8_t>::type ring_buffer_pos_t;
typedef uvalue_t(Cfg::RX_SIZE - 1) ring_buffer_pos_t;
struct ring_buffer_r {
volatile ring_buffer_pos_t head, tail;

View file

@ -119,7 +119,7 @@ void pciSetup(const int8_t pin) {
void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
#if HAS_X_MAX
#if USE_X_MAX
#if (digitalPinToInterrupt(X_MAX_PIN) != NOT_AN_INTERRUPT)
_ATTACH(X_MAX_PIN);
#else
@ -127,7 +127,7 @@ void setup_endstop_interrupts() {
pciSetup(X_MAX_PIN);
#endif
#endif
#if HAS_X_MIN
#if USE_X_MIN
#if (digitalPinToInterrupt(X_MIN_PIN) != NOT_AN_INTERRUPT)
_ATTACH(X_MIN_PIN);
#else
@ -135,7 +135,7 @@ void setup_endstop_interrupts() {
pciSetup(X_MIN_PIN);
#endif
#endif
#if HAS_Y_MAX
#if USE_Y_MAX
#if (digitalPinToInterrupt(Y_MAX_PIN) != NOT_AN_INTERRUPT)
_ATTACH(Y_MAX_PIN);
#else
@ -143,7 +143,7 @@ void setup_endstop_interrupts() {
pciSetup(Y_MAX_PIN);
#endif
#endif
#if HAS_Y_MIN
#if USE_Y_MIN
#if (digitalPinToInterrupt(Y_MIN_PIN) != NOT_AN_INTERRUPT)
_ATTACH(Y_MIN_PIN);
#else
@ -151,7 +151,7 @@ void setup_endstop_interrupts() {
pciSetup(Y_MIN_PIN);
#endif
#endif
#if HAS_Z_MAX
#if USE_Z_MAX
#if (digitalPinToInterrupt(Z_MAX_PIN) != NOT_AN_INTERRUPT)
_ATTACH(Z_MAX_PIN);
#else
@ -159,7 +159,7 @@ void setup_endstop_interrupts() {
pciSetup(Z_MAX_PIN);
#endif
#endif
#if HAS_Z_MIN
#if USE_Z_MIN
#if (digitalPinToInterrupt(Z_MIN_PIN) != NOT_AN_INTERRUPT)
_ATTACH(Z_MIN_PIN);
#else
@ -167,97 +167,97 @@ void setup_endstop_interrupts() {
pciSetup(Z_MIN_PIN);
#endif
#endif
#if HAS_I_MAX
#if USE_I_MAX
#if (digitalPinToInterrupt(I_MAX_PIN) != NOT_AN_INTERRUPT)
_ATTACH(I_MAX_PIN);
#else
static_assert(digitalPinHasPCICR(I_MAX_PIN), "I_MAX_PIN is not interrupt-capable");
static_assert(digitalPinHasPCICR(I_MAX_PIN), "I_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue.");
pciSetup(I_MAX_PIN);
#endif
#elif HAS_I_MIN
#elif USE_I_MIN
#if (digitalPinToInterrupt(I_MIN_PIN) != NOT_AN_INTERRUPT)
_ATTACH(I_MIN_PIN);
#else
static_assert(digitalPinHasPCICR(I_MIN_PIN), "I_MIN_PIN is not interrupt-capable");
static_assert(digitalPinHasPCICR(I_MIN_PIN), "I_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue.");
pciSetup(I_MIN_PIN);
#endif
#endif
#if HAS_J_MAX
#if USE_J_MAX
#if (digitalPinToInterrupt(J_MAX_PIN) != NOT_AN_INTERRUPT)
_ATTACH(J_MAX_PIN);
#else
static_assert(digitalPinHasPCICR(J_MAX_PIN), "J_MAX_PIN is not interrupt-capable");
static_assert(digitalPinHasPCICR(J_MAX_PIN), "J_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue.");
pciSetup(J_MAX_PIN);
#endif
#elif HAS_J_MIN
#elif USE_J_MIN
#if (digitalPinToInterrupt(J_MIN_PIN) != NOT_AN_INTERRUPT)
_ATTACH(J_MIN_PIN);
#else
static_assert(digitalPinHasPCICR(J_MIN_PIN), "J_MIN_PIN is not interrupt-capable");
static_assert(digitalPinHasPCICR(J_MIN_PIN), "J_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue.");
pciSetup(J_MIN_PIN);
#endif
#endif
#if HAS_K_MAX
#if USE_K_MAX
#if (digitalPinToInterrupt(K_MAX_PIN) != NOT_AN_INTERRUPT)
_ATTACH(K_MAX_PIN);
#else
static_assert(digitalPinHasPCICR(K_MAX_PIN), "K_MAX_PIN is not interrupt-capable");
static_assert(digitalPinHasPCICR(K_MAX_PIN), "K_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue.");
pciSetup(K_MAX_PIN);
#endif
#elif HAS_K_MIN
#elif USE_K_MIN
#if (digitalPinToInterrupt(K_MIN_PIN) != NOT_AN_INTERRUPT)
_ATTACH(K_MIN_PIN);
#else
static_assert(digitalPinHasPCICR(K_MIN_PIN), "K_MIN_PIN is not interrupt-capable");
static_assert(digitalPinHasPCICR(K_MIN_PIN), "K_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue.");
pciSetup(K_MIN_PIN);
#endif
#endif
#if HAS_U_MAX
#if USE_U_MAX
#if (digitalPinToInterrupt(U_MAX_PIN) != NOT_AN_INTERRUPT)
_ATTACH(U_MAX_PIN);
#else
static_assert(digitalPinHasPCICR(U_MAX_PIN), "U_MAX_PIN is not interrupt-capable");
static_assert(digitalPinHasPCICR(U_MAX_PIN), "U_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue.");
pciSetup(U_MAX_PIN);
#endif
#elif HAS_U_MIN
#elif USE_U_MIN
#if (digitalPinToInterrupt(U_MIN_PIN) != NOT_AN_INTERRUPT)
_ATTACH(U_MIN_PIN);
#else
static_assert(digitalPinHasPCICR(U_MIN_PIN), "U_MIN_PIN is not interrupt-capable");
static_assert(digitalPinHasPCICR(U_MIN_PIN), "U_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue.");
pciSetup(U_MIN_PIN);
#endif
#endif
#if HAS_V_MAX
#if USE_V_MAX
#if (digitalPinToInterrupt(V_MAX_PIN) != NOT_AN_INTERRUPT)
_ATTACH(V_MAX_PIN);
#else
static_assert(digitalPinHasPCICR(V_MAX_PIN), "V_MAX_PIN is not interrupt-capable");
static_assert(digitalPinHasPCICR(V_MAX_PIN), "V_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue.");
pciSetup(V_MAX_PIN);
#endif
#elif HAS_V_MIN
#elif USE_V_MIN
#if (digitalPinToInterrupt(V_MIN_PIN) != NOT_AN_INTERRUPT)
_ATTACH(V_MIN_PIN);
#else
static_assert(digitalPinHasPCICR(V_MIN_PIN), "V_MIN_PIN is not interrupt-capable");
static_assert(digitalPinHasPCICR(V_MIN_PIN), "V_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue.");
pciSetup(V_MIN_PIN);
#endif
#endif
#if HAS_W_MAX
#if USE_W_MAX
#if (digitalPinToInterrupt(W_MAX_PIN) != NOT_AN_INTERRUPT)
_ATTACH(W_MAX_PIN);
#else
static_assert(digitalPinHasPCICR(W_MAX_PIN), "W_MAX_PIN is not interrupt-capable");
static_assert(digitalPinHasPCICR(W_MAX_PIN), "W_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue.");
pciSetup(W_MAX_PIN);
#endif
#elif HAS_W_MIN
#elif USE_W_MIN
#if (digitalPinToInterrupt(W_MIN_PIN) != NOT_AN_INTERRUPT)
_ATTACH(W_MIN_PIN);
#else
static_assert(digitalPinHasPCICR(W_MIN_PIN), "W_MIN_PIN is not interrupt-capable");
static_assert(digitalPinHasPCICR(W_MIN_PIN), "W_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue.");
pciSetup(W_MIN_PIN);
#endif
#endif
#if HAS_X2_MAX
#if USE_X2_MAX
#if (digitalPinToInterrupt(X2_MAX_PIN) != NOT_AN_INTERRUPT)
_ATTACH(X2_MAX_PIN);
#else
@ -265,7 +265,7 @@ void setup_endstop_interrupts() {
pciSetup(X2_MAX_PIN);
#endif
#endif
#if HAS_X2_MIN
#if USE_X2_MIN
#if (digitalPinToInterrupt(X2_MIN_PIN) != NOT_AN_INTERRUPT)
_ATTACH(X2_MIN_PIN);
#else
@ -273,7 +273,7 @@ void setup_endstop_interrupts() {
pciSetup(X2_MIN_PIN);
#endif
#endif
#if HAS_Y2_MAX
#if USE_Y2_MAX
#if (digitalPinToInterrupt(Y2_MAX_PIN) != NOT_AN_INTERRUPT)
_ATTACH(Y2_MAX_PIN);
#else
@ -281,7 +281,7 @@ void setup_endstop_interrupts() {
pciSetup(Y2_MAX_PIN);
#endif
#endif
#if HAS_Y2_MIN
#if USE_Y2_MIN
#if (digitalPinToInterrupt(Y2_MIN_PIN) != NOT_AN_INTERRUPT)
_ATTACH(Y2_MIN_PIN);
#else
@ -289,7 +289,7 @@ void setup_endstop_interrupts() {
pciSetup(Y2_MIN_PIN);
#endif
#endif
#if HAS_Z2_MAX
#if USE_Z2_MAX
#if (digitalPinToInterrupt(Z2_MAX_PIN) != NOT_AN_INTERRUPT)
_ATTACH(Z2_MAX_PIN);
#else
@ -297,7 +297,7 @@ void setup_endstop_interrupts() {
pciSetup(Z2_MAX_PIN);
#endif
#endif
#if HAS_Z2_MIN
#if USE_Z2_MIN
#if (digitalPinToInterrupt(Z2_MIN_PIN) != NOT_AN_INTERRUPT)
_ATTACH(Z2_MIN_PIN);
#else
@ -305,7 +305,7 @@ void setup_endstop_interrupts() {
pciSetup(Z2_MIN_PIN);
#endif
#endif
#if HAS_Z3_MAX
#if USE_Z3_MAX
#if (digitalPinToInterrupt(Z3_MAX_PIN) != NOT_AN_INTERRUPT)
_ATTACH(Z3_MAX_PIN);
#else
@ -313,7 +313,7 @@ void setup_endstop_interrupts() {
pciSetup(Z3_MAX_PIN);
#endif
#endif
#if HAS_Z3_MIN
#if USE_Z3_MIN
#if (digitalPinToInterrupt(Z3_MIN_PIN) != NOT_AN_INTERRUPT)
_ATTACH(Z3_MIN_PIN);
#else
@ -321,7 +321,7 @@ void setup_endstop_interrupts() {
pciSetup(Z3_MIN_PIN);
#endif
#endif
#if HAS_Z4_MAX
#if USE_Z4_MAX
#if (digitalPinToInterrupt(Z4_MAX_PIN) != NOT_AN_INTERRUPT)
_ATTACH(Z4_MAX_PIN);
#else
@ -329,7 +329,7 @@ void setup_endstop_interrupts() {
pciSetup(Z4_MAX_PIN);
#endif
#endif
#if HAS_Z4_MIN
#if USE_Z4_MIN
#if (digitalPinToInterrupt(Z4_MIN_PIN) != NOT_AN_INTERRUPT)
_ATTACH(Z4_MIN_PIN);
#else

View file

@ -255,84 +255,6 @@ enum ClockSource2 : uint8_t {
#define SET_FOCB(T,V) SET_FOC(T,B,V)
#define SET_FOCC(T,V) SET_FOC(T,C,V)
#if 0
/**
* PWM availability macros
*/
// Determine which hardware PWMs are already in use
#define _PWM_CHK_FAN_B(P) (P == E0_AUTO_FAN_PIN || P == E1_AUTO_FAN_PIN || P == E2_AUTO_FAN_PIN || P == E3_AUTO_FAN_PIN || P == E4_AUTO_FAN_PIN || P == E5_AUTO_FAN_PIN || P == E6_AUTO_FAN_PIN || P == E7_AUTO_FAN_PIN || P == CHAMBER_AUTO_FAN_PIN || P == COOLER_AUTO_FAN_PIN)
#if PIN_EXISTS(CONTROLLER_FAN)
#define PWM_CHK_FAN_B(P) (_PWM_CHK_FAN_B(P) || P == CONTROLLER_FAN_PIN)
#else
#define PWM_CHK_FAN_B(P) _PWM_CHK_FAN_B(P)
#endif
#if ANY_PIN(FAN, FAN1, FAN2, FAN3, FAN4, FAN5, FAN6, FAN7)
#if PIN_EXISTS(FAN7)
#define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN || P == FAN3_PIN || P == FAN4_PIN || P == FAN5_PIN || P == FAN6_PIN || P == FAN7_PIN)
#elif PIN_EXISTS(FAN6)
#define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN || P == FAN3_PIN || P == FAN4_PIN || P == FAN5_PIN || P == FAN6_PIN)
#elif PIN_EXISTS(FAN5)
#define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN || P == FAN3_PIN || P == FAN4_PIN || P == FAN5_PIN)
#elif PIN_EXISTS(FAN4)
#define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN || P == FAN3_PIN || P == FAN4_PIN)
#elif PIN_EXISTS(FAN3)
#define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN || P == FAN3_PIN)
#elif PIN_EXISTS(FAN2)
#define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN)
#elif PIN_EXISTS(FAN1)
#define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN)
#else
#define PWM_CHK_FAN_A(P) (P == FAN0_PIN)
#endif
#else
#define PWM_CHK_FAN_A(P) false
#endif
#if HAS_MOTOR_CURRENT_PWM
#if PIN_EXISTS(MOTOR_CURRENT_PWM_XY)
#define PWM_CHK_MOTOR_CURRENT(P) (P == MOTOR_CURRENT_PWM_E_PIN || P == MOTOR_CURRENT_PWM_E0_PIN || P == MOTOR_CURRENT_PWM_E1_PIN || P == MOTOR_CURRENT_PWM_Z_PIN || P == MOTOR_CURRENT_PWM_XY_PIN)
#elif PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
#define PWM_CHK_MOTOR_CURRENT(P) (P == MOTOR_CURRENT_PWM_E_PIN || P == MOTOR_CURRENT_PWM_E0_PIN || P == MOTOR_CURRENT_PWM_E1_PIN || P == MOTOR_CURRENT_PWM_Z_PIN)
#else
#define PWM_CHK_MOTOR_CURRENT(P) (P == MOTOR_CURRENT_PWM_E_PIN || P == MOTOR_CURRENT_PWM_E0_PIN || P == MOTOR_CURRENT_PWM_E1_PIN)
#endif
#else
#define PWM_CHK_MOTOR_CURRENT(P) false
#endif
#ifdef NUM_SERVOS
#if AVR_ATmega2560_FAMILY
#define PWM_CHK_SERVO(P) (P == 5 || (NUM_SERVOS > 12 && P == 6) || (NUM_SERVOS > 24 && P == 46)) // PWMS 3A, 4A & 5A
#elif AVR_ATmega2561_FAMILY
#define PWM_CHK_SERVO(P) (P == 5) // PWM3A
#elif AVR_ATmega1284_FAMILY
#define PWM_CHK_SERVO(P) false
#elif AVR_AT90USB1286_FAMILY
#define PWM_CHK_SERVO(P) (P == 16) // PWM3A
#elif AVR_ATmega328_FAMILY
#define PWM_CHK_SERVO(P) false
#endif
#else
#define PWM_CHK_SERVO(P) false
#endif
#if ENABLED(BARICUDA)
#if HAS_HEATER_1 && HAS_HEATER_2
#define PWM_CHK_HEATER(P) (P == HEATER_1_PIN || P == HEATER_2_PIN)
#elif HAS_HEATER_1
#define PWM_CHK_HEATER(P) (P == HEATER_1_PIN)
#endif
#else
#define PWM_CHK_HEATER(P) false
#endif
#define PWM_CHK(P) (PWM_CHK_HEATER(P) || PWM_CHK_SERVO(P) || PWM_CHK_MOTOR_CURRENT(P) || PWM_CHK_FAN_A(P) || PWM_CHK_FAN_B(P))
#endif // PWM_CHK is not used in Marlin
// define which hardware PWMs are available for the current CPU
// all timer 1 PWMS deleted from this list because they are never available
#if AVR_ATmega2560_FAMILY

View file

@ -27,6 +27,7 @@
* Hardware Pin : 02 03 06 07 01 05 15 16 17 18 23 24 25 26 64 63 13 12 46 45 44 43 78 77 76 75 74 73 72 71 60 59 58 57 56 55 54 53 50 70 52 51 42 41 40 39 38 37 36 35 22 21 20 19 97 96 95 94 93 92 91 90 89 88 87 86 85 84 83 82 | 04 08 09 10 11 14 27 28 29 30 31 32 33 34 47 48 49 61 62 65 66 67 68 69 79 80 81 98 99 100
* Port : E0 E1 E4 E5 G5 E3 H3 H4 H5 H6 B4 B5 B6 B7 J1 J0 H1 H0 D3 D2 D1 D0 A0 A1 A2 A3 A4 A5 A6 A7 C7 C6 C5 C4 C3 C2 C1 C0 D7 G2 G1 G0 L7 L6 L5 L4 L3 L2 L1 L0 B3 B2 B1 B0 F0 F1 F2 F3 F4 F5 F6 F7 K0 K1 K2 K3 K4 K5 K6 K7 | E2 E6 E7 xx xx H2 H7 G3 G4 xx xx xx xx xx D4 D5 D6 xx xx J2 J3 J4 J5 J6 J7 xx xx xx xx xx
* Logical Pin : 00 01 02 03 04 05 06 07 08 09 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 | 78 79 80 xx xx 84 85 71 70 xx xx xx xx xx 81 82 83 xx xx 72 73 75 76 77 74 xx xx xx xx xx
* Analog Input : 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15
*
* Arduino Pin Layout video: https://youtu.be/rIqeVCX09FA
* AVR alternate pin function overview video: https://youtu.be/1yd8wuI5Plg
@ -34,39 +35,36 @@
#include "../fastio.h"
// change for your board
#define DEBUG_LED DIO21
// UART
#define RXD DIO0
#define TXD DIO1
#define RXD 0
#define TXD 1
// SPI
#define SCK DIO52
#define MISO DIO50
#define MOSI DIO51
#define SS DIO53
#define MISO 50
#define MOSI 51
#define SCK 52
#define SS 53
// TWI (I2C)
#define SCL DIO21
#define SDA DIO20
#define SCL 21
#define SDA 20
// Timers and PWM
#define OC0A DIO13
#define OC0B DIO4
#define OC1A DIO11
#define OC1B DIO12
#define OC2A DIO10
#define OC2B DIO9
#define OC3A DIO5
#define OC3B DIO2
#define OC3C DIO3
#define OC4A DIO6
#define OC4B DIO7
#define OC4C DIO8
#define OC5A DIO46
#define OC5B DIO45
#define OC5C DIO44
#define OC0A 13
#define OC0B 4
#define OC1A 11
#define OC1B 12
#define OC2A 10
#define OC2B 9
#define OC3A 5
#define OC3B 2
#define OC3C 3
#define OC4A 6
#define OC4B 7
#define OC4C 8
#define OC5A 46
#define OC5B 45
#define OC5C 44
// Digital I/O

View file

@ -33,32 +33,29 @@
#include "../fastio.h"
// change for your board
#define DEBUG_LED DIO46
// UART
#define RXD DIO0
#define TXD DIO1
#define RXD 0
#define TXD 1
// SPI
#define SCK DIO10
#define MISO DIO12
#define MOSI DIO11
#define SS DIO16
#define SCK 10
#define MISO 12
#define MOSI 11
#define SS 16
// TWI (I2C)
#define SCL DIO17
#define SDA DIO18
#define SCL 17
#define SDA 18
// Timers and PWM
#define OC0A DIO9
#define OC0B DIO4
#define OC1A DIO7
#define OC1B DIO8
#define OC2A DIO6
#define OC3A DIO5
#define OC3B DIO2
#define OC3C DIO3
#define OC0A 9
#define OC0B 4
#define OC1A 7
#define OC1B 8
#define OC2A 6
#define OC3A 5
#define OC3B 2
#define OC3C 3
// Digital I/O

View file

@ -33,29 +33,27 @@
#include "../fastio.h"
#define DEBUG_LED AIO5
// UART
#define RXD DIO0
#define TXD DIO1
#define RXD 0
#define TXD 1
// SPI
#define SCK DIO13
#define MISO DIO12
#define MOSI DIO11
#define SS DIO10
#define SS 10
#define MOSI 11
#define MISO 12
#define SCK 13
// TWI (I2C)
#define SCL AIO5
#define SDA AIO4
// Timers and PWM
#define OC0A DIO6
#define OC0B DIO5
#define OC1A DIO9
#define OC1B DIO10
#define OC2A DIO11
#define OC2B DIO3
#define OC0A 6
#define OC0B 5
#define OC1A 9
#define OC1B 10
#define OC2A 11
#define OC2B 3
// Digital I/O

View file

@ -59,34 +59,32 @@
#include "../fastio.h"
#define DEBUG_LED DIO0
// UART
#define RXD DIO8
#define TXD DIO9
#define RXD0 DIO8
#define TXD0 DIO9
#define RXD 8
#define TXD 9
#define RXD0 8
#define TXD0 9
#define RXD1 DIO10
#define TXD1 DIO11
#define RXD1 10
#define TXD1 11
// SPI
#define SCK DIO7
#define MISO DIO6
#define MOSI DIO5
#define SS DIO4
#define SS 4
#define MOSI 5
#define MISO 6
#define SCK 7
// TWI (I2C)
#define SCL DIO16
#define SDA DIO17
#define SCL 16
#define SDA 17
// Timers and PWM
#define OC0A DIO3
#define OC0B DIO4
#define OC1A DIO13
#define OC1B DIO12
#define OC2A DIO15
#define OC2B DIO14
#define OC0A 3
#define OC0B 4
#define OC1A 13
#define OC1B 12
#define OC2A 15
#define OC2B 14
// Digital I/O

View file

@ -34,14 +34,11 @@
#include "../fastio.h"
// change for your board
#define DEBUG_LED DIO31 /* led D5 red */
// SPI
#define SCK DIO21 // 9
#define MISO DIO23 // 11
#define MOSI DIO22 // 10
#define SS DIO20 // 8
#define SS 20 // 8
#define SCK 21 // 9
#define MOSI 22 // 10
#define MISO 23 // 11
// Digital I/O

View file

@ -20,3 +20,7 @@
*
*/
#pragma once
#ifndef SERIAL_PORT
#define SERIAL_PORT 0
#endif

View file

@ -109,7 +109,7 @@ void PRINT_ARRAY_NAME(uint8_t x) {
* Print a pin's PWM status.
* Return true if it's currently a PWM pin.
*/
static bool pwm_status(uint8_t pin) {
bool pwm_status(uint8_t pin) {
char buffer[20]; // for the sprintf statements
switch (digitalPinToTimer_DEBUG(pin)) {
@ -229,12 +229,12 @@ const volatile uint8_t* const PWM_OCR[][3] PROGMEM = {
#define OCR_VAL(T, L) pgm_read_word(&PWM_OCR[T][L])
static void err_is_counter() { SERIAL_ECHOPGM(" non-standard PWM mode"); }
static void err_is_interrupt() { SERIAL_ECHOPGM(" compare interrupt enabled"); }
static void err_prob_interrupt() { SERIAL_ECHOPGM(" overflow interrupt enabled"); }
static void print_is_also_tied() { SERIAL_ECHOPGM(" is also tied to this pin"); SERIAL_ECHO_SP(14); }
void err_is_counter() { SERIAL_ECHOPGM(" non-standard PWM mode"); }
void err_is_interrupt() { SERIAL_ECHOPGM(" compare interrupt enabled"); }
void err_prob_interrupt() { SERIAL_ECHOPGM(" overflow interrupt enabled"); }
void print_is_also_tied() { SERIAL_ECHOPGM(" is also tied to this pin"); SERIAL_ECHO_SP(14); }
inline void com_print(const uint8_t N, const uint8_t Z) {
void com_print(const uint8_t N, const uint8_t Z) {
const uint8_t *TCCRA = (uint8_t*)TCCR_A(N);
SERIAL_ECHOPGM(" COM", AS_DIGIT(N));
SERIAL_CHAR(Z);
@ -276,7 +276,7 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N -
if (TEST(*TMSK, TOIE)) err_prob_interrupt();
}
static void pwm_details(uint8_t pin) {
void pwm_details(uint8_t pin) {
switch (digitalPinToTimer_DEBUG(pin)) {
#if ABTEST(0)
@ -350,47 +350,41 @@ static void pwm_details(uint8_t pin) {
} // pwm_details
#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
int digitalRead_mod(const pin_t pin) { // same as digitalRead except the PWM stop section has been removed
const uint8_t port = digitalPinToPort_DEBUG(pin);
return (port != NOT_A_PIN) && (*portInputRegister(port) & digitalPinToBitMask_DEBUG(pin)) ? HIGH : LOW;
}
#endif
#ifndef PRINT_PORT
void print_port(const pin_t pin) { // print port number
#ifdef digitalPinToPort_DEBUG
uint8_t x;
SERIAL_ECHOPGM(" Port: ");
#if AVR_AT90USB1286_FAMILY
x = (pin == 46 || pin == 47) ? 'E' : digitalPinToPort_DEBUG(pin) + 64;
#else
x = digitalPinToPort_DEBUG(pin) + 64;
#endif
SERIAL_CHAR(x);
void print_port(int8_t pin) { // print port number
#ifdef digitalPinToPort_DEBUG
uint8_t x;
SERIAL_ECHOPGM(" Port: ");
#if AVR_AT90USB1286_FAMILY
x = (pin == 46 || pin == 47) ? 'E' : digitalPinToPort_DEBUG(pin) + 64;
#else
x = digitalPinToPort_DEBUG(pin) + 64;
#endif
SERIAL_CHAR(x);
#if AVR_AT90USB1286_FAMILY
if (pin == 46)
x = '2';
else if (pin == 47)
x = '3';
else {
uint8_t temp = digitalPinToBitMask_DEBUG(pin);
for (x = '0'; x < '9' && temp != 1; x++) temp >>= 1;
}
#else
#if AVR_AT90USB1286_FAMILY
if (pin == 46)
x = '2';
else if (pin == 47)
x = '3';
else {
uint8_t temp = digitalPinToBitMask_DEBUG(pin);
for (x = '0'; x < '9' && temp != 1; x++) temp >>= 1;
#endif
SERIAL_CHAR(x);
}
#else
SERIAL_ECHO_SP(10);
uint8_t temp = digitalPinToBitMask_DEBUG(pin);
for (x = '0'; x < '9' && temp != 1; x++) temp >>= 1;
#endif
}
#define PRINT_PORT(p) print_port(p)
#endif
SERIAL_CHAR(x);
#else
SERIAL_ECHO_SP(10);
#endif
}
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)

View file

@ -123,7 +123,7 @@ typedef Servo hal_servo_t;
//
// ADC
//
#define HAL_ADC_VREF 3.3
#define HAL_ADC_VREF_MV 3300
#define HAL_ADC_RESOLUTION 10
#ifndef analogInputToDigitalPin

View file

@ -30,6 +30,7 @@
#include <WString.h>
#include "../../inc/MarlinConfigPre.h"
#include "../../core/types.h"
#include "../../core/serial_hook.h"
// Define constants and variables for buffering incoming serial data. We're
@ -52,10 +53,6 @@
// #error "TX_BUFFER_SIZE must be 0, a power of 2 greater than 1, and no greater than 256."
//#endif
// Templated type selector
template<bool b, typename T, typename F> struct TypeSelector { typedef T type;} ;
template<typename T, typename F> struct TypeSelector<false, T, F> { typedef F type; };
// Templated structure wrapper
template<typename S, unsigned int addr> struct StructWrapper {
constexpr StructWrapper(int) {}
@ -76,7 +73,7 @@ protected:
static constexpr int HWUART_IRQ_ID = IRQ_IDS[Cfg::PORT];
// Base size of type on buffer size
typedef typename TypeSelector<(Cfg::RX_SIZE>256), uint16_t, uint8_t>::type ring_buffer_pos_t;
typedef uvalue_t(Cfg::RX_SIZE - 1) ring_buffer_pos_t;
struct ring_buffer_r {
volatile ring_buffer_pos_t head, tail;

View file

@ -85,12 +85,6 @@ void install_min_serial() {
void __attribute__((naked, alias("JumpHandler_ASM"))) MemManage_Handler();
void __attribute__((naked, alias("JumpHandler_ASM"))) NMI_Handler();
}
void __attribute__((naked, alias("JumpHandler_ASM"))) HardFault_Handler();
void __attribute__((naked, alias("JumpHandler_ASM"))) BusFault_Handler();
void __attribute__((naked, alias("JumpHandler_ASM"))) UsageFault_Handler();
void __attribute__((naked, alias("JumpHandler_ASM"))) MemManage_Handler();
void __attribute__((naked, alias("JumpHandler_ASM"))) NMI_Handler();
}
#endif
#endif // POSTMORTEM_DEBUGGING

View file

@ -291,7 +291,7 @@ static bool ee_PageWrite(uint16_t page, const void *data) {
uint32_t *p1 = (uint32_t*)addrflash;
uint32_t *p2 = (uint32_t*)data;
int count = 0;
for (i =0; i<PageSize >> 2; i++) {
for (i = 0; i < PageSize >> 2; i++) {
if (p1[i] != p2[i]) {
uint32_t delta = p1[i] ^ p2[i];
while (delta) {

View file

@ -47,33 +47,33 @@ void endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN));
TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN));
TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN));
TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN));
TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN));
TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN));
TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN));
TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN));
TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN));
TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN));
TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN));
TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN));
TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN));
TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN));
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN));
TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN));
TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN));
TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN));
TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN));
TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN));
TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN));
TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN));
TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN));
TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN));
TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN));
TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN));
TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN));
TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN));
TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN));
TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN));
TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN));
TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN));
TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN));
TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN));
TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN));
TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN));
TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN));
TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN));
TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN));
TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN));
TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN));
TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN));
TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN));
TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN));
TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN));
TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN));
}

View file

@ -189,12 +189,12 @@
*/
// UART
#define RXD DIO0
#define TXD DIO1
#define RXD 0
#define TXD 1
// TWI (I2C)
#define SCL DIO21
#define SDA DIO20
#define SCL 21
#define SDA 20
/**
* pins

View file

@ -64,7 +64,6 @@
#define NUMBER_PINS_TOTAL PINS_COUNT
#define digitalRead_mod(p) extDigitalRead(p) // AVR digitalRead disabled PWM before it read the pin
#define PRINT_PORT(p)
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%02d"), p); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
@ -93,6 +92,8 @@ void pwm_details(int32_t pin) {
}
}
void print_port(const pin_t) {}
/**
* DUE Board pin | PORT | Label
* ----------------+--------+-------

View file

@ -175,7 +175,7 @@ uint8_t MarlinHAL::get_reset_source() { return rtc_get_reset_reason(1); }
void MarlinHAL::reboot() { ESP.restart(); }
void _delay_ms(int delay_ms) { delay(delay_ms); }
void _delay_ms(const int ms) { delay(ms); }
// return free memory between end of heap (or end bss) and whatever is current
int MarlinHAL::freeMemory() { return ESP.getFreeHeap(); }

View file

@ -171,7 +171,7 @@ void _delay_ms(const int ms);
// MarlinHAL Class
// ------------------------
#define HAL_ADC_VREF 3.3
#define HAL_ADC_VREF_MV 3300
#define HAL_ADC_RESOLUTION 10
class MarlinHAL {

View file

@ -42,33 +42,33 @@ void ICACHE_RAM_ATTR endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN));
TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN));
TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN));
TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN));
TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN));
TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN));
TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN));
TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN));
TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN));
TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN));
TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN));
TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN));
TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN));
TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN));
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN));
TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN));
TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN));
TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN));
TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN));
TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN));
TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN));
TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN));
TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN));
TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN));
TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN));
TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN));
TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN));
TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN));
TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN));
TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN));
TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN));
TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN));
TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN));
TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN));
TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN));
TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN));
TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN));
TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN));
TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN));
TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN));
TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN));
TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN));
TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN));
TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN));
TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN));
TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN));
}

View file

@ -134,8 +134,8 @@ static void IRAM_ATTR i2s_intr_handler_default(void *arg) {
if (high_priority_task_awoken == pdTRUE) portYIELD_FROM_ISR();
// clear interrupt
I2S0.int_clr.val = I2S0.int_st.val; //clear pending interrupt
// Clear pending interrupt
I2S0.int_clr.val = I2S0.int_st.val;
}
void stepperTask(void *parameter) {

View file

@ -52,7 +52,7 @@ void OTA_init() {
})
.onError([](ota_error_t error) {
Serial.printf("Error[%u]: ", error);
char *str;
const char *str = "unknown";
switch (error) {
case OTA_AUTH_ERROR: str = "Auth Failed"; break;
case OTA_BEGIN_ERROR: str = "Begin Failed"; break;

View file

@ -53,8 +53,7 @@ uint8_t MarlinHAL::active_ch = 0;
uint16_t MarlinHAL::adc_value() {
const pin_t pin = analogInputToDigitalPin(active_ch);
if (!VALID_PIN(pin)) return 0;
const uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF);
return data; // return 10bit value as Marlin expects
return uint16_t((Gpio::get(pin) >> 2) & 0x3FF); // return 10bit value as Marlin expects
}
void MarlinHAL::reboot() { /* Reset the application state and GPIO */ }

View file

@ -80,8 +80,8 @@ extern MSerialT usb_serial;
#define CRITICAL_SECTION_END()
// ADC
#define HAL_ADC_VREF 5.0
#define HAL_ADC_RESOLUTION 10
#define HAL_ADC_VREF_MV 5000
#define HAL_ADC_RESOLUTION 10
// ------------------------
// Class Utilities

View file

@ -28,6 +28,9 @@
#include <pinmapping.h>
#define strlcpy(A, B, C) strncpy(A, B, (C) - 1)
#define strlcpy_P(A, B, C) strncpy_P(A, B, (C) - 1)
#define HIGH 0x01
#define LOW 0x00

View file

@ -28,36 +28,33 @@
* Translation of routines & variables used by pinsDebug.h
*/
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
#define pwm_details(pin) NOOP // (do nothing)
#define pwm_status(pin) false // Print a pin's PWM status. Return true if it's currently a PWM pin.
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
#define IS_ANALOG(P) (DIGITAL_PIN_TO_ANALOG_PIN(P) >= 0 ? 1 : 0)
#define digitalRead_mod(p) digitalRead(p)
#define PRINT_PORT(p)
#define GET_ARRAY_PIN(p) pin_array[p].pin
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
// active ADC function/mode/code values for PINSEL registers
constexpr int8_t ADC_pin_mode(pin_t pin) {
return (-1);
}
constexpr int8_t ADC_pin_mode(pin_t pin) { return -1; }
int8_t get_pin_mode(pin_t pin) {
if (!VALID_PIN(pin)) return -1;
return 0;
}
int8_t get_pin_mode(const pin_t pin) { return VALID_PIN(pin) ? 0 : -1; }
bool GET_PINMODE(pin_t pin) {
int8_t pin_mode = get_pin_mode(pin);
if (pin_mode == -1 || pin_mode == ADC_pin_mode(pin)) // found an invalid pin or active analog pin
bool GET_PINMODE(const pin_t pin) {
const int8_t pin_mode = get_pin_mode(pin);
if (pin_mode == -1 || pin_mode == ADC_pin_mode(pin)) // Invalid pin or active analog pin
return false;
return (Gpio::getMode(pin) != 0); //input/output state
return (Gpio::getMode(pin) != 0); // Input/output state
}
bool GET_ARRAY_IS_DIGITAL(pin_t pin) {
bool GET_ARRAY_IS_DIGITAL(const pin_t pin) {
return (!IS_ANALOG(pin) || get_pin_mode(pin) != ADC_pin_mode(pin));
}
void pwm_details(const pin_t pin) {}
bool pwm_status(const pin_t) { return false; }
void print_port(const pin_t) {}

View file

@ -23,11 +23,22 @@
#include "../../inc/MarlinConfig.h"
#include "../shared/Delay.h"
#include "../../../gcode/parser.h"
#include "../../core/millis_t.h"
#include <usb/usb.h>
#include <usb/usbcfg.h>
#include <usb/usbhw.h>
#include <usb/usbcore.h>
#include <usb/cdc.h>
#include <usb/cdcuser.h>
#include <usb/mscuser.h>
#include <CDCSerial.h>
#include <usb/mscuser.h>
DefaultSerial1 USBSerial(false, UsbSerial);
uint32_t MarlinHAL::adc_result = 0;
pin_t MarlinHAL::adc_pin = 0;
// U8glib required functions
extern "C" {
@ -48,6 +59,138 @@ int freeMemory() {
return result;
}
extern "C" {
#include <debug_frmwrk.h>
int isLPC1769();
void disk_timerproc();
}
extern uint32_t MSC_SD_Init(uint8_t pdrv);
void SysTick_Callback() { disk_timerproc(); }
TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
void MarlinHAL::init() {
// Init LEDs
#if PIN_EXISTS(LED)
SET_DIR_OUTPUT(LED_PIN);
WRITE_PIN_CLR(LED_PIN);
#if PIN_EXISTS(LED2)
SET_DIR_OUTPUT(LED2_PIN);
WRITE_PIN_CLR(LED2_PIN);
#if PIN_EXISTS(LED3)
SET_DIR_OUTPUT(LED3_PIN);
WRITE_PIN_CLR(LED3_PIN);
#if PIN_EXISTS(LED4)
SET_DIR_OUTPUT(LED4_PIN);
WRITE_PIN_CLR(LED4_PIN);
#endif
#endif
#endif
// Flash status LED 3 times to indicate Marlin has started booting
for (uint8_t i = 0; i < 6; ++i) {
TOGGLE(LED_PIN);
delay(100);
}
#endif
// Init Servo Pins
#define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW)
#if HAS_SERVO_0
INIT_SERVO(0);
#endif
#if HAS_SERVO_1
INIT_SERVO(1);
#endif
#if HAS_SERVO_2
INIT_SERVO(2);
#endif
#if HAS_SERVO_3
INIT_SERVO(3);
#endif
#if HAS_SERVO_4
INIT_SERVO(4);
#endif
#if HAS_SERVO_5
INIT_SERVO(5);
#endif
//debug_frmwrk_init();
//_DBG("\n\nDebug running\n");
// Initialize the SD card chip select pins as soon as possible
#if PIN_EXISTS(SD_SS)
OUT_WRITE(SD_SS_PIN, HIGH);
#endif
#if PIN_EXISTS(ONBOARD_SD_CS) && ONBOARD_SD_CS_PIN != SD_SS_PIN
OUT_WRITE(ONBOARD_SD_CS_PIN, HIGH);
#endif
#ifdef LPC1768_ENABLE_CLKOUT_12M
/**
* CLKOUTCFG register
* bit 8 (CLKOUT_EN) = enables CLKOUT signal. Disabled for now to prevent glitch when enabling GPIO.
* bits 7:4 (CLKOUTDIV) = set to 0 for divider setting of /1
* bits 3:0 (CLKOUTSEL) = set to 1 to select main crystal oscillator as CLKOUT source
*/
LPC_SC->CLKOUTCFG = (0<<8)|(0<<4)|(1<<0);
// set P1.27 pin to function 01 (CLKOUT)
PINSEL_CFG_Type PinCfg;
PinCfg.Portnum = 1;
PinCfg.Pinnum = 27;
PinCfg.Funcnum = 1; // function 01 (CLKOUT)
PinCfg.OpenDrain = 0; // not open drain
PinCfg.Pinmode = 2; // no pull-up/pull-down
PINSEL_ConfigPin(&PinCfg);
// now set CLKOUT_EN bit
SBI(LPC_SC->CLKOUTCFG, 8);
#endif
USB_Init(); // USB Initialization
USB_Connect(false); // USB clear connection
delay(1000); // Give OS time to notice
USB_Connect(true);
TERN_(HAS_SD_HOST_DRIVE, MSC_SD_Init(0)); // Enable USB SD card access
const millis_t usb_timeout = millis() + 2000;
while (!USB_Configuration && PENDING(millis(), usb_timeout)) {
delay(50);
idletask();
#if PIN_EXISTS(LED)
TOGGLE(LED_PIN); // Flash quickly during USB initialization
#endif
}
HAL_timer_init();
TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler
}
#include "../../sd/cardreader.h"
// HAL idle task
void MarlinHAL::idletask() {
#if HAS_SHARED_MEDIA
// If Marlin is using the SD card we need to lock it to prevent access from
// a PC via USB.
// Other HALs use IS_SD_PRINTING() and IS_SD_FILE_OPEN() to check for access but
// this will not reliably detect delete operations. To be safe we will lock
// the disk if Marlin has it mounted. Unfortunately there is currently no way
// to unmount the disk from the LCD menu.
// if (IS_SD_PRINTING() || IS_SD_FILE_OPEN())
if (card.isMounted())
MSC_Aquire_Lock();
else
MSC_Release_Lock();
#endif
// Perform USB stack housekeeping
MSC_RunDeferredCommands();
}
void MarlinHAL::reboot() { NVIC_SystemReset(); }
uint8_t MarlinHAL::get_reset_source() {
@ -112,6 +255,8 @@ void flashFirmware(const int16_t) {
#endif // USE_WATCHDOG
#include "../../../gcode/parser.h"
// For M42/M43, scan command line for pin code
// return index into pin map array if found and the pin is valid.
// return dval if not found or not a valid pin.

View file

@ -101,7 +101,7 @@ extern DefaultSerial1 USBSerial;
#error "LCD_SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB."
#endif
#if HAS_DGUS_LCD
#define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.available()
#define LCD_SERIAL_TX_BUFFER_FREE() LCD_SERIAL.available()
#endif
#endif
@ -127,7 +127,7 @@ extern DefaultSerial1 USBSerial;
// K = 6, 565 samples, 500Hz sample rate, 1.13s convergence on full range step
// Memory usage per ADC channel (bytes): 4 (32 Bytes for 8 channels)
#define HAL_ADC_VREF 3.3 // ADC voltage reference
#define HAL_ADC_VREF_MV 3300 // ADC voltage reference
#define HAL_ADC_RESOLUTION 12 // 15 bit maximum, raw temperature is stored as int16_t
#define HAL_ADC_FILTERED // Disable oversampling done in Marlin as ADC values already filtered in HAL
@ -165,7 +165,9 @@ int16_t PARSED_PIN_INDEX(const char code, const int16_t dval);
// Defines
// ------------------------
#define PLATFORM_M997_SUPPORT
#ifndef PLATFORM_M997_SUPPORT
#define PLATFORM_M997_SUPPORT
#endif
void flashFirmware(const int16_t);
#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment
@ -241,15 +243,18 @@ public:
// Begin ADC sampling on the given pin. Called from Temperature::isr!
static uint32_t adc_result;
static void adc_start(const pin_t pin) {
adc_result = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits
}
static pin_t adc_pin;
static void adc_start(const pin_t pin) { adc_pin = pin; }
// Is the ADC ready for reading?
static bool adc_ready() { return true; }
static bool adc_ready() { return LPC176x::adc_hardware.done(LPC176x::pin_get_adc_channel(adc_pin)); }
// The current value of the ADC register
static uint16_t adc_value() { return uint16_t(adc_result); }
static uint16_t adc_value() {
adc_result = FilteredADC::read(adc_pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits
return uint16_t(adc_result);
}
/**
* Set the PWM duty cycle for the pin to the given value.

View file

@ -30,16 +30,6 @@
#endif
#include "../../core/serial_hook.h"
#ifndef SERIAL_PORT
#define SERIAL_PORT 0
#endif
#ifndef RX_BUFFER_SIZE
#define RX_BUFFER_SIZE 128
#endif
#ifndef TX_BUFFER_SIZE
#define TX_BUFFER_SIZE 32
#endif
class MarlinSerial : public HardwareSerial<RX_BUFFER_SIZE, TX_BUFFER_SIZE> {
public:
MarlinSerial(LPC_UART_TypeDef *UARTx) : HardwareSerial<RX_BUFFER_SIZE, TX_BUFFER_SIZE>(UARTx) { }

View file

@ -39,7 +39,6 @@
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#pragma once
/**
* Based on "servo.h - Interrupt driven Servo library for Arduino using 16 bit timers -

View file

@ -44,73 +44,97 @@ void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
#define LPC1768_PIN_INTERRUPT_M(pin) ((pin >> 0x5 & 0x7) == 0 || (pin >> 0x5 & 0x7) == 2)
#if HAS_X_MAX
#if USE_X_MAX
#if !LPC1768_PIN_INTERRUPT_M(X_MAX_PIN)
#error "X_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(X_MAX_PIN);
#endif
#if HAS_X_MIN
#if USE_X_MIN
#if !LPC1768_PIN_INTERRUPT_M(X_MIN_PIN)
#error "X_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(X_MIN_PIN);
#endif
#if HAS_Y_MAX
#if USE_Y_MAX
#if !LPC1768_PIN_INTERRUPT_M(Y_MAX_PIN)
#error "Y_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Y_MAX_PIN);
#endif
#if HAS_Y_MIN
#if USE_Y_MIN
#if !LPC1768_PIN_INTERRUPT_M(Y_MIN_PIN)
#error "Y_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Y_MIN_PIN);
#endif
#if HAS_Z_MAX
#if USE_Z_MAX
#if !LPC1768_PIN_INTERRUPT_M(Z_MAX_PIN)
#error "Z_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z_MAX_PIN);
#endif
#if HAS_Z_MIN
#if USE_Z_MIN
#if !LPC1768_PIN_INTERRUPT_M(Z_MIN_PIN)
#error "Z_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z_MIN_PIN);
#endif
#if HAS_Z2_MAX
#if USE_X2_MAX
#if !LPC1768_PIN_INTERRUPT_M(X2_MAX_PIN)
#error "X2_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(X2_MAX_PIN);
#endif
#if USE_X2_MIN
#if !LPC1768_PIN_INTERRUPT_M(X2_MIN_PIN)
#error "X2_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(X2_MIN_PIN);
#endif
#if USE_Y2_MAX
#if !LPC1768_PIN_INTERRUPT_M(Y2_MAX_PIN)
#error "Y2_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Y2_MAX_PIN);
#endif
#if USE_Y2_MIN
#if !LPC1768_PIN_INTERRUPT_M(Y2_MIN_PIN)
#error "Y2_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Y2_MIN_PIN);
#endif
#if USE_Z2_MAX
#if !LPC1768_PIN_INTERRUPT_M(Z2_MAX_PIN)
#error "Z2_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z2_MAX_PIN);
#endif
#if HAS_Z2_MIN
#if USE_Z2_MIN
#if !LPC1768_PIN_INTERRUPT_M(Z2_MIN_PIN)
#error "Z2_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z2_MIN_PIN);
#endif
#if HAS_Z3_MAX
#if USE_Z3_MAX
#if !LPC1768_PIN_INTERRUPT_M(Z3_MAX_PIN)
#error "Z3_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z3_MAX_PIN);
#endif
#if HAS_Z3_MIN
#if USE_Z3_MIN
#if !LPC1768_PIN_INTERRUPT_M(Z3_MIN_PIN)
#error "Z3_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z3_MIN_PIN);
#endif
#if HAS_Z4_MAX
#if USE_Z4_MAX
#if !LPC1768_PIN_INTERRUPT_M(Z4_MAX_PIN)
#error "Z4_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z4_MAX_PIN);
#endif
#if HAS_Z4_MIN
#if USE_Z4_MIN
#if !LPC1768_PIN_INTERRUPT_M(Z4_MIN_PIN)
#error "Z4_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
@ -122,69 +146,69 @@ void setup_endstop_interrupts() {
#endif
_ATTACH(Z_MIN_PROBE_PIN);
#endif
#if HAS_I_MAX
#if USE_I_MAX
#if !LPC1768_PIN_INTERRUPT_M(I_MAX_PIN)
#error "I_MAX_PIN is not INTERRUPT-capable."
#error "I_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(I_MAX_PIN);
#elif HAS_I_MIN
#elif USE_I_MIN
#if !LPC1768_PIN_INTERRUPT_M(I_MIN_PIN)
#error "I_MIN_PIN is not INTERRUPT-capable."
#error "I_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(I_MIN_PIN);
#endif
#if HAS_J_MAX
#if USE_J_MAX
#if !LPC1768_PIN_INTERRUPT_M(J_MAX_PIN)
#error "J_MAX_PIN is not INTERRUPT-capable."
#error "J_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(J_MAX_PIN);
#elif HAS_J_MIN
#elif USE_J_MIN
#if !LPC1768_PIN_INTERRUPT_M(J_MIN_PIN)
#error "J_MIN_PIN is not INTERRUPT-capable."
#error "J_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(J_MIN_PIN);
#endif
#if HAS_K_MAX
#if USE_K_MAX
#if !LPC1768_PIN_INTERRUPT_M(K_MAX_PIN)
#error "K_MAX_PIN is not INTERRUPT-capable."
#error "K_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(K_MAX_PIN);
#elif HAS_K_MIN
#elif USE_K_MIN
#if !LPC1768_PIN_INTERRUPT_M(K_MIN_PIN)
#error "K_MIN_PIN is not INTERRUPT-capable."
#error "K_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(K_MIN_PIN);
#endif
#if HAS_U_MAX
#if USE_U_MAX
#if !LPC1768_PIN_INTERRUPT_M(U_MAX_PIN)
#error "U_MAX_PIN is not INTERRUPT-capable."
#error "U_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(U_MAX_PIN);
#elif HAS_U_MIN
#elif USE_U_MIN
#if !LPC1768_PIN_INTERRUPT_M(U_MIN_PIN)
#error "U_MIN_PIN is not INTERRUPT-capable."
#error "U_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(U_MIN_PIN);
#endif
#if HAS_V_MAX
#if USE_V_MAX
#if !LPC1768_PIN_INTERRUPT_M(V_MAX_PIN)
#error "V_MAX_PIN is not INTERRUPT-capable."
#error "V_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(V_MAX_PIN);
#elif HAS_V_MIN
#elif USE_V_MIN
#if !LPC1768_PIN_INTERRUPT_M(V_MIN_PIN)
#error "V_MIN_PIN is not INTERRUPT-capable."
#error "V_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(V_MIN_PIN);
#endif
#if HAS_W_MAX
#if USE_W_MAX
#if !LPC1768_PIN_INTERRUPT_M(W_MAX_PIN)
#error "W_MAX_PIN is not INTERRUPT-capable."
#error "W_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(W_MAX_PIN);
#elif HAS_W_MIN
#elif USE_W_MIN
#if !LPC1768_PIN_INTERRUPT_M(W_MIN_PIN)
#error "W_MIN_PIN is not INTERRUPT-capable."
#error "W_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(W_MIN_PIN);
#endif

View file

@ -20,3 +20,7 @@
*
*/
#pragma once
#ifndef SERIAL_PORT
#define SERIAL_PORT 0
#endif

View file

@ -24,3 +24,10 @@
#if DISABLED(NO_SD_HOST_DRIVE)
#define HAS_SD_HOST_DRIVE 1
#endif
#ifndef RX_BUFFER_SIZE
#define RX_BUFFER_SIZE 128
#endif
#ifndef TX_BUFFER_SIZE
#define TX_BUFFER_SIZE 32
#endif

View file

@ -1,163 +0,0 @@
/**
* 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/>.
*
*/
#ifdef TARGET_LPC1768
#include <usb/usb.h>
#include <usb/usbcfg.h>
#include <usb/usbhw.h>
#include <usb/usbcore.h>
#include <usb/cdc.h>
#include <usb/cdcuser.h>
#include <usb/mscuser.h>
#include <CDCSerial.h>
#include <usb/mscuser.h>
#include "../../inc/MarlinConfig.h"
#include "../../core/millis_t.h"
#include "../../sd/cardreader.h"
extern uint32_t MSC_SD_Init(uint8_t pdrv);
extern "C" {
#include <debug_frmwrk.h>
extern "C" int isLPC1769();
extern "C" void disk_timerproc();
}
void SysTick_Callback() { disk_timerproc(); }
TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
void MarlinHAL::init() {
// Init LEDs
#if PIN_EXISTS(LED)
SET_DIR_OUTPUT(LED_PIN);
WRITE_PIN_CLR(LED_PIN);
#if PIN_EXISTS(LED2)
SET_DIR_OUTPUT(LED2_PIN);
WRITE_PIN_CLR(LED2_PIN);
#if PIN_EXISTS(LED3)
SET_DIR_OUTPUT(LED3_PIN);
WRITE_PIN_CLR(LED3_PIN);
#if PIN_EXISTS(LED4)
SET_DIR_OUTPUT(LED4_PIN);
WRITE_PIN_CLR(LED4_PIN);
#endif
#endif
#endif
// Flash status LED 3 times to indicate Marlin has started booting
for (uint8_t i = 0; i < 6; ++i) {
TOGGLE(LED_PIN);
delay(100);
}
#endif
// Init Servo Pins
#define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW)
#if HAS_SERVO_0
INIT_SERVO(0);
#endif
#if HAS_SERVO_1
INIT_SERVO(1);
#endif
#if HAS_SERVO_2
INIT_SERVO(2);
#endif
#if HAS_SERVO_3
INIT_SERVO(3);
#endif
//debug_frmwrk_init();
//_DBG("\n\nDebug running\n");
// Initialize the SD card chip select pins as soon as possible
#if PIN_EXISTS(SD_SS)
OUT_WRITE(SD_SS_PIN, HIGH);
#endif
#if PIN_EXISTS(ONBOARD_SD_CS) && ONBOARD_SD_CS_PIN != SD_SS_PIN
OUT_WRITE(ONBOARD_SD_CS_PIN, HIGH);
#endif
#ifdef LPC1768_ENABLE_CLKOUT_12M
/**
* CLKOUTCFG register
* bit 8 (CLKOUT_EN) = enables CLKOUT signal. Disabled for now to prevent glitch when enabling GPIO.
* bits 7:4 (CLKOUTDIV) = set to 0 for divider setting of /1
* bits 3:0 (CLKOUTSEL) = set to 1 to select main crystal oscillator as CLKOUT source
*/
LPC_SC->CLKOUTCFG = (0<<8)|(0<<4)|(1<<0);
// set P1.27 pin to function 01 (CLKOUT)
PINSEL_CFG_Type PinCfg;
PinCfg.Portnum = 1;
PinCfg.Pinnum = 27;
PinCfg.Funcnum = 1; // function 01 (CLKOUT)
PinCfg.OpenDrain = 0; // not open drain
PinCfg.Pinmode = 2; // no pull-up/pull-down
PINSEL_ConfigPin(&PinCfg);
// now set CLKOUT_EN bit
SBI(LPC_SC->CLKOUTCFG, 8);
#endif
USB_Init(); // USB Initialization
USB_Connect(false); // USB clear connection
delay(1000); // Give OS time to notice
USB_Connect(true);
TERN_(HAS_SD_HOST_DRIVE, MSC_SD_Init(0)); // Enable USB SD card access
const millis_t usb_timeout = millis() + 2000;
while (!USB_Configuration && PENDING(millis(), usb_timeout)) {
delay(50);
idletask();
#if PIN_EXISTS(LED)
TOGGLE(LED_PIN); // Flash quickly during USB initialization
#endif
}
HAL_timer_init();
TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler
}
// HAL idle task
void MarlinHAL::idletask() {
#if HAS_SHARED_MEDIA
// If Marlin is using the SD card we need to lock it to prevent access from
// a PC via USB.
// Other HALs use IS_SD_PRINTING() and IS_SD_FILE_OPEN() to check for access but
// this will not reliably detect delete operations. To be safe we will lock
// the disk if Marlin has it mounted. Unfortunately there is currently no way
// to unmount the disk from the LCD menu.
// if (IS_SD_PRINTING() || IS_SD_FILE_OPEN())
if (card.isMounted())
MSC_Aquire_Lock();
else
MSC_Release_Lock();
#endif
// Perform USB stack housekeeping
MSC_RunDeferredCommands();
}
#endif // TARGET_LPC1768

View file

@ -29,11 +29,8 @@
*/
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
#define pwm_details(pin) NOOP // do nothing
#define pwm_status(pin) false // Print a pin's PWM status. Return true if it's currently a PWM pin.
#define IS_ANALOG(P) (DIGITAL_PIN_TO_ANALOG_PIN(P) >= 0 ? 1 : 0)
#define digitalRead_mod(p) extDigitalRead(p)
#define PRINT_PORT(p)
#define GET_ARRAY_PIN(p) pin_array[p].pin
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("P%d_%02d"), LPC176x::pin_port(p), LPC176x::pin_bit(p)); SERIAL_ECHO(buffer); }while(0)
@ -46,10 +43,14 @@
#endif
bool GET_PINMODE(const pin_t pin) {
if (!LPC176x::pin_is_valid(pin) || LPC176x::pin_adc_enabled(pin)) // found an invalid pin or active analog pin
if (!LPC176x::pin_is_valid(pin) || LPC176x::pin_adc_enabled(pin)) // Invalid pin or active analog pin
return false;
return LPC176x::gpio_direction(pin);
}
#define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital)
void print_port(const pin_t) {}
void pwm_details(const pin_t) {}
bool pwm_status(const pin_t) { return false; }

View file

@ -23,7 +23,7 @@
#include "../../core/macros.h"
#if ALL(HAS_MEDIA, HAS_MARLINUI_U8GLIB) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_EN == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN)
#if ALL(HAS_MARLINUI_U8GLIB, HAS_MEDIA) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_EN == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN)
#define SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently
// needed due to the speed and mode required for communicating with each device being different.
// This requirement can be removed if the SPI access to these devices is updated to use

View file

@ -20,6 +20,8 @@
*
*/
#ifdef TARGET_LPC1768
#include "../../../inc/MarlinConfig.h"
#if HAS_SPI_TFT
@ -139,7 +141,8 @@ void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Coun
DataTransferBegin(DATASIZE_16BIT);
SPIx.dmaSendAsync(Data, Count, MemoryIncrease);
TERN_(TFT_SHARED_SPI, while (isBusy()));
TERN_(TFT_SHARED_IO, while (isBusy()));
}
#endif // HAS_SPI_TFT
#endif // TARGET_LPC1768

View file

@ -49,7 +49,7 @@
#define DATASIZE_8BIT SSP_DATABIT_8
#define DATASIZE_16BIT SSP_DATABIT_16
#define TFT_IO_DRIVER TFT_SPI
#define DMA_MAX_SIZE 0xFFF
#define DMA_MAX_WORDS 0xFFF
#define DMA_MINC_ENABLE 1
#define DMA_MINC_DISABLE 0
@ -82,8 +82,8 @@ public:
static void WriteSequence(uint16_t *Data, uint16_t Count) { Transmit(DMA_MINC_ENABLE, Data, Count); }
static void WriteMultiple(uint16_t Color, uint32_t Count) {
while (Count > 0) {
Transmit(DMA_MINC_DISABLE, &Color, Count > DMA_MAX_SIZE ? DMA_MAX_SIZE : Count);
Count = Count > DMA_MAX_SIZE ? Count - DMA_MAX_SIZE : 0;
Transmit(DMA_MINC_DISABLE, &Color, Count > DMA_MAX_WORDS ? DMA_MAX_WORDS : Count);
Count = Count > DMA_MAX_WORDS ? Count - DMA_MAX_WORDS : 0;
}
}
};

View file

@ -20,6 +20,8 @@
*
*/
#ifdef TARGET_LPC1768
#include "../../../inc/MarlinConfig.h"
#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS
@ -130,4 +132,5 @@ uint16_t XPT2046::SoftwareIO(uint16_t data) {
return result;
}
#endif // HAS_TFT_XPT2046
#endif // HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS
#endif // TARGET_LPC1768

View file

@ -114,8 +114,8 @@ extern MSerialT serial_stream_3;
// ADC
// ------------------------
#define HAL_ADC_VREF 5.0
#define HAL_ADC_RESOLUTION 10
#define HAL_ADC_VREF_MV 5000
#define HAL_ADC_RESOLUTION 10
/* ---------------- Delay in cycles */

View file

@ -0,0 +1,48 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2021 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/>.
*
*/
#ifdef __PLAT_NATIVE_SIM__
#include "../../inc/MarlinConfig.h"
#include "pinsDebug.h"
int8_t ADC_pin_mode(pin_t pin) { return -1; }
int8_t get_pin_mode(const pin_t pin) { return VALID_PIN(pin) ? 0 : -1; }
bool GET_PINMODE(const pin_t pin) {
const int8_t pin_mode = get_pin_mode(pin);
if (pin_mode == -1 || pin_mode == ADC_pin_mode(pin)) // Invalid pin or active analog pin
return false;
return (Gpio::getMode(pin) != 0); // Input/output state
}
bool GET_ARRAY_IS_DIGITAL(const pin_t pin) {
return !IS_ANALOG(pin) || get_pin_mode(pin) != ADC_pin_mode(pin);
}
void print_port(const pin_t) {}
void pwm_details(const pin_t) {}
bool pwm_status(const pin_t) { return false; }
#endif

View file

@ -30,35 +30,19 @@
*/
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
#define pwm_details(pin) NOOP // do nothing
#define pwm_status(pin) false // Print a pin's PWM status. Return true if it's currently a PWM pin.
#define IS_ANALOG(P) (DIGITAL_PIN_TO_ANALOG_PIN(P) >= 0 ? 1 : 0)
#define digitalRead_mod(p) digitalRead(p)
#define PRINT_PORT(p)
#define GET_ARRAY_PIN(p) pin_array[p].pin
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
// active ADC function/mode/code values for PINSEL registers
inline constexpr int8_t ADC_pin_mode(pin_t pin) {
return (-1);
}
inline int8_t get_pin_mode(pin_t pin) {
if (!VALID_PIN(pin)) return -1;
return 0;
}
inline bool GET_PINMODE(pin_t pin) {
int8_t pin_mode = get_pin_mode(pin);
if (pin_mode == -1 || pin_mode == ADC_pin_mode(pin)) // found an invalid pin or active analog pin
return false;
return (Gpio::getMode(pin) != 0); //input/output state
}
inline bool GET_ARRAY_IS_DIGITAL(pin_t pin) {
return (!IS_ANALOG(pin) || get_pin_mode(pin) != ADC_pin_mode(pin));
}
// Active ADC function/mode/code values for PINSEL registers
int8_t ADC_pin_mode(pin_t pin);
int8_t get_pin_mode(const pin_t pin);
bool GET_PINMODE(const pin_t pin);
bool GET_ARRAY_IS_DIGITAL(const pin_t pin);
void print_port(const pin_t);
void pwm_details(const pin_t);
bool pwm_status(const pin_t);

View file

@ -33,6 +33,7 @@
#define DATASIZE_8BIT 8
#define DATASIZE_16BIT 16
#define TFT_IO_DRIVER TFT_SPI
#define DMA_MAX_WORDS 0xFFFF
#define DMA_MINC_ENABLE 1
#define DMA_MINC_DISABLE 0

View file

@ -110,7 +110,7 @@ typedef Servo hal_servo_t;
//
#define HAL_ADC_FILTERED 1 // Disable Marlin's oversampling. The HAL filters ADC values.
#define HAL_ADC_VREF 3.3
#define HAL_ADC_VREF_MV 3300
#define HAL_ADC_RESOLUTION 12
#define HAL_ADC_AIN_START ADC_INPUTCTRL_MUXPOS_PIN3
#define HAL_ADC_AIN_NUM_SENSORS 3

View file

@ -37,19 +37,23 @@ static const uint8_t flashdata[TOTAL_FLASH_SIZE] __attribute__((__aligned__(256
#include "../shared/eeprom_api.h"
size_t PersistentStore::capacity() {
return MARLIN_EEPROM_SIZE;
/* const uint8_t psz = NVMCTRL->SEESTAT.bit.PSZ,
size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
/*
const uint8_t psz = NVMCTRL->SEESTAT.bit.PSZ,
sblk = NVMCTRL->SEESTAT.bit.SBLK;
return (!psz && !sblk) ? 0
: (psz <= 2) ? (0x200 << psz)
: (sblk == 1 || psz == 3) ? 4096
: (sblk == 2 || psz == 4) ? 8192
: (sblk <= 4 || psz == 5) ? 16384
: (sblk >= 9 && psz == 7) ? 65536
: 32768;*/
return (
(!psz && !sblk) ? 0
: (psz <= 2) ? (0x200 << psz)
: (sblk == 1 || psz == 3) ? 4096
: (sblk == 2 || psz == 4) ? 8192
: (sblk <= 4 || psz == 5) ? 16384
: (sblk >= 9 && psz == 7) ? 65536
: 32768
) - eeprom_exclude_size;
}
*/
uint32_t PAGE_SIZE;
uint32_t ROW_SIZE;

View file

@ -54,30 +54,34 @@
#include "../../module/endstops.h"
#define MATCH_EILINE(P1,P2) (P1 != P2 && PIN_TO_EILINE(P1) == PIN_TO_EILINE(P2))
#define MATCH_X_MAX_EILINE(P) TERN0(HAS_X_MAX, DEFER4(MATCH_EILINE)(P, X_MAX_PIN))
#define MATCH_X_MIN_EILINE(P) TERN0(HAS_X_MIN, DEFER4(MATCH_EILINE)(P, X_MIN_PIN))
#define MATCH_Y_MAX_EILINE(P) TERN0(HAS_Y_MAX, DEFER4(MATCH_EILINE)(P, Y_MAX_PIN))
#define MATCH_Y_MIN_EILINE(P) TERN0(HAS_Y_MIN, DEFER4(MATCH_EILINE)(P, Y_MIN_PIN))
#define MATCH_Z_MAX_EILINE(P) TERN0(HAS_Z_MAX, DEFER4(MATCH_EILINE)(P, Z_MAX_PIN))
#define MATCH_Z_MIN_EILINE(P) TERN0(HAS_Z_MIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PIN))
#define MATCH_I_MAX_EILINE(P) TERN0(HAS_I_MAX, DEFER4(MATCH_EILINE)(P, I_MAX_PIN))
#define MATCH_I_MIN_EILINE(P) TERN0(HAS_I_MIN, DEFER4(MATCH_EILINE)(P, I_MIN_PIN))
#define MATCH_J_MAX_EILINE(P) TERN0(HAS_J_MAX, DEFER4(MATCH_EILINE)(P, J_MAX_PIN))
#define MATCH_J_MIN_EILINE(P) TERN0(HAS_J_MIN, DEFER4(MATCH_EILINE)(P, J_MIN_PIN))
#define MATCH_K_MAX_EILINE(P) TERN0(HAS_K_MAX, DEFER4(MATCH_EILINE)(P, K_MAX_PIN))
#define MATCH_K_MIN_EILINE(P) TERN0(HAS_K_MIN, DEFER4(MATCH_EILINE)(P, K_MIN_PIN))
#define MATCH_U_MAX_EILINE(P) TERN0(HAS_U_MAX, DEFER4(MATCH_EILINE)(P, U_MAX_PIN))
#define MATCH_U_MIN_EILINE(P) TERN0(HAS_U_MIN, DEFER4(MATCH_EILINE)(P, U_MIN_PIN))
#define MATCH_V_MAX_EILINE(P) TERN0(HAS_V_MAX, DEFER4(MATCH_EILINE)(P, V_MAX_PIN))
#define MATCH_V_MIN_EILINE(P) TERN0(HAS_V_MIN, DEFER4(MATCH_EILINE)(P, V_MIN_PIN))
#define MATCH_W_MAX_EILINE(P) TERN0(HAS_W_MAX, DEFER4(MATCH_EILINE)(P, W_MAX_PIN))
#define MATCH_W_MIN_EILINE(P) TERN0(HAS_W_MIN, DEFER4(MATCH_EILINE)(P, W_MIN_PIN))
#define MATCH_Z2_MAX_EILINE(P) TERN0(HAS_Z2_MAX, DEFER4(MATCH_EILINE)(P, Z2_MAX_PIN))
#define MATCH_Z2_MIN_EILINE(P) TERN0(HAS_Z2_MIN, DEFER4(MATCH_EILINE)(P, Z2_MIN_PIN))
#define MATCH_Z3_MAX_EILINE(P) TERN0(HAS_Z3_MAX, DEFER4(MATCH_EILINE)(P, Z3_MAX_PIN))
#define MATCH_Z3_MIN_EILINE(P) TERN0(HAS_Z3_MIN, DEFER4(MATCH_EILINE)(P, Z3_MIN_PIN))
#define MATCH_Z4_MAX_EILINE(P) TERN0(HAS_Z4_MAX, DEFER4(MATCH_EILINE)(P, Z4_MAX_PIN))
#define MATCH_Z4_MIN_EILINE(P) TERN0(HAS_Z4_MIN, DEFER4(MATCH_EILINE)(P, Z4_MIN_PIN))
#define MATCH_X_MAX_EILINE(P) TERN0(USE_X_MAX, DEFER4(MATCH_EILINE)(P, X_MAX_PIN))
#define MATCH_X_MIN_EILINE(P) TERN0(USE_X_MIN, DEFER4(MATCH_EILINE)(P, X_MIN_PIN))
#define MATCH_Y_MAX_EILINE(P) TERN0(USE_Y_MAX, DEFER4(MATCH_EILINE)(P, Y_MAX_PIN))
#define MATCH_Y_MIN_EILINE(P) TERN0(USE_Y_MIN, DEFER4(MATCH_EILINE)(P, Y_MIN_PIN))
#define MATCH_Z_MAX_EILINE(P) TERN0(USE_Z_MAX, DEFER4(MATCH_EILINE)(P, Z_MAX_PIN))
#define MATCH_Z_MIN_EILINE(P) TERN0(USE_Z_MIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PIN))
#define MATCH_I_MAX_EILINE(P) TERN0(USE_I_MAX, DEFER4(MATCH_EILINE)(P, I_MAX_PIN))
#define MATCH_I_MIN_EILINE(P) TERN0(USE_I_MIN, DEFER4(MATCH_EILINE)(P, I_MIN_PIN))
#define MATCH_J_MAX_EILINE(P) TERN0(USE_J_MAX, DEFER4(MATCH_EILINE)(P, J_MAX_PIN))
#define MATCH_J_MIN_EILINE(P) TERN0(USE_J_MIN, DEFER4(MATCH_EILINE)(P, J_MIN_PIN))
#define MATCH_K_MAX_EILINE(P) TERN0(USE_K_MAX, DEFER4(MATCH_EILINE)(P, K_MAX_PIN))
#define MATCH_K_MIN_EILINE(P) TERN0(USE_K_MIN, DEFER4(MATCH_EILINE)(P, K_MIN_PIN))
#define MATCH_U_MAX_EILINE(P) TERN0(USE_U_MAX, DEFER4(MATCH_EILINE)(P, U_MAX_PIN))
#define MATCH_U_MIN_EILINE(P) TERN0(USE_U_MIN, DEFER4(MATCH_EILINE)(P, U_MIN_PIN))
#define MATCH_V_MAX_EILINE(P) TERN0(USE_V_MAX, DEFER4(MATCH_EILINE)(P, V_MAX_PIN))
#define MATCH_V_MIN_EILINE(P) TERN0(USE_V_MIN, DEFER4(MATCH_EILINE)(P, V_MIN_PIN))
#define MATCH_W_MAX_EILINE(P) TERN0(USE_W_MAX, DEFER4(MATCH_EILINE)(P, W_MAX_PIN))
#define MATCH_W_MIN_EILINE(P) TERN0(USE_W_MIN, DEFER4(MATCH_EILINE)(P, W_MIN_PIN))
#define MATCH_X2_MAX_EILINE(P) TERN0(USE_X2_MAX, DEFER4(MATCH_EILINE)(P, X2_MAX_PIN))
#define MATCH_X2_MIN_EILINE(P) TERN0(USE_X2_MIN, DEFER4(MATCH_EILINE)(P, X2_MIN_PIN))
#define MATCH_Y2_MAX_EILINE(P) TERN0(USE_Y2_MAX, DEFER4(MATCH_EILINE)(P, Y2_MAX_PIN))
#define MATCH_Y2_MIN_EILINE(P) TERN0(USE_Y2_MIN, DEFER4(MATCH_EILINE)(P, Y2_MIN_PIN))
#define MATCH_Z2_MAX_EILINE(P) TERN0(USE_Z2_MAX, DEFER4(MATCH_EILINE)(P, Z2_MAX_PIN))
#define MATCH_Z2_MIN_EILINE(P) TERN0(USE_Z2_MIN, DEFER4(MATCH_EILINE)(P, Z2_MIN_PIN))
#define MATCH_Z3_MAX_EILINE(P) TERN0(USE_Z3_MAX, DEFER4(MATCH_EILINE)(P, Z3_MAX_PIN))
#define MATCH_Z3_MIN_EILINE(P) TERN0(USE_Z3_MIN, DEFER4(MATCH_EILINE)(P, Z3_MIN_PIN))
#define MATCH_Z4_MAX_EILINE(P) TERN0(USE_Z4_MAX, DEFER4(MATCH_EILINE)(P, Z4_MAX_PIN))
#define MATCH_Z4_MIN_EILINE(P) TERN0(USE_Z4_MIN, DEFER4(MATCH_EILINE)(P, Z4_MIN_PIN))
#define MATCH_Z_MIN_PROBE_EILINE(P) TERN0(HAS_Z_MIN_PROBE_PIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PROBE_PIN))
#define AVAILABLE_EILINE(P) ( PIN_TO_EILINE(P) != -1 \
@ -90,6 +94,8 @@
&& !MATCH_U_MAX_EILINE(P) && !MATCH_U_MIN_EILINE(P) \
&& !MATCH_V_MAX_EILINE(P) && !MATCH_V_MIN_EILINE(P) \
&& !MATCH_W_MAX_EILINE(P) && !MATCH_W_MIN_EILINE(P) \
&& !MATCH_X2_MAX_EILINE(P) && !MATCH_X2_MIN_EILINE(P) \
&& !MATCH_Y2_MAX_EILINE(P) && !MATCH_Y2_MIN_EILINE(P) \
&& !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P) \
&& !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P) \
&& !MATCH_Z4_MAX_EILINE(P) && !MATCH_Z4_MIN_EILINE(P) \
@ -100,153 +106,177 @@ void endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE)
#if HAS_X_MAX
#if USE_X_MAX
#if !AVAILABLE_EILINE(X_MAX_PIN)
#error "X_MAX_PIN has no EXTINT line available."
#error "X_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(X_MAX_PIN);
#endif
#if HAS_X_MIN
#if USE_X_MIN
#if !AVAILABLE_EILINE(X_MIN_PIN)
#error "X_MIN_PIN has no EXTINT line available."
#error "X_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(X_MIN_PIN);
#endif
#if HAS_Y_MAX
#if USE_Y_MAX
#if !AVAILABLE_EILINE(Y_MAX_PIN)
#error "Y_MAX_PIN has no EXTINT line available."
#error "Y_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Y_MAX_PIN);
#endif
#if HAS_Y_MIN
#if USE_Y_MIN
#if !AVAILABLE_EILINE(Y_MIN_PIN)
#error "Y_MIN_PIN has no EXTINT line available."
#error "Y_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Y_MIN_PIN);
#endif
#if HAS_Z_MAX
#if USE_Z_MAX
#if !AVAILABLE_EILINE(Z_MAX_PIN)
#error "Z_MAX_PIN has no EXTINT line available."
#error "Z_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z_MAX_PIN);
#endif
#if HAS_Z_MIN
#if USE_Z_MIN
#if !AVAILABLE_EILINE(Z_MIN_PIN)
#error "Z_MIN_PIN has no EXTINT line available."
#error "Z_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z_MIN_PIN);
#endif
#if HAS_Z2_MAX
#if USE_X2_MAX
#if !AVAILABLE_EILINE(X2_MAX_PIN)
#error "X2_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(X2_MAX_PIN);
#endif
#if USE_X2_MIN
#if !AVAILABLE_EILINE(X2_MIN_PIN)
#error "X2_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(X2_MIN_PIN);
#endif
#if USE_Y2_MAX
#if !AVAILABLE_EILINE(Y2_MAX_PIN)
#error "Y2_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Y2_MAX_PIN);
#endif
#if USE_Y2_MIN
#if !AVAILABLE_EILINE(Y2_MIN_PIN)
#error "Y2_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Y2_MIN_PIN);
#endif
#if USE_Z2_MAX
#if !AVAILABLE_EILINE(Z2_MAX_PIN)
#error "Z2_MAX_PIN has no EXTINT line available."
#error "Z2_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z2_MAX_PIN);
#endif
#if HAS_Z2_MIN
#if USE_Z2_MIN
#if !AVAILABLE_EILINE(Z2_MIN_PIN)
#error "Z2_MIN_PIN has no EXTINT line available."
#error "Z2_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z2_MIN_PIN);
#endif
#if HAS_Z3_MAX
#if USE_Z3_MAX
#if !AVAILABLE_EILINE(Z3_MAX_PIN)
#error "Z3_MAX_PIN has no EXTINT line available."
#error "Z3_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z3_MAX_PIN);
#endif
#if HAS_Z3_MIN
#if USE_Z3_MIN
#if !AVAILABLE_EILINE(Z3_MIN_PIN)
#error "Z3_MIN_PIN has no EXTINT line available."
#error "Z3_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z3_MIN_PIN);
#endif
#if HAS_Z4_MAX
#if USE_Z4_MAX
#if !AVAILABLE_EILINE(Z4_MAX_PIN)
#error "Z4_MAX_PIN has no EXTINT line available."
#error "Z4_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z4_MAX_PIN);
#endif
#if HAS_Z4_MIN
#if USE_Z4_MIN
#if !AVAILABLE_EILINE(Z4_MIN_PIN)
#error "Z4_MIN_PIN has no EXTINT line available."
#error "Z4_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z4_MIN_PIN);
#endif
#if HAS_Z_MIN_PROBE_PIN
#if !AVAILABLE_EILINE(Z_MIN_PROBE_PIN)
#error "Z_MIN_PROBE_PIN has no EXTINT line available."
#error "Z_MIN_PROBE_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z_MIN_PROBE_PIN);
#endif
#if HAS_I_MAX
#if USE_I_MAX
#if !AVAILABLE_EILINE(I_MAX_PIN)
#error "I_MAX_PIN has no EXTINT line available."
#error "I_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(I_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_I_MIN
#if USE_I_MIN
#if !AVAILABLE_EILINE(I_MIN_PIN)
#error "I_MIN_PIN has no EXTINT line available."
#error "I_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(I_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_J_MAX
#if USE_J_MAX
#if !AVAILABLE_EILINE(J_MAX_PIN)
#error "J_MAX_PIN has no EXTINT line available."
#error "J_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(J_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_J_MIN
#if USE_J_MIN
#if !AVAILABLE_EILINE(J_MIN_PIN)
#error "J_MIN_PIN has no EXTINT line available."
#error "J_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(J_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_K_MAX
#if USE_K_MAX
#if !AVAILABLE_EILINE(K_MAX_PIN)
#error "K_MAX_PIN has no EXTINT line available."
#error "K_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(K_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_K_MIN
#if USE_K_MIN
#if !AVAILABLE_EILINE(K_MIN_PIN)
#error "K_MIN_PIN has no EXTINT line available."
#error "K_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(K_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_U_MAX
#if USE_U_MAX
#if !AVAILABLE_EILINE(U_MAX_PIN)
#error "U_MAX_PIN has no EXTINT line available."
#error "U_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(U_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_U_MIN
#if USE_U_MIN
#if !AVAILABLE_EILINE(U_MIN_PIN)
#error "U_MIN_PIN has no EXTINT line available."
#error "U_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(U_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_V_MAX
#if USE_V_MAX
#if !AVAILABLE_EILINE(V_MAX_PIN)
#error "V_MAX_PIN has no EXTINT line available."
#error "V_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(V_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_V_MIN
#if USE_V_MIN
#if !AVAILABLE_EILINE(V_MIN_PIN)
#error "V_MIN_PIN has no EXTINT line available."
#error "V_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(V_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_W_MAX
#if USE_W_MAX
#if !AVAILABLE_EILINE(W_MAX_PIN)
#error "W_MAX_PIN has no EXTINT line available."
#error "W_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(W_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_W_MIN
#if USE_W_MIN
#if !AVAILABLE_EILINE(W_MIN_PIN)
#error "W_MIN_PIN has no EXTINT line available."
#error "W_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(W_MIN_PIN, endstop_ISR, CHANGE);
#endif

View file

@ -41,8 +41,8 @@
#error "EMERGENCY_PARSER is not yet implemented for SAMD21. Disable EMERGENCY_PARSER to continue."
#endif
#if ENABLED(SDIO_SUPPORT)
#error "SDIO_SUPPORT is not supported on SAMD21."
#if ENABLED(ONBOARD_SDIO)
#error "ONBOARD_SDIO is not supported on SAMD21."
#endif
#if ENABLED(FAST_PWM_FAN)

View file

@ -60,13 +60,17 @@
#ifdef __SAMD21__
#include "../../../inc/MarlinConfigPre.h"
#if HAS_MARLINUI_U8GLIB
#include <U8glib-HAL.h>
#include "SPI.h"
#include "../../shared/HAL_SPI.h"
#ifndef LCD_SPI_SPEED
#define LCD_SPI_SPEED SPI_QUARTER_SPEED
#define LCD_SPI_SPEED SPI_HALF_SPEED
#endif
void u8g_SetPIOutput(u8g_t *u8g, uint8_t pin_index) {
@ -81,8 +85,6 @@ void u8g_SetPILevel(u8g_t *u8g, uint8_t pin_index, uint8_t level) {
uint8_t u8g_com_samd21_st7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {
static SPISettings lcdSPIConfig;
switch (msg) {
case U8G_COM_MSG_STOP:
break;
@ -95,7 +97,6 @@ uint8_t u8g_com_samd21_st7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val
u8g_SetPILevel(u8g, U8G_PI_CS, LOW);
spiBegin();
lcdSPIConfig = SPISettings(900000, MSBFIRST, SPI_MODE0);
u8g->pin_list[U8G_PI_A0_STATE] = 0;
break;
@ -113,7 +114,7 @@ uint8_t u8g_com_samd21_st7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val
break;
case U8G_COM_MSG_WRITE_BYTE:
SPI.beginTransaction(lcdSPIConfig);
spiBeginTransaction(LCD_SPI_SPEED, MSBFIRST, SPI_MODE0);
if (u8g->pin_list[U8G_PI_A0_STATE] == 0) { // command
SPI.transfer(0x0f8); u8g->pin_list[U8G_PI_A0_STATE] = 2;
@ -128,7 +129,7 @@ uint8_t u8g_com_samd21_st7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val
break;
case U8G_COM_MSG_WRITE_SEQ:
SPI.beginTransaction(lcdSPIConfig);
spiBeginTransaction(LCD_SPI_SPEED, MSBFIRST, SPI_MODE0);
if (u8g->pin_list[U8G_PI_A0_STATE] == 0 ) { // command
SPI.transfer(0x0f8); u8g->pin_list[U8G_PI_A0_STATE] = 2;
@ -151,4 +152,6 @@ uint8_t u8g_com_samd21_st7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val
return 1;
}
#endif // HAS_MARLINUI_U8GLIB
#endif // __SAMD21__

View file

@ -47,24 +47,27 @@
#endif
#endif
#define GET_TEMP_0_ADC() TERN(HAS_TEMP_ADC_0, PIN_TO_ADC(TEMP_0_PIN), -1)
#define GET_TEMP_1_ADC() TERN(HAS_TEMP_ADC_1, PIN_TO_ADC(TEMP_1_PIN), -1)
#define GET_TEMP_2_ADC() TERN(HAS_TEMP_ADC_2, PIN_TO_ADC(TEMP_2_PIN), -1)
#define GET_TEMP_3_ADC() TERN(HAS_TEMP_ADC_3, PIN_TO_ADC(TEMP_3_PIN), -1)
#define GET_TEMP_4_ADC() TERN(HAS_TEMP_ADC_4, PIN_TO_ADC(TEMP_4_PIN), -1)
#define GET_TEMP_5_ADC() TERN(HAS_TEMP_ADC_5, PIN_TO_ADC(TEMP_5_PIN), -1)
#define GET_TEMP_6_ADC() TERN(HAS_TEMP_ADC_6, PIN_TO_ADC(TEMP_6_PIN), -1)
#define GET_TEMP_7_ADC() TERN(HAS_TEMP_ADC_7, PIN_TO_ADC(TEMP_7_PIN), -1)
#define GET_BED_ADC() TERN(HAS_TEMP_ADC_BED, PIN_TO_ADC(TEMP_BED_PIN), -1)
#define GET_CHAMBER_ADC() TERN(HAS_TEMP_ADC_CHAMBER, PIN_TO_ADC(TEMP_CHAMBER_PIN), -1)
#define GET_PROBE_ADC() TERN(HAS_TEMP_ADC_PROBE, PIN_TO_ADC(TEMP_PROBE_PIN), -1)
#define GET_COOLER_ADC() TERN(HAS_TEMP_ADC_COOLER, PIN_TO_ADC(TEMP_COOLER_PIN), -1)
#define GET_BOARD_ADC() TERN(HAS_TEMP_ADC_BOARD, PIN_TO_ADC(TEMP_BOARD_PIN), -1)
#define GET_FILAMENT_WIDTH_ADC() TERN(FILAMENT_WIDTH_SENSOR, PIN_TO_ADC(FILWIDTH_PIN), -1)
#define GET_BUTTONS_ADC() TERN(HAS_ADC_BUTTONS, PIN_TO_ADC(ADC_KEYPAD_PIN), -1)
#define GET_JOY_ADC_X() TERN(HAS_JOY_ADC_X, PIN_TO_ADC(JOY_X_PIN), -1)
#define GET_JOY_ADC_Y() TERN(HAS_JOY_ADC_Y, PIN_TO_ADC(JOY_Y_PIN), -1)
#define GET_JOY_ADC_Z() TERN(HAS_JOY_ADC_Z, PIN_TO_ADC(JOY_Z_PIN), -1)
#define GET_TEMP_0_ADC() TERN(HAS_TEMP_ADC_0, PIN_TO_ADC(TEMP_0_PIN), -1)
#define GET_TEMP_1_ADC() TERN(HAS_TEMP_ADC_1, PIN_TO_ADC(TEMP_1_PIN), -1)
#define GET_TEMP_2_ADC() TERN(HAS_TEMP_ADC_2, PIN_TO_ADC(TEMP_2_PIN), -1)
#define GET_TEMP_3_ADC() TERN(HAS_TEMP_ADC_3, PIN_TO_ADC(TEMP_3_PIN), -1)
#define GET_TEMP_4_ADC() TERN(HAS_TEMP_ADC_4, PIN_TO_ADC(TEMP_4_PIN), -1)
#define GET_TEMP_5_ADC() TERN(HAS_TEMP_ADC_5, PIN_TO_ADC(TEMP_5_PIN), -1)
#define GET_TEMP_6_ADC() TERN(HAS_TEMP_ADC_6, PIN_TO_ADC(TEMP_6_PIN), -1)
#define GET_TEMP_7_ADC() TERN(HAS_TEMP_ADC_7, PIN_TO_ADC(TEMP_7_PIN), -1)
#define GET_BED_ADC() TERN(HAS_TEMP_ADC_BED, PIN_TO_ADC(TEMP_BED_PIN), -1)
#define GET_CHAMBER_ADC() TERN(HAS_TEMP_ADC_CHAMBER, PIN_TO_ADC(TEMP_CHAMBER_PIN), -1)
#define GET_PROBE_ADC() TERN(HAS_TEMP_ADC_PROBE, PIN_TO_ADC(TEMP_PROBE_PIN), -1)
#define GET_COOLER_ADC() TERN(HAS_TEMP_ADC_COOLER, PIN_TO_ADC(TEMP_COOLER_PIN), -1)
#define GET_BOARD_ADC() TERN(HAS_TEMP_ADC_BOARD, PIN_TO_ADC(TEMP_BOARD_PIN), -1)
#define GET_SOC_ADC() TERN(HAS_TEMP_ADC_BOARD, PIN_TO_ADC(TEMP_BOARD_PIN), -1)
#define GET_FILAMENT_WIDTH_ADC() TERN(FILAMENT_WIDTH_SENSOR, PIN_TO_ADC(FILWIDTH_PIN), -1)
#define GET_BUTTONS_ADC() TERN(HAS_ADC_BUTTONS, PIN_TO_ADC(ADC_KEYPAD_PIN), -1)
#define GET_JOY_ADC_X() TERN(HAS_JOY_ADC_X, PIN_TO_ADC(JOY_X_PIN), -1)
#define GET_JOY_ADC_Y() TERN(HAS_JOY_ADC_Y, PIN_TO_ADC(JOY_Y_PIN), -1)
#define GET_JOY_ADC_Z() TERN(HAS_JOY_ADC_Z, PIN_TO_ADC(JOY_Z_PIN), -1)
#define GET_POWERMON_ADC_CURRENT() TERN(POWER_MONITOR_CURRENT, PIN_TO_ADC(POWER_MONITOR_CURRENT_PIN), -1)
#define GET_POWERMON_ADC_VOLTS() TERN(POWER_MONITOR_VOLTAGE, PIN_TO_ADC(POWER_MONITOR_VOLTAGE_PIN), -1)
#define IS_ADC_REQUIRED(n) ( \
GET_TEMP_0_ADC() == n || GET_TEMP_1_ADC() == n || GET_TEMP_2_ADC() == n || GET_TEMP_3_ADC() == n \
@ -77,6 +80,7 @@
|| GET_FILAMENT_WIDTH_ADC() == n \
|| GET_BUTTONS_ADC() == n \
|| GET_JOY_ADC_X() == n || GET_JOY_ADC_Y() == n || GET_JOY_ADC_Z() == n \
|| GET_POWERMON_ADC_CURRENT() == n || GET_POWERMON_ADC_VOLTS() == n \
)
#if IS_ADC_REQUIRED(0)
@ -151,6 +155,15 @@ enum ADCIndex {
#if GET_JOY_ADC_Z() == 0
JOY_Z,
#endif
#if GET_POWERMON_ADC_CURRENT() == 0
POWERMON_CURRENT,
#endif
#if GET_POWERMON_ADC_VOLTS() == 0
POWERMON_VOLTAGE,
#endif
// Indexes for ADC1 after those for ADC0
#if GET_TEMP_0_ADC() == 1
TEMP_0,
#endif
@ -205,6 +218,12 @@ enum ADCIndex {
#if GET_JOY_ADC_Z() == 1
JOY_Z,
#endif
#if GET_POWERMON_ADC_CURRENT() == 1
POWERMON_CURRENT,
#endif
#if GET_POWERMON_ADC_VOLTS() == 1
POWERMON_VOLTAGE,
#endif
ADC_COUNT
};
@ -318,7 +337,15 @@ enum ADCIndex {
#if GET_JOY_ADC_Z() == 0
JOY_Z_PIN,
#endif
// ADC1 pins
#if GET_POWERMON_ADC_CURRENT() == 0
POWER_MONITOR_CURRENT_PIN,
#endif
#if GET_POWERMON_ADC_VOLTS() == 0
POWER_MONITOR_VOLTAGE_PIN,
#endif
// Pins for ADC1 after ADC0
#if GET_TEMP_0_ADC() == 1
TEMP_0_PIN,
#endif
@ -373,6 +400,12 @@ enum ADCIndex {
#if GET_JOY_ADC_Z() == 1
JOY_Z_PIN,
#endif
#if GET_POWERMON_ADC_CURRENT() == 1
POWER_MONITOR_CURRENT_PIN,
#endif
#if GET_POWERMON_ADC_VOLTS() == 1
POWER_MONITOR_VOLTAGE_PIN,
#endif
};
static uint16_t adc_results[ADC_COUNT];
@ -435,6 +468,12 @@ enum ADCIndex {
#if GET_JOY_ADC_Z() == 0
{ PIN_TO_INPUTCTRL(JOY_Z_PIN) },
#endif
#if GET_POWERMON_ADC_CURRENT() == 0
{ PIN_TO_INPUTCTRL(POWER_MONITOR_CURRENT_PIN) },
#endif
#if GET_POWERMON_ADC_VOLTS() == 0
{ PIN_TO_INPUTCTRL(POWER_MONITOR_VOLTAGE_PIN) },
#endif
};
#define ADC0_AINCOUNT COUNT(adc0_dma_regs_list)
@ -498,6 +537,12 @@ enum ADCIndex {
#if GET_JOY_ADC_Z() == 1
{ PIN_TO_INPUTCTRL(JOY_Z_PIN) },
#endif
#if GET_POWERMON_ADC_CURRENT() == 1
{ PIN_TO_INPUTCTRL(POWER_MONITOR_CURRENT_PIN) },
#endif
#if GET_POWERMON_ADC_VOLTS() == 1
{ PIN_TO_INPUTCTRL(POWER_MONITOR_VOLTAGE_PIN) },
#endif
};
#define ADC1_AINCOUNT COUNT(adc1_dma_regs_list)

View file

@ -112,7 +112,7 @@ typedef Servo hal_servo_t;
//
//#define HAL_ADC_FILTERED // Disable Marlin's oversampling. The HAL filters ADC values.
#define HAL_ADC_VREF 3.3
#define HAL_ADC_VREF_MV 3300
#define HAL_ADC_RESOLUTION 10 // ... 12
//

View file

@ -53,31 +53,35 @@
#include "../../module/endstops.h"
#define MATCH_EILINE(P1,P2) (P1 != P2 && PIN_TO_EILINE(P1) == PIN_TO_EILINE(P2))
#define MATCH_X_MAX_EILINE(P) TERN0(HAS_X_MAX, DEFER4(MATCH_EILINE)(P, X_MAX_PIN))
#define MATCH_X_MIN_EILINE(P) TERN0(HAS_X_MIN, DEFER4(MATCH_EILINE)(P, X_MIN_PIN))
#define MATCH_Y_MAX_EILINE(P) TERN0(HAS_Y_MAX, DEFER4(MATCH_EILINE)(P, Y_MAX_PIN))
#define MATCH_Y_MIN_EILINE(P) TERN0(HAS_Y_MIN, DEFER4(MATCH_EILINE)(P, Y_MIN_PIN))
#define MATCH_Z_MAX_EILINE(P) TERN0(HAS_Z_MAX, DEFER4(MATCH_EILINE)(P, Z_MAX_PIN))
#define MATCH_Z_MIN_EILINE(P) TERN0(HAS_Z_MIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PIN))
#define MATCH_I_MAX_EILINE(P) TERN0(HAS_I_MAX, DEFER4(MATCH_EILINE)(P, I_MAX_PIN))
#define MATCH_I_MIN_EILINE(P) TERN0(HAS_I_MIN, DEFER4(MATCH_EILINE)(P, I_MIN_PIN))
#define MATCH_J_MAX_EILINE(P) TERN0(HAS_J_MAX, DEFER4(MATCH_EILINE)(P, J_MAX_PIN))
#define MATCH_J_MIN_EILINE(P) TERN0(HAS_J_MIN, DEFER4(MATCH_EILINE)(P, J_MIN_PIN))
#define MATCH_K_MAX_EILINE(P) TERN0(HAS_K_MAX, DEFER4(MATCH_EILINE)(P, K_MAX_PIN))
#define MATCH_K_MIN_EILINE(P) TERN0(HAS_K_MIN, DEFER4(MATCH_EILINE)(P, K_MIN_PIN))
#define MATCH_U_MAX_EILINE(P) TERN0(HAS_U_MAX, DEFER4(MATCH_EILINE)(P, U_MAX_PIN))
#define MATCH_U_MIN_EILINE(P) TERN0(HAS_U_MIN, DEFER4(MATCH_EILINE)(P, U_MIN_PIN))
#define MATCH_V_MAX_EILINE(P) TERN0(HAS_V_MAX, DEFER4(MATCH_EILINE)(P, V_MAX_PIN))
#define MATCH_V_MIN_EILINE(P) TERN0(HAS_V_MIN, DEFER4(MATCH_EILINE)(P, V_MIN_PIN))
#define MATCH_W_MAX_EILINE(P) TERN0(HAS_W_MAX, DEFER4(MATCH_EILINE)(P, W_MAX_PIN))
#define MATCH_W_MIN_EILINE(P) TERN0(HAS_W_MIN, DEFER4(MATCH_EILINE)(P, W_MIN_PIN))
#define MATCH_Z2_MAX_EILINE(P) TERN0(HAS_Z2_MAX, DEFER4(MATCH_EILINE)(P, Z2_MAX_PIN))
#define MATCH_Z2_MIN_EILINE(P) TERN0(HAS_Z2_MIN, DEFER4(MATCH_EILINE)(P, Z2_MIN_PIN))
#define MATCH_Z3_MAX_EILINE(P) TERN0(HAS_Z3_MAX, DEFER4(MATCH_EILINE)(P, Z3_MAX_PIN))
#define MATCH_Z3_MIN_EILINE(P) TERN0(HAS_Z3_MIN, DEFER4(MATCH_EILINE)(P, Z3_MIN_PIN))
#define MATCH_Z4_MAX_EILINE(P) TERN0(HAS_Z4_MAX, DEFER4(MATCH_EILINE)(P, Z4_MAX_PIN))
#define MATCH_Z4_MIN_EILINE(P) TERN0(HAS_Z4_MIN, DEFER4(MATCH_EILINE)(P, Z4_MIN_PIN))
#define MATCH_Z_MIN_PROBE_EILINE(P) TERN0(HAS_Z_MIN_PROBE_PIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PROBE_PIN))
#define MATCH_X_MAX_EILINE(P) TERN0(USE_X_MAX, DEFER4(MATCH_EILINE)(P, X_MAX_PIN))
#define MATCH_X_MIN_EILINE(P) TERN0(USE_X_MIN, DEFER4(MATCH_EILINE)(P, X_MIN_PIN))
#define MATCH_Y_MAX_EILINE(P) TERN0(USE_Y_MAX, DEFER4(MATCH_EILINE)(P, Y_MAX_PIN))
#define MATCH_Y_MIN_EILINE(P) TERN0(USE_Y_MIN, DEFER4(MATCH_EILINE)(P, Y_MIN_PIN))
#define MATCH_Z_MAX_EILINE(P) TERN0(USE_Z_MAX, DEFER4(MATCH_EILINE)(P, Z_MAX_PIN))
#define MATCH_Z_MIN_EILINE(P) TERN0(USE_Z_MIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PIN))
#define MATCH_I_MAX_EILINE(P) TERN0(USE_I_MAX, DEFER4(MATCH_EILINE)(P, I_MAX_PIN))
#define MATCH_I_MIN_EILINE(P) TERN0(USE_I_MIN, DEFER4(MATCH_EILINE)(P, I_MIN_PIN))
#define MATCH_J_MAX_EILINE(P) TERN0(USE_J_MAX, DEFER4(MATCH_EILINE)(P, J_MAX_PIN))
#define MATCH_J_MIN_EILINE(P) TERN0(USE_J_MIN, DEFER4(MATCH_EILINE)(P, J_MIN_PIN))
#define MATCH_K_MAX_EILINE(P) TERN0(USE_K_MAX, DEFER4(MATCH_EILINE)(P, K_MAX_PIN))
#define MATCH_K_MIN_EILINE(P) TERN0(USE_K_MIN, DEFER4(MATCH_EILINE)(P, K_MIN_PIN))
#define MATCH_U_MAX_EILINE(P) TERN0(USE_U_MAX, DEFER4(MATCH_EILINE)(P, U_MAX_PIN))
#define MATCH_U_MIN_EILINE(P) TERN0(USE_U_MIN, DEFER4(MATCH_EILINE)(P, U_MIN_PIN))
#define MATCH_V_MAX_EILINE(P) TERN0(USE_V_MAX, DEFER4(MATCH_EILINE)(P, V_MAX_PIN))
#define MATCH_V_MIN_EILINE(P) TERN0(USE_V_MIN, DEFER4(MATCH_EILINE)(P, V_MIN_PIN))
#define MATCH_W_MAX_EILINE(P) TERN0(USE_W_MAX, DEFER4(MATCH_EILINE)(P, W_MAX_PIN))
#define MATCH_W_MIN_EILINE(P) TERN0(USE_W_MIN, DEFER4(MATCH_EILINE)(P, W_MIN_PIN))
#define MATCH_X2_MAX_EILINE(P) TERN0(USE_X2_MAX, DEFER4(MATCH_EILINE)(P, X2_MAX_PIN))
#define MATCH_X2_MIN_EILINE(P) TERN0(USE_X2_MIN, DEFER4(MATCH_EILINE)(P, X2_MIN_PIN))
#define MATCH_Y2_MAX_EILINE(P) TERN0(USE_Y2_MAX, DEFER4(MATCH_EILINE)(P, Y2_MAX_PIN))
#define MATCH_Y2_MIN_EILINE(P) TERN0(USE_Y2_MIN, DEFER4(MATCH_EILINE)(P, Y2_MIN_PIN))
#define MATCH_Z2_MAX_EILINE(P) TERN0(USE_Z2_MAX, DEFER4(MATCH_EILINE)(P, Z2_MAX_PIN))
#define MATCH_Z2_MIN_EILINE(P) TERN0(USE_Z2_MIN, DEFER4(MATCH_EILINE)(P, Z2_MIN_PIN))
#define MATCH_Z3_MAX_EILINE(P) TERN0(USE_Z3_MAX, DEFER4(MATCH_EILINE)(P, Z3_MAX_PIN))
#define MATCH_Z3_MIN_EILINE(P) TERN0(USE_Z3_MIN, DEFER4(MATCH_EILINE)(P, Z3_MIN_PIN))
#define MATCH_Z4_MAX_EILINE(P) TERN0(USE_Z4_MAX, DEFER4(MATCH_EILINE)(P, Z4_MAX_PIN))
#define MATCH_Z4_MIN_EILINE(P) TERN0(USE_Z4_MIN, DEFER4(MATCH_EILINE)(P, Z4_MIN_PIN))
#define MATCH_Z_MIN_PROBE_EILINE(P) TERN0(HAS_Z_MIN_PROBE+PIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PROBE_PIN))
#define AVAILABLE_EILINE(P) ( PIN_TO_EILINE(P) != -1 \
&& !MATCH_X_MAX_EILINE(P) && !MATCH_X_MIN_EILINE(P) \
@ -89,6 +93,8 @@
&& !MATCH_U_MAX_EILINE(P) && !MATCH_U_MIN_EILINE(P) \
&& !MATCH_V_MAX_EILINE(P) && !MATCH_V_MIN_EILINE(P) \
&& !MATCH_W_MAX_EILINE(P) && !MATCH_W_MIN_EILINE(P) \
&& !MATCH_X2_MAX_EILINE(P) && !MATCH_X2_MIN_EILINE(P) \
&& !MATCH_Y2_MAX_EILINE(P) && !MATCH_Y2_MIN_EILINE(P) \
&& !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P) \
&& !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P) \
&& !MATCH_Z4_MAX_EILINE(P) && !MATCH_Z4_MIN_EILINE(P) \
@ -99,153 +105,153 @@ void endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE)
#if HAS_X_MAX
#if USE_X_MAX
#if !AVAILABLE_EILINE(X_MAX_PIN)
#error "X_MAX_PIN has no EXTINT line available."
#error "X_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(X_MAX_PIN);
#endif
#if HAS_X_MIN
#if USE_X_MIN
#if !AVAILABLE_EILINE(X_MIN_PIN)
#error "X_MIN_PIN has no EXTINT line available."
#error "X_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(X_MIN_PIN);
#endif
#if HAS_Y_MAX
#if USE_Y_MAX
#if !AVAILABLE_EILINE(Y_MAX_PIN)
#error "Y_MAX_PIN has no EXTINT line available."
#error "Y_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Y_MAX_PIN);
#endif
#if HAS_Y_MIN
#if USE_Y_MIN
#if !AVAILABLE_EILINE(Y_MIN_PIN)
#error "Y_MIN_PIN has no EXTINT line available."
#error "Y_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Y_MIN_PIN);
#endif
#if HAS_Z_MAX
#if USE_Z_MAX
#if !AVAILABLE_EILINE(Z_MAX_PIN)
#error "Z_MAX_PIN has no EXTINT line available."
#error "Z_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z_MAX_PIN);
#endif
#if HAS_Z_MIN
#if USE_Z_MIN
#if !AVAILABLE_EILINE(Z_MIN_PIN)
#error "Z_MIN_PIN has no EXTINT line available."
#error "Z_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z_MIN_PIN);
#endif
#if HAS_Z2_MAX
#if USE_Z2_MAX
#if !AVAILABLE_EILINE(Z2_MAX_PIN)
#error "Z2_MAX_PIN has no EXTINT line available."
#error "Z2_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z2_MAX_PIN);
#endif
#if HAS_Z2_MIN
#if USE_Z2_MIN
#if !AVAILABLE_EILINE(Z2_MIN_PIN)
#error "Z2_MIN_PIN has no EXTINT line available."
#error "Z2_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z2_MIN_PIN);
#endif
#if HAS_Z3_MAX
#if USE_Z3_MAX
#if !AVAILABLE_EILINE(Z3_MAX_PIN)
#error "Z3_MAX_PIN has no EXTINT line available."
#error "Z3_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z3_MAX_PIN);
#endif
#if HAS_Z3_MIN
#if USE_Z3_MIN
#if !AVAILABLE_EILINE(Z3_MIN_PIN)
#error "Z3_MIN_PIN has no EXTINT line available."
#error "Z3_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z3_MIN_PIN);
#endif
#if HAS_Z4_MAX
#if USE_Z4_MAX
#if !AVAILABLE_EILINE(Z4_MAX_PIN)
#error "Z4_MAX_PIN has no EXTINT line available."
#error "Z4_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z4_MAX_PIN);
#endif
#if HAS_Z4_MIN
#if USE_Z4_MIN
#if !AVAILABLE_EILINE(Z4_MIN_PIN)
#error "Z4_MIN_PIN has no EXTINT line available."
#error "Z4_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z4_MIN_PIN);
#endif
#if HAS_Z_MIN_PROBE_PIN
#if !AVAILABLE_EILINE(Z_MIN_PROBE_PIN)
#error "Z_MIN_PROBE_PIN has no EXTINT line available."
#error "Z_MIN_PROBE_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
_ATTACH(Z_MIN_PROBE_PIN);
#endif
#if HAS_I_MAX
#if USE_I_MAX
#if !AVAILABLE_EILINE(I_MAX_PIN)
#error "I_MAX_PIN has no EXTINT line available."
#error "I_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(I_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_I_MIN
#if USE_I_MIN
#if !AVAILABLE_EILINE(I_MIN_PIN)
#error "I_MIN_PIN has no EXTINT line available."
#error "I_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(I_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_J_MAX
#if USE_J_MAX
#if !AVAILABLE_EILINE(J_MAX_PIN)
#error "J_MAX_PIN has no EXTINT line available."
#error "J_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(J_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_J_MIN
#if USE_J_MIN
#if !AVAILABLE_EILINE(J_MIN_PIN)
#error "J_MIN_PIN has no EXTINT line available."
#error "J_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(J_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_K_MAX
#if USE_K_MAX
#if !AVAILABLE_EILINE(K_MAX_PIN)
#error "K_MAX_PIN has no EXTINT line available."
#error "K_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(K_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_K_MIN
#if USE_K_MIN
#if !AVAILABLE_EILINE(K_MIN_PIN)
#error "K_MIN_PIN has no EXTINT line available."
#error "K_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(K_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_U_MAX
#if USE_U_MAX
#if !AVAILABLE_EILINE(U_MAX_PIN)
#error "U_MAX_PIN has no EXTINT line available."
#error "U_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(U_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_U_MIN
#if USE_U_MIN
#if !AVAILABLE_EILINE(U_MIN_PIN)
#error "U_MIN_PIN has no EXTINT line available."
#error "U_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(U_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_V_MAX
#if USE_V_MAX
#if !AVAILABLE_EILINE(V_MAX_PIN)
#error "V_MAX_PIN has no EXTINT line available."
#error "V_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(V_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_V_MIN
#if USE_V_MIN
#if !AVAILABLE_EILINE(V_MIN_PIN)
#error "V_MIN_PIN has no EXTINT line available."
#error "V_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(V_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_W_MAX
#if USE_W_MAX
#if !AVAILABLE_EILINE(W_MAX_PIN)
#error "W_MAX_PIN has no EXTINT line available."
#error "W_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(W_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_W_MIN
#if USE_W_MIN
#if !AVAILABLE_EILINE(W_MIN_PIN)
#error "W_MIN_PIN has no EXTINT line available."
#error "W_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
attachInterrupt(W_MIN_PIN, endstop_ISR, CHANGE);
#endif

View file

@ -54,8 +54,8 @@
#error "EMERGENCY_PARSER is not yet implemented for SAMD51. Disable EMERGENCY_PARSER to continue."
#endif
#if ENABLED(SDIO_SUPPORT)
#error "SDIO_SUPPORT is not supported on SAMD51."
#if ENABLED(ONBOARD_SDIO)
#error "ONBOARD_SDIO is not supported on SAMD51."
#endif
#if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_FREQUENCY

View file

@ -69,7 +69,7 @@ void MarlinHAL::init() {
constexpr int cpuFreq = F_CPU;
UNUSED(cpuFreq);
#if HAS_MEDIA && DISABLED(SDIO_SUPPORT) && (defined(SDSS) && SDSS != -1)
#if HAS_MEDIA && DISABLED(ONBOARD_SDIO) && (defined(SDSS) && SDSS != -1)
OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up
#endif

View file

@ -55,64 +55,64 @@
#define _MSERIAL(X) MSerial##X
#define MSERIAL(X) _MSERIAL(X)
#if WITHIN(SERIAL_PORT, 1, 6)
#if WITHIN(SERIAL_PORT, 1, 9)
#define MYSERIAL1 MSERIAL(SERIAL_PORT)
#elif !defined(USBCON)
#error "SERIAL_PORT must be from 1 to 6."
#error "SERIAL_PORT must be from 1 to 9."
#elif SERIAL_PORT == -1
#define MYSERIAL1 MSerialUSB
#else
#error "SERIAL_PORT must be from 1 to 6, or -1 for Native USB."
#error "SERIAL_PORT must be from 1 to 9, or -1 for Native USB."
#endif
#ifdef SERIAL_PORT_2
#if WITHIN(SERIAL_PORT_2, 1, 6)
#if WITHIN(SERIAL_PORT_2, 1, 9)
#define MYSERIAL2 MSERIAL(SERIAL_PORT_2)
#elif !defined(USBCON)
#error "SERIAL_PORT must be from 1 to 6."
#error "SERIAL_PORT_2 must be from 1 to 9."
#elif SERIAL_PORT_2 == -1
#define MYSERIAL2 MSerialUSB
#else
#error "SERIAL_PORT_2 must be from 1 to 6, or -1 for Native USB."
#error "SERIAL_PORT_2 must be from 1 to 9, or -1 for Native USB."
#endif
#endif
#ifdef SERIAL_PORT_3
#if WITHIN(SERIAL_PORT_3, 1, 6)
#if WITHIN(SERIAL_PORT_3, 1, 9)
#define MYSERIAL3 MSERIAL(SERIAL_PORT_3)
#elif !defined(USBCON)
#error "SERIAL_PORT must be from 1 to 6."
#error "SERIAL_PORT_3 must be from 1 to 9."
#elif SERIAL_PORT_3 == -1
#define MYSERIAL3 MSerialUSB
#else
#error "SERIAL_PORT_3 must be from 1 to 6, or -1 for Native USB."
#error "SERIAL_PORT_3 must be from 1 to 9, or -1 for Native USB."
#endif
#endif
#ifdef MMU2_SERIAL_PORT
#if WITHIN(MMU2_SERIAL_PORT, 1, 6)
#if WITHIN(MMU2_SERIAL_PORT, 1, 9)
#define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT)
#elif !defined(USBCON)
#error "SERIAL_PORT must be from 1 to 6."
#error "MMU2_SERIAL_PORT must be from 1 to 9."
#elif MMU2_SERIAL_PORT == -1
#define MMU2_SERIAL MSerialUSB
#else
#error "MMU2_SERIAL_PORT must be from 1 to 6, or -1 for Native USB."
#error "MMU2_SERIAL_PORT must be from 1 to 9, or -1 for Native USB."
#endif
#endif
#ifdef LCD_SERIAL_PORT
#if WITHIN(LCD_SERIAL_PORT, 1, 6)
#if WITHIN(LCD_SERIAL_PORT, 1, 9)
#define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT)
#elif !defined(USBCON)
#error "SERIAL_PORT must be from 1 to 6."
#error "LCD_SERIAL_PORT must be from 1 to 9."
#elif LCD_SERIAL_PORT == -1
#define LCD_SERIAL MSerialUSB
#else
#error "LCD_SERIAL_PORT must be from 1 to 6, or -1 for Native USB."
#error "LCD_SERIAL_PORT must be from 1 to 9, or -1 for Native USB."
#endif
#if HAS_DGUS_LCD
#define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite()
#define LCD_SERIAL_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite()
#endif
#endif
@ -137,11 +137,7 @@
typedef double isr_float_t; // FPU ops are used for single-precision, so use double for ISRs.
#if defined(STM32G0B1xx) || defined(STM32H7xx)
typedef int32_t pin_t;
#else
typedef int16_t pin_t;
#endif
typedef int32_t pin_t; // Parity with platform/ststm32
class libServo;
typedef libServo hal_servo_t;
@ -158,7 +154,7 @@ typedef libServo hal_servo_t;
#define HAL_ADC_RESOLUTION 12
#endif
#define HAL_ADC_VREF 3.3
#define HAL_ADC_VREF_MV 3300
//
// Pin Mapping for M42, M43, M226
@ -173,7 +169,9 @@ typedef libServo hal_servo_t;
#define JTAGSWD_RESET() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_RESET); // Reset: FULL SWD+JTAG
#endif
#define PLATFORM_M997_SUPPORT
#ifndef PLATFORM_M997_SUPPORT
#define PLATFORM_M997_SUPPORT
#endif
void flashFirmware(const int16_t);
// Maple Compatibility

View file

@ -37,6 +37,15 @@
#ifndef USART5
#define USART5 UART5
#endif
#ifndef USART7
#define USART7 UART7
#endif
#ifndef USART8
#define USART8 UART8
#endif
#ifndef USART9
#define USART9 UART9
#endif
#define DECLARE_SERIAL_PORT(ser_num) \
void _rx_complete_irq_ ## ser_num (serial_t * obj); \

View file

@ -44,7 +44,7 @@ struct USARTMin {
volatile uint32_t CR2;
};
#if WITHIN(SERIAL_PORT, 1, 6)
#if WITHIN(SERIAL_PORT, 1, 9)
// Depending on the CPU, the serial port is different for USART1
static const uintptr_t regsAddr[] = {
TERN(STM32F1xx, 0x40013800, 0x40011000), // USART1
@ -52,7 +52,10 @@ struct USARTMin {
0x40004800, // USART3
0x40004C00, // UART4_BASE
0x40005000, // UART5_BASE
0x40011400 // USART6
0x40011400, // USART6
0x40007800, // UART7_BASE
0x40007C00, // UART8_BASE
0x40011800 // UART9_BASE
};
static USARTMin * regs = (USARTMin*)regsAddr[SERIAL_PORT - 1];
#endif
@ -115,7 +118,7 @@ static void TXBegin() {
// A SW memory barrier, to ensure GCC does not overoptimize loops
#define sw_barrier() __asm__ volatile("": : :"memory");
static void TX(char c) {
#if WITHIN(SERIAL_PORT, 1, 6)
#if WITHIN(SERIAL_PORT, 1, 9)
constexpr uint32_t usart_sr_txe = _BV(7);
while (!(regs->SR & usart_sr_txe)) {
hal.watchdog_refresh();
@ -134,18 +137,18 @@ void install_min_serial() {
}
#if NONE(DYNAMIC_VECTORTABLE, STM32F0xx, STM32G0xx) // Cortex M0 can't jump to a symbol that's too far from the current function, so we work around this in exception_arm.cpp
extern "C" {
__attribute__((naked)) void JumpHandler_ASM() {
__asm__ __volatile__ (
"b CommonHandler_ASM\n"
);
extern "C" {
__attribute__((naked)) void JumpHandler_ASM() {
__asm__ __volatile__ (
"b CommonHandler_ASM\n"
);
}
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) HardFault_Handler();
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) BusFault_Handler();
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) UsageFault_Handler();
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) MemManage_Handler();
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) NMI_Handler();
}
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) HardFault_Handler();
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) BusFault_Handler();
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) UsageFault_Handler();
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) MemManage_Handler();
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) NMI_Handler();
}
#endif
#endif // POSTMORTEM_DEBUGGING

View file

@ -28,33 +28,33 @@ void endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE)
TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN));
TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN));
TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN));
TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN));
TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN));
TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN));
TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN));
TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN));
TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN));
TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN));
TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN));
TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN));
TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN));
TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN));
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN));
TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN));
TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN));
TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN));
TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN));
TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN));
TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN));
TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN));
TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN));
TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN));
TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN));
TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN));
TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN));
TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN));
TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN));
TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN));
TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN));
TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN));
TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN));
TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN));
TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN));
TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN));
TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN));
TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN));
TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN));
TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN));
TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN));
TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN));
TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN));
TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN));
TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN));
TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN));
}

View file

@ -40,6 +40,12 @@
#define BLOCK_SIZE 512
#define PRODUCT_ID 0x29
#ifndef SD_MULTIBLOCK_RETRY_CNT
#define SD_MULTIBLOCK_RETRY_CNT 1
#elif SD_MULTIBLOCK_RETRY_CNT < 1
#error "SD_MULTIBLOCK_RETRY_CNT must be greater than or equal to 1."
#endif
class Sd2CardUSBMscHandler : public USBMscHandler {
public:
DiskIODriver* diskIODriver() {
@ -65,19 +71,29 @@ public:
// single block
if (blkLen == 1) {
hal.watchdog_refresh();
sd2card->writeBlock(blkAddr, pBuf);
return true;
return sd2card->writeBlock(blkAddr, pBuf);
}
// multi block optimization
sd2card->writeStart(blkAddr, blkLen);
while (blkLen--) {
hal.watchdog_refresh();
sd2card->writeData(pBuf);
pBuf += BLOCK_SIZE;
bool done = false;
for (uint16_t rcount = SD_MULTIBLOCK_RETRY_CNT; !done && rcount--;) {
uint8_t *cBuf = pBuf;
sd2card->writeStart(blkAddr, blkLen);
bool okay = true; // Assume success
for (uint32_t i = blkLen; i--;) {
hal.watchdog_refresh();
if (!sd2card->writeData(cBuf)) { // Write. Did it fail?
sd2card->writeStop(); // writeStop for new writeStart
okay = false; // Failed, so retry
break; // Go to while... below
}
cBuf += BLOCK_SIZE;
}
done = okay; // Done if no error occurred
}
sd2card->writeStop();
return true;
if (done) sd2card->writeStop();
return done;
}
bool Read(uint8_t *pBuf, uint32_t blkAddr, uint16_t blkLen) {
@ -85,24 +101,32 @@ public:
// single block
if (blkLen == 1) {
hal.watchdog_refresh();
sd2card->readBlock(blkAddr, pBuf);
return true;
return sd2card->readBlock(blkAddr, pBuf);
}
// multi block optimization
sd2card->readStart(blkAddr);
while (blkLen--) {
hal.watchdog_refresh();
sd2card->readData(pBuf);
pBuf += BLOCK_SIZE;
bool done = false;
for (uint16_t rcount = SD_MULTIBLOCK_RETRY_CNT; !done && rcount--;) {
uint8_t *cBuf = pBuf;
sd2card->readStart(blkAddr);
bool okay = true; // Assume success
for (uint32_t i = blkLen; i--;) {
hal.watchdog_refresh();
if (!sd2card->readData(cBuf)) { // Read. Did it fail?
sd2card->readStop(); // readStop for new readStart
okay = false; // Failed, so retry
break; // Go to while... below
}
cBuf += BLOCK_SIZE;
}
done = okay; // Done if no error occurred
}
sd2card->readStop();
return true;
if (done) sd2card->readStop();
return done;
}
bool IsReady() {
return diskIODriver()->isReady();
}
bool IsReady() { return diskIODriver()->isReady(); }
};
Sd2CardUSBMscHandler usbMscHandler;

View file

@ -111,13 +111,14 @@ const XrefInfo pin_xref[] PROGMEM = {
#if NUM_ANALOG_FIRST >= NUM_DIGITAL_PINS
#define HAS_HIGH_ANALOG_PINS 1
#endif
#define NUM_ANALOG_LAST ((NUM_ANALOG_FIRST) + (NUM_ANALOG_INPUTS) - 1)
#ifndef NUM_ANALOG_LAST
#define NUM_ANALOG_LAST ((NUM_ANALOG_FIRST) + (NUM_ANALOG_INPUTS) - 1)
#endif
#define NUMBER_PINS_TOTAL ((NUM_DIGITAL_PINS) + TERN0(HAS_HIGH_ANALOG_PINS, NUM_ANALOG_INPUTS))
#define VALID_PIN(P) (WITHIN(P, 0, (NUM_DIGITAL_PINS) - 1) || TERN0(HAS_HIGH_ANALOG_PINS, WITHIN(P, NUM_ANALOG_FIRST, NUM_ANALOG_LAST)))
#define digitalRead_mod(Ard_num) extDigitalRead(Ard_num) // must use Arduino pin numbers when doing reads
#define PRINT_PIN(Q)
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PORT(ANUM) port_print(ANUM)
#define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1 // will report analog pin number in the print port routine
// x is a variable used to search pin_array
@ -185,7 +186,7 @@ bool is_digital(const pin_t Ard_num) {
return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT;
}
void port_print(const pin_t Ard_num) {
void print_port(const pin_t Ard_num) {
char buffer[16];
pin_t Index;
for (Index = 0; Index < NUMBER_PINS_TOTAL; Index++)

View file

@ -26,7 +26,7 @@
#include "../../inc/MarlinConfig.h"
#if ENABLED(SDIO_SUPPORT)
#if ENABLED(ONBOARD_SDIO)
#include "sdio.h"
@ -453,5 +453,5 @@ uint32_t SDIO_GetCardSize() {
return (uint32_t)(hsd.SdCard.BlockNbr) * (hsd.SdCard.BlockSize);
}
#endif // SDIO_SUPPORT
#endif // ONBOARD_SDIO
#endif // HAL_STM32

View file

@ -41,7 +41,7 @@
#define DATASIZE_8BIT SPI_DATASIZE_8BIT
#define DATASIZE_16BIT SPI_DATASIZE_16BIT
#define TFT_IO_DRIVER TFT_FSMC
#define DMA_MAX_SIZE 0xFFFF
#define DMA_MAX_WORDS 0xFFFF
#define TFT_DATASIZE TERN(TFT_INTERFACE_FSMC_8BIT, DATASIZE_8BIT, DATASIZE_16BIT)
typedef TERN(TFT_INTERFACE_FSMC_8BIT, uint8_t, uint16_t) tft_data_t;
@ -81,8 +81,8 @@ class TFT_FSMC {
static void WriteSequence(uint16_t *Data, uint16_t Count) { Transmit(DMA_PINC_ENABLE, Data, Count); }
static void WriteMultiple(uint16_t Color, uint32_t Count) {
while (Count > 0) {
Transmit(DMA_MINC_DISABLE, &Color, Count > DMA_MAX_SIZE ? DMA_MAX_SIZE : Count);
Count = Count > DMA_MAX_SIZE ? Count - DMA_MAX_SIZE : 0;
Transmit(DMA_MINC_DISABLE, &Color, Count > DMA_MAX_WORDS ? DMA_MAX_WORDS : Count);
Count = Count > DMA_MAX_WORDS ? Count - DMA_MAX_WORDS : 0;
}
}
};

View file

@ -32,7 +32,7 @@
#define DATASIZE_8BIT SPI_DATASIZE_8BIT
#define DATASIZE_16BIT SPI_DATASIZE_16BIT
#define TFT_IO_DRIVER TFT_LTDC
#define DMA_MAX_SIZE 0xFFFF
#define DMA_MAX_WORDS 0xFFFF
#define TFT_DATASIZE DATASIZE_16BIT
typedef uint16_t tft_data_t;
@ -71,8 +71,8 @@ class TFT_LTDC {
static void WriteSequence(uint16_t *Data, uint16_t Count) { Transmit(DMA_PINC_ENABLE, Data, Count); }
static void WriteMultiple(uint16_t Color, uint32_t Count) {
while (Count > 0) {
Transmit(DMA_PINC_DISABLE, &Color, Count > DMA_MAX_SIZE ? DMA_MAX_SIZE : Count);
Count = Count > DMA_MAX_SIZE ? Count - DMA_MAX_SIZE : 0;
Transmit(DMA_PINC_DISABLE, &Color, Count > DMA_MAX_WORDS ? DMA_MAX_WORDS : Count);
Count = Count > DMA_MAX_WORDS ? Count - DMA_MAX_WORDS : 0;
}
}
};

View file

@ -242,7 +242,7 @@ void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Coun
SET_BIT(SPIx.Instance->CR2, SPI_CR2_TXDMAEN); // Enable Tx DMA Request
TERN_(TFT_SHARED_SPI, while (isBusy()));
TERN_(TFT_SHARED_IO, while (isBusy()));
}
void TFT_SPI::Transmit(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {

View file

@ -38,8 +38,9 @@
#define DATASIZE_8BIT SPI_DATASIZE_8BIT
#define DATASIZE_16BIT SPI_DATASIZE_16BIT
#define DATASIZE_32BIT SPI_DATASIZE_32BIT
#define TFT_IO_DRIVER TFT_SPI
#define DMA_MAX_SIZE 0xFFFF
#define DMA_MAX_WORDS 0xFFFF
class TFT_SPI {
private:
@ -78,8 +79,8 @@ public:
static void WriteSequence(uint16_t *Data, uint16_t Count) { Transmit(DMA_MINC_ENABLE, Data, Count); }
static void WriteMultiple(uint16_t Color, uint32_t Count) {
while (Count > 0) {
Transmit(DMA_MINC_DISABLE, &Color, Count > DMA_MAX_SIZE ? DMA_MAX_SIZE : Count);
Count = Count > DMA_MAX_SIZE ? Count - DMA_MAX_SIZE : 0;
Transmit(DMA_MINC_DISABLE, &Color, Count > DMA_MAX_WORDS ? DMA_MAX_WORDS : Count);
Count = Count > DMA_MAX_WORDS ? Count - DMA_MAX_WORDS : 0;
}
}
};

View file

@ -139,7 +139,7 @@
static_assert(false, "LCD_SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.")
#endif
#if HAS_DGUS_LCD
#define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite()
#define LCD_SERIAL_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite()
#endif
#endif
@ -189,7 +189,7 @@ typedef int8_t pin_t;
#define HAL_ADC_RESOLUTION 12
#endif
#define HAL_ADC_VREF 3.3
#define HAL_ADC_VREF_MV 3300
uint16_t analogRead(const pin_t pin); // need hal.adc_enable() first
void analogWrite(const pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!?
@ -204,7 +204,9 @@ void analogWrite(const pin_t pin, int pwm_val8); // PWM only! mul by 257 in mapl
#define JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY)
#define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE)
#define PLATFORM_M997_SUPPORT
#ifndef PLATFORM_M997_SUPPORT
#define PLATFORM_M997_SUPPORT
#endif
void flashFirmware(const int16_t);
#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment
@ -219,8 +221,6 @@ void flashFirmware(const int16_t);
// Memory related
#define __bss_end __bss_end__
void _delay_ms(const int ms);
extern "C" char* _sbrk(int incr);
#pragma GCC diagnostic push

View file

@ -28,7 +28,7 @@
// Copied from ~/.platformio/packages/framework-arduinoststm32-maple/STM32F1/system/libmaple/usart_private.h
// Changed to handle Emergency Parser
static inline __always_inline void my_usart_irq(ring_buffer *rb, ring_buffer *wb, usart_reg_map *regs, MSerialT &serial) {
FORCE_INLINE void my_usart_irq(ring_buffer *rb, ring_buffer *wb, usart_reg_map *regs, MSerialT &serial) {
/* Handle RXNEIE and TXEIE interrupts.
* RXNE signifies availability of a byte in DR.
*
@ -77,7 +77,7 @@ static inline __always_inline void my_usart_irq(ring_buffer *rb, ring_buffer *wb
// Not every MarlinSerial port should handle emergency parsing.
// It would not make sense to parse G-Code from TMC responses, for example.
constexpr bool serial_handles_emergency(int port) {
return false
return (false
#ifdef SERIAL_PORT
|| (SERIAL_PORT) == port
#endif
@ -87,7 +87,7 @@ constexpr bool serial_handles_emergency(int port) {
#ifdef LCD_SERIAL_PORT
|| (LCD_SERIAL_PORT) == port
#endif
;
);
}
#define DEFINE_HWSERIAL_MARLIN(name, n) \

View file

@ -53,33 +53,33 @@ void endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE)
TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN));
TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN));
TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN));
TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN));
TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN));
TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN));
TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN));
TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN));
TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN));
TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN));
TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN));
TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN));
TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN));
TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN));
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN));
TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN));
TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN));
TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN));
TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN));
TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN));
TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN));
TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN));
TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN));
TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN));
TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN));
TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN));
TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN));
TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN));
TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN));
TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN));
TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN));
TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN));
TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN));
TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN));
TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN));
TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN));
TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN));
TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN));
TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN));
TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN));
TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN));
TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN));
TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN));
TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN));
TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN));
TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN));
}

View file

@ -28,7 +28,7 @@
#define USE_SHARED_EEPROM 1
#endif
// Allow SDSUPPORT to be disabled
// Allow for no media drives
#if !HAS_MEDIA
#undef SDIO_SUPPORT
#undef ONBOARD_SDIO
#endif

View file

@ -41,11 +41,9 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS];
#define NUMBER_PINS_TOTAL BOARD_NR_GPIO_PINS
#define VALID_PIN(pin) (pin >= 0 && pin < BOARD_NR_GPIO_PINS)
#define GET_ARRAY_PIN(p) pin_t(pin_array[p].pin)
#define pwm_status(pin) PWM_PIN(pin)
#define digitalRead_mod(p) extDigitalRead(p)
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3hd "), int16_t(p)); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PORT(p) print_port(p)
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 21 // space needed to be pretty if not first name assigned to a pin
@ -54,20 +52,18 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS];
#define M43_NEVER_TOUCH(Q) (Q >= 9 && Q <= 12) // SERIAL/USB pins PA9(TX) PA10(RX)
#endif
static int8_t get_pin_mode(pin_t pin) {
return VALID_PIN(pin) ? _GET_MODE(pin) : -1;
}
int8_t get_pin_mode(const pin_t pin) { return VALID_PIN(pin) ? _GET_MODE(pin) : -1; }
static pin_t DIGITAL_PIN_TO_ANALOG_PIN(pin_t pin) {
pin_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t pin) {
if (!VALID_PIN(pin)) return -1;
int8_t adc_channel = int8_t(PIN_MAP[pin].adc_channel);
pin_t adc_channel = pin_t(PIN_MAP[pin].adc_channel);
#ifdef NUM_ANALOG_INPUTS
if (adc_channel >= NUM_ANALOG_INPUTS) adc_channel = ADCx;
if (adc_channel >= NUM_ANALOG_INPUTS) adc_channel = (pin_t)ADCx;
#endif
return pin_t(adc_channel);
return adc_channel;
}
static bool IS_ANALOG(pin_t pin) {
bool IS_ANALOG(const pin_t pin) {
if (!VALID_PIN(pin)) return false;
if (PIN_MAP[pin].adc_channel != ADCx) {
#ifdef NUM_ANALOG_INPUTS
@ -78,11 +74,11 @@ static bool IS_ANALOG(pin_t pin) {
return false;
}
static bool GET_PINMODE(const pin_t pin) {
bool GET_PINMODE(const pin_t pin) {
return VALID_PIN(pin) && !IS_INPUT(pin);
}
static bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) {
bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) {
const pin_t pin = GET_ARRAY_PIN(array_pin);
return (!IS_ANALOG(pin)
#ifdef NUM_ANALOG_INPUTS
@ -93,7 +89,7 @@ static bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) {
#include "../../inc/MarlinConfig.h" // Allow pins/pins.h to set density
static void pwm_details(const pin_t pin) {
void pwm_details(const pin_t pin) {
if (PWM_PIN(pin)) {
timer_dev * const tdev = PIN_MAP[pin].timer_device;
const uint8_t channel = PIN_MAP[pin].timer_channel;
@ -113,7 +109,9 @@ static void pwm_details(const pin_t pin) {
}
}
static void print_port(pin_t pin) {
bool pwm_status(const pin_t pin) { return PWM_PIN(pin); }
void print_port(const pin_t pin) {
const char port = 'A' + char(pin >> 4); // pin div 16
const int16_t gbit = PIN_MAP[pin].gpio_bit;
char buffer[8];

View file

@ -135,8 +135,13 @@ bool SDIO_ReadBlock_DMA(uint32_t blockAddress, uint8_t *data) {
}
bool SDIO_ReadBlock(uint32_t blockAddress, uint8_t *data) {
uint32_t retries = SDIO_READ_RETRIES;
while (retries--) if (SDIO_ReadBlock_DMA(blockAddress, data)) return true;
uint8_t retries = SDIO_READ_RETRIES;
while (retries--) {
if (SDIO_ReadBlock_DMA(blockAddress, data)) return true;
#if SD_RETRY_DELAY_MS
delay(SD_RETRY_DELAY_MS);
#endif
}
return false;
}

View file

@ -20,6 +20,8 @@
*
*/
#ifdef __STM32F1__
#include "../../../inc/MarlinConfig.h"
#if HAS_FSMC_TFT
@ -260,3 +262,5 @@ void TFT_FSMC::Transmit(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count)
}
#endif // HAS_FSMC_TFT
#endif // __STM32F1__

View file

@ -33,7 +33,7 @@
#define DATASIZE_8BIT DMA_SIZE_8BITS
#define DATASIZE_16BIT DMA_SIZE_16BITS
#define TFT_IO_DRIVER TFT_FSMC
#define DMA_MAX_SIZE 0xFFFF
#define DMA_MAX_WORDS 0xFFFF
#define DMA_PINC_ENABLE DMA_PINC_MODE
#define DMA_PINC_DISABLE 0
@ -70,8 +70,8 @@ class TFT_FSMC {
static void WriteSequence(uint16_t *Data, uint16_t Count) { Transmit(DMA_PINC_ENABLE, Data, Count); }
static void WriteMultiple(uint16_t Color, uint32_t Count) {
while (Count > 0) {
Transmit(DMA_PINC_DISABLE, &Color, Count > DMA_MAX_SIZE ? DMA_MAX_SIZE : Count);
Count = Count > DMA_MAX_SIZE ? Count - DMA_MAX_SIZE : 0;
Transmit(DMA_PINC_DISABLE, &Color, Count > DMA_MAX_WORDS ? DMA_MAX_WORDS : Count);
Count = Count > DMA_MAX_WORDS ? Count - DMA_MAX_WORDS : 0;
}
}
};

View file

@ -20,6 +20,8 @@
*
*/
#ifdef __STM32F1__
#include "../../../inc/MarlinConfig.h"
#if HAS_SPI_TFT
@ -154,7 +156,7 @@ void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Coun
DataTransferBegin();
SPIx.dmaSendAsync(Data, Count, MemoryIncrease == DMA_MINC_ENABLE);
TERN_(TFT_SHARED_SPI, while (isBusy()));
TERN_(TFT_SHARED_IO, while (isBusy()));
}
void TFT_SPI::Transmit(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
@ -165,3 +167,5 @@ void TFT_SPI::Transmit(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count)
}
#endif // HAS_SPI_TFT
#endif // __STM32F1__

View file

@ -56,7 +56,7 @@
#define DATASIZE_8BIT DATA_SIZE_8BIT
#define DATASIZE_16BIT DATA_SIZE_16BIT
#define TFT_IO_DRIVER TFT_SPI
#define DMA_MAX_SIZE 0xFFFF
#define DMA_MAX_WORDS 0xFFFF
#define DMA_MINC_ENABLE DMA_MINC_MODE
#define DMA_MINC_DISABLE 0
@ -89,8 +89,8 @@ public:
static void WriteSequence(uint16_t *Data, uint16_t Count) { Transmit(DMA_MINC_ENABLE, Data, Count); }
static void WriteMultiple(uint16_t Color, uint32_t Count) {
while (Count > 0) {
Transmit(DMA_MINC_DISABLE, &Color, Count > DMA_MAX_SIZE ? DMA_MAX_SIZE : Count);
Count = Count > DMA_MAX_SIZE ? Count - DMA_MAX_SIZE : 0;
Transmit(DMA_MINC_DISABLE, &Color, Count > DMA_MAX_WORDS ? DMA_MAX_WORDS : Count);
Count = Count > DMA_MAX_WORDS ? Count - DMA_MAX_WORDS : 0;
}
}
};

View file

@ -20,6 +20,8 @@
*
*/
#ifdef __STM32F1__
#include "../../../inc/MarlinConfig.h"
#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS
@ -141,4 +143,6 @@ uint16_t XPT2046::SoftwareIO(uint16_t data) {
return result;
}
#endif // HAS_TFT_XPT2046
#endif // HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS
#endif // __STM32F1__

View file

@ -101,7 +101,7 @@ uint32_t __get_PRIMASK(void); // CMSIS
#define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
#endif
#define HAL_ADC_VREF 3.3
#define HAL_ADC_VREF_MV 3300
#define HAL_ADC_RESOLUTION 10
//

View file

@ -47,33 +47,33 @@ void endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN));
TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN));
TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN));
TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN));
TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN));
TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN));
TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN));
TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN));
TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN));
TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN));
TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN));
TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN));
TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN));
TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN));
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN));
TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN));
TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN));
TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN));
TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN));
TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN));
TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN));
TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN));
TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN));
TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN));
TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN));
TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN));
TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN));
TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN));
TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN));
TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN));
TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN));
TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN));
TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN));
TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN));
TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN));
TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN));
TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN));
TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN));
TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN));
TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN));
TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN));
TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN));
TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN));
TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN));
TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN));
TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN));
}

View file

@ -106,7 +106,7 @@ typedef int8_t pin_t;
#define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
#endif
#define HAL_ADC_VREF 3.3
#define HAL_ADC_VREF_MV 3300
#define HAL_ADC_RESOLUTION 10
//

View file

@ -46,33 +46,33 @@ void endstop_ISR() { endstops.update(); }
*/
void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN));
TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN));
TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN));
TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN));
TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN));
TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN));
TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN));
TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN));
TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN));
TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN));
TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN));
TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN));
TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN));
TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN));
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN));
TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN));
TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN));
TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN));
TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN));
TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN));
TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN));
TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN));
TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN));
TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN));
TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN));
TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN));
TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN));
TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN));
TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN));
TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN));
TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN));
TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN));
TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN));
TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN));
TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN));
TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN));
TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN));
TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN));
TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN));
TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN));
TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN));
TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN));
TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN));
TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN));
TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN));
TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN));
}

View file

@ -55,12 +55,12 @@
#define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(0) && (P) <= analogInputToDigitalPin(9)) || ((P) >= analogInputToDigitalPin(12) && (P) <= analogInputToDigitalPin(20))
void HAL_print_analog_pin(char buffer[], int8_t pin) {
void print_analog_pin(char buffer[], int8_t pin) {
if (pin <= 23) sprintf_P(buffer, PSTR("(A%2d) "), int(pin - 14));
else if (pin <= 39) sprintf_P(buffer, PSTR("(A%2d) "), int(pin - 19));
}
void HAL_analog_pin_state(char buffer[], int8_t pin) {
void analog_pin_state(char buffer[], int8_t pin) {
if (pin <= 23) sprintf_P(buffer, PSTR("Analog in =% 5d"), analogRead(pin - 14));
else if (pin <= 39) sprintf_P(buffer, PSTR("Analog in =% 5d"), analogRead(pin - 19));
}
@ -77,7 +77,7 @@ void HAL_analog_pin_state(char buffer[], int8_t pin) {
* Print a pin's PWM status.
* Return true if it's currently a PWM pin.
*/
bool HAL_pwm_status(int8_t pin) {
bool pwm_status(int8_t pin) {
char buffer[20]; // for the sprintf statements
switch (pin) {
FTM_CASE(0,0);
@ -108,4 +108,4 @@ bool HAL_pwm_status(int8_t pin) {
SERIAL_ECHOPGM(" ");
}
static void HAL_pwm_details(uint8_t pin) { /* TODO */ }
void pwm_details(uint8_t pin) { /* TODO */ }

View file

@ -39,9 +39,19 @@
#define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
#define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X)
#if WITHIN(SERIAL_PORT, 0, 3)
#if WITHIN(SERIAL_PORT, 0, 8)
IMPLEMENT_SERIAL(SERIAL_PORT);
#endif
#ifdef SERIAL_PORT_2
#if WITHIN(SERIAL_PORT_2, 0, 8)
IMPLEMENT_SERIAL(SERIAL_PORT_2);
#endif
#endif
#ifdef SERIAL_PORT_3
#if WITHIN(SERIAL_PORT_3, 0, 8)
IMPLEMENT_SERIAL(SERIAL_PORT_3);
#endif
#endif
USBSerialType USBSerial(false, SerialUSB);
// ------------------------

View file

@ -80,7 +80,7 @@ extern USBSerialType USBSerial;
#define MSERIAL(X) _MSERIAL(X)
#if SERIAL_PORT == -1
#define MYSERIAL1 SerialUSB
#define MYSERIAL1 USBSerial
#elif WITHIN(SERIAL_PORT, 0, 8)
DECLARE_SERIAL(SERIAL_PORT);
#define MYSERIAL1 MSERIAL(SERIAL_PORT)
@ -90,16 +90,28 @@ extern USBSerialType USBSerial;
#ifdef SERIAL_PORT_2
#if SERIAL_PORT_2 == -1
#define MYSERIAL2 usbSerial
#define MYSERIAL2 USBSerial
#elif SERIAL_PORT_2 == -2
#define MYSERIAL2 ethernet.telnetClient
#elif WITHIN(SERIAL_PORT_2, 0, 8)
DECLARE_SERIAL(SERIAL_PORT_2);
#define MYSERIAL2 MSERIAL(SERIAL_PORT_2)
#else
#error "SERIAL_PORT_2 must be from 0 to 8, or -1 for Native USB, or -2 for Ethernet."
#endif
#endif
#ifdef SERIAL_PORT_3
#if SERIAL_PORT_3 == -1
#define MYSERIAL3 USBSerial
#elif WITHIN(SERIAL_PORT_3, 0, 8)
DECLARE_SERIAL(SERIAL_PORT_3);
#define MYSERIAL3 MSERIAL(SERIAL_PORT_3)
#else
#error "SERIAL_PORT_3 must be from 0 to 8, or -1 for Native USB."
#endif
#endif
// ------------------------
// Types
// ------------------------
@ -124,7 +136,7 @@ typedef int8_t pin_t;
#define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
#endif
#define HAL_ADC_VREF 3.3
#define HAL_ADC_VREF_MV 3300
#define HAL_ADC_RESOLUTION 10
#define HAL_ADC_FILTERED // turn off ADC oversampling

View file

@ -46,27 +46,33 @@ void endstop_ISR() { endstops.update(); }
*/
void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN));
TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN));
TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN));
TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN));
TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN));
TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN));
TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN));
TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN));
TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN));
TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN));
TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN));
TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN));
TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN));
TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN));
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN));
TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN));
TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN));
TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN));
TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN));
TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN));
TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN));
TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN));
TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN));
TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN));
TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN));
TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN));
TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN));
TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN));
TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN));
TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN));
TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN));
TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN));
TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN));
TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN));
TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN));
TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN));
TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN));
TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN));
TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN));
TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN));
}

View file

@ -30,7 +30,6 @@
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
#define digitalRead_mod(p) extDigitalRead(p) // AVR digitalRead disabled PWM before it read the pin
#define PRINT_PORT(p)
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%02d"), p); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
@ -39,7 +38,6 @@
#define VALID_PIN(pin) (pin >= 0 && pin < int8_t(NUMBER_PINS_TOTAL))
#define DIGITAL_PIN_TO_ANALOG_PIN(p) int(p - analogInputToDigitalPin(0))
#define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(0) && (P) <= analogInputToDigitalPin(13)) || ((P) >= analogInputToDigitalPin(14) && (P) <= analogInputToDigitalPin(17))
#define pwm_status(pin) HAL_pwm_status(pin)
#define GET_PINMODE(PIN) (VALID_PIN(pin) && IS_OUTPUT(pin))
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
@ -120,12 +118,12 @@ const struct pwm_pin_info_struct pwm_pin_info[] = {
#endif
};
void HAL_print_analog_pin(char buffer[], int8_t pin) {
void print_analog_pin(char buffer[], const pin_t pin) {
if (pin <= 23) sprintf_P(buffer, PSTR("(A%2d) "), int(pin - 14));
else if (pin <= 41) sprintf_P(buffer, PSTR("(A%2d) "), int(pin - 24));
}
void HAL_analog_pin_state(char buffer[], int8_t pin) {
void analog_pin_state(char buffer[], const pin_t pin) {
if (pin <= 23) sprintf_P(buffer, PSTR("Analog in =% 5d"), analogRead(pin - 14));
else if (pin <= 41) sprintf_P(buffer, PSTR("Analog in =% 5d"), analogRead(pin - 24));
}
@ -136,14 +134,14 @@ void HAL_analog_pin_state(char buffer[], int8_t pin) {
* Print a pin's PWM status.
* Return true if it's currently a PWM pin.
*/
bool HAL_pwm_status(int8_t pin) {
bool pwm_status(const pin_t pin) {
char buffer[20]; // for the sprintf statements
const struct pwm_pin_info_struct *info;
if (pin >= CORE_NUM_DIGITAL) return 0;
info = pwm_pin_info + pin;
if (pin >= CORE_NUM_DIGITAL) return false;
if (info->type == 0) return 0;
info = pwm_pin_info + pin;
if (info->type == 0) return false;
/* TODO decode pwm value from timers */
// for now just indicate if output is set as pwm
@ -151,4 +149,6 @@ bool HAL_pwm_status(int8_t pin) {
return (*(portConfigRegister(pin)) == info->muxval);
}
static void pwm_details(uint8_t pin) { /* TODO */ }
void pwm_details(const pin_t) { /* TODO */ }
void print_port(const pin_t) {}

View file

@ -55,7 +55,12 @@ static const char *UnwTabGetFunctionName(const UnwindCallbacks *cb, uint32_t add
return nullptr;
if ((flag_word & 0xFF000000) == 0xFF000000) {
return (const char *)(address - 4 - (flag_word & 0x00FFFFFF));
const uint32_t fn_name_addr = address - 4 - (flag_word & 0x00FFFFFF);
// Ensure the address is readable to avoid returning a bogus pointer
uint8_t dummy = 0;
if (cb->readB(fn_name_addr, &dummy))
return (const char *)fn_name_addr;
}
return nullptr;
}

View file

@ -277,8 +277,6 @@ void CommonHandler_C(ContextStateFrame * frame, unsigned long lr, unsigned long
if (!faulted_from_exception) { // Not sure about the non_usage_fault, we want to try anyway, don't we ? && !non_usage_fault_occurred)
// Try to resume to our handler here
CFSR |= CFSR; // The ARM programmer manual says you must write to 1 all fault bits to clear them so this instruction is correct
// The frame will not be valid when returning anymore, let's clean it
savedFrame.CFSR = 0;
frame->pc = (uint32_t)resume_from_fault; // Patch where to return to
frame->lr = 0xDEADBEEF; // If our handler returns (it shouldn't), let's make it trigger an exception immediately

View file

@ -0,0 +1,367 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 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
//
// Faux pins for Dependency Check
//
//
// STM32 Pin Names
//
#define PA0 0x10
#define PA1 0x11
#define PA2 0x12
#define PA3 0x13
#define PA4 0x14
#define PA5 0x15
#define PA6 0x16
#define PA7 0x17
#define PA8 0x18
#define PA9 0x19
#define PA10 0x1A
#define PA11 0x1B
#define PA12 0x1C
#define PA13 0x1D
#define PA14 0x1E
#define PA15 0x1F
#define PB0 0x20
#define PB1 0x21
#define PB2 0x22
#define PB3 0x23
#define PB4 0x24
#define PB5 0x25
#define PB6 0x26
#define PB7 0x27
#define PB8 0x28
#define PB9 0x29
#define PB10 0x2A
#define PB11 0x2B
#define PB12 0x2C
#define PB13 0x2D
#define PB14 0x2E
#define PB15 0x2F
#define PC0 0x30
#define PC1 0x31
#define PC2 0x32
#define PC3 0x33
#define PC4 0x34
#define PC5 0x35
#define PC6 0x36
#define PC7 0x37
#define PC8 0x38
#define PC9 0x39
#define PC10 0x3A
#define PC11 0x3B
#define PC12 0x3C
#define PC13 0x3D
#define PC14 0x3E
#define PC15 0x3F
#define PD0 0x40
#define PD1 0x41
#define PD2 0x42
#define PD3 0x43
#define PD4 0x44
#define PD5 0x45
#define PD6 0x46
#define PD7 0x47
#define PD8 0x48
#define PD9 0x49
#define PD10 0x4A
#define PD11 0x4B
#define PD12 0x4C
#define PD13 0x4D
#define PD14 0x4E
#define PD15 0x4F
#define PE0 0x50
#define PE1 0x51
#define PE2 0x52
#define PE3 0x53
#define PE4 0x54
#define PE5 0x55
#define PE6 0x56
#define PE7 0x57
#define PE8 0x58
#define PE9 0x59
#define PE10 0x5A
#define PE11 0x5B
#define PE12 0x5C
#define PE13 0x5D
#define PE14 0x5E
#define PE15 0x5F
#define PF0 0x60
#define PF1 0x61
#define PF2 0x62
#define PF3 0x63
#define PF4 0x64
#define PF5 0x65
#define PF6 0x66
#define PF7 0x67
#define PF8 0x68
#define PF9 0x69
#define PF10 0x6A
#define PF11 0x6B
#define PF12 0x6C
#define PF13 0x6D
#define PF14 0x6E
#define PF15 0x6F
#define PG0 0x70
#define PG1 0x71
#define PG2 0x72
#define PG3 0x73
#define PG4 0x74
#define PG5 0x75
#define PG6 0x76
#define PG7 0x77
#define PG8 0x78
#define PG9 0x79
#define PG10 0x7A
#define PG11 0x7B
#define PG12 0x7C
#define PG13 0x7D
#define PG14 0x7E
#define PG15 0x7F
#define PH0 0x80
#define PH1 0x81
#define PH2 0x82
#define PH3 0x83
#define PH4 0x84
#define PH5 0x85
#define PH6 0x86
#define PH7 0x87
#define PH8 0x88
#define PH9 0x89
#define PH10 0x8A
#define PH11 0x8B
#define PH12 0x8C
#define PH13 0x8D
#define PH14 0x8E
#define PH15 0x8F
#define PI0 0x90
#define PI1 0x91
#define PI2 0x92
#define PI3 0x93
#define PI4 0x94
#define PI5 0x95
#define PI6 0x96
#define PI7 0x97
#define PI8 0x98
#define PI9 0x99
#define PI10 0x9A
#define PI11 0x9B
#define PI12 0x9C
#define PI13 0x9D
#define PI14 0x9E
#define PI15 0x9F
#define PJ0 0xA0
#define PJ1 0xA1
#define PJ2 0xA2
#define PJ3 0xA3
#define PJ4 0xA4
#define PJ5 0xA5
#define PJ6 0xA6
#define PJ7 0xA7
#define PJ8 0xA8
#define PJ9 0xA9
#define PJ10 0xAA
#define PJ11 0xAB
#define PJ12 0xAC
#define PJ13 0xAD
#define PJ14 0xAE
#define PJ15 0xAF
//
// LPC Pin Names
//
#define P0_00 100
#define P0_01 101
#define P0_02 102
#define P0_03 103
#define P0_04 104
#define P0_05 105
#define P0_06 106
#define P0_07 107
#define P0_08 108
#define P0_09 109
#define P0_10 110
#define P0_11 111
#define P0_12 112
#define P0_13 113
#define P0_14 114
#define P0_15 115
#define P0_16 116
#define P0_17 117
#define P0_18 118
#define P0_19 119
#define P0_20 120
#define P0_21 121
#define P0_22 122
#define P0_23 123
#define P0_24 124
#define P0_25 125
#define P0_26 126
#define P0_27 127
#define P0_28 128
#define P0_29 129
#define P0_30 130
#define P0_31 131
#define P1_00 200
#define P1_01 201
#define P1_02 202
#define P1_03 203
#define P1_04 204
#define P1_05 205
#define P1_06 206
#define P1_07 207
#define P1_08 208
#define P1_09 209
#define P1_10 210
#define P1_11 211
#define P1_12 212
#define P1_13 213
#define P1_14 214
#define P1_15 215
#define P1_16 216
#define P1_17 217
#define P1_18 218
#define P1_19 219
#define P1_20 220
#define P1_21 221
#define P1_22 222
#define P1_23 223
#define P1_24 224
#define P1_25 225
#define P1_26 226
#define P1_27 227
#define P1_28 228
#define P1_29 229
#define P1_30 230
#define P1_31 231
#define P2_00 300
#define P2_01 301
#define P2_02 302
#define P2_03 303
#define P2_04 304
#define P2_05 305
#define P2_06 306
#define P2_07 307
#define P2_08 308
#define P2_09 309
#define P2_10 310
#define P2_11 311
#define P2_12 312
#define P2_13 313
#define P2_14 314
#define P2_15 315
#define P2_16 316
#define P2_17 317
#define P2_18 318
#define P2_19 319
#define P2_20 320
#define P2_21 321
#define P2_22 322
#define P2_23 323
#define P2_24 324
#define P2_25 325
#define P2_26 326
#define P2_27 327
#define P2_28 328
#define P2_29 329
#define P2_30 330
#define P2_31 331
#define P3_00 400
#define P3_01 401
#define P3_02 402
#define P3_03 403
#define P3_04 404
#define P3_05 405
#define P3_06 406
#define P3_07 407
#define P3_08 408
#define P3_09 409
#define P3_10 410
#define P3_11 411
#define P3_12 412
#define P3_13 413
#define P3_14 414
#define P3_15 415
#define P3_16 416
#define P3_17 417
#define P3_18 418
#define P3_19 419
#define P3_20 420
#define P3_21 421
#define P3_22 422
#define P3_23 423
#define P3_24 424
#define P3_25 425
#define P3_26 426
#define P3_27 427
#define P3_28 428
#define P3_29 429
#define P3_30 430
#define P3_31 431
#define P4_00 500
#define P4_01 501
#define P4_02 502
#define P4_03 503
#define P4_04 504
#define P4_05 505
#define P4_06 506
#define P4_07 507
#define P4_08 508
#define P4_09 509
#define P4_10 510
#define P4_11 511
#define P4_12 512
#define P4_13 513
#define P4_14 514
#define P4_15 515
#define P4_16 516
#define P4_17 517
#define P4_18 518
#define P4_19 519
#define P4_20 520
#define P4_21 521
#define P4_22 522
#define P4_23 523
#define P4_24 524
#define P4_25 525
#define P4_26 526
#define P4_27 527
#define P4_28 528
#define P4_29 529
#define P4_30 530
#define P4_31 531

View file

@ -60,8 +60,8 @@
ServoInfo_t servo_info[MAX_SERVOS]; // static array of servo info structures
uint8_t ServoCount = 0; // the total number of attached servos
#define SERVO_MIN(v) (MIN_PULSE_WIDTH - (v) * 4) // minimum value in uS for this servo
#define SERVO_MAX(v) (MAX_PULSE_WIDTH - (v) * 4) // maximum value in uS for this servo
#define SERVO_MIN_US(v) (MIN_PULSE_WIDTH - (v) * 4) // minimum value in uS for this servo
#define SERVO_MAX_US(v) (MAX_PULSE_WIDTH - (v) * 4) // maximum value in uS for this servo
/************ static functions common to all instances ***********************/
@ -117,7 +117,7 @@ void Servo::detach() {
void Servo::write(int value) {
if (value < MIN_PULSE_WIDTH) // treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds)
value = map(constrain(value, 0, 180), 0, 180, SERVO_MIN(min), SERVO_MAX(max));
value = map(constrain(value, 0, 180), 0, 180, SERVO_MIN_US(min), SERVO_MAX_US(max));
writeMicroseconds(value);
}
@ -126,8 +126,8 @@ void Servo::writeMicroseconds(int value) {
byte channel = servoIndex;
if (channel < MAX_SERVOS) { // ensure channel is valid
// ensure pulse width is valid
value = constrain(value, SERVO_MIN(min), SERVO_MAX(max)) - (TRIM_DURATION);
value = usToTicks(value); // convert to ticks after compensating for interrupt overhead - 12 Aug 2009
LIMIT(value, SERVO_MIN_US(min), SERVO_MAX_US(max));
value = usToTicks(value - (TRIM_DURATION)); // convert to ticks after compensating for interrupt overhead - 12 Aug 2009
CRITICAL_SECTION_START();
servo_info[channel].ticks = value;
@ -136,7 +136,7 @@ void Servo::writeMicroseconds(int value) {
}
// return the value as degrees
int Servo::read() { return map(readMicroseconds() + 1, SERVO_MIN(min), SERVO_MAX(max), 0, 180); }
int Servo::read() { return map(readMicroseconds() + 1, SERVO_MIN_US(min), SERVO_MAX_US(max), 0, 180); }
int Servo::readMicroseconds() {
return (servoIndex == INVALID_SERVO) ? 0 : ticksToUs(servo_info[servoIndex].ticks) + (TRIM_DURATION);