Distinguish between analog/digital auto fans (#13298)
This commit is contained in:
parent
2513f6b550
commit
2212da453a
27 changed files with 371 additions and 61 deletions
|
@ -24,9 +24,9 @@
|
|||
/**
|
||||
* Pin mapping for the 1280 and 2560
|
||||
*
|
||||
* 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 xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx
|
||||
* 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 72 75 76 77 74 xx xx xx xx xx
|
||||
*/
|
||||
|
||||
#include "fastio_AVR.h"
|
||||
|
@ -487,6 +487,9 @@
|
|||
#define DIO69_DDR DDRK
|
||||
#define DIO69_PWM NULL
|
||||
|
||||
//#define FASTIO_EXT_START 70
|
||||
//#define FASTIO_EXT_END 85
|
||||
|
||||
#define DIO70_PIN PING4
|
||||
#define DIO70_RPORT PING
|
||||
#define DIO70_WPORT PORTG
|
||||
|
|
238
Marlin/src/HAL/HAL_AVR/fastio_AVR.cpp
Normal file
238
Marlin/src/HAL/HAL_AVR/fastio_AVR.cpp
Normal file
|
@ -0,0 +1,238 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 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 <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* Fast I/O for extended pins
|
||||
*/
|
||||
|
||||
#ifdef __AVR__
|
||||
|
||||
#include "fastio_AVR.h"
|
||||
|
||||
#ifdef FASTIO_EXT_START
|
||||
|
||||
#include <Arduino.h>
|
||||
|
||||
#define _IS_EXT(P) WITHIN(P, FASTIO_EXT_START, FASTIO_EXT_END)
|
||||
|
||||
void extDigitalWrite(const int8_t pin, const uint8_t state) {
|
||||
#define _WCASE(N) case N: WRITE(N, state); break
|
||||
switch (pin) {
|
||||
default: digitalWrite(pin, state);
|
||||
#if _IS_EXT(70)
|
||||
_WCASE(70);
|
||||
#endif
|
||||
#if _IS_EXT(71)
|
||||
_WCASE(71);
|
||||
#endif
|
||||
#if _IS_EXT(72)
|
||||
_WCASE(72);
|
||||
#endif
|
||||
#if _IS_EXT(73)
|
||||
_WCASE(73);
|
||||
#endif
|
||||
#if _IS_EXT(74)
|
||||
_WCASE(74);
|
||||
#endif
|
||||
#if _IS_EXT(75)
|
||||
_WCASE(75);
|
||||
#endif
|
||||
#if _IS_EXT(76)
|
||||
_WCASE(76);
|
||||
#endif
|
||||
#if _IS_EXT(77)
|
||||
_WCASE(77);
|
||||
#endif
|
||||
#if _IS_EXT(78)
|
||||
_WCASE(78);
|
||||
#endif
|
||||
#if _IS_EXT(79)
|
||||
_WCASE(79);
|
||||
#endif
|
||||
#if _IS_EXT(80)
|
||||
_WCASE(80);
|
||||
#endif
|
||||
#if _IS_EXT(81)
|
||||
_WCASE(81);
|
||||
#endif
|
||||
#if _IS_EXT(82)
|
||||
_WCASE(82);
|
||||
#endif
|
||||
#if _IS_EXT(83)
|
||||
_WCASE(83);
|
||||
#endif
|
||||
#if _IS_EXT(84)
|
||||
_WCASE(84);
|
||||
#endif
|
||||
#if _IS_EXT(85)
|
||||
_WCASE(85);
|
||||
#endif
|
||||
#if _IS_EXT(86)
|
||||
_WCASE(86);
|
||||
#endif
|
||||
#if _IS_EXT(87)
|
||||
_WCASE(87);
|
||||
#endif
|
||||
#if _IS_EXT(88)
|
||||
_WCASE(88);
|
||||
#endif
|
||||
#if _IS_EXT(89)
|
||||
_WCASE(89);
|
||||
#endif
|
||||
#if _IS_EXT(90)
|
||||
_WCASE(90);
|
||||
#endif
|
||||
#if _IS_EXT(91)
|
||||
_WCASE(91);
|
||||
#endif
|
||||
#if _IS_EXT(92)
|
||||
_WCASE(92);
|
||||
#endif
|
||||
#if _IS_EXT(93)
|
||||
_WCASE(93);
|
||||
#endif
|
||||
#if _IS_EXT(94)
|
||||
_WCASE(94);
|
||||
#endif
|
||||
#if _IS_EXT(95)
|
||||
_WCASE(95);
|
||||
#endif
|
||||
#if _IS_EXT(96)
|
||||
_WCASE(96);
|
||||
#endif
|
||||
#if _IS_EXT(97)
|
||||
_WCASE(97);
|
||||
#endif
|
||||
#if _IS_EXT(98)
|
||||
_WCASE(98);
|
||||
#endif
|
||||
#if _IS_EXT(99)
|
||||
_WCASE(99);
|
||||
#endif
|
||||
#if _IS_EXT(100)
|
||||
_WCASE(100);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t extDigitalRead(const int8_t pin) {
|
||||
#define _RCASE(N) case N: return READ(N)
|
||||
switch (pin) {
|
||||
default: return digitalRead(pin);
|
||||
#if _IS_EXT(70)
|
||||
_RCASE(70);
|
||||
#endif
|
||||
#if _IS_EXT(71)
|
||||
_RCASE(71);
|
||||
#endif
|
||||
#if _IS_EXT(72)
|
||||
_RCASE(72);
|
||||
#endif
|
||||
#if _IS_EXT(73)
|
||||
_RCASE(73);
|
||||
#endif
|
||||
#if _IS_EXT(74)
|
||||
_RCASE(74);
|
||||
#endif
|
||||
#if _IS_EXT(75)
|
||||
_RCASE(75);
|
||||
#endif
|
||||
#if _IS_EXT(76)
|
||||
_RCASE(76);
|
||||
#endif
|
||||
#if _IS_EXT(77)
|
||||
_RCASE(77);
|
||||
#endif
|
||||
#if _IS_EXT(78)
|
||||
_RCASE(78);
|
||||
#endif
|
||||
#if _IS_EXT(79)
|
||||
_RCASE(79);
|
||||
#endif
|
||||
#if _IS_EXT(80)
|
||||
_RCASE(80);
|
||||
#endif
|
||||
#if _IS_EXT(81)
|
||||
_RCASE(81);
|
||||
#endif
|
||||
#if _IS_EXT(82)
|
||||
_RCASE(82);
|
||||
#endif
|
||||
#if _IS_EXT(83)
|
||||
_RCASE(83);
|
||||
#endif
|
||||
#if _IS_EXT(84)
|
||||
_RCASE(84);
|
||||
#endif
|
||||
#if _IS_EXT(85)
|
||||
_RCASE(85);
|
||||
#endif
|
||||
#if _IS_EXT(86)
|
||||
_RCASE(86);
|
||||
#endif
|
||||
#if _IS_EXT(87)
|
||||
_RCASE(87);
|
||||
#endif
|
||||
#if _IS_EXT(88)
|
||||
_RCASE(88);
|
||||
#endif
|
||||
#if _IS_EXT(89)
|
||||
_RCASE(89);
|
||||
#endif
|
||||
#if _IS_EXT(90)
|
||||
_RCASE(90);
|
||||
#endif
|
||||
#if _IS_EXT(91)
|
||||
_RCASE(91);
|
||||
#endif
|
||||
#if _IS_EXT(92)
|
||||
_RCASE(92);
|
||||
#endif
|
||||
#if _IS_EXT(93)
|
||||
_RCASE(93);
|
||||
#endif
|
||||
#if _IS_EXT(94)
|
||||
_RCASE(94);
|
||||
#endif
|
||||
#if _IS_EXT(95)
|
||||
_RCASE(95);
|
||||
#endif
|
||||
#if _IS_EXT(96)
|
||||
_RCASE(96);
|
||||
#endif
|
||||
#if _IS_EXT(97)
|
||||
_RCASE(97);
|
||||
#endif
|
||||
#if _IS_EXT(98)
|
||||
_RCASE(98);
|
||||
#endif
|
||||
#if _IS_EXT(99)
|
||||
_RCASE(99);
|
||||
#endif
|
||||
#if _IS_EXT(100)
|
||||
_RCASE(100);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
#endif // FASTIO_EXT_START
|
||||
#endif // __AVR__
|
|
@ -85,6 +85,15 @@
|
|||
#define _GET_OUTPUT(IO) TEST(DIO ## IO ## _DDR, DIO ## IO ## _PIN)
|
||||
#define _GET_TIMER(IO) DIO ## IO ## _PWM
|
||||
|
||||
// digitalRead/Write wrappers
|
||||
#ifdef FASTIO_EXT_START
|
||||
void extDigitalWrite(const int8_t pin, const uint8_t state);
|
||||
uint8_t extDigitalRead(const int8_t pin);
|
||||
#else
|
||||
#define extDigitalWrite(IO,V) digitalWrite(IO,V)
|
||||
#define extDigitalRead(IO) digitalRead(IO)
|
||||
#endif
|
||||
|
||||
#define READ(IO) _READ(IO)
|
||||
#define WRITE(IO,V) _WRITE(IO,V)
|
||||
#define TOGGLE(IO) _TOGGLE(IO)
|
||||
|
|
|
@ -105,7 +105,7 @@ const uint8_t PROGMEM digital_pin_to_port_PGM[] = {
|
|||
|
||||
// digitalPinToBitMask(pin) is OK
|
||||
|
||||
#define digitalRead_mod(p) digitalRead(p) // Teensyduino's version of digitalRead doesn't
|
||||
// disable the PWMs so we can use it as is
|
||||
#define digitalRead_mod(p) extDigitalRead(p) // Teensyduino's version of digitalRead doesn't
|
||||
// disable the PWMs so we can use it as is
|
||||
|
||||
// portModeRegister(pin) is OK
|
||||
|
|
|
@ -73,14 +73,14 @@ static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t
|
|||
*TCNTn = 0; // channel set to -1 indicated that refresh interval completed so reset the timer
|
||||
else {
|
||||
if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && SERVO(timer, Channel[timer]).Pin.isActive)
|
||||
digitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, LOW); // pulse this channel low if activated
|
||||
extDigitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, LOW); // pulse this channel low if activated
|
||||
}
|
||||
|
||||
Channel[timer]++; // increment to the next channel
|
||||
if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) {
|
||||
*OCRnA = *TCNTn + SERVO(timer, Channel[timer]).ticks;
|
||||
if (SERVO(timer, Channel[timer]).Pin.isActive) // check if activated
|
||||
digitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, HIGH); // it's an active channel so pulse it high
|
||||
extDigitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, HIGH); // it's an active channel so pulse it high
|
||||
}
|
||||
else {
|
||||
// finished all channels so wait for the refresh period to expire before starting over
|
||||
|
|
|
@ -77,13 +77,13 @@ void Servo_Handler(timer16_Sequence_t timer, Tc *tc, uint8_t channel) {
|
|||
if (Channel[timer] < 0)
|
||||
tc->TC_CHANNEL[channel].TC_CCR |= TC_CCR_SWTRG; // channel set to -1 indicated that refresh interval completed so reset the timer
|
||||
else if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && SERVO(timer, Channel[timer]).Pin.isActive)
|
||||
digitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, LOW); // pulse this channel low if activated
|
||||
extDigitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, LOW); // pulse this channel low if activated
|
||||
|
||||
Channel[timer]++; // increment to the next channel
|
||||
if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) {
|
||||
tc->TC_CHANNEL[channel].TC_RA = tc->TC_CHANNEL[channel].TC_CV + SERVO(timer,Channel[timer]).ticks;
|
||||
if (SERVO(timer,Channel[timer]).Pin.isActive) // check if activated
|
||||
digitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, HIGH); // its an active channel so pulse it high
|
||||
extDigitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, HIGH); // its an active channel so pulse it high
|
||||
}
|
||||
else {
|
||||
// finished all channels so wait for the refresh period to expire before starting over
|
||||
|
|
|
@ -42,7 +42,7 @@ void tone(const pin_t _pin, const unsigned int frequency, const unsigned long du
|
|||
|
||||
void noTone(const pin_t _pin) {
|
||||
HAL_timer_disable_interrupt(TONE_TIMER_NUM);
|
||||
digitalWrite(_pin, LOW);
|
||||
extDigitalWrite(_pin, LOW);
|
||||
}
|
||||
|
||||
HAL_TONE_TIMER_ISR {
|
||||
|
@ -51,7 +51,7 @@ HAL_TONE_TIMER_ISR {
|
|||
|
||||
if (toggles) {
|
||||
toggles--;
|
||||
digitalWrite(tone_pin, (pin_state ^= 1));
|
||||
extDigitalWrite(tone_pin, (pin_state ^= 1));
|
||||
}
|
||||
else noTone(tone_pin); // turn off interrupt
|
||||
}
|
||||
|
|
|
@ -81,8 +81,6 @@
|
|||
// Toggle a pin
|
||||
#define _TOGGLE(IO) _WRITE(IO, !READ(IO))
|
||||
|
||||
#include <pins_arduino.h>
|
||||
|
||||
#if MB(PRINTRBOARD_G2)
|
||||
|
||||
#include "G2_pins.h"
|
||||
|
@ -185,6 +183,10 @@
|
|||
// Shorthand
|
||||
#define OUT_WRITE(IO,V) { SET_OUTPUT(IO); WRITE(IO,V); }
|
||||
|
||||
// digitalRead/Write wrappers
|
||||
#define extDigitalRead(IO) digitalRead(IO)
|
||||
#define extDigitalWrite(IO,V) digitalWrite(IO,V)
|
||||
|
||||
/**
|
||||
* Ports and functions
|
||||
* Added as necessary or if I feel like it- not a comprehensive list!
|
||||
|
|
|
@ -63,7 +63,7 @@
|
|||
|
||||
#define NUMBER_PINS_TOTAL PINS_COUNT
|
||||
|
||||
#define digitalRead_mod(p) digitalRead(p) // AVR digitalRead disabled PWM before it read the pin
|
||||
#define digitalRead_mod(p) extDigitalRead(p) // AVR digitalRead disabled PWM before it read the pin
|
||||
#define PRINT_PORT(p)
|
||||
#define NAME_FORMAT(p) PSTR("%-##p##s")
|
||||
#define PRINT_ARRAY_NAME(x) do {sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer);} while (0)
|
||||
|
|
|
@ -53,6 +53,10 @@
|
|||
|
||||
#define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
|
||||
|
||||
// digitalRead/Write wrappers
|
||||
#define extDigitalRead(IO) digitalRead(IO)
|
||||
#define extDigitalWrite(IO,V) digitalWrite(IO,V)
|
||||
|
||||
//
|
||||
// Ports and functions
|
||||
//
|
||||
|
|
|
@ -121,3 +121,7 @@
|
|||
|
||||
// Shorthand
|
||||
#define OUT_WRITE(IO,V) do{ SET_OUTPUT(IO); WRITE(IO,V); }while(0)
|
||||
|
||||
// digitalRead/Write wrappers
|
||||
#define extDigitalRead(IO) digitalRead(IO)
|
||||
#define extDigitalWrite(IO,V) digitalWrite(IO,V)
|
||||
|
|
|
@ -121,3 +121,7 @@
|
|||
|
||||
// Shorthand
|
||||
#define OUT_WRITE(IO,V) do{ SET_OUTPUT(IO); WRITE(IO,V); }while(0)
|
||||
|
||||
// digitalRead/Write wrappers
|
||||
#define extDigitalRead(IO) digitalRead(IO)
|
||||
#define extDigitalWrite(IO,V) digitalWrite(IO,V)
|
||||
|
|
|
@ -32,7 +32,7 @@
|
|||
#define pwm_details(pin) pin = pin // do nothing // print PWM details
|
||||
#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 digitalRead_mod(p) extDigitalRead(p)
|
||||
#define PRINT_PORT(p)
|
||||
#define GET_ARRAY_PIN(p) pin_array[p].pin
|
||||
#define NAME_FORMAT(p) PSTR("%-##p##s")
|
||||
|
|
|
@ -79,3 +79,7 @@ void FastIO_init(); // Must be called before using fast io macros
|
|||
|
||||
#define PWM_PIN(p) digitalPinHasPWM(p)
|
||||
#define USEABLE_HARDWARE_PWM(p) PWM_PIN(p)
|
||||
|
||||
// digitalRead/Write wrappers
|
||||
#define extDigitalRead(IO) digitalRead(IO)
|
||||
#define extDigitalWrite(IO,V) digitalWrite(IO,V)
|
||||
|
|
|
@ -50,3 +50,7 @@
|
|||
|
||||
#define PWM_PIN(p) true
|
||||
#define USEABLE_HARDWARE_PWM(p) PWM_PIN(p)
|
||||
|
||||
// digitalRead/Write wrappers
|
||||
#define extDigitalRead(IO) digitalRead(IO)
|
||||
#define extDigitalWrite(IO,V) digitalWrite(IO,V)
|
||||
|
|
|
@ -54,6 +54,10 @@
|
|||
#define PWM_PIN(p) true
|
||||
#define USEABLE_HARDWARE_PWM(p) PWM_PIN(p)
|
||||
|
||||
// digitalRead/Write wrappers
|
||||
#define extDigitalRead(IO) digitalRead(IO)
|
||||
#define extDigitalWrite(IO,V) digitalWrite(IO,V)
|
||||
|
||||
//
|
||||
// Pins Definitions
|
||||
//
|
||||
|
|
|
@ -191,9 +191,9 @@ void TMC26XStepper::start() {
|
|||
pinMode(dir_pin, OUTPUT);
|
||||
pinMode(cs_pin, OUTPUT);
|
||||
//SET_OUTPUT(STEPPER_ENABLE_PIN);
|
||||
digitalWrite(step_pin, LOW);
|
||||
digitalWrite(dir_pin, LOW);
|
||||
digitalWrite(cs_pin, HIGH);
|
||||
extDigitalWrite(step_pin, LOW);
|
||||
extDigitalWrite(dir_pin, LOW);
|
||||
extDigitalWrite(cs_pin, HIGH);
|
||||
|
||||
STEPPER_SPI.begin();
|
||||
STEPPER_SPI.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE3));
|
||||
|
@ -261,10 +261,10 @@ char TMC26XStepper::move(void) {
|
|||
// increment or decrement the step number,
|
||||
// depending on direction:
|
||||
if (this->direction == 1)
|
||||
digitalWrite(step_pin, HIGH);
|
||||
extDigitalWrite(step_pin, HIGH);
|
||||
else {
|
||||
digitalWrite(dir_pin, HIGH);
|
||||
digitalWrite(step_pin, HIGH);
|
||||
extDigitalWrite(dir_pin, HIGH);
|
||||
extDigitalWrite(step_pin, HIGH);
|
||||
}
|
||||
// get the timeStamp of when you stepped:
|
||||
this->last_step_time = time;
|
||||
|
@ -272,8 +272,8 @@ char TMC26XStepper::move(void) {
|
|||
// decrement the steps left:
|
||||
steps_left--;
|
||||
//disable the step & dir pins
|
||||
digitalWrite(step_pin, LOW);
|
||||
digitalWrite(dir_pin, LOW);
|
||||
extDigitalWrite(step_pin, LOW);
|
||||
extDigitalWrite(dir_pin, LOW);
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
@ -864,7 +864,7 @@ inline void TMC26XStepper::send262(uint32_t datagram) {
|
|||
//}
|
||||
|
||||
//select the TMC driver
|
||||
digitalWrite(cs_pin, LOW);
|
||||
extDigitalWrite(cs_pin, LOW);
|
||||
|
||||
//ensure that only valid bist are set (0-19)
|
||||
//datagram &=REGISTER_BIT_PATTERN;
|
||||
|
@ -893,7 +893,7 @@ inline void TMC26XStepper::send262(uint32_t datagram) {
|
|||
#endif
|
||||
|
||||
//deselect the TMC chip
|
||||
digitalWrite(cs_pin, HIGH);
|
||||
extDigitalWrite(cs_pin, HIGH);
|
||||
|
||||
//restore the previous SPI mode if neccessary
|
||||
//if the mode is not correct set it to mode 3
|
||||
|
|
|
@ -53,6 +53,10 @@
|
|||
#define PWM_PIN(p) true
|
||||
#define USEABLE_HARDWARE_PWM(p) PWM_PIN(p)
|
||||
|
||||
// digitalRead/Write wrappers
|
||||
#define extDigitalRead(IO) digitalRead(IO)
|
||||
#define extDigitalWrite(IO,V) digitalWrite(IO,V)
|
||||
|
||||
//
|
||||
// Pins Definitions
|
||||
//
|
||||
|
|
|
@ -85,6 +85,10 @@
|
|||
|
||||
#define OUT_WRITE(IO,V) do{ SET_OUTPUT(IO); WRITE(IO,V); }while(0)
|
||||
|
||||
// digitalRead/Write wrappers
|
||||
#define extDigitalRead(IO) digitalRead(IO)
|
||||
#define extDigitalWrite(IO,V) digitalWrite(IO,V)
|
||||
|
||||
/**
|
||||
* Ports, functions, and pins
|
||||
*/
|
||||
|
|
|
@ -84,6 +84,10 @@
|
|||
|
||||
#define OUT_WRITE(IO,V) do{ SET_OUTPUT(IO); WRITE(IO,V); }while(0)
|
||||
|
||||
// digitalRead/Write wrappers
|
||||
#define extDigitalRead(IO) digitalRead(IO)
|
||||
#define extDigitalWrite(IO,V) digitalWrite(IO,V)
|
||||
|
||||
/**
|
||||
* Ports, functions, and pins
|
||||
*/
|
||||
|
|
|
@ -83,7 +83,7 @@ uint8_t L6470_transfer(uint8_t data, int16_t ss_pin, const uint8_t chain_positio
|
|||
uint8_t data_out = 0;
|
||||
|
||||
// first device in chain has data sent last
|
||||
digitalWrite(ss_pin, LOW);
|
||||
extDigitalWrite(ss_pin, LOW);
|
||||
|
||||
for (uint8_t i = L6470::chain[0]; (i >= 1) && !spi_abort; i--) { // stop sending data if spi_abort is active
|
||||
DISABLE_ISRS(); // disable interrupts during SPI transfer (can't allow partial command to chips)
|
||||
|
@ -92,7 +92,7 @@ uint8_t L6470_transfer(uint8_t data, int16_t ss_pin, const uint8_t chain_positio
|
|||
if (i == chain_position) data_out = temp;
|
||||
}
|
||||
|
||||
digitalWrite(ss_pin, HIGH);
|
||||
extDigitalWrite(ss_pin, HIGH);
|
||||
return data_out;
|
||||
}
|
||||
|
||||
|
|
|
@ -77,9 +77,9 @@ inline void toggle_pins() {
|
|||
{
|
||||
pinMode(pin, OUTPUT);
|
||||
for (int16_t j = 0; j < repeat; j++) {
|
||||
digitalWrite(pin, 0); safe_delay(wait);
|
||||
digitalWrite(pin, 1); safe_delay(wait);
|
||||
digitalWrite(pin, 0); safe_delay(wait);
|
||||
extDigitalWrite(pin, 0); safe_delay(wait);
|
||||
extDigitalWrite(pin, 1); safe_delay(wait);
|
||||
extDigitalWrite(pin, 0); safe_delay(wait);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -285,7 +285,7 @@ void GcodeSuite::M43() {
|
|||
pin_state[pin - first_pin] = analogRead(DIGITAL_PIN_TO_ANALOG_PIN(pin)); // int16_t pin_state[...]
|
||||
else
|
||||
//*/
|
||||
pin_state[i - first_pin] = digitalRead(pin);
|
||||
pin_state[i - first_pin] = extDigitalRead(pin);
|
||||
}
|
||||
|
||||
#if HAS_RESUME_CONTINUE
|
||||
|
@ -307,7 +307,7 @@ void GcodeSuite::M43() {
|
|||
? analogRead(DIGITAL_PIN_TO_ANALOG_PIN(pin)) : // int16_t val
|
||||
:
|
||||
//*/
|
||||
digitalRead(pin);
|
||||
extDigitalRead(pin);
|
||||
if (val != pin_state[i - first_pin]) {
|
||||
report_pin_state_extended(pin, ignore_protection, false);
|
||||
pin_state[i - first_pin] = val;
|
||||
|
|
|
@ -43,9 +43,9 @@ void GcodeSuite::M226() {
|
|||
switch (pin_state) {
|
||||
case 1: target = HIGH; break;
|
||||
case 0: target = LOW; break;
|
||||
case -1: target = !digitalRead(pin); break;
|
||||
case -1: target = !extDigitalRead(pin); break;
|
||||
}
|
||||
while (digitalRead(pin) != target) idle();
|
||||
while (extDigitalRead(pin) != target) idle();
|
||||
}
|
||||
} // pin_state -1 0 1 && pin > -1
|
||||
} // parser.seen('P')
|
||||
|
|
|
@ -50,7 +50,7 @@ void GcodeSuite::M42() {
|
|||
if (!parser.boolval('I') && pin_is_protected(pin)) return protected_pin_err();
|
||||
|
||||
pinMode(pin, OUTPUT);
|
||||
digitalWrite(pin, pin_status);
|
||||
extDigitalWrite(pin, pin_status);
|
||||
analogWrite(pin, pin_status);
|
||||
|
||||
#if FAN_COUNT > 0
|
||||
|
|
|
@ -453,7 +453,7 @@ void _O2 Endstops::M119() {
|
|||
}
|
||||
SERIAL_ECHOPGM(MSG_FILAMENT_RUNOUT_SENSOR);
|
||||
if (i > 1) { SERIAL_CHAR(' '); SERIAL_CHAR('0' + i); }
|
||||
print_es_state(digitalRead(pin) != FIL_RUNOUT_INVERTING);
|
||||
print_es_state(extDigitalRead(pin) != FIL_RUNOUT_INVERTING);
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
|
|
@ -632,15 +632,16 @@ int Temperature::getHeaterPower(const int heater) {
|
|||
#if HAS_AUTO_FAN
|
||||
|
||||
void Temperature::checkExtruderAutoFans() {
|
||||
static const pin_t fanPin[] PROGMEM = { E0_AUTO_FAN_PIN, E1_AUTO_FAN_PIN, E2_AUTO_FAN_PIN, E3_AUTO_FAN_PIN, E4_AUTO_FAN_PIN, E5_AUTO_FAN_PIN, CHAMBER_AUTO_FAN_PIN };
|
||||
static const uint8_t fanBit[] PROGMEM = {
|
||||
0,
|
||||
AUTO_1_IS_0 ? 0 : 1,
|
||||
AUTO_2_IS_0 ? 0 : AUTO_2_IS_1 ? 1 : 2,
|
||||
AUTO_3_IS_0 ? 0 : AUTO_3_IS_1 ? 1 : AUTO_3_IS_2 ? 2 : 3,
|
||||
AUTO_4_IS_0 ? 0 : AUTO_4_IS_1 ? 1 : AUTO_4_IS_2 ? 2 : AUTO_4_IS_3 ? 3 : 4,
|
||||
AUTO_5_IS_0 ? 0 : AUTO_5_IS_1 ? 1 : AUTO_5_IS_2 ? 2 : AUTO_5_IS_3 ? 3 : AUTO_5_IS_4 ? 4 : 5,
|
||||
AUTO_CHAMBER_IS_0 ? 0 : AUTO_CHAMBER_IS_1 ? 1 : AUTO_CHAMBER_IS_2 ? 2 : AUTO_CHAMBER_IS_3 ? 3 : AUTO_CHAMBER_IS_4 ? 4 : 5
|
||||
AUTO_4_IS_0 ? 0 : AUTO_4_IS_1 ? 1 : AUTO_4_IS_2 ? 2 : AUTO_4_IS_3 ? 3 : 4,
|
||||
AUTO_5_IS_0 ? 0 : AUTO_5_IS_1 ? 1 : AUTO_5_IS_2 ? 2 : AUTO_5_IS_3 ? 3 : AUTO_5_IS_4 ? 4 : 5
|
||||
#if HAS_TEMP_CHAMBER
|
||||
, AUTO_CHAMBER_IS_0 ? 0 : AUTO_CHAMBER_IS_1 ? 1 : AUTO_CHAMBER_IS_2 ? 2 : AUTO_CHAMBER_IS_3 ? 3 : AUTO_CHAMBER_IS_4 ? 4 : AUTO_CHAMBER_IS_5 ? 5 : 6
|
||||
#endif
|
||||
};
|
||||
uint8_t fanState = 0;
|
||||
|
||||
|
@ -650,29 +651,50 @@ int Temperature::getHeaterPower(const int heater) {
|
|||
|
||||
#if HAS_TEMP_CHAMBER
|
||||
if (current_temperature_chamber > EXTRUDER_AUTO_FAN_TEMPERATURE)
|
||||
SBI(fanState, pgm_read_byte(&fanBit[5]));
|
||||
SBI(fanState, pgm_read_byte(&fanBit[6]));
|
||||
#endif
|
||||
|
||||
#define _UPDATE_AUTO_FAN(P,D,A) do{ \
|
||||
if (USEABLE_HARDWARE_PWM(P##_AUTO_FAN_PIN)) \
|
||||
analogWrite(P##_AUTO_FAN_PIN, A); \
|
||||
else \
|
||||
WRITE(P##_AUTO_FAN_PIN, D); \
|
||||
}while(0)
|
||||
|
||||
uint8_t fanDone = 0;
|
||||
for (uint8_t f = 0; f < COUNT(fanPin); f++) {
|
||||
const pin_t pin =
|
||||
#ifdef ARDUINO
|
||||
pgm_read_byte(&fanPin[f])
|
||||
#else
|
||||
fanPin[f]
|
||||
#endif
|
||||
;
|
||||
for (uint8_t f = 0; f < COUNT(fanBit); f++) {
|
||||
const uint8_t bit = pgm_read_byte(&fanBit[f]);
|
||||
if (pin >= 0 && !TEST(fanDone, bit)) {
|
||||
uint8_t newFanSpeed = TEST(fanState, bit) ? EXTRUDER_AUTO_FAN_SPEED : 0;
|
||||
#if ENABLED(AUTO_POWER_E_FANS)
|
||||
autofan_speed[f] = newFanSpeed;
|
||||
if (TEST(fanDone, bit)) continue;
|
||||
const bool fan_on = TEST(fanState, bit);
|
||||
const uint8_t speed = fan_on ? EXTRUDER_AUTO_FAN_SPEED : 0;
|
||||
#if ENABLED(AUTO_POWER_E_FANS)
|
||||
autofan_speed[f] = speed;
|
||||
#endif
|
||||
switch (f) {
|
||||
#if HAS_AUTO_FAN_0
|
||||
case 0: _UPDATE_AUTO_FAN(E0, fan_on, speed); break;
|
||||
#endif
|
||||
#if HAS_AUTO_FAN_1
|
||||
case 1: _UPDATE_AUTO_FAN(E1, fan_on, speed); break;
|
||||
#endif
|
||||
#if HAS_AUTO_FAN_2
|
||||
case 2: _UPDATE_AUTO_FAN(E2, fan_on, speed); break;
|
||||
#endif
|
||||
#if HAS_AUTO_FAN_3
|
||||
case 3: _UPDATE_AUTO_FAN(E3, fan_on, speed); break;
|
||||
#endif
|
||||
#if HAS_AUTO_FAN_4
|
||||
case 4: _UPDATE_AUTO_FAN(E4, fan_on, speed); break;
|
||||
#endif
|
||||
#if HAS_AUTO_FAN_5
|
||||
case 5: _UPDATE_AUTO_FAN(E5, fan_on, speed); break;
|
||||
#endif
|
||||
#if HAS_AUTO_CHAMBER_FAN
|
||||
case 6: _UPDATE_AUTO_FAN(CHAMBER, fan_on, speed); break;
|
||||
#endif
|
||||
// this idiom allows both digital and PWM fan outputs (see M42 handling).
|
||||
digitalWrite(pin, newFanSpeed);
|
||||
analogWrite(pin, newFanSpeed);
|
||||
SBI(fanDone, bit);
|
||||
}
|
||||
SBI(fanDone, bit);
|
||||
UNUSED(fan_on); UNUSED(speed);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -156,13 +156,13 @@ uint32_t Sd2Card::cardSize() {
|
|||
}
|
||||
|
||||
void Sd2Card::chipDeselect() {
|
||||
digitalWrite(chipSelectPin_, HIGH);
|
||||
extDigitalWrite(chipSelectPin_, HIGH);
|
||||
spiSend(0xFF); // Ensure MISO goes high impedance
|
||||
}
|
||||
|
||||
void Sd2Card::chipSelect() {
|
||||
spiInit(spiRate_);
|
||||
digitalWrite(chipSelectPin_, LOW);
|
||||
extDigitalWrite(chipSelectPin_, LOW);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -241,8 +241,8 @@ bool Sd2Card::init(const uint8_t sckRateID/*=0*/, const pin_t chipSelectPin/*=SD
|
|||
#endif
|
||||
|
||||
// Set pin modes
|
||||
digitalWrite(chipSelectPin_, HIGH); // For some CPUs pinMode can write the wrong data so init desired data value first
|
||||
pinMode(chipSelectPin_, OUTPUT); // Solution for #8746 by @benlye
|
||||
extDigitalWrite(chipSelectPin_, HIGH); // For some CPUs pinMode can write the wrong data so init desired data value first
|
||||
pinMode(chipSelectPin_, OUTPUT); // Solution for #8746 by @benlye
|
||||
spiBegin();
|
||||
|
||||
// Set SCK rate for initialization commands
|
||||
|
|
Loading…
Reference in a new issue