Преглед на файлове

Make LPC1768 pinmapping not specific to Re-ARM (#8063)

* Merging early because of build failures.  See #8105

* Make LPC1768 pinmapping not specific to Re-ARM

* Add HAL_PIN_TYPE and LPC1768 pin features

* M43 Updates

* Move pin map into pinsDebug_LPC1768.h

* Incorporate comments and M226

* Fix persistent store compilation issues

* Update pin features

* Update MKS SBASE pins

* Use native LPC1768 pin numbers in M42, M43, and M226
Thomas Moore преди 6 години
родител
ревизия
9e699811d2
променени са 49 файла, в които са добавени 1177 реда и са изтрити 1339 реда
  1. 1
    0
      .gitignore
  2. 9
    1
      Marlin/src/HAL/HAL_AVR/HAL_AVR.h
  3. 2
    2
      Marlin/src/HAL/HAL_AVR/HAL_pinsDebug_AVR.h
  4. 1
    1
      Marlin/src/HAL/HAL_AVR/pinsDebug_AVR_8_bit.h
  5. 4
    0
      Marlin/src/HAL/HAL_DUE/HAL_Due.h
  6. 2
    2
      Marlin/src/HAL/HAL_DUE/HAL_timers_Due.h
  7. 15
    12
      Marlin/src/HAL/HAL_LPC1768/HAL.cpp
  8. 4
    4
      Marlin/src/HAL/HAL_LPC1768/HAL_timers.h
  9. 509
    0
      Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.cpp
  10. 8
    444
      Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.h
  11. 1
    4
      Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.cpp
  12. 2
    3
      Marlin/src/HAL/HAL_LPC1768/SoftwareSerial.cpp
  13. 4
    4
      Marlin/src/HAL/HAL_LPC1768/WInterrupts.cpp
  14. 18
    21
      Marlin/src/HAL/HAL_LPC1768/arduino.cpp
  15. 6
    6
      Marlin/src/HAL/HAL_LPC1768/fastio.h
  16. 1
    1
      Marlin/src/HAL/HAL_LPC1768/include/Wire.h
  17. 8
    5
      Marlin/src/HAL/HAL_LPC1768/include/arduino.h
  18. 1
    1
      Marlin/src/HAL/HAL_LPC1768/include/digipot_mcp4451_I2C_routines.c
  19. 1
    2
      Marlin/src/HAL/HAL_LPC1768/lpc1768_flag_script.py
  20. 0
    1
      Marlin/src/HAL/HAL_LPC1768/main.cpp
  21. 4
    3
      Marlin/src/HAL/HAL_LPC1768/persistent_store_impl.cpp
  22. 0
    464
      Marlin/src/HAL/HAL_LPC1768/pinmap_re_arm.h
  23. 50
    0
      Marlin/src/HAL/HAL_LPC1768/pinmapping.cpp
  24. 187
    5
      Marlin/src/HAL/HAL_LPC1768/pinmapping.h
  25. 33
    31
      Marlin/src/HAL/HAL_LPC1768/pinsDebug_LPC1768.h
  26. 5
    5
      Marlin/src/HAL/HAL_LPC1768/spi_pins.h
  27. 6
    0
      Marlin/src/HAL/HAL_STM32F1/HAL_Stm32f1.h
  28. 5
    5
      Marlin/src/HAL/HAL_STM32F1/HAL_timers_Stm32f1.h
  29. 6
    0
      Marlin/src/HAL/HAL_TEENSY35_36/HAL_Teensy.h
  30. 2
    2
      Marlin/src/HAL/HAL_TEENSY35_36/HAL_timers_Teensy.h
  31. 1
    1
      Marlin/src/HAL/HAL_pinsDebug.h
  32. 7
    4
      Marlin/src/Marlin.cpp
  33. 1
    1
      Marlin/src/Marlin.h
  34. 1
    0
      Marlin/src/core/serial.cpp
  35. 0
    1
      Marlin/src/core/serial.h
  36. 15
    10
      Marlin/src/gcode/config/M43.cpp
  37. 7
    6
      Marlin/src/gcode/control/M226.cpp
  38. 7
    6
      Marlin/src/gcode/control/M42.cpp
  39. 10
    9
      Marlin/src/gcode/parser.h
  40. 11
    11
      Marlin/src/module/stepper.cpp
  41. 5
    5
      Marlin/src/module/stepper.h
  42. 7
    2
      Marlin/src/pins/pins.h
  43. 6
    5
      Marlin/src/pins/pinsDebug.h
  44. 78
    81
      Marlin/src/pins/pins_MKS_SBASE.h
  45. 1
    1
      Marlin/src/pins/pins_RAMPS.h
  46. 118
    160
      Marlin/src/pins/pins_RAMPS_RE_ARM.h
  47. 1
    1
      Marlin/src/sd/Sd2Card.cpp
  48. 2
    2
      Marlin/src/sd/Sd2Card.h
  49. 4
    4
      platformio.ini

+ 1
- 0
.gitignore Целия файл

@@ -158,6 +158,7 @@ vc-fileutils.settings
158 158
 
159 159
 #Visual Studio Code
160 160
 .vscode
161
+.vscode/c_cpp_properties.json
161 162
 
162 163
 #cmake
163 164
 CMakeLists.txt

+ 9
- 1
Marlin/src/HAL/HAL_AVR/HAL_AVR.h Целия файл

@@ -66,9 +66,11 @@
66 66
 // Types
67 67
 // --------------------------------------------------------------------------
68 68
 
69
-#define HAL_TIMER_TYPE uint16_t
69
+typedef uint16_t timer_t;
70 70
 #define HAL_TIMER_TYPE_MAX 0xFFFF
71 71
 
72
+typedef int8_t pin_t;
73
+
72 74
 #define HAL_SERVO_LIB Servo
73 75
 
74 76
 // --------------------------------------------------------------------------
@@ -153,4 +155,10 @@ inline void HAL_adc_init(void) {
153 155
 
154 156
 #define HAL_READ_ADC ADC
155 157
 
158
+#define GET_PIN_MAP_PIN(index) index
159
+#define GET_PIN_MAP_INDEX(pin) pin
160
+#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
161
+
162
+#define HAL_SENSITIVE_PINS 0, 1
163
+
156 164
 #endif // _HAL_AVR_H_

+ 2
- 2
Marlin/src/HAL/HAL_AVR/HAL_pinsDebug_AVR.h Целия файл

@@ -82,7 +82,7 @@ void HAL_analog_pin_state(char buffer[], int8_t pin) {
82 82
 
83 83
 typedef struct {
84 84
   const char * const name;
85
-  uint8_t pin;
85
+  pin_t pin;
86 86
   bool is_digital;
87 87
 } PinInfo;
88 88
 
@@ -457,7 +457,7 @@ static void print_input_or_output(const bool isout) {
457 457
 }
458 458
 
459 459
 // pretty report with PWM info
460
-inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = false, const char *start_string = "") {
460
+inline void report_pin_state_extended(pin_t pin, bool ignore, bool extended = false, const char *start_string = "") {
461 461
   uint8_t temp_char;
462 462
   char *name_mem_pointer, buffer[30];   // for the sprintf statements
463 463
   bool found = false, multi_name_pin = false;

+ 1
- 1
Marlin/src/HAL/HAL_AVR/pinsDebug_AVR_8_bit.h Целия файл

@@ -397,6 +397,6 @@ static void pwm_details(uint8_t pin) {
397 397
 
398 398
 #endif
399 399
 
400
-#define GET_PIN_INFO(pin) do{}while(0)
400
+#define PRINT_PIN(p) do {sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer);} while (0)
401 401
 
402 402
 #endif // _PINSDEBUG_AVR_8_BIT_

+ 4
- 0
Marlin/src/HAL/HAL_DUE/HAL_Due.h Целия файл

@@ -96,6 +96,7 @@
96 96
 // Types
97 97
 // --------------------------------------------------------------------------
98 98
 
99
+typedef int8_t pin_t;
99 100
 
100 101
 // --------------------------------------------------------------------------
101 102
 // Public Variables
@@ -166,6 +167,9 @@ uint16_t HAL_getAdcFreerun(uint8_t chan, bool wait_for_conversion = false);
166 167
 void HAL_enable_AdcFreerun(void);
167 168
 //void HAL_disable_AdcFreerun(uint8_t chan);
168 169
 
170
+#define GET_PIN_MAP_PIN(index) index
171
+#define GET_PIN_MAP_INDEX(pin) pin
172
+#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
169 173
 
170 174
 // --------------------------------------------------------------------------
171 175
 //

+ 2
- 2
Marlin/src/HAL/HAL_DUE/HAL_timers_Due.h Целия файл

@@ -40,7 +40,7 @@
40 40
 
41 41
 #define FORCE_INLINE __attribute__((always_inline)) inline
42 42
 
43
-#define HAL_TIMER_TYPE uint32_t
43
+typedef uint32_t timer_t;
44 44
 #define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
45 45
 
46 46
 #define STEP_TIMER_NUM 3  // index of timer to use for stepper
@@ -92,7 +92,7 @@ static FORCE_INLINE void HAL_timer_set_count(const uint8_t timer_num, const uint
92 92
   pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_RC = count;
93 93
 }
94 94
 
95
-static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_count(const uint8_t timer_num) {
95
+static FORCE_INLINE timer_t HAL_timer_get_count(const uint8_t timer_num) {
96 96
   const tTimerConfig *pConfig = &TimerConfig[timer_num];
97 97
   return pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_RC;
98 98
 }

+ 15
- 12
Marlin/src/HAL/HAL_LPC1768/HAL.cpp Целия файл

@@ -81,14 +81,16 @@ void HAL_adc_init(void) {
81 81
 extern void kill(const char*);
82 82
 extern const char errormagic[];
83 83
 
84
-void HAL_adc_enable_channel(int pin) {
85
-  if (!WITHIN(pin, 0, NUM_ANALOG_INPUTS - 1)) {
86
-    MYSERIAL.printf("%sINVALID ANALOG PORT:%d\n", errormagic, pin);
84
+void HAL_adc_enable_channel(int ch) {
85
+  pin_t pin = analogInputToDigitalPin(ch);
86
+
87
+  if (pin == -1) {
88
+    MYSERIAL.printf("%sINVALID ANALOG PORT:%d\n", errormagic, ch);
87 89
     kill(MSG_KILLED);
88 90
   }
89 91
 
90
-  int8_t pin_port = adc_pin_map[pin].port,
91
-         pin_port_pin = adc_pin_map[pin].pin,
92
+  int8_t pin_port = LPC1768_PIN_PORT(pin),
93
+         pin_port_pin = LPC1768_PIN_PIN(pin),
92 94
          pinsel_start_bit = pin_port_pin > 15 ? 2 * (pin_port_pin - 16) : 2 * pin_port_pin;
93 95
   uint8_t pin_sel_register = (pin_port == 0 && pin_port_pin <= 15) ? 0 :
94 96
                               pin_port == 0                        ? 1 :
@@ -111,15 +113,16 @@ void HAL_adc_enable_channel(int pin) {
111 113
 }
112 114
 
113 115
 uint8_t active_adc = 0;
114
-void HAL_adc_start_conversion(const uint8_t adc_pin) {
115
-  if (adc_pin >= (NUM_ANALOG_INPUTS) || adc_pin_map[adc_pin].port == 0xFF) {
116
-    MYSERIAL.printf("HAL: HAL_adc_start_conversion: no pinmap for %d\n", adc_pin);
116
+void HAL_adc_start_conversion(const uint8_t ch) {
117
+  if (analogInputToDigitalPin(ch) == -1) {
118
+    MYSERIAL.printf("HAL: HAL_adc_start_conversion: invalid channel %d\n", ch);
117 119
     return;
118 120
   }
119
-  LPC_ADC->ADCR &= ~0xFF;                       // Reset
120
-  SBI(LPC_ADC->ADCR, adc_pin_map[adc_pin].adc); // Select Channel
121
-  SBI(LPC_ADC->ADCR, 24);                       // Start conversion
122
-  active_adc = adc_pin;
121
+
122
+  LPC_ADC->ADCR &= ~0xFF; // Reset
123
+  SBI(LPC_ADC->ADCR, ch); // Select Channel
124
+  SBI(LPC_ADC->ADCR, 24); // Start conversion
125
+  active_adc = ch;
123 126
 }
124 127
 
125 128
 bool HAL_adc_finished(void) {

+ 4
- 4
Marlin/src/HAL/HAL_LPC1768/HAL_timers.h Целия файл

@@ -40,7 +40,7 @@
40 40
 
41 41
 #define FORCE_INLINE __attribute__((always_inline)) inline
42 42
 
43
-#define HAL_TIMER_TYPE uint32_t
43
+typedef uint32_t timer_t;
44 44
 #define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
45 45
 
46 46
 #define STEP_TIMER_NUM 0  // index of timer to use for stepper
@@ -77,7 +77,7 @@
77 77
 void HAL_timer_init(void);
78 78
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
79 79
 
80
-static FORCE_INLINE void HAL_timer_set_count(const uint8_t timer_num, const HAL_TIMER_TYPE count) {
80
+static FORCE_INLINE void HAL_timer_set_count(const uint8_t timer_num, const timer_t count) {
81 81
   switch (timer_num) {
82 82
     case 0:
83 83
       LPC_TIM0->MR0 = count;
@@ -92,7 +92,7 @@ static FORCE_INLINE void HAL_timer_set_count(const uint8_t timer_num, const HAL_
92 92
   }
93 93
 }
94 94
 
95
-static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_count(const uint8_t timer_num) {
95
+static FORCE_INLINE timer_t HAL_timer_get_count(const uint8_t timer_num) {
96 96
   switch (timer_num) {
97 97
     case 0: return LPC_TIM0->MR0;
98 98
     case 1: return LPC_TIM1->MR0;
@@ -100,7 +100,7 @@ static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_count(const uint8_t timer_num)
100 100
   return 0;
101 101
 }
102 102
 
103
-static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_current_count(const uint8_t timer_num) {
103
+static FORCE_INLINE timer_t HAL_timer_get_current_count(const uint8_t timer_num) {
104 104
   switch (timer_num) {
105 105
     case 0: return LPC_TIM0->TC;
106 106
     case 1: return LPC_TIM1->TC;

+ 509
- 0
Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.cpp Целия файл

@@ -0,0 +1,509 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+/**
24
+ * The class Servo uses the PWM class to implement its functions
25
+ *
26
+ * All PWMs use the same repetition rate - 20mS because that's the normal servo rate
27
+*/
28
+
29
+/**
30
+ * This is a hybrid system.
31
+ *
32
+ * The PWM1 module is used to directly control the Servo 0, 1 & 3 pins.  This keeps
33
+ * the pulse width jitter to under a microsecond.
34
+ *
35
+ * For all other pins the PWM1 module is used to generate interrupts.  The ISR
36
+ * routine does the actual setting/clearing of pins.  The upside is that any pin can
37
+ * have a PWM channel assigned to it.  The downside is that there is more pulse width
38
+ * jitter. The jitter depends on what else is happening in the system and what ISRs
39
+ * prempt the PWM ISR.  Writing to the SD card can add 20 microseconds to the pulse
40
+ * width.
41
+ */
42
+
43
+/**
44
+ * The data structures are setup to minimize the computation done by the ISR which
45
+ * minimizes ISR execution time.  Execution times are 2.2 - 3.7 microseconds.
46
+ *
47
+ * Two tables are used.  active_table is used by the ISR.  Changes to the table are
48
+ * are done by copying the active_table into the work_table, updating the work_table
49
+ * and then swapping the two tables.  Swapping is done by manipulating pointers.
50
+ *
51
+ * Immediately after the swap the ISR uses the work_table until the start of the
52
+ * next 20mS cycle. During this transition the "work_table" is actually the table
53
+ * that was being used before the swap.  The "active_table" contains the data that
54
+ * will start being used at the start of the next 20mS period.  This keeps the pins
55
+ * well behaved during the transition.
56
+ *
57
+ * The ISR's priority is set to the maximum otherwise other ISRs can cause considerable
58
+ * jitter in the PWM high time.
59
+ *
60
+ * See the end of this file for details on the hardware/firmware interaction
61
+ */
62
+
63
+
64
+#ifdef TARGET_LPC1768
65
+#include <lpc17xx_pinsel.h>
66
+#include "LPC1768_PWM.h"
67
+#include "arduino.h"
68
+
69
+#define NUM_PWMS 6
70
+
71
+typedef struct {            // holds all data needed to control/init one of the PWM channels
72
+    uint8_t             sequence;       // 0: available slot, 1 - 6: PWM channel assigned to that slot
73
+    pin_t               pin;
74
+    uint16_t            PWM_mask;       // MASK TO CHECK/WRITE THE IR REGISTER
75
+    volatile uint32_t*  set_register;
76
+    volatile uint32_t*  clr_register;
77
+    uint32_t            write_mask;     // USED BY SET/CLEAR COMMANDS
78
+    uint32_t            microseconds;   // value written to MR register
79
+    uint32_t            min;            // lower value limit checked by WRITE routine before writing to the MR register
80
+    uint32_t            max;            // upper value limit checked by WRITE routine before writing to the MR register
81
+    bool                PWM_flag;       // 0 - USED BY sERVO, 1 - USED BY ANALOGWRITE
82
+    uint8_t             servo_index;    // 0 - MAX_SERVO -1 : servo index,  0xFF : PWM channel
83
+    bool                active_flag;    // THIS TABLE ENTRY IS ACTIVELY TOGGLING A PIN
84
+    uint8_t             assigned_MR;    // Which MR (1-6) is used by this logical channel
85
+    uint32_t            PCR_bit;        // PCR register bit to enable PWM1 control of this pin
86
+    uint32_t            PINSEL3_bits;   // PINSEL3 register bits to set pin mode to PWM1 control
87
+
88
+} PWM_map;
89
+
90
+
91
+#define MICRO_MAX 0xffffffff
92
+
93
+#define PWM_MAP_INIT_ROW {0, 0xff, 0, 0, 0, 0, MICRO_MAX, 0, 0, 0, 0, 0, 0, 0, 0}
94
+#define PWM_MAP_INIT {PWM_MAP_INIT_ROW,\
95
+                      PWM_MAP_INIT_ROW,\
96
+                      PWM_MAP_INIT_ROW,\
97
+                      PWM_MAP_INIT_ROW,\
98
+                      PWM_MAP_INIT_ROW,\
99
+                      PWM_MAP_INIT_ROW,\
100
+                     };
101
+
102
+PWM_map PWM1_map_A[NUM_PWMS] = PWM_MAP_INIT;
103
+PWM_map PWM1_map_B[NUM_PWMS] = PWM_MAP_INIT;
104
+
105
+PWM_map *active_table = PWM1_map_A;
106
+PWM_map *work_table = PWM1_map_B;
107
+PWM_map *ISR_table;
108
+
109
+
110
+#define IR_BIT(p) (p >= 0 && p <= 3 ? p : p + 4 )
111
+#define COPY_ACTIVE_TABLE    for (uint8_t i = 0; i < 6 ; i++) work_table[i] = active_table[i]
112
+#define PIN_IS_INVERTED(p) 0  // place holder in case inverting PWM output is offered
113
+
114
+
115
+/**
116
+ *  Prescale register and MR0 register values
117
+ *
118
+ *               100MHz PCLK          50MHz PCLK          25MHz PCLK         12.5MHz PCLK
119
+ *             -----------------   -----------------   -----------------   -----------------
120
+ *  desired    prescale  MR0       prescale  MR0       prescale  MR0       prescale  MR0        resolution
121
+ *  prescale   register  register  register  register  register  register  register  register   in degrees
122
+ *  freq       value     value     value     value     value     value     value     value
123
+ *
124
+ *      8        11.5    159,999      5.25   159,999       2.13  159,999    0.5625   159,999    0.023
125
+ *      4        24       79,999     11.5     79,999       5.25   79,999    2.125     79,999    0.045
126
+ *      2        49       39,999     24       39,999      11.5    39,999    5.25      39,999    0.090
127
+ *      1        99       19,999     49       19,999      24      19,999   11.5       19,999    0.180
128
+ *    0.5       199        9,999     99        9,999      49       9,999   24          9,999    0.360
129
+ *   0.25       399        4,999    199        4,999      99       4,999   49          4,999    0.720
130
+ *  0.125       799        2,499    399        2,499     199       2,499   99          2,499    1.440
131
+ *
132
+ *  The desired prescale frequency comes from an input in the range of 544 - 2400 microseconds and the
133
+ *  desire to just shift the input left or right as needed.
134
+ *
135
+ *  A resolution of 0.2 degrees seems reasonable so a prescale frequency output of 1MHz is being used.
136
+ *  It also means we don't need to scale the input.
137
+ *
138
+ *  The PCLK is set to 25MHz because that's the slowest one that gives whole numbers for prescale and
139
+ *  MR0 registers.
140
+ *
141
+ *  Final settings:
142
+ *   PCLKSEL0: 0x0
143
+ *   PWM1PR:   0x018 (24)
144
+ *   PWM1MR0:  0x04E1F (19,999)
145
+ *
146
+ */
147
+
148
+
149
+void LPC1768_PWM_init(void) {
150
+  #define SBIT_CNTEN     0  // PWM1 counter & pre-scaler enable/disable
151
+  #define SBIT_CNTRST    1  // reset counters to known state
152
+  #define SBIT_PWMEN     3  // 1 - PWM, 0 - timer
153
+  #define SBIT_PWMMR0R   1
154
+  #define PCPWM1         6
155
+  #define PCLK_PWM1      12
156
+
157
+  LPC_SC->PCONP |= (1 << PCPWM1);      // enable PWM1 controller (enabled on power up)
158
+  LPC_SC->PCLKSEL0 &= ~(0x3 << PCLK_PWM1);
159
+  LPC_SC->PCLKSEL0 |= (LPC_PWM1_PCLKSEL0 << PCLK_PWM1);
160
+  LPC_PWM1->MR0 = LPC_PWM1_MR0;                // TC resets every 19,999 + 1 cycles - sets PWM cycle(Ton+Toff) to 20 mS
161
+                                        // MR0 must be set before TCR enables the PWM
162
+  LPC_PWM1->TCR = _BV(SBIT_CNTEN) | _BV(SBIT_CNTRST)| _BV(SBIT_PWMEN);;  // enable counters, reset counters, set mode to PWM
163
+  LPC_PWM1->TCR &= ~(_BV(SBIT_CNTRST));  // take counters out of reset
164
+  LPC_PWM1->PR  =  LPC_PWM1_PR;
165
+  LPC_PWM1->MCR = (_BV(SBIT_PWMMR0R) | _BV(0));     // Reset TC if it matches MR0, disable all interrupts except for MR0
166
+  LPC_PWM1->CTCR = 0;                   // disable counter mode (enable PWM mode)
167
+
168
+  LPC_PWM1->LER = 0x07F;  // Set the latch Enable Bits to load the new Match Values for MR0 - MR6
169
+  // Set all PWMs to single edge
170
+  LPC_PWM1->PCR = 0;    // single edge mode for all channels, PWM1 control of outputs off
171
+
172
+  NVIC_EnableIRQ(PWM1_IRQn);     // Enable interrupt handler
173
+  //      NVIC_SetPriority(PWM1_IRQn, NVIC_EncodePriority(0, 10, 0));  // normal priority for PWM module
174
+  NVIC_SetPriority(PWM1_IRQn, NVIC_EncodePriority(0, 0, 0));  // minimizes jitter due to higher priority ISRs
175
+}
176
+
177
+
178
+bool PWM_table_swap = false;  // flag to tell the ISR that the tables have been swapped
179
+bool PWM_MR0_wait = false;  // flag to ensure don't delay MR0 interrupt
180
+
181
+
182
+bool LPC1768_PWM_attach_pin(pin_t pin, uint32_t min /* = 1 */, uint32_t max /* = (LPC_PWM1_MR0 - MR0_MARGIN) */, uint8_t servo_index /* = 0xff */) {
183
+  while (PWM_table_swap) delay(5);  // don't do anything until the previous change has been implemented by the ISR
184
+  COPY_ACTIVE_TABLE;  // copy active table into work table
185
+  uint8_t slot = 0;
186
+  for (uint8_t i = 0; i < NUM_PWMS ; i++)         // see if already in table
187
+    if (work_table[i].pin == pin) return 1;
188
+
189
+  for (uint8_t i = 1; (i < NUM_PWMS + 1) && !slot; i++)         // find empty slot
190
+    if ( !(work_table[i - 1].set_register)) slot = i;  // any item that can't be zero when active or just attached is OK
191
+  if (!slot) return 0;
192
+  slot--;  // turn it into array index
193
+
194
+  work_table[slot].pin = pin;     // init slot
195
+  work_table[slot].PWM_mask = 0;  // real value set by PWM_write
196
+  work_table[slot].set_register = PIN_IS_INVERTED(pin) ? &LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOCLR : &LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOSET;
197
+  work_table[slot].clr_register = PIN_IS_INVERTED(pin) ? &LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOSET : &LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOCLR;
198
+  work_table[slot].write_mask = LPC_PIN(LPC1768_PIN_PIN(pin));
199
+  work_table[slot].microseconds = MICRO_MAX;
200
+  work_table[slot].min = min;
201
+  work_table[slot].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
202
+  work_table[slot].servo_index = servo_index;
203
+  work_table[slot].active_flag = false;
204
+
205
+  //swap tables
206
+  PWM_MR0_wait = true;
207
+  while (PWM_MR0_wait) delay(5);  //wait until MR0 interrupt has happend so don't delay it.
208
+
209
+  NVIC_DisableIRQ(PWM1_IRQn);
210
+  PWM_map *pointer_swap = active_table;
211
+  active_table = work_table;
212
+  work_table = pointer_swap;
213
+  PWM_table_swap = true;  // tell the ISR that the tables have been swapped
214
+  NVIC_EnableIRQ(PWM1_IRQn);  // re-enable PWM interrupts
215
+
216
+  return 1;
217
+}
218
+
219
+#define pin_11_PWM_channel 2
220
+#define pin_6_PWM_channel  3
221
+#define pin_4_PWM_channel  1
222
+
223
+// used to keep track of which Match Registers have been used and if they will be used by the
224
+// PWM1 module to directly control the pin or will be used to generate an interrupt
225
+typedef struct {                        // status of PWM1 channel
226
+    uint8_t map_used;                   // 0 - this MR register not used/assigned
227
+    uint8_t map_PWM_INT;                // 0 - available for interrupts, 1 - in use by PWM
228
+    pin_t map_PWM_PIN;                  // pin for this PwM1 controlled pin / port
229
+    volatile uint32_t* MR_register;     // address of the MR register for this PWM1 channel
230
+    uint32_t PCR_bit;                   // PCR register bit to enable PWM1 control of this pin
231
+    uint32_t PINSEL3_bits;              // PINSEL3 register bits to set pin mode to PWM1 control
232
+} MR_map;
233
+
234
+MR_map map_MR[NUM_PWMS];
235
+
236
+void LPC1768_PWM_update_map_MR(void) {
237
+  map_MR[0] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_4_PWM_channel)  ? 1 : 0),  4, &LPC_PWM1->MR1, 0, 0};
238
+  map_MR[1] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_11_PWM_channel) ? 1 : 0), 11, &LPC_PWM1->MR2, 0, 0};
239
+  map_MR[2] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_6_PWM_channel)  ? 1 : 0),  6, &LPC_PWM1->MR3, 0, 0};
240
+  map_MR[3] = {0, 0,  0, &LPC_PWM1->MR4, 0, 0};
241
+  map_MR[4] = {0, 0,  0, &LPC_PWM1->MR5, 0, 0};
242
+  map_MR[5] = {0, 0,  0, &LPC_PWM1->MR6, 0, 0};
243
+}
244
+
245
+
246
+uint32_t LPC1768_PWM_interrupt_mask = 1;
247
+
248
+void LPC1768_PWM_update(void) {
249
+  for (uint8_t i = NUM_PWMS; --i;) {  // (bubble) sort table by microseconds
250
+    bool didSwap = false;
251
+    PWM_map temp;
252
+    for (uint16_t j = 0; j < i; ++j) {
253
+      if (work_table[j].microseconds > work_table[j + 1].microseconds) {
254
+        temp = work_table[j + 1];
255
+        work_table[j + 1] = work_table[j];
256
+        work_table[j] = temp;
257
+        didSwap = true;
258
+      }
259
+    }
260
+    if (!didSwap) break;
261
+  }
262
+
263
+  LPC1768_PWM_interrupt_mask = 0;                          // set match registers to new values, build IRQ mask
264
+  for (uint8_t i = 0; i < NUM_PWMS; i++) {
265
+    if (work_table[i].active_flag == true) {
266
+      work_table[i].sequence = i + 1;
267
+
268
+      // first see if there is a PWM1 controlled pin for this entry
269
+      bool found = false;
270
+      for (uint8_t j = 0; (j < NUM_PWMS) && !found; j++) {
271
+        if ( (map_MR[j].map_PWM_PIN == work_table[i].pin) && map_MR[j].map_PWM_INT ) {
272
+          *map_MR[j].MR_register = work_table[i].microseconds;  // found one of the PWM pins
273
+          work_table[i].PWM_mask = 0;
274
+          work_table[i].PCR_bit = map_MR[j].PCR_bit;            // PCR register bit to enable PWM1 control of this pin
275
+          work_table[i].PINSEL3_bits = map_MR[j].PINSEL3_bits;  // PINSEL3 register bits to set pin mode to PWM1 control} MR_map;
276
+          map_MR[j].map_used = 2;
277
+          work_table[i].assigned_MR = j +1;                    // only used to help in debugging
278
+          found = true;
279
+        }
280
+      }
281
+
282
+      // didn't find a PWM1 pin so get an interrupt
283
+      for (uint8_t k = 0; (k < NUM_PWMS) && !found; k++) {
284
+        if ( !(map_MR[k].map_PWM_INT || map_MR[k].map_used)) {
285
+          *map_MR[k].MR_register = work_table[i].microseconds;  // found one for an interrupt pin
286
+          map_MR[k].map_used = 1;
287
+          LPC1768_PWM_interrupt_mask |= _BV(3 * (k + 1));  // set bit in the MCR to enable this MR to generate an interrupt
288
+          work_table[i].PWM_mask = _BV(IR_BIT(k + 1));  // bit in the IR that will go active when this MR generates an interrupt
289
+          work_table[i].assigned_MR = k +1;                // only used to help in debugging
290
+          found = true;
291
+        }
292
+      }
293
+    }
294
+    else
295
+      work_table[i].sequence = 0;
296
+  }
297
+  LPC1768_PWM_interrupt_mask |= (uint32_t) _BV(0);  // add in MR0 interrupt
298
+
299
+   // swap tables
300
+
301
+  PWM_MR0_wait = true;
302
+  while (PWM_MR0_wait) delay(5);  //wait until MR0 interrupt has happend so don't delay it.
303
+
304
+  NVIC_DisableIRQ(PWM1_IRQn);
305
+  LPC_PWM1->LER = 0x07E;  // Set the latch Enable Bits to load the new Match Values for MR1 - MR6
306
+  PWM_map *pointer_swap = active_table;
307
+  active_table = work_table;
308
+  work_table = pointer_swap;
309
+  PWM_table_swap = true;  // tell the ISR that the tables have been swapped
310
+  NVIC_EnableIRQ(PWM1_IRQn);  // re-enable PWM interrupts
311
+}
312
+
313
+
314
+bool LPC1768_PWM_write(pin_t pin, uint32_t value) {
315
+  while (PWM_table_swap) delay(5);  // don't do anything until the previous change has been implemented by the ISR
316
+  COPY_ACTIVE_TABLE;  // copy active table into work table
317
+  uint8_t slot = 0xFF;
318
+  for (uint8_t i = 0; i < NUM_PWMS; i++)         // find slot
319
+    if (work_table[i].pin == pin) slot = i;
320
+  if (slot == 0xFF) return false;    // return error if pin not found
321
+
322
+  LPC1768_PWM_update_map_MR();
323
+
324
+  switch(pin) {
325
+    case P1_20:                        // Servo 0, PWM1 channel 2 (Pin 11  P1.20 PWM1.2)
326
+      map_MR[pin_11_PWM_channel - 1].PCR_bit = _BV(8 + pin_11_PWM_channel);  // enable PWM1 module control of this pin
327
+      map_MR[pin_11_PWM_channel - 1].map_PWM_INT = 1;               // 0 - available for interrupts, 1 - in use by PWM
328
+      map_MR[pin_11_PWM_channel - 1].PINSEL3_bits = 0x2 <<  8;      // ISR must do this AFTER setting PCR
329
+      break;
330
+    case P1_21:                        // Servo 1, PWM1 channel 3 (Pin 6  P1.21 PWM1.3)
331
+      map_MR[pin_6_PWM_channel - 1].PCR_bit = _BV(8 + pin_6_PWM_channel);                  // enable PWM1 module control of this pin
332
+      map_MR[pin_6_PWM_channel - 1].map_PWM_INT = 1;                // 0 - available for interrupts, 1 - in use by PWM
333
+      map_MR[pin_6_PWM_channel - 1].PINSEL3_bits = 0x2 << 10;       // ISR must do this AFTER setting PCR
334
+      break;
335
+    case P1_18:                        // Servo 3, PWM1 channel 1 (Pin 4  P1.18 PWM1.1)
336
+      map_MR[pin_4_PWM_channel - 1].PCR_bit = _BV(8 + pin_4_PWM_channel);                  // enable PWM1 module control of this pin
337
+      map_MR[pin_4_PWM_channel - 1].map_PWM_INT = 1;                // 0 - available for interrupts, 1 - in use by PWM
338
+      map_MR[pin_4_PWM_channel - 1].PINSEL3_bits =  0x2 <<  4;       // ISR must do this AFTER setting PCR
339
+      break;
340
+    default:                                                        // ISR pins
341
+      pinMode(pin, OUTPUT);  // set pin to output but don't write anything in case it's already in use
342
+      break;
343
+  }
344
+
345
+  work_table[slot].microseconds = MAX(MIN(value, work_table[slot].max), work_table[slot].min);
346
+  work_table[slot].active_flag = true;
347
+
348
+  LPC1768_PWM_update();
349
+
350
+  return 1;
351
+}
352
+
353
+
354
+bool LPC1768_PWM_detach_pin(pin_t pin) {
355
+  while (PWM_table_swap) delay(5);  // don't do anything until the previous change has been implemented by the ISR
356
+  COPY_ACTIVE_TABLE;  // copy active table into work table
357
+  uint8_t slot = 0xFF;
358
+  for (uint8_t i = 0; i < NUM_PWMS; i++)         // find slot
359
+    if (work_table[i].pin == pin) slot = i;
360
+  if (slot == 0xFF) return false;    // return error if pin not found
361
+
362
+  LPC1768_PWM_update_map_MR();
363
+
364
+  // OK to make these changes before the MR0 interrupt
365
+  switch(pin) {
366
+    case P1_20:                        // Servo 0, PWM1 channel 2  (Pin 11  P1.20 PWM1.2)
367
+      LPC_PWM1->PCR &= ~(_BV(8 + pin_11_PWM_channel));                 // disable PWM1 module control of this pin
368
+      map_MR[pin_11_PWM_channel - 1].PCR_bit = 0;
369
+      LPC_PINCON->PINSEL3 &= ~(0x3 <<  8);    // return pin to general purpose I/O
370
+      map_MR[pin_11_PWM_channel - 1].PINSEL3_bits = 0;
371
+      map_MR[pin_11_PWM_channel - 1].map_PWM_INT = 0;               // 0 - available for interrupts, 1 - in use by PWM
372
+      break;
373
+    case P1_21:                        // Servo 1, PWM1 channel 3  (Pin 6  P1.21 PWM1.3)
374
+      LPC_PWM1->PCR &= ~(_BV(8 + pin_6_PWM_channel));                  // disable PWM1 module control of this pin
375
+      map_MR[pin_6_PWM_channel - 1].PCR_bit = 0;
376
+      LPC_PINCON->PINSEL3 &= ~(0x3 << 10);  // return pin to general purpose I/O
377
+      map_MR[pin_6_PWM_channel - 1].PINSEL3_bits = 0;
378
+      map_MR[pin_6_PWM_channel - 1].map_PWM_INT = 0;                // 0 - available for interrupts, 1 - in use by PWM
379
+      break;
380
+    case P1_18:                        // Servo 3, PWM1 channel 1 (Pin 4  P1.18 PWM1.1)
381
+      LPC_PWM1->PCR &= ~(_BV(8 + pin_4_PWM_channel));                  // disable PWM1 module control of this pin
382
+      map_MR[pin_4_PWM_channel - 1].PCR_bit =  0;
383
+      LPC_PINCON->PINSEL3 &= ~(0x3 <<  4);  // return pin to general purpose I/O
384
+      map_MR[pin_4_PWM_channel - 1].PINSEL3_bits =  0;
385
+      map_MR[pin_4_PWM_channel - 1].map_PWM_INT = 0;                // 0 - available for interrupts, 1 - in use by PWM
386
+      break;
387
+  }
388
+
389
+  pinMode(pin, INPUT);
390
+
391
+  work_table[slot] = PWM_MAP_INIT_ROW;
392
+
393
+  LPC1768_PWM_update();
394
+
395
+  return 1;
396
+}
397
+
398
+
399
+bool useable_hardware_PWM(pin_t pin) {
400
+  COPY_ACTIVE_TABLE;  // copy active table into work table
401
+  for (uint8_t i = 0; i < NUM_PWMS; i++)         // see if it's already setup
402
+    if (work_table[i].pin == pin && work_table[i].sequence) return true;
403
+  for (uint8_t i = 0; i < NUM_PWMS; i++)         // see if there is an empty slot
404
+    if (!work_table[i].sequence) return true;
405
+  return false;    // only get here if neither the above are true
406
+}
407
+
408
+////////////////////////////////////////////////////////////////////////////////
409
+
410
+#define HAL_PWM_LPC1768_ISR  extern "C" void PWM1_IRQHandler(void)
411
+
412
+
413
+// Both loops could be terminated when the last active channel is found but that would
414
+// result in variations ISR run time which results in variations in pulse width
415
+
416
+/**
417
+ * Changes to PINSEL3, PCR and MCR are only done during the MR0 interrupt otherwise
418
+ * the wrong pin may be toggled or even have the system hang.
419
+ */
420
+
421
+
422
+HAL_PWM_LPC1768_ISR {
423
+  if (PWM_table_swap) ISR_table = work_table;   // use old table if a swap was just done
424
+  else ISR_table = active_table;
425
+
426
+  if (LPC_PWM1->IR & 0x1) {                                      // MR0 interrupt
427
+    ISR_table = active_table;                    // MR0 means new values could have been loaded so set everything
428
+    if (PWM_table_swap) LPC_PWM1->MCR = LPC1768_PWM_interrupt_mask; // enable new PWM individual channel interrupts
429
+
430
+    for (uint8_t i = 0; i < NUM_PWMS; i++) {
431
+      if(ISR_table[i].active_flag && !((ISR_table[i].pin == P1_20) ||
432
+                                       (ISR_table[i].pin == P1_21) ||
433
+                                       (ISR_table[i].pin == P1_18)))
434
+        *ISR_table[i].set_register = ISR_table[i].write_mask;       // set pins for all enabled interrupt channels active
435
+      if (PWM_table_swap && ISR_table[i].PCR_bit) {
436
+        LPC_PWM1->PCR |= ISR_table[i].PCR_bit;              // enable PWM1 module control of this pin
437
+        LPC_PINCON->PINSEL3 |= ISR_table[i].PINSEL3_bits;   // set pin mode to PWM1 control - must be done after PCR
438
+      }
439
+    }
440
+    PWM_table_swap = false;
441
+    PWM_MR0_wait = false;
442
+    LPC_PWM1->IR = 0x01;                                             // clear the MR0 interrupt flag bit
443
+  }
444
+  else {
445
+    for (uint8_t i = 0; i < NUM_PWMS ; i++)
446
+      if (ISR_table[i].active_flag && (LPC_PWM1->IR & ISR_table[i].PWM_mask) ){
447
+        LPC_PWM1->IR = ISR_table[i].PWM_mask;       // clear the interrupt flag bits for expected interrupts
448
+        *ISR_table[i].clr_register = ISR_table[i].write_mask;   // set channel to inactive
449
+      }
450
+  }
451
+
452
+  LPC_PWM1->IR = 0x70F;  // guarantees all interrupt flags are cleared which, if there is an unexpected
453
+                           // PWM interrupt, will keep the ISR from hanging which will crash the controller
454
+
455
+return;
456
+}
457
+#endif
458
+
459
+/////////////////////////////////////////////////////////////////
460
+/////////////////  HARDWARE FIRMWARE INTERACTION ////////////////
461
+/////////////////////////////////////////////////////////////////
462
+
463
+/**
464
+ *  Almost all changes to the hardware registers must be coordinated with the Match Register 0 (MR0)
465
+ *  interrupt.  The only exception is detaching pins.  It doesn't matter when they go
466
+ *  tristate.
467
+ *
468
+ *  The LPC1768_PWM_init routine kicks off the MR0 interrupt.  This interrupt is never disabled or
469
+ *  delayed.
470
+ *
471
+ *  The PWM_table_swap flag is set when the firmware has swapped in an updated table.  It is
472
+ *  cleared by the ISR during the MR0 interrupt as it completes the swap and accompanying updates.
473
+ *  It serves two purposes:
474
+ *    1) Tells the ISR that the tables have been swapped
475
+ *    2) Keeps the firmware from starting a new update until the previous one has been completed.
476
+ *
477
+ *  The PWM_MR0_wait flag is set when the firmware is ready to swap in an updated table and cleared by
478
+ *  the ISR during the MR0 interrupt.  It is used to avoid delaying the MR0 interrupt when swapping in
479
+ *  an updated table.  This avoids glitches in pulse width and/or repetition rate.
480
+ *
481
+ *  The sequence of events during a write to a PWM channel is:
482
+ *    1) Waits until PWM_table_swap flag is false before starting
483
+ *    2) Copies the active table into the work table
484
+ *    3) Updates the work table
485
+ *         NOTES - MR1-MR6 are updated at this time.  The updates aren't put into use until the first
486
+ *                 MR0 after the LER register has been written.  The LER register is written during the
487
+ *                 table swap process.
488
+ *               - The MCR mask is created at this time.  It is not used until the ISR writes the MCR
489
+ *                 during the MR0 interrupt in the table swap process.
490
+ *    4) Sets the PWM_MR0_wait flag
491
+ *    5) ISR clears the PWM_MR0_wait flag during the next MR0 interrupt
492
+ *    6) Once the PWM_MR0_wait flag is cleared then the firmware:
493
+ *          disables the ISR interrupt
494
+ *          swaps the pointers to the tables
495
+ *          writes to the LER register
496
+ *          sets the PWM_table_swap flag active
497
+ *          re-enables the ISR
498
+ *     7) On the next interrupt the ISR changes its pointer to the work table which is now the old,
499
+ *        unmodified, active table.
500
+ *     8) On the next MR0 interrupt the ISR:
501
+ *          switches over to the active table
502
+ *          clears the PWM_table_swap and PWM_MR0_wait flags
503
+ *          updates the MCR register with the possibly new interrupt sources/assignments
504
+ *          writes to the PCR register to enable the direct control of the Servo 0, 1 & 3 pins by the PWM1 module
505
+ *          sets the PINSEL3 register to function/mode 0x2 for the Servo 0, 1 & 3 pins
506
+ *             NOTE - PCR must be set before PINSEL
507
+ *          sets the pins controlled by the ISR to their active states
508
+ */
509
+

+ 8
- 444
Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.h Целия файл

@@ -60,88 +60,7 @@
60 60
  * See the end of this file for details on the hardware/firmware interaction
61 61
  */
62 62
 
63
-
64
-#ifdef TARGET_LPC1768
65
-#include <lpc17xx_pinsel.h>
66
-
67
-#define NUM_PWMS 6
68
-
69
-typedef struct {            // holds all data needed to control/init one of the PWM channels
70
-    uint8_t  sequence;       // 0: available slot, 1 - 6: PWM channel assigned to that slot
71
-    uint8_t  logical_pin;
72
-    uint16_t PWM_mask;       // MASK TO CHECK/WRITE THE IR REGISTER
73
-    volatile uint32_t* set_register;
74
-    volatile uint32_t* clr_register;
75
-    uint32_t write_mask;     // USED BY SET/CLEAR COMMANDS
76
-    uint32_t microseconds;   // value written to MR register
77
-    uint32_t min;            // lower value limit checked by WRITE routine before writing to the MR register
78
-    uint32_t max;            // upper value limit checked by WRITE routine before writing to the MR register
79
-    bool     PWM_flag;       // 0 - USED BY sERVO, 1 - USED BY ANALOGWRITE
80
-    uint8_t  servo_index;    // 0 - MAX_SERVO -1 : servo index,  0xFF : PWM channel
81
-    bool     active_flag;    // THIS TABLE ENTRY IS ACTIVELY TOGGLING A PIN
82
-    uint8_t  assigned_MR;    // Which MR (1-6) is used by this logical channel
83
-    uint32_t PCR_bit;        // PCR register bit to enable PWM1 control of this pin
84
-    uint32_t PINSEL3_bits;   // PINSEL3 register bits to set pin mode to PWM1 control
85
-
86
-} PWM_map;
87
-
88
-
89
-#define MICRO_MAX 0xffffffff
90
-
91
-#define PWM_MAP_INIT_ROW {0, 0xff, 0, 0, 0, 0, MICRO_MAX, 0, 0, 0, 0, 0, 0, 0, 0}
92
-#define PWM_MAP_INIT {PWM_MAP_INIT_ROW,\
93
-                      PWM_MAP_INIT_ROW,\
94
-                      PWM_MAP_INIT_ROW,\
95
-                      PWM_MAP_INIT_ROW,\
96
-                      PWM_MAP_INIT_ROW,\
97
-                      PWM_MAP_INIT_ROW,\
98
-                     };
99
-
100
-PWM_map PWM1_map_A[NUM_PWMS] = PWM_MAP_INIT;
101
-PWM_map PWM1_map_B[NUM_PWMS] = PWM_MAP_INIT;
102
-
103
-PWM_map *active_table = PWM1_map_A;
104
-PWM_map *work_table = PWM1_map_B;
105
-PWM_map *ISR_table;
106
-
107
-
108
-#define IR_BIT(p) (p >= 0 && p <= 3 ? p : p + 4 )
109
-#define COPY_ACTIVE_TABLE    for (uint8_t i = 0; i < 6 ; i++) work_table[i] = active_table[i]
110
-#define PIN_IS_INVERTED(p) 0  // place holder in case inverting PWM output is offered
111
-
112
-
113
-/**
114
- *  Prescale register and MR0 register values
115
- *
116
- *               100MHz PCLK          50MHz PCLK          25MHz PCLK         12.5MHz PCLK
117
- *             -----------------   -----------------   -----------------   -----------------
118
- *  desired    prescale  MR0       prescale  MR0       prescale  MR0       prescale  MR0        resolution
119
- *  prescale   register  register  register  register  register  register  register  register   in degrees
120
- *  freq       value     value     value     value     value     value     value     value
121
- *
122
- *      8        11.5    159,999      5.25   159,999       2.13  159,999    0.5625   159,999    0.023
123
- *      4        24       79,999     11.5     79,999       5.25   79,999    2.125     79,999    0.045
124
- *      2        49       39,999     24       39,999      11.5    39,999    5.25      39,999    0.090
125
- *      1        99       19,999     49       19,999      24      19,999   11.5       19,999    0.180
126
- *    0.5       199        9,999     99        9,999      49       9,999   24          9,999    0.360
127
- *   0.25       399        4,999    199        4,999      99       4,999   49          4,999    0.720
128
- *  0.125       799        2,499    399        2,499     199       2,499   99          2,499    1.440
129
- *
130
- *  The desired prescale frequency comes from an input in the range of 544 - 2400 microseconds and the
131
- *  desire to just shift the input left or right as needed.
132
- *
133
- *  A resolution of 0.2 degrees seems reasonable so a prescale frequency output of 1MHz is being used.
134
- *  It also means we don't need to scale the input.
135
- *
136
- *  The PCLK is set to 25MHz because that's the slowest one that gives whole numbers for prescale and
137
- *  MR0 registers.
138
- *
139
- *  Final settings:
140
- *   PCLKSEL0: 0x0
141
- *   PWM1PR:   0x018 (24)
142
- *   PWM1MR0:  0x04E1F (19,999)
143
- *
144
- */
63
+ #include "fastio.h"
145 64
 
146 65
 #define LPC_PWM1_MR0 19999  // base repetition rate minus one count - 20mS
147 66
 #define LPC_PWM1_PR 24      // prescaler value - prescaler divide by 24 + 1  -  1 MHz output
@@ -149,365 +68,10 @@ PWM_map *ISR_table;
149 68
                                  // 0: 25MHz, 1: 100MHz, 2: 50MHz, 3: 12.5MHZ to PWM1 prescaler
150 69
 #define MR0_MARGIN 200       // if channel value too close to MR0 the system locks up
151 70
 
152
-
153
-void LPC1768_PWM_init(void) {
154
-  #define SBIT_CNTEN     0  // PWM1 counter & pre-scaler enable/disable
155
-  #define SBIT_CNTRST    1  // reset counters to known state
156
-  #define SBIT_PWMEN     3  // 1 - PWM, 0 - timer
157
-  #define SBIT_PWMMR0R   1
158
-  #define PCPWM1         6
159
-  #define PCLK_PWM1      12
160
-
161
-  LPC_SC->PCONP |= (1 << PCPWM1);      // enable PWM1 controller (enabled on power up)
162
-  LPC_SC->PCLKSEL0 &= ~(0x3 << PCLK_PWM1);
163
-  LPC_SC->PCLKSEL0 |= (LPC_PWM1_PCLKSEL0 << PCLK_PWM1);
164
-  LPC_PWM1->MR0 = LPC_PWM1_MR0;                // TC resets every 19,999 + 1 cycles - sets PWM cycle(Ton+Toff) to 20 mS
165
-                                        // MR0 must be set before TCR enables the PWM
166
-  LPC_PWM1->TCR = _BV(SBIT_CNTEN) | _BV(SBIT_CNTRST)| _BV(SBIT_PWMEN);;  // enable counters, reset counters, set mode to PWM
167
-  LPC_PWM1->TCR &= ~(_BV(SBIT_CNTRST));  // take counters out of reset
168
-  LPC_PWM1->PR  =  LPC_PWM1_PR;
169
-  LPC_PWM1->MCR = (_BV(SBIT_PWMMR0R) | _BV(0));     // Reset TC if it matches MR0, disable all interrupts except for MR0
170
-  LPC_PWM1->CTCR = 0;                   // disable counter mode (enable PWM mode)
171
-
172
-  LPC_PWM1->LER = 0x07F;  // Set the latch Enable Bits to load the new Match Values for MR0 - MR6
173
-  // Set all PWMs to single edge
174
-  LPC_PWM1->PCR = 0;    // single edge mode for all channels, PWM1 control of outputs off
175
-
176
-  NVIC_EnableIRQ(PWM1_IRQn);     // Enable interrupt handler
177
-  //      NVIC_SetPriority(PWM1_IRQn, NVIC_EncodePriority(0, 10, 0));  // normal priority for PWM module
178
-  NVIC_SetPriority(PWM1_IRQn, NVIC_EncodePriority(0, 0, 0));  // minimizes jitter due to higher priority ISRs
179
-}
180
-
181
-
182
-bool PWM_table_swap = false;  // flag to tell the ISR that the tables have been swapped
183
-bool PWM_MR0_wait = false;  // flag to ensure don't delay MR0 interrupt
184
-
185
-
186
-bool LPC1768_PWM_attach_pin(uint8_t pin, uint32_t min = 1, uint32_t max = (LPC_PWM1_MR0 - MR0_MARGIN), uint8_t servo_index = 0xff) {
187
-  while (PWM_table_swap) delay(5);  // don't do anything until the previous change has been implemented by the ISR
188
-  COPY_ACTIVE_TABLE;  // copy active table into work table
189
-  uint8_t slot = 0;
190
-  for (uint8_t i = 0; i < NUM_PWMS ; i++)         // see if already in table
191
-    if (work_table[i].logical_pin == pin) return 1;
192
-
193
-  for (uint8_t i = 1; (i < NUM_PWMS + 1) && !slot; i++)         // find empty slot
194
-    if ( !(work_table[i - 1].set_register)) slot = i;  // any item that can't be zero when active or just attached is OK
195
-  if (!slot) return 0;
196
-  slot--;  // turn it into array index
197
-
198
-  work_table[slot].logical_pin = pin;  // init slot
199
-  work_table[slot].PWM_mask = 0;  // real value set by PWM_write
200
-  work_table[slot].set_register = PIN_IS_INVERTED(pin) ? &LPC_GPIO(pin_map[pin].port)->FIOCLR : &LPC_GPIO(pin_map[pin].port)->FIOSET;
201
-  work_table[slot].clr_register = PIN_IS_INVERTED(pin) ? &LPC_GPIO(pin_map[pin].port)->FIOSET : &LPC_GPIO(pin_map[pin].port)->FIOCLR;
202
-  work_table[slot].write_mask = LPC_PIN(pin_map[pin].pin);
203
-  work_table[slot].microseconds = MICRO_MAX;
204
-  work_table[slot].min = min;
205
-  work_table[slot].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
206
-  work_table[slot].servo_index = servo_index;
207
-  work_table[slot].active_flag = false;
208
-
209
-  //swap tables
210
-  PWM_MR0_wait = true;
211
-  while (PWM_MR0_wait) delay(5);  //wait until MR0 interrupt has happend so don't delay it.
212
-
213
-  NVIC_DisableIRQ(PWM1_IRQn);
214
-  PWM_map *pointer_swap = active_table;
215
-  active_table = work_table;
216
-  work_table = pointer_swap;
217
-  PWM_table_swap = true;  // tell the ISR that the tables have been swapped
218
-  NVIC_EnableIRQ(PWM1_IRQn);  // re-enable PWM interrupts
219
-
220
-  return 1;
221
-}
222
-
223
-#define pin_11_PWM_channel 2
224
-#define pin_6_PWM_channel  3
225
-#define pin_4_PWM_channel  1
226
-
227
-// used to keep track of which Match Registers have been used and if they will be used by the
228
-// PWM1 module to directly control the pin or will be used to generate an interrupt
229
-typedef struct {                        // status of PWM1 channel
230
-    uint8_t map_used;                   // 0 - this MR register not used/assigned
231
-    uint8_t map_PWM_INT;                // 0 - available for interrupts, 1 - in use by PWM
232
-    uint8_t map_PWM_PIN;                // logical pin number for this PwM1 controlled pin / port
233
-    volatile uint32_t* MR_register;     // address of the MR register for this PWM1 channel
234
-    uint32_t PCR_bit;                   // PCR register bit to enable PWM1 control of this pin
235
-    uint32_t PINSEL3_bits;              // PINSEL3 register bits to set pin mode to PWM1 control
236
-} MR_map;
237
-
238
-MR_map map_MR[NUM_PWMS];
239
-
240
-void LPC1768_PWM_update_map_MR(void) {
241
-  map_MR[0] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_4_PWM_channel)  ? 1 : 0),  4, &LPC_PWM1->MR1, 0, 0};
242
-  map_MR[1] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_11_PWM_channel) ? 1 : 0), 11, &LPC_PWM1->MR2, 0, 0};
243
-  map_MR[2] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_6_PWM_channel)  ? 1 : 0),  6, &LPC_PWM1->MR3, 0, 0};
244
-  map_MR[3] = {0, 0,  0, &LPC_PWM1->MR4, 0, 0};
245
-  map_MR[4] = {0, 0,  0, &LPC_PWM1->MR5, 0, 0};
246
-  map_MR[5] = {0, 0,  0, &LPC_PWM1->MR6, 0, 0};
247
-}
248
-
249
-
250
-uint32_t LPC1768_PWM_interrupt_mask = 1;
251
-
252
-void LPC1768_PWM_update(void) {
253
-  for (uint8_t i = NUM_PWMS; --i;) {  // (bubble) sort table by microseconds
254
-    bool didSwap = false;
255
-    PWM_map temp;
256
-    for (uint16_t j = 0; j < i; ++j) {
257
-      if (work_table[j].microseconds > work_table[j + 1].microseconds) {
258
-        temp = work_table[j + 1];
259
-        work_table[j + 1] = work_table[j];
260
-        work_table[j] = temp;
261
-        didSwap = true;
262
-      }
263
-    }
264
-    if (!didSwap) break;
265
-  }
266
-
267
-  LPC1768_PWM_interrupt_mask = 0;                          // set match registers to new values, build IRQ mask
268
-  for (uint8_t i = 0; i < NUM_PWMS; i++) {
269
-    if (work_table[i].active_flag == true) {
270
-      work_table[i].sequence = i + 1;
271
-
272
-      // first see if there is a PWM1 controlled pin for this entry
273
-      bool found = false;
274
-      for (uint8_t j = 0; (j < NUM_PWMS) && !found; j++) {
275
-        if ( (map_MR[j].map_PWM_PIN == work_table[i].logical_pin) && map_MR[j].map_PWM_INT ) {
276
-          *map_MR[j].MR_register = work_table[i].microseconds;  // found one of the PWM pins
277
-          work_table[i].PWM_mask = 0;
278
-          work_table[i].PCR_bit = map_MR[j].PCR_bit;            // PCR register bit to enable PWM1 control of this pin
279
-          work_table[i].PINSEL3_bits = map_MR[j].PINSEL3_bits;  // PINSEL3 register bits to set pin mode to PWM1 control} MR_map;
280
-          map_MR[j].map_used = 2;
281
-          work_table[i].assigned_MR = j +1;                    // only used to help in debugging
282
-          found = true;
283
-        }
284
-      }
285
-
286
-      // didn't find a PWM1 pin so get an interrupt
287
-      for (uint8_t k = 0; (k < NUM_PWMS) && !found; k++) {
288
-        if ( !(map_MR[k].map_PWM_INT || map_MR[k].map_used)) {
289
-          *map_MR[k].MR_register = work_table[i].microseconds;  // found one for an interrupt pin
290
-          map_MR[k].map_used = 1;
291
-          LPC1768_PWM_interrupt_mask |= _BV(3 * (k + 1));  // set bit in the MCR to enable this MR to generate an interrupt
292
-          work_table[i].PWM_mask = _BV(IR_BIT(k + 1));  // bit in the IR that will go active when this MR generates an interrupt
293
-          work_table[i].assigned_MR = k +1;                // only used to help in debugging
294
-          found = true;
295
-        }
296
-      }
297
-    }
298
-    else
299
-      work_table[i].sequence = 0;
300
-  }
301
-  LPC1768_PWM_interrupt_mask |= (uint32_t) _BV(0);  // add in MR0 interrupt
302
-
303
-   // swap tables
304
-
305
-  PWM_MR0_wait = true;
306
-  while (PWM_MR0_wait) delay(5);  //wait until MR0 interrupt has happend so don't delay it.
307
-
308
-  NVIC_DisableIRQ(PWM1_IRQn);
309
-  LPC_PWM1->LER = 0x07E;  // Set the latch Enable Bits to load the new Match Values for MR1 - MR6
310
-  PWM_map *pointer_swap = active_table;
311
-  active_table = work_table;
312
-  work_table = pointer_swap;
313
-  PWM_table_swap = true;  // tell the ISR that the tables have been swapped
314
-  NVIC_EnableIRQ(PWM1_IRQn);  // re-enable PWM interrupts
315
-}
316
-
317
-
318
-bool LPC1768_PWM_write(uint8_t pin, uint32_t value) {
319
-  while (PWM_table_swap) delay(5);  // don't do anything until the previous change has been implemented by the ISR
320
-  COPY_ACTIVE_TABLE;  // copy active table into work table
321
-  uint8_t slot = 0xFF;
322
-  for (uint8_t i = 0; i < NUM_PWMS; i++)         // find slot
323
-    if (work_table[i].logical_pin == pin) slot = i;
324
-  if (slot == 0xFF) return false;    // return error if pin not found
325
-
326
-  LPC1768_PWM_update_map_MR();
327
-
328
-  switch(pin) {
329
-    case 11:                        // Servo 0, PWM1 channel 2 (Pin 11  P1.20 PWM1.2)
330
-      map_MR[pin_11_PWM_channel - 1].PCR_bit = _BV(8 + pin_11_PWM_channel);  // enable PWM1 module control of this pin
331
-      map_MR[pin_11_PWM_channel - 1].map_PWM_INT = 1;               // 0 - available for interrupts, 1 - in use by PWM
332
-      map_MR[pin_11_PWM_channel - 1].PINSEL3_bits = 0x2 <<  8;      // ISR must do this AFTER setting PCR
333
-      break;
334
-    case  6:                        // Servo 1, PWM1 channel 3 (Pin 6  P1.21 PWM1.3)
335
-      map_MR[pin_6_PWM_channel - 1].PCR_bit = _BV(8 + pin_6_PWM_channel);                  // enable PWM1 module control of this pin
336
-      map_MR[pin_6_PWM_channel - 1].map_PWM_INT = 1;                // 0 - available for interrupts, 1 - in use by PWM
337
-      map_MR[pin_6_PWM_channel - 1].PINSEL3_bits = 0x2 << 10;       // ISR must do this AFTER setting PCR
338
-      break;
339
-    case  4:                        // Servo 3, PWM1 channel 1 (Pin 4  P1.18 PWM1.1)
340
-      map_MR[pin_4_PWM_channel - 1].PCR_bit = _BV(8 + pin_4_PWM_channel);                  // enable PWM1 module control of this pin
341
-      map_MR[pin_4_PWM_channel - 1].map_PWM_INT = 1;                // 0 - available for interrupts, 1 - in use by PWM
342
-      map_MR[pin_4_PWM_channel - 1].PINSEL3_bits =  0x2 <<  4;       // ISR must do this AFTER setting PCR
343
-      break;
344
-    default:                                                        // ISR pins
345
-      pinMode(pin, OUTPUT);  // set pin to output but don't write anything in case it's already in use
346
-      break;
347
-  }
348
-
349
-  work_table[slot].microseconds = MAX(MIN(value, work_table[slot].max), work_table[slot].min);
350
-  work_table[slot].active_flag = true;
351
-
352
-  LPC1768_PWM_update();
353
-
354
-  return 1;
355
-}
356
-
357
-
358
-bool LPC1768_PWM_detach_pin(uint8_t pin) {
359
-  while (PWM_table_swap) delay(5);  // don't do anything until the previous change has been implemented by the ISR
360
-  COPY_ACTIVE_TABLE;  // copy active table into work table
361
-  uint8_t slot = 0xFF;
362
-  for (uint8_t i = 0; i < NUM_PWMS; i++)         // find slot
363
-    if (work_table[i].logical_pin == pin) slot = i;
364
-  if (slot == 0xFF) return false;    // return error if pin not found
365
-
366
-  LPC1768_PWM_update_map_MR();
367
-
368
-  // OK to make these changes before the MR0 interrupt
369
-  switch(pin) {
370
-    case 11:                        // Servo 0, PWM1 channel 2  (Pin 11  P1.20 PWM1.2)
371
-      LPC_PWM1->PCR &= ~(_BV(8 + pin_11_PWM_channel));                 // disable PWM1 module control of this pin
372
-      map_MR[pin_11_PWM_channel - 1].PCR_bit = 0;
373
-      LPC_PINCON->PINSEL3 &= ~(0x3 <<  8);    // return pin to general purpose I/O
374
-      map_MR[pin_11_PWM_channel - 1].PINSEL3_bits = 0;
375
-      map_MR[pin_11_PWM_channel - 1].map_PWM_INT = 0;               // 0 - available for interrupts, 1 - in use by PWM
376
-      break;
377
-    case  6:                        // Servo 1, PWM1 channel 3  (Pin 6  P1.21 PWM1.3)
378
-      LPC_PWM1->PCR &= ~(_BV(8 + pin_6_PWM_channel));                  // disable PWM1 module control of this pin
379
-      map_MR[pin_6_PWM_channel - 1].PCR_bit = 0;
380
-      LPC_PINCON->PINSEL3 &= ~(0x3 << 10);  // return pin to general purpose I/O
381
-      map_MR[pin_6_PWM_channel - 1].PINSEL3_bits = 0;
382
-      map_MR[pin_6_PWM_channel - 1].map_PWM_INT = 0;                // 0 - available for interrupts, 1 - in use by PWM
383
-      break;
384
-    case  4:                        // Servo 3, PWM1 channel 1 (Pin 4  P1.18 PWM1.1)
385
-      LPC_PWM1->PCR &= ~(_BV(8 + pin_4_PWM_channel));                  // disable PWM1 module control of this pin
386
-      map_MR[pin_4_PWM_channel - 1].PCR_bit =  0;
387
-      LPC_PINCON->PINSEL3 &= ~(0x3 <<  4);  // return pin to general purpose I/O
388
-      map_MR[pin_4_PWM_channel - 1].PINSEL3_bits =  0;
389
-      map_MR[pin_4_PWM_channel - 1].map_PWM_INT = 0;                // 0 - available for interrupts, 1 - in use by PWM
390
-      break;
391
-  }
392
-
393
-  pinMode(pin, INPUT);
394
-
395
-  work_table[slot] = PWM_MAP_INIT_ROW;
396
-
397
-  LPC1768_PWM_update();
398
-
399
-  return 1;
400
-}
401
-
402
-
403
-bool useable_hardware_PWM(uint8_t pin) {
404
-  COPY_ACTIVE_TABLE;  // copy active table into work table
405
-  for (uint8_t i = 0; i < NUM_PWMS; i++)         // see if it's already setup
406
-    if (work_table[i].logical_pin == pin && work_table[i].sequence) return true;
407
-  for (uint8_t i = 0; i < NUM_PWMS; i++)         // see if there is an empty slot
408
-    if (!work_table[i].sequence) return true;
409
-  return false;    // only get here if neither the above are true
410
-}
411
-
412
-////////////////////////////////////////////////////////////////////////////////
413
-
414
-#define HAL_PWM_LPC1768_ISR  extern "C" void PWM1_IRQHandler(void)
415
-
416
-
417
-// Both loops could be terminated when the last active channel is found but that would
418
-// result in variations ISR run time which results in variations in pulse width
419
-
420
-/**
421
- * Changes to PINSEL3, PCR and MCR are only done during the MR0 interrupt otherwise
422
- * the wrong pin may be toggled or even have the system hang.
423
- */
424
-
425
-
426
-HAL_PWM_LPC1768_ISR {
427
-  if (PWM_table_swap) ISR_table = work_table;   // use old table if a swap was just done
428
-  else ISR_table = active_table;
429
-
430
-  if (LPC_PWM1->IR & 0x1) {                                      // MR0 interrupt
431
-    ISR_table = active_table;                    // MR0 means new values could have been loaded so set everything
432
-    if (PWM_table_swap) LPC_PWM1->MCR = LPC1768_PWM_interrupt_mask; // enable new PWM individual channel interrupts
433
-
434
-    for (uint8_t i = 0; i < NUM_PWMS; i++) {
435
-      if(ISR_table[i].active_flag && !((ISR_table[i].logical_pin ==  11) ||
436
-                                       (ISR_table[i].logical_pin ==  4) ||
437
-                                       (ISR_table[i].logical_pin ==  6)))
438
-        *ISR_table[i].set_register = ISR_table[i].write_mask;       // set pins for all enabled interrupt channels active
439
-      if (PWM_table_swap && ISR_table[i].PCR_bit) {
440
-        LPC_PWM1->PCR |= ISR_table[i].PCR_bit;              // enable PWM1 module control of this pin
441
-        LPC_PINCON->PINSEL3 |= ISR_table[i].PINSEL3_bits;   // set pin mode to PWM1 control - must be done after PCR
442
-      }
443
-    }
444
-    PWM_table_swap = false;
445
-    PWM_MR0_wait = false;
446
-    LPC_PWM1->IR = 0x01;                                             // clear the MR0 interrupt flag bit
447
-  }
448
-  else {
449
-    for (uint8_t i = 0; i < NUM_PWMS ; i++)
450
-      if (ISR_table[i].active_flag && (LPC_PWM1->IR & ISR_table[i].PWM_mask) ){
451
-        LPC_PWM1->IR = ISR_table[i].PWM_mask;       // clear the interrupt flag bits for expected interrupts
452
-        *ISR_table[i].clr_register = ISR_table[i].write_mask;   // set channel to inactive
453
-      }
454
-  }
455
-
456
-  LPC_PWM1->IR = 0x70F;  // guarantees all interrupt flags are cleared which, if there is an unexpected
457
-                           // PWM interrupt, will keep the ISR from hanging which will crash the controller
458
-
459
-return;
460
-}
461
-#endif
462
-
463
-/////////////////////////////////////////////////////////////////
464
-/////////////////  HARDWARE FIRMWARE INTERACTION ////////////////
465
-/////////////////////////////////////////////////////////////////
466
-
467
-/**
468
- *  Almost all changes to the hardware registers must be coordinated with the Match Register 0 (MR0)
469
- *  interrupt.  The only exception is detaching pins.  It doesn't matter when they go
470
- *  tristate.
471
- *
472
- *  The LPC1768_PWM_init routine kicks off the MR0 interrupt.  This interrupt is never disabled or
473
- *  delayed.
474
- *
475
- *  The PWM_table_swap flag is set when the firmware has swapped in an updated table.  It is
476
- *  cleared by the ISR during the MR0 interrupt as it completes the swap and accompanying updates.
477
- *  It serves two purposes:
478
- *    1) Tells the ISR that the tables have been swapped
479
- *    2) Keeps the firmware from starting a new update until the previous one has been completed.
480
- *
481
- *  The PWM_MR0_wait flag is set when the firmware is ready to swap in an updated table and cleared by
482
- *  the ISR during the MR0 interrupt.  It is used to avoid delaying the MR0 interrupt when swapping in
483
- *  an updated table.  This avoids glitches in pulse width and/or repetition rate.
484
- *
485
- *  The sequence of events during a write to a PWM channel is:
486
- *    1) Waits until PWM_table_swap flag is false before starting
487
- *    2) Copies the active table into the work table
488
- *    3) Updates the work table
489
- *         NOTES - MR1-MR6 are updated at this time.  The updates aren't put into use until the first
490
- *                 MR0 after the LER register has been written.  The LER register is written during the
491
- *                 table swap process.
492
- *               - The MCR mask is created at this time.  It is not used until the ISR writes the MCR
493
- *                 during the MR0 interrupt in the table swap process.
494
- *    4) Sets the PWM_MR0_wait flag
495
- *    5) ISR clears the PWM_MR0_wait flag during the next MR0 interrupt
496
- *    6) Once the PWM_MR0_wait flag is cleared then the firmware:
497
- *          disables the ISR interrupt
498
- *          swaps the pointers to the tables
499
- *          writes to the LER register
500
- *          sets the PWM_table_swap flag active
501
- *          re-enables the ISR
502
- *     7) On the next interrupt the ISR changes its pointer to the work table which is now the old,
503
- *        unmodified, active table.
504
- *     8) On the next MR0 interrupt the ISR:
505
- *          switches over to the active table
506
- *          clears the PWM_table_swap and PWM_MR0_wait flags
507
- *          updates the MCR register with the possibly new interrupt sources/assignments
508
- *          writes to the PCR register to enable the direct control of the Servo 0, 1 & 3 pins by the PWM1 module
509
- *          sets the PINSEL3 register to function/mode 0x2 for the Servo 0, 1 & 3 pins
510
- *             NOTE - PCR must be set before PINSEL
511
- *          sets the pins controlled by the ISR to their active states
512
- */
513
-
71
+void LPC1768_PWM_init(void);
72
+bool LPC1768_PWM_attach_pin(pin_t pin, uint32_t min = 1, uint32_t max = (LPC_PWM1_MR0 - MR0_MARGIN), uint8_t servo_index = 0xff);
73
+void LPC1768_PWM_update_map_MR(void);
74
+void LPC1768_PWM_update(void);
75
+bool LPC1768_PWM_write(pin_t pin, uint32_t value);
76
+bool LPC1768_PWM_detach_pin(pin_t pin);
77
+bool useable_hardware_PWM(pin_t pin);

+ 1
- 4
Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.cpp Целия файл

@@ -64,13 +64,10 @@
64 64
 
65 65
 #if HAS_SERVOS && defined(TARGET_LPC1768)
66 66
 
67
+  #include "LPC1768_PWM.h"
67 68
   #include "LPC1768_Servo.h"
68 69
   #include "servo_private.h"
69 70
 
70
-  extern bool LPC1768_PWM_attach_pin(uint8_t, uint32_t, uint32_t, uint8_t);
71
-  extern bool LPC1768_PWM_write(uint8_t, uint32_t);
72
-  extern bool LPC1768_PWM_detach_pin(uint8_t);
73
-
74 71
   ServoInfo_t servo_info[MAX_SERVOS];                  // static array of servo info structures
75 72
   uint8_t ServoCount = 0;                              // the total number of attached servos
76 73
 

+ 2
- 3
Marlin/src/HAL/HAL_LPC1768/SoftwareSerial.cpp Целия файл

@@ -40,7 +40,6 @@ http://arduiniana.org.
40 40
 #include <stdarg.h>
41 41
 #include "arduino.h"
42 42
 #include "pinmapping.h"
43
-#include "pinmap_re_arm.h"
44 43
 #include "fastio.h"
45 44
 #include "SoftwareSerial.h"
46 45
 
@@ -253,8 +252,8 @@ void SoftwareSerial::setRX(uint8_t rx)
253 252
   //if (!_inverse_logic)
254 253
   // digitalWrite(rx, HIGH);
255 254
   _receivePin = rx;
256
-  _receivePort = pin_map[rx].port;
257
-  _receivePortPin = pin_map[rx].pin;
255
+  _receivePort = LPC1768_PIN_PORT(rx);
256
+  _receivePortPin = LPC1768_PIN_PIN(rx);
258 257
 /*  GPIO_T * rxPort = digitalPinToPort(rx);
259 258
   _receivePortRegister = portInputRegister(rxPort);
260 259
   _receiveBitMask = digitalPinToBitMask(rx);*/

+ 4
- 4
Marlin/src/HAL/HAL_LPC1768/WInterrupts.cpp Целия файл

@@ -54,8 +54,8 @@ void attachInterrupt(const uint32_t pin, void (*callback)(void), uint32_t mode)
54 54
     __initialize();
55 55
     ++enabled;
56 56
   }
57
-  uint8_t myport = pin_map[pin].port,
58
-          mypin = pin_map[pin].pin;
57
+  uint8_t myport = LPC1768_PIN_PORT(pin),
58
+          mypin = LPC1768_PIN_PIN(pin);
59 59
 
60 60
   if (myport == 0)
61 61
     callbacksP0[mypin] = callback;
@@ -69,8 +69,8 @@ void attachInterrupt(const uint32_t pin, void (*callback)(void), uint32_t mode)
69 69
 void detachInterrupt(const uint32_t pin) {
70 70
   if (!INTERRUPT_PIN(pin)) return;
71 71
 
72
-  const uint8_t myport = pin_map[pin].port,
73
-                mypin = pin_map[pin].pin;
72
+  const uint8_t myport = LPC1768_PIN_PORT(pin),
73
+                mypin = LPC1768_PIN_PIN(pin);
74 74
 
75 75
   // Disable interrupt
76 76
   GpioDisableInt(myport, mypin);

+ 18
- 21
Marlin/src/HAL/HAL_LPC1768/arduino.cpp Целия файл

@@ -23,6 +23,7 @@
23 23
 #ifdef TARGET_LPC1768
24 24
 
25 25
 #include "../../inc/MarlinConfig.h"
26
+#include "LPC1768_PWM.h"
26 27
 
27 28
 #include <lpc17xx_pinsel.h>
28 29
 
@@ -70,26 +71,26 @@ extern "C" void delay(const int msec) {
70 71
 
71 72
 // IO functions
72 73
 // As defined by Arduino INPUT(0x0), OUPUT(0x1), INPUT_PULLUP(0x2)
73
-void pinMode(uint8_t pin, uint8_t mode) {
74
-  if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
74
+void pinMode(pin_t pin, uint8_t mode) {
75
+  if (!VALID_PIN(pin))
75 76
     return;
76 77
 
77
-  PINSEL_CFG_Type config = { pin_map[pin].port,
78
-                             pin_map[pin].pin,
78
+  PINSEL_CFG_Type config = { LPC1768_PIN_PORT(pin),
79
+                             LPC1768_PIN_PIN(pin),
79 80
                              PINSEL_FUNC_0,
80 81
                              PINSEL_PINMODE_TRISTATE,
81 82
                              PINSEL_PINMODE_NORMAL };
82 83
   switch(mode) {
83 84
   case INPUT:
84
-    LPC_GPIO(pin_map[pin].port)->FIODIR &= ~LPC_PIN(pin_map[pin].pin);
85
+    LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
85 86
     PINSEL_ConfigPin(&config);
86 87
     break;
87 88
   case OUTPUT:
88
-    LPC_GPIO(pin_map[pin].port)->FIODIR |=  LPC_PIN(pin_map[pin].pin);
89
+    LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR |=  LPC_PIN(LPC1768_PIN_PIN(pin));
89 90
     PINSEL_ConfigPin(&config);
90 91
     break;
91 92
   case INPUT_PULLUP:
92
-    LPC_GPIO(pin_map[pin].port)->FIODIR &= ~LPC_PIN(pin_map[pin].pin);
93
+    LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
93 94
     config.Pinmode = PINSEL_PINMODE_PULLUP;
94 95
     PINSEL_ConfigPin(&config);
95 96
     break;
@@ -98,14 +99,14 @@ void pinMode(uint8_t pin, uint8_t mode) {
98 99
   }
99 100
 }
100 101
 
101
-void digitalWrite(uint8_t pin, uint8_t pin_status) {
102
-  if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
102
+void digitalWrite(pin_t pin, uint8_t pin_status) {
103
+  if (!VALID_PIN(pin))
103 104
     return;
104 105
 
105 106
   if (pin_status)
106
-    LPC_GPIO(pin_map[pin].port)->FIOSET = LPC_PIN(pin_map[pin].pin);
107
+    LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOSET = LPC_PIN(LPC1768_PIN_PIN(pin));
107 108
   else
108
-    LPC_GPIO(pin_map[pin].port)->FIOCLR = LPC_PIN(pin_map[pin].pin);
109
+    LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOCLR = LPC_PIN(LPC1768_PIN_PIN(pin));
109 110
 
110 111
   pinMode(pin, OUTPUT);  // Set pin mode on every write (Arduino version does this)
111 112
 
@@ -118,23 +119,19 @@ void digitalWrite(uint8_t pin, uint8_t pin_status) {
118 119
      */
119 120
 }
120 121
 
121
-bool digitalRead(uint8_t pin) {
122
-  if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF) {
122
+bool digitalRead(pin_t pin) {
123
+  if (!VALID_PIN(pin)) {
123 124
     return false;
124 125
   }
125
-  return LPC_GPIO(pin_map[pin].port)->FIOPIN & LPC_PIN(pin_map[pin].pin) ? 1 : 0;
126
+  return LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOPIN & LPC_PIN(LPC1768_PIN_PIN(pin)) ? 1 : 0;
126 127
 }
127 128
 
128
-void analogWrite(uint8_t pin, int pwm_value) {  // 1 - 254: pwm_value, 0: LOW, 255: HIGH
129
-
130
-  extern bool LPC1768_PWM_attach_pin(uint8_t, uint32_t, uint32_t, uint8_t);
131
-  extern bool LPC1768_PWM_write(uint8_t, uint32_t);
132
-  extern bool LPC1768_PWM_detach_pin(uint8_t);
129
+void analogWrite(pin_t pin, int pwm_value) {  // 1 - 254: pwm_value, 0: LOW, 255: HIGH
133 130
   #define MR0_MARGIN 200       // if channel value too close to MR0 the system locks up
134 131
 
135 132
   static bool out_of_PWM_slots = false;
136 133
 
137
-  if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
134
+  if (!VALID_PIN(pin))
138 135
     return;
139 136
 
140 137
   uint value = MAX(MIN(pwm_value, 255), 0);
@@ -155,7 +152,7 @@ void analogWrite(uint8_t pin, int pwm_value) {  // 1 - 254: pwm_value, 0: LOW, 2
155 152
 
156 153
 extern bool HAL_adc_finished();
157 154
 
158
-uint16_t analogRead(uint8_t adc_pin) {
155
+uint16_t analogRead(pin_t adc_pin) {
159 156
   HAL_adc_start_conversion(adc_pin);
160 157
   while (!HAL_adc_finished());  // Wait for conversion to finish
161 158
   return HAL_adc_get_result();

+ 6
- 6
Marlin/src/HAL/HAL_LPC1768/fastio.h Целия файл

@@ -45,15 +45,15 @@ bool useable_hardware_PWM(uint8_t pin);
45 45
 #define LPC_PIN(pin)            (1UL << pin)
46 46
 #define LPC_GPIO(port)          ((volatile LPC_GPIO_TypeDef *)(LPC_GPIO0_BASE + LPC_PORT_OFFSET * port))
47 47
 
48
-#define SET_DIR_INPUT(IO)       (LPC_GPIO(DIO ## IO ## _PORT)->FIODIR &= ~LPC_PIN(DIO ## IO ##_PIN))
49
-#define SET_DIR_OUTPUT(IO)      (LPC_GPIO(DIO ## IO ## _PORT)->FIODIR |=  LPC_PIN(DIO ## IO ##_PIN))
48
+#define SET_DIR_INPUT(IO)       (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(IO)))
49
+#define SET_DIR_OUTPUT(IO)      (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIODIR |=  LPC_PIN(LPC1768_PIN_PIN(IO)))
50 50
 
51
-#define SET_MODE(IO, mode)      (pin_mode((DIO ## IO ## _PORT, DIO ## IO ## _PIN), mode))
51
+#define SET_MODE(IO, mode)      (pin_mode((LPC1768_PIN_PORT(IO), LPC1768_PIN_PIN(IO)), mode))
52 52
 
53
-#define WRITE_PIN_SET(IO)       (LPC_GPIO(DIO ## IO ## _PORT)->FIOSET = LPC_PIN(DIO ## IO ##_PIN))
54
-#define WRITE_PIN_CLR(IO)       (LPC_GPIO(DIO ## IO ## _PORT)->FIOCLR = LPC_PIN(DIO ## IO ##_PIN))
53
+#define WRITE_PIN_SET(IO)       (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIOSET = LPC_PIN(LPC1768_PIN_PIN(IO)))
54
+#define WRITE_PIN_CLR(IO)       (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIOCLR = LPC_PIN(LPC1768_PIN_PIN(IO)))
55 55
 
56
-#define READ_PIN(IO)            ((LPC_GPIO(DIO ## IO ## _PORT)->FIOPIN & LPC_PIN(DIO ## IO ##_PIN)) ? 1 : 0)
56
+#define READ_PIN(IO)            ((LPC_GPIO(LPC1768_PIN_PORT(IO))->FIOPIN & LPC_PIN(LPC1768_PIN_PIN(IO))) ? 1 : 0)
57 57
 #define WRITE_PIN(IO, v)        ((v) ? WRITE_PIN_SET(IO) : WRITE_PIN_CLR(IO))
58 58
 
59 59
 /**

+ 1
- 1
Marlin/src/HAL/HAL_LPC1768/include/Wire.h Целия файл

@@ -21,7 +21,7 @@
21 21
 
22 22
 // Modified for use with the mcp4451 digipot routine
23 23
 
24
-#if defined(TARGET_LPC1768)
24
+#ifdef TARGET_LPC1768
25 25
 
26 26
 #ifndef TwoWire_h
27 27
 #define TwoWire_h

+ 8
- 5
Marlin/src/HAL/HAL_LPC1768/include/arduino.h Целия файл

@@ -26,6 +26,8 @@
26 26
 #include <stdint.h>
27 27
 #include <math.h>
28 28
 
29
+#include "../pinmapping.h"
30
+
29 31
 #define LOW          0x00
30 32
 #define HIGH         0x01
31 33
 #define CHANGE       0x02
@@ -83,6 +85,7 @@ extern "C" void GpioDisableInt(uint32_t port, uint32_t pin);
83 85
 #define pgm_read_word(addr)       pgm_read_word_near(addr)
84 86
 #define pgm_read_dword(addr)      pgm_read_dword_near(addr)
85 87
 
88
+#define memcpy_P memcpy
86 89
 #define sprintf_P sprintf
87 90
 #define strstr_P strstr
88 91
 #define strncpy_P strncpy
@@ -99,11 +102,11 @@ void delayMicroseconds(unsigned long);
99 102
 uint32_t millis();
100 103
 
101 104
 //IO functions
102
-void pinMode(uint8_t, uint8_t);
103
-void digitalWrite(uint8_t, uint8_t);
104
-bool digitalRead(uint8_t);
105
-void analogWrite(uint8_t, int);
106
-uint16_t analogRead(uint8_t);
105
+void pinMode(pin_t, uint8_t);
106
+void digitalWrite(pin_t, uint8_t);
107
+bool digitalRead(pin_t);
108
+void analogWrite(pin_t, int);
109
+uint16_t analogRead(pin_t);
107 110
 
108 111
 // EEPROM
109 112
 void eeprom_write_byte(unsigned char *pos, unsigned char value);

+ 1
- 1
Marlin/src/HAL/HAL_LPC1768/include/digipot_mcp4451_I2C_routines.c Целия файл

@@ -25,7 +25,7 @@
25 25
 
26 26
 
27 27
 
28
-#if defined(TARGET_LPC1768)
28
+#ifdef TARGET_LPC1768
29 29
 
30 30
   #ifdef __cplusplus
31 31
     extern "C" {

+ 1
- 2
Marlin/src/HAL/HAL_LPC1768/lpc1768_flag_script.py Целия файл

@@ -22,8 +22,7 @@ if __name__ == "__main__":
22 22
 
23 23
                     "-MMD",
24 24
                     "-MP",
25
-                    "-DTARGET_LPC1768",
26
-                    "-DIS_REARM"
25
+                    "-DTARGET_LPC1768"
27 26
                   ])
28 27
 
29 28
   for i in range(1, len(sys.argv)):

+ 0
- 1
Marlin/src/HAL/HAL_LPC1768/main.cpp Целия файл

@@ -100,7 +100,6 @@ int main(void) {
100 100
 
101 101
   HAL_timer_init();
102 102
 
103
-  extern void LPC1768_PWM_init();
104 103
   LPC1768_PWM_init();
105 104
 
106 105
   setup();

+ 4
- 3
Marlin/src/HAL/HAL_LPC1768/persistent_store_impl.cpp Целия файл

@@ -50,7 +50,8 @@ bool access_start() {
50 50
   if (res) MSC_Release_Lock();
51 51
 
52 52
   if (res == FR_OK) {
53
-    uint16_t bytes_written, file_size = f_size(&eeprom_file);
53
+    UINT bytes_written;
54
+    FSIZE_t file_size = f_size(&eeprom_file);
54 55
     f_lseek(&eeprom_file, file_size);
55 56
     while (file_size <= E2END && res == FR_OK) {
56 57
       res = f_write(&eeprom_file, &eeprom_erase_value, 1, &bytes_written);
@@ -99,7 +100,7 @@ bool access_finish() {
99 100
 
100 101
 bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
101 102
   FRESULT s;
102
-  uint16_t bytes_written = 0;
103
+  UINT bytes_written = 0;
103 104
 
104 105
   s = f_lseek(&eeprom_file, pos);
105 106
   if (s) {
@@ -128,7 +129,7 @@ bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
128 129
 }
129 130
 
130 131
 bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) {
131
-  uint16_t bytes_read = 0;
132
+  UINT bytes_read = 0;
132 133
   FRESULT s;
133 134
   s = f_lseek(&eeprom_file, pos);
134 135
   if ( s ) {

+ 0
- 464
Marlin/src/HAL/HAL_LPC1768/pinmap_re_arm.h Целия файл

@@ -1,464 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
- *
21
- */
22
-
23
-#ifndef __PINMAP_RE_ARM_H__
24
-#define __PINMAP_RE_ARM_H__
25
-
26
-// ******************
27
-// Runtime pinmapping
28
-// ******************
29
-
30
-#if SERIAL_PORT == 0
31
-  #define NUM_ANALOG_INPUTS 6
32
-#else
33
-  #define NUM_ANALOG_INPUTS 8
34
-#endif
35
-
36
-const adc_pin_data adc_pin_map[] = {
37
-  {0, 23, 0},         //A0 (T0) - D67 - TEMP_0_PIN
38
-  {0, 24, 1},         //A1 (T1) - D68 - TEMP_BED_PIN
39
-  {0, 25, 2},         //A2 (T2) - D69 - TEMP_1_PIN
40
-  {0, 26, 3},         //A3 - D63
41
-  {1, 30, 4},         //A4 - D37 - BUZZER_PIN
42
-  {1, 31, 5},         //A5 - D49 - SD_DETECT_PIN
43
-  #if SERIAL_PORT != 0
44
-    {0,  3, 6},       //A6 - D0  - RXD0
45
-    {0,  2, 7}        //A7 - D1  - TXD0
46
-  #endif
47
-};
48
-
49
-constexpr FORCE_INLINE int8_t analogInputToDigitalPin(int8_t p) {
50
-  return (p == 0 ? 67:
51
-          p == 1 ? 68:
52
-          p == 2 ? 69:
53
-          p == 3 ? 63:
54
-          p == 4 ? 37:
55
-          p == 5 ? 49:
56
-          #if SERIAL_PORT != 0
57
-            p == 6 ?  0:
58
-            p == 7 ?  1:
59
-          #endif
60
-          -1);
61
-}
62
-
63
-constexpr FORCE_INLINE int8_t DIGITAL_PIN_TO_ANALOG_PIN(int8_t p) {
64
-  return (p == 67 ? 0:
65
-          p == 68 ? 1:
66
-          p == 69 ? 2:
67
-          p == 63 ? 3:
68
-          p == 37 ? 4:
69
-          p == 49 ? 5:
70
-          #if SERIAL_PORT != 0
71
-            p == 0  ? 6:
72
-            p == 1  ? 7:
73
-          #endif
74
-          -1);
75
-}
76
-
77
-#define NUM_DIGITAL_PINS 84
78
-
79
-#define VALID_PIN(r)  (r <   0 ? 0 :\
80
-                       r ==  7 ? 0 :\
81
-                       r == 17 ? 0 :\
82
-                       r == 22 ? 0 :\
83
-                       r == 23 ? 0 :\
84
-                       r == 25 ? 0 :\
85
-                       r == 27 ? 0 :\
86
-                       r == 29 ? 0 :\
87
-                       r == 32 ? 0 :\
88
-                       r == 39 ? 0 :\
89
-                       r == 40 ? 0 :\
90
-                       r == 42 ? 0 :\
91
-                       r == 43 ? 0 :\
92
-                       r == 44 ? 0 :\
93
-                       r == 45 ? 0 :\
94
-                       r == 47 ? 0 :\
95
-                       r == 64 ? 0 :\
96
-                       r == 65 ? 0 :\
97
-                       r == 66 ? 0 :\
98
-                       r >= NUM_DIGITAL_PINS ? 0 : 1)
99
-
100
-#define PWM_PIN(r)  (r <   0 ? 0 :\
101
-                       r ==  3 ? 1 :\
102
-                       r ==  4 ? 1 :\
103
-                       r ==  6 ? 1 :\
104
-                       r ==  9 ? 1 :\
105
-                       r == 10 ? 1 :\
106
-                       r == 11 ? 1 :\
107
-                       r == 14 ? 1 :\
108
-                       r == 26 ? 1 :\
109
-                       r == 46 ? 1 :\
110
-                       r == 53 ? 1 :\
111
-                       r == 54 ? 1 :\
112
-                       r == 60 ? 1 : 0)
113
-
114
-#define NUM_INTERRUPT_PINS 35
115
-
116
-#define INTERRUPT_PIN(r)  ( r< 0  ? 0 :\
117
-                        r == 0  ? 1 :\
118
-                        r == 1  ? 1 :\
119
-                        r == 8  ? 1 :\
120
-                        r == 9  ? 1 :\
121
-                        r == 10 ? 1 :\
122
-                        r == 12 ? 1 :\
123
-                        r == 16 ? 1 :\
124
-                        r == 20 ? 1 :\
125
-                        r == 21 ? 1 :\
126
-                        r == 24 ? 1 :\
127
-                        r == 25 ? 1 :\
128
-                        r == 26 ? 1 :\
129
-                        r == 28 ? 1 :\
130
-                        r == 34 ? 1 :\
131
-                        r == 35 ? 1 :\
132
-                        r == 36 ? 1 :\
133
-                        r == 38 ? 1 :\
134
-                        r == 46 ? 1 :\
135
-                        r == 48 ? 1 :\
136
-                        r == 50 ? 1 :\
137
-                        r == 51 ? 1 :\
138
-                        r == 52 ? 1 :\
139
-                        r == 54 ? 1 :\
140
-                        r == 55 ? 1 :\
141
-                        r == 56 ? 1 :\
142
-                        r == 57 ? 1 :\
143
-                        r == 58 ? 1 :\
144
-                        r == 59 ? 1 :\
145
-                        r == 60 ? 1 :\
146
-                        r == 61 ? 1 :\
147
-                        r == 62 ? 1 :\
148
-                        r == 63 ? 1 :\
149
-                        r == 67 ? 1 :\
150
-                        r == 68 ? 1 :\
151
-                        r == 69 ? 1 : 0)
152
-                        /*Internal SD Card */
153
-                        /*r == 80 ? 1 :\
154
-                        r == 81 ? 1 :\
155
-                        r == 82 ? 1 :\
156
-                        r == 83 ? 1 :\*/
157
-
158
-const pin_data pin_map[] = { // pin map for variable pin function
159
-  {0,3},        //  DIO0   RXD0             A6               J4-4                           AUX-1
160
-  {0,2},        //  DIO1   TXD0             A7               J4-5                           AUX-1
161
-  {1,25},       //  DIO2   X_MAX_PIN                          10K PULLUP TO 3.3v, 1K SERIES
162
-  {1,24},       //  DIO3   X_MIN_PIN                          10K PULLUP TO 3.3v, 1K SERIES
163
-  {1,18},       //  DIO4   SERVO3_PIN        FIL_RUNOUT_PIN   5V output, PWM
164
-  {1,19},       //  DIO5   SERVO2_PIN
165
-  {1,21},       //  DIO6   SERVO1_PIN       J5-1
166
-  {0xFF,0xFF},  //  DIO7   N/C
167
-  {2,7},        //  DIO8   RAMPS_D8_PIN
168
-  {2,4},        //  DIO9   RAMPS_D9_PIN     PWM
169
-  {2,5},        //  DIO10  RAMPS_D10_PIN    PWM
170
-  {1,20},       //  DIO11  SERVO0_PIN
171
-  {2,12},       //  DIO12  PS_ON_PIN
172
-  {4,28},       //  DIO13  LED_PIN
173
-  {1,26},       //  DIO14  Y_MIN_PIN                          10K PULLUP TO 3.3v, 1K SERIES
174
-  {1,27},       //  DIO15  Y_MAX_PIN                          10K PULLUP TO 3.3v, 1K SERIES
175
-  {0,16},       //  DIO16  LCD_PINS_RS      J3-7
176
-  {0xFF,0xFF},  //  DIO17  LCD_PINS_ENABLE   MOSI_PIN(MOSI0)  J3-10                          AUX-3
177
-  {1,29},       //  DIO18  Z_MIN_PIN                          10K PULLUP TO 3.3v, 1K SERIES
178
-  {1,28},       //  DIO19  Z_MAX_PIN                          10K PULLUP TO 3.3v, 1K SERIES
179
-  {0,0},        //  DIO20  SCA
180
-  {0,1},        //  DIO21  SCL
181
-  {0xFF,0xFF},  //  DIO22  N/C
182
-  {0xFF,0xFF},  //  DIO23  LCD_PINS_D4       SCK_PIN(SCLK0)   J3-9                           AUX-3
183
-  {0,4},        //  DIO24  E0_ENABLE_PIN
184
-  {0xFF,0xFF},  //  DIO25  N/C
185
-  {2,0},        //  DIO26  E0_STEP_PIN
186
-  {0xFF,0xFF},  //  DIO27  N/C
187
-  {0,5},        //  DIO28  E0_DIR_PIN
188
-  {0xFF,0xFF},  //  DIO29  N/C
189
-  {4,29},       //  DIO30  E1_ENABLE_PIN
190
-  {3,26},       //  DIO31  BTN_EN1
191
-  {0xFF,0xFF},  //  DIO32  N/C
192
-  {3,25},       //  DIO33  BTN_EN2          J3-4
193
-  {2,13},       //  DIO34  E1_DIR_PIN
194
-  {2,11},       //  DIO35  BTN_ENC          J3-3
195
-  {2,8},        //  DIO36  E1_STEP_PIN
196
-  {1,30},       //  DIO37  BEEPER_PIN       A4                                              not 5V tolerant
197
-  {0,10},       //  DIO38  X_ENABLE_PIN
198
-  {0xFF,0xFF},  //  DIO39  N/C
199
-  {0xFF,0xFF},  //  DIO40  N/C
200
-  {1,22},       //  DIO41  KILL_PIN         J5-4
201
-  {0xFF,0xFF},  //  DIO42  N/C
202
-  {0xFF,0xFF},  //  DIO43  N/C
203
-  {0xFF,0xFF},  //  DIO44  N/C
204
-  {0xFF,0xFF},  //  DIO45  N/C
205
-  {2,3},        //  DIO46  Z_STEP_PIN
206
-  {0xFF,0xFF},  //  DIO47  N/C
207
-  {0,22},       //  DIO48  Z_DIR_PIN
208
-  {1,31},       //  DIO49  SD_DETECT_PIN    A5               J3-1                           not 5V tolerant
209
-  {0,17},       //  DIO50  MISO_PIN(MISO0)                                                   AUX-3
210
-  {0,18},       //  DIO51  MOSI_PIN(MOSI0)   LCD_PINS_ENABLE  J3-10                          AUX-3
211
-  {0,15},       //  DIO52  SCK_PIN(SCLK0)    LCD_PINS_D4      J3-9                           AUX-3
212
-  {1,23},       //  DIO53  SDSS(SSEL0)      J3-5                                             AUX-3
213
-  {2,1},        //  DIO54  X_STEP_PIN
214
-  {0,11},       //  DIO55  X_DIR_PIN
215
-  {0,19},       //  DIO56  Y_ENABLE_PIN
216
-  {0,27},       //  DIO57                   AUX-1             open collector
217
-  {0,28},       //  DIO58                   AUX-1             open collector
218
-  {2,6},        //  DIO59  LCD_A0           J3-8                                             AUX-2
219
-  {2,2},        //  DIO60  Y_STEP_PIN
220
-  {0,20},       //  DIO61  Y_DIR_PIN
221
-  {0,21},       //  DIO62  Z_ENABLE_PIN
222
-  {0,26},       //  DIO63  AUX-2             A3               J5-3                           AUX-2
223
-  {0xFF,0xFF},  //  DIO64  N/C
224
-  {0xFF,0xFF},  //  DIO65  N/C
225
-  {0xFF,0xFF},  //  DIO66  N/C
226
-  {0,23},       //  DIO67  TEMP_0_PIN       A0
227
-  {0,24},       //  DIO68  TEMP_BED_PIN     A1
228
-  {0,25},       //  DIO69  TEMP_1_PIN       A2
229
-  {1,16},       //  DIO70                   J12-3             ENET_MOC
230
-  {1,17},       //  DIO71                   J12-4             ENET_MDIO
231
-  {1,15},       //  DIO72                   J12-5             REF_CLK
232
-  {1,14},       //  DIO73                   J12-6             ENET_RX_ER
233
-  {1,9},        //  DIO74                   J12-7             ENET_RXD0
234
-  {1,10},       //  DIO75                   J12-8             ENET_RXD1
235
-  {1,8},        //  DIO76                   J12-9             ENET_CRS
236
-  {1,4},        //  DIO77                   J12-10            ENET_TX_EN
237
-  {1,0},        //  DIO78                   J12-11            ENET_TXD0
238
-  {1,1},        //  DIO79                   J12-12            ENET_TXD1
239
-  {0,14},       //  DIO80                   MKS-SBASE	J7-6 & EXP1-5
240
-  {0,7},        //  DIO81  SD-SCK           MKS-SBASE	on board SD card and EXP2-2
241
-  {0,8},        //  DIO82  SD-MISO          MKS-SBASE	on board SD card and EXP2-1
242
-  {0,9},        //  DIO83  SD-MOSI          MKS-SBASE 	n board SD card and EXP2-6
243
-//  {0,6},        //  DIO84  SD-CS            on board SD card
244
-
245
-};
246
-
247
-// ***********************
248
-// Preprocessor pinmapping
249
-// ***********************
250
-
251
-//#define RXD0                      0  //              A16               J4-4                           AUX-1
252
-#define DIO0_PORT 0
253
-#define DIO0_PIN 3
254
-//#define TXD0                      1  //              A17               J4-5                           AUX-1
255
-#define DIO1_PORT 0
256
-#define DIO1_PIN 2
257
-//#define X_MAX_PIN                 2  //                           10K PULLUP TO 3.3v, 1K SERIES
258
-#define DIO2_PORT 1
259
-#define DIO2_PIN 25
260
-//#define X_MIN_PIN                 3  //                           10K PULLUP TO 3.3v, 1K SERIES
261
-#define DIO3_PORT 1
262
-#define DIO3_PIN 24
263
-//#define SERVO3_PIN                4  //         FIL_RUNOUT_PIN   5V output, PWM
264
-#define DIO4_PORT 1
265
-#define DIO4_PIN 18
266
-//#define SERVO2_PIN                5  //
267
-#define DIO5_PORT 1
268
-#define DIO5_PIN 19
269
-//#define SERVO1_PIN                6  //        J5-1
270
-#define DIO6_PORT 1
271
-#define DIO6_PIN 21
272
-//#define RAMPS_D8_PIN              8  //
273
-#define DIO8_PORT 2
274
-#define DIO8_PIN 7
275
-//#define RAMPS_D9_PIN              9  //      PWM
276
-#define DIO9_PORT 2
277
-#define DIO9_PIN 4
278
-//#define RAMPS_D10_PIN             10  //     PWM
279
-#define DIO10_PORT 2
280
-#define DIO10_PIN 5
281
-//#define SERVO0_PIN                11  //
282
-#define DIO11_PORT 1
283
-#define DIO11_PIN 20
284
-//#define PS_ON_PIN                 12  //
285
-#define DIO12_PORT 2
286
-#define DIO12_PIN 12
287
-//#define LED_PIN                   13  //
288
-#define DIO13_PORT 4
289
-#define DIO13_PIN 28
290
-//#define Y_MIN_PIN                 14  //                           10K PULLUP TO 3.3v, 1K SERIES
291
-#define DIO14_PORT 1
292
-#define DIO14_PIN 26
293
-//#define Y_MAX_PIN                 15  //                           10K PULLUP TO 3.3v, 1K SERIES
294
-#define DIO15_PORT 1
295
-#define DIO15_PIN 27
296
-//#define LCD_PINS_RS               16  //       J3-7
297
-#define DIO16_PORT 0
298
-#define DIO16_PIN 16
299
-//#define Z_MIN_PIN                 18  //                           10K PULLUP TO 3.3v, 1K SERIES
300
-#define DIO18_PORT 1
301
-#define DIO18_PIN 29
302
-//#define Z_MAX_PIN                 19  //                           10K PULLUP TO 3.3v, 1K SERIES
303
-#define DIO19_PORT 1
304
-#define DIO19_PIN 28
305
-//#define SCA                       20  //
306
-#define DIO20_PORT 0
307
-#define DIO20_PIN 0
308
-//#define SCL                       21  //
309
-#define DIO21_PORT 0
310
-#define DIO21_PIN 1
311
-//#define E0_ENABLE_PIN             24  //
312
-#define DIO24_PORT 0
313
-#define DIO24_PIN 4
314
-//#define E0_STEP_PIN               26  //
315
-#define DIO26_PORT 2
316
-#define DIO26_PIN 0
317
-//#define E0_DIR_PIN                28  //
318
-#define DIO28_PORT 0
319
-#define DIO28_PIN 5
320
-//#define E1_ENABLE_PIN             30  //
321
-#define DIO30_PORT 4
322
-#define DIO30_PIN 29
323
-//#define BTN_EN1                   31  //
324
-#define DIO31_PORT 3
325
-#define DIO31_PIN 26
326
-//#define BTN_EN2                   33  //           J3-4
327
-#define DIO33_PORT 3
328
-#define DIO33_PIN 25
329
-//#define E1_DIR_PIN                34  //
330
-#define DIO34_PORT 2
331
-#define DIO34_PIN 13
332
-//#define BTN_ENC                   35  //           J3-3
333
-#define DIO35_PORT 2
334
-#define DIO35_PIN 11
335
-//#define E1_STEP_PIN               36  //
336
-#define DIO36_PORT 2
337
-#define DIO36_PIN 8
338
-//#define BEEPER_PIN                37  //        A18                                              not 5V tolerant
339
-#define DIO37_PORT 1
340
-#define DIO37_PIN 30
341
-//#define X_ENABLE_PIN              38  //
342
-#define DIO38_PORT 0
343
-#define DIO38_PIN 10
344
-//#define KILL_PIN                  41  //          J5-4
345
-#define DIO41_PORT 1
346
-#define DIO41_PIN 22
347
-//#define Z_STEP_PIN                46  //
348
-#define DIO46_PORT 2
349
-#define DIO46_PIN 3
350
-//#define Z_DIR_PIN                 48  //
351
-#define DIO48_PORT 0
352
-#define DIO48_PIN 22
353
-//#define SD_DETECT_PIN             49  //     A19               J3-1                           not 5V tolerant
354
-#define DIO49_PORT 1
355
-#define DIO49_PIN 31
356
-//#define MISO_PIN(MISO0)           50  //                                                    AUX-3
357
-#define DIO50_PORT 0
358
-#define DIO50_PIN 17
359
-//#define MOSI_PIN(MOSI0)           51  //    LCD_PINS_ENABLE  J3-10                          AUX-3
360
-#define DIO51_PORT 0
361
-#define DIO51_PIN 18
362
-//#define SCK_PIN(SCLK0)            52  //     LCD_PINS_D4      J3-9                           AUX-3
363
-#define DIO52_PORT 0
364
-#define DIO52_PIN 15
365
-//#define SDSS(SSEL0)               53  //       J3-5                                             AUX-3
366
-#define DIO53_PORT 1
367
-#define DIO53_PIN 23
368
-//#define X_STEP_PIN                54  //
369
-#define DIO54_PORT 2
370
-#define DIO54_PIN 1
371
-//#define X_DIR_PIN                 55  //
372
-#define DIO55_PORT 0
373
-#define DIO55_PIN 11
374
-//#define Y_ENABLE_PIN              56  //
375
-#define DIO56_PORT 0
376
-#define DIO56_PIN 19
377
-//#define AUX-1                     57  //              open collector
378
-#define DIO57_PORT 0
379
-#define DIO57_PIN 27
380
-//#define AUX-1                     58  //              open collector
381
-#define DIO58_PORT 0
382
-#define DIO58_PIN 28
383
-//#define LCD_A0                    59  //            J3-8                                             AUX-2
384
-#define DIO59_PORT 2
385
-#define DIO59_PIN 6
386
-//#define Y_STEP_PIN                60  //
387
-#define DIO60_PORT 2
388
-#define DIO60_PIN 2
389
-//#define Y_DIR_PIN                 61  //
390
-#define DIO61_PORT 0
391
-#define DIO61_PIN 20
392
-//#define Z_ENABLE_PIN              62  //
393
-#define DIO62_PORT 0
394
-#define DIO62_PIN 21
395
-//#define AUX-2                     63  //              A9               J5-3                           AUX-2
396
-#define DIO63_PORT 0
397
-#define DIO63_PIN 26
398
-//#define TEMP_0_PIN                67  //        A13
399
-#define DIO67_PORT 0
400
-#define DIO67_PIN 23
401
-//#define TEMP_BED_PIN              68  //      A14
402
-#define DIO68_PORT 0
403
-#define DIO68_PIN 24
404
-//#define TEMP_1_PIN                69  //        A15
405
-#define DIO69_PORT 0
406
-#define DIO69_PIN 25
407
-//#define J12-3                     70  //              ENET_MOC
408
-#define DIO70_PORT 1
409
-#define DIO70_PIN 16
410
-//#define J12-4                     71  //              ENET_MDIO
411
-#define DIO71_PORT 1
412
-#define DIO71_PIN 17
413
-//#define J12-5                     72  //              REF_CLK
414
-#define DIO72_PORT 1
415
-#define DIO72_PIN 15
416
-//#define J12-6                     73  //              ENET_RX_ER
417
-#define DIO73_PORT 1
418
-#define DIO73_PIN 14
419
-//#define J12-7                     74  //              ENET_RXD0
420
-#define DIO74_PORT 1
421
-#define DIO74_PIN 9
422
-//#define J12-8                     75  //              ENET_RXD1
423
-#define DIO75_PORT 1
424
-#define DIO75_PIN 10
425
-//#define J12-9                     76  //              ENET_CRS
426
-#define DIO76_PORT 1
427
-#define DIO76_PIN 8
428
-//#define J12-10                    77  //             ENET_TX_EN
429
-#define DIO77_PORT 1
430
-#define DIO77_PIN 4
431
-//#define J12-11                    78  //             ENET_TXD0
432
-#define DIO78_PORT 1
433
-#define DIO78_PIN 0
434
-//#define J12-12                    79  //             ENET_TXD1
435
-#define DIO79_PORT 1
436
-#define DIO79_PIN 1
437
-//#define J7-6                      80  //             MKS-SBASE	J7-6
438
-#define DIO80_PORT 0
439
-#define DIO80_PIN 14
440
-//#define EXP2-2                    81  //             MKS-SBASE 	on board SD card and EXP2
441
-#define DIO81_PORT 0
442
-#define DIO81_PIN  7
443
-//#define EXP2-1                    82  //             MKS-SBASE 	on board SD card and EXP2
444
-#define DIO82_PORT 0
445
-#define DIO82_PIN  8
446
-//#define EXP2-6                    83  //             MKS-SBASE 	on board SD card and EXP2
447
-#define DIO83_PORT 0
448
-#define DIO83_PIN  9
449
-/**
450
-//#define SD-CS                     81  //             on board SD card
451
-#define DIO81_PORT 0
452
-#define DIO81_PIN 6
453
-//#define SD-SCK                    82  //            on board SD card
454
-#define DIO82_PORT 0
455
-#define DIO82_PIN 7
456
-//#define SD-MISO                   83  //           on board SD card
457
-#define DIO83_PORT 0
458
-#define DIO83_PIN 8
459
-//#define SD-MOSI                   84  //           on board SD card
460
-#define DIO84_PORT 0
461
-#define DIO84_PIN 9
462
-*/
463
-
464
-#endif //__PINMAP_RE_ARM_H__

+ 50
- 0
Marlin/src/HAL/HAL_LPC1768/pinmapping.cpp Целия файл

@@ -0,0 +1,50 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+#ifdef TARGET_LPC1768
24
+
25
+#include "../../inc/MarlinConfig.h"
26
+#include "../../gcode/parser.h"
27
+
28
+int16_t GET_PIN_MAP_INDEX(pin_t pin) {
29
+  const uint8_t pin_port = LPC1768_PIN_PORT(pin),
30
+                pin_pin = LPC1768_PIN_PIN(pin);
31
+  for (size_t i = 0; i < NUM_DIGITAL_PINS; ++i)
32
+    if (LPC1768_PIN_PORT(pin_map[i]) == pin_port && LPC1768_PIN_PIN(pin_map[i]) == pin_pin)
33
+      return i;
34
+
35
+  return -1;
36
+}
37
+
38
+int16_t PARSED_PIN_INDEX(char code, int16_t dval) {
39
+  if (parser.seenval(code)) {
40
+    int port, pin;
41
+    if (sscanf(parser.strval(code), "%d.%d", &port, &pin) == 2)
42
+      for (size_t i = 0; i < NUM_DIGITAL_PINS; ++i)
43
+        if (LPC1768_PIN_PORT(pin_map[i]) == port && LPC1768_PIN_PIN(pin_map[i]) == pin)
44
+          return i;
45
+  }
46
+
47
+  return dval;
48
+}
49
+
50
+#endif // TARGET_LPC1768

+ 187
- 5
Marlin/src/HAL/HAL_LPC1768/pinmapping.h Целия файл

@@ -24,13 +24,195 @@
24 24
 #define __HAL_PINMAPPING_H__
25 25
 #include "../../core/macros.h"
26 26
 
27
-struct pin_data { uint8_t port, pin; };
28
-struct adc_pin_data { uint8_t port, pin, adc; };
27
+typedef int16_t pin_t;
29 28
 
30
-#if ENABLED(IS_REARM)
31
-  #include "pinmap_re_arm.h"
29
+const uint8_t PIN_FEATURE_INTERRUPT = 1 << 0;
30
+const uint8_t PIN_FEATURE_PWM = 1 << 1;
31
+constexpr uint8_t PIN_FEATURE_ADC(const int8_t chan) { return (((chan + 1) & 0b1111) << 2); }
32
+
33
+constexpr pin_t LPC1768_PIN(const uint8_t port, const uint8_t pin, const uint8_t feat = 0) {
34
+  return (((pin_t)feat << 8) | (((pin_t)port & 0x7) << 5) | ((pin_t)pin & 0x1F));
35
+}
36
+
37
+constexpr uint8_t LPC1768_PIN_PORT(const pin_t pin) { return ((uint8_t)((pin >> 5) & 0b111)); }
38
+constexpr uint8_t LPC1768_PIN_PIN(const pin_t pin) { return ((uint8_t)(pin & 0b11111)); }
39
+constexpr bool LPC1768_PIN_INTERRUPT(const pin_t pin) { return (((pin >> 8) & PIN_FEATURE_INTERRUPT) != 0); }
40
+constexpr bool LPC1768_PIN_PWM(const pin_t pin) { return (((pin >> 8) & PIN_FEATURE_PWM) != 0); }
41
+constexpr int8_t LPC1768_PIN_ADC(const pin_t pin) { return (int8_t)((pin >> 8) & 0b1111) - 1; }
42
+
43
+// ******************
44
+// Runtime pinmapping
45
+// ******************
46
+#if SERIAL_PORT != 3
47
+  const pin_t P0_0  = LPC1768_PIN(0,  0, PIN_FEATURE_INTERRUPT);
48
+  const pin_t P0_1  = LPC1768_PIN(0,  1, PIN_FEATURE_INTERRUPT);
49
+#endif
50
+#if SERIAL_PORT != 0
51
+  const pin_t P0_2  = LPC1768_PIN(0,  2, PIN_FEATURE_INTERRUPT | PIN_FEATURE_ADC(7));
52
+  const pin_t P0_3  = LPC1768_PIN(0,  3, PIN_FEATURE_INTERRUPT | PIN_FEATURE_ADC(6));
53
+#endif
54
+const pin_t P0_4  = LPC1768_PIN(0,  4, PIN_FEATURE_INTERRUPT);
55
+const pin_t P0_5  = LPC1768_PIN(0,  5, PIN_FEATURE_INTERRUPT);
56
+const pin_t P0_6  = LPC1768_PIN(0,  6, PIN_FEATURE_INTERRUPT);
57
+const pin_t P0_7  = LPC1768_PIN(0,  7, PIN_FEATURE_INTERRUPT);
58
+const pin_t P0_8  = LPC1768_PIN(0,  8, PIN_FEATURE_INTERRUPT);
59
+const pin_t P0_9  = LPC1768_PIN(0,  9, PIN_FEATURE_INTERRUPT);
60
+#if SERIAL_PORT != 2
61
+  const pin_t P0_10 = LPC1768_PIN(0, 10, PIN_FEATURE_INTERRUPT);
62
+  const pin_t P0_11 = LPC1768_PIN(0, 11, PIN_FEATURE_INTERRUPT);
63
+#endif
64
+#if SERIAL_PORT != 1
65
+  const pin_t P0_15 = LPC1768_PIN(0, 15, PIN_FEATURE_INTERRUPT);
66
+  const pin_t P0_16 = LPC1768_PIN(0, 16, PIN_FEATURE_INTERRUPT);
67
+#endif
68
+const pin_t P0_17 = LPC1768_PIN(0, 17, PIN_FEATURE_INTERRUPT);
69
+const pin_t P0_18 = LPC1768_PIN(0, 18, PIN_FEATURE_INTERRUPT);
70
+const pin_t P0_19 = LPC1768_PIN(0, 19, PIN_FEATURE_INTERRUPT);
71
+const pin_t P0_20 = LPC1768_PIN(0, 20, PIN_FEATURE_INTERRUPT);
72
+const pin_t P0_21 = LPC1768_PIN(0, 21, PIN_FEATURE_INTERRUPT);
73
+const pin_t P0_22 = LPC1768_PIN(0, 22, PIN_FEATURE_INTERRUPT);
74
+const pin_t P0_23 = LPC1768_PIN(0, 23, PIN_FEATURE_INTERRUPT | PIN_FEATURE_ADC(0));
75
+const pin_t P0_24 = LPC1768_PIN(0, 24, PIN_FEATURE_INTERRUPT | PIN_FEATURE_ADC(1));
76
+const pin_t P0_25 = LPC1768_PIN(0, 25, PIN_FEATURE_INTERRUPT | PIN_FEATURE_ADC(2));
77
+const pin_t P0_26 = LPC1768_PIN(0, 26, PIN_FEATURE_INTERRUPT | PIN_FEATURE_ADC(3));
78
+const pin_t P0_27 = LPC1768_PIN(0, 27, PIN_FEATURE_INTERRUPT);
79
+const pin_t P0_28 = LPC1768_PIN(0, 28, PIN_FEATURE_INTERRUPT);
80
+const pin_t P0_29 = LPC1768_PIN(0, 29, PIN_FEATURE_INTERRUPT);
81
+const pin_t P0_30 = LPC1768_PIN(0, 30, PIN_FEATURE_INTERRUPT);
82
+const pin_t P1_0  = LPC1768_PIN(1,  0);
83
+const pin_t P1_1  = LPC1768_PIN(1,  1);
84
+const pin_t P1_4  = LPC1768_PIN(1,  4);
85
+const pin_t P1_8  = LPC1768_PIN(1,  8);
86
+const pin_t P1_9  = LPC1768_PIN(1,  9);
87
+const pin_t P1_10 = LPC1768_PIN(1, 10);
88
+const pin_t P1_14 = LPC1768_PIN(1, 14);
89
+const pin_t P1_15 = LPC1768_PIN(1, 15);
90
+const pin_t P1_16 = LPC1768_PIN(1, 16);
91
+const pin_t P1_17 = LPC1768_PIN(1, 17);
92
+const pin_t P1_18 = LPC1768_PIN(1, 18, PIN_FEATURE_PWM);
93
+const pin_t P1_19 = LPC1768_PIN(1, 19);
94
+const pin_t P1_20 = LPC1768_PIN(1, 20, PIN_FEATURE_PWM);
95
+const pin_t P1_21 = LPC1768_PIN(1, 21, PIN_FEATURE_PWM);
96
+const pin_t P1_22 = LPC1768_PIN(1, 22);
97
+const pin_t P1_23 = LPC1768_PIN(1, 23, PIN_FEATURE_PWM);
98
+const pin_t P1_24 = LPC1768_PIN(1, 24, PIN_FEATURE_PWM);
99
+const pin_t P1_25 = LPC1768_PIN(1, 25);
100
+const pin_t P1_26 = LPC1768_PIN(1, 26, PIN_FEATURE_PWM);
101
+const pin_t P1_27 = LPC1768_PIN(1, 27);
102
+const pin_t P1_28 = LPC1768_PIN(1, 28);
103
+const pin_t P1_29 = LPC1768_PIN(1, 29);
104
+const pin_t P1_30 = LPC1768_PIN(1, 30, PIN_FEATURE_ADC(4));
105
+const pin_t P1_31 = LPC1768_PIN(1, 31, PIN_FEATURE_ADC(5));
106
+const pin_t P2_0  = LPC1768_PIN(2,  0, PIN_FEATURE_INTERRUPT | PIN_FEATURE_PWM);
107
+const pin_t P2_1  = LPC1768_PIN(2,  1, PIN_FEATURE_INTERRUPT | PIN_FEATURE_PWM);
108
+const pin_t P2_2  = LPC1768_PIN(2,  2, PIN_FEATURE_INTERRUPT | PIN_FEATURE_PWM);
109
+const pin_t P2_3  = LPC1768_PIN(2,  3, PIN_FEATURE_INTERRUPT | PIN_FEATURE_PWM);
110
+const pin_t P2_4  = LPC1768_PIN(2,  4, PIN_FEATURE_INTERRUPT | PIN_FEATURE_PWM);
111
+const pin_t P2_5  = LPC1768_PIN(2,  5, PIN_FEATURE_INTERRUPT | PIN_FEATURE_PWM);
112
+const pin_t P2_6  = LPC1768_PIN(2,  6, PIN_FEATURE_INTERRUPT);
113
+const pin_t P2_7  = LPC1768_PIN(2,  7, PIN_FEATURE_INTERRUPT);
114
+const pin_t P2_8  = LPC1768_PIN(2,  8, PIN_FEATURE_INTERRUPT);
115
+const pin_t P2_9  = LPC1768_PIN(2,  9, PIN_FEATURE_INTERRUPT);
116
+const pin_t P2_10 = LPC1768_PIN(2, 10, PIN_FEATURE_INTERRUPT);
117
+const pin_t P2_11 = LPC1768_PIN(2, 11, PIN_FEATURE_INTERRUPT);
118
+const pin_t P2_12 = LPC1768_PIN(2, 12, PIN_FEATURE_INTERRUPT);
119
+const pin_t P2_13 = LPC1768_PIN(2, 13, PIN_FEATURE_INTERRUPT);
120
+const pin_t P3_25 = LPC1768_PIN(3, 25, PIN_FEATURE_PWM);
121
+const pin_t P3_26 = LPC1768_PIN(3, 26, PIN_FEATURE_PWM);
122
+const pin_t P4_28 = LPC1768_PIN(4, 28);
123
+const pin_t P4_29 = LPC1768_PIN(4, 29);
124
+
125
+constexpr bool VALID_PIN(const pin_t p) {
126
+  return (
127
+    #if SERIAL_PORT == 0
128
+      (LPC1768_PIN_PORT(p) == 0 && LPC1768_PIN_PIN(p) <= 1)             ||
129
+      (LPC1768_PIN_PORT(p) == 0 && WITHIN(LPC1768_PIN_PIN(p), 4, 11))   ||
130
+    #elif SERIAL_PORT == 2
131
+      (LPC1768_PIN_PORT(p) == 0 && LPC1768_PIN_PIN(p) <= 9)             ||
132
+    #elif SERIAL_PORT == 3
133
+      (LPC1768_PIN_PORT(p) == 0 && WITHIN(LPC1768_PIN_PIN(p), 2, 11))   ||
134
+    #else
135
+      (LPC1768_PIN_PORT(p) == 0 && LPC1768_PIN_PIN(p) <= 11)            ||
136
+    #endif
137
+    #if SERIAL_PORT == 1
138
+      (LPC1768_PIN_PORT(p) == 0 && WITHIN(LPC1768_PIN_PIN(p), 17, 30))  ||
139
+    #else
140
+      (LPC1768_PIN_PORT(p) == 0 && WITHIN(LPC1768_PIN_PIN(p), 15, 30))  ||
141
+    #endif
142
+    (LPC1768_PIN_PORT(p) == 1 && LPC1768_PIN_PIN(p) == 1)             ||
143
+    (LPC1768_PIN_PORT(p) == 1 && LPC1768_PIN_PIN(p) == 4)             ||
144
+    (LPC1768_PIN_PORT(p) == 1 && WITHIN(LPC1768_PIN_PIN(p), 8, 10))   ||
145
+    (LPC1768_PIN_PORT(p) == 1 && WITHIN(LPC1768_PIN_PIN(p), 14, 31))  ||
146
+    (LPC1768_PIN_PORT(p) == 2 && LPC1768_PIN_PIN(p) <= 13)            ||
147
+    (LPC1768_PIN_PORT(p) == 3 && WITHIN(LPC1768_PIN_PIN(p), 25, 26))  ||
148
+    (LPC1768_PIN_PORT(p) == 4 && WITHIN(LPC1768_PIN_PIN(p), 28, 29))
149
+  );
150
+}
151
+
152
+constexpr bool PWM_PIN(const pin_t p) {
153
+  return (VALID_PIN(p) && LPC1768_PIN_PWM(p));
154
+}
155
+
156
+constexpr bool INTERRUPT_PIN(const pin_t p) {
157
+  return (VALID_PIN(p) && LPC1768_PIN_INTERRUPT(p));
158
+}
159
+
160
+#if SERIAL_PORT == 0
161
+  #define NUM_ANALOG_INPUTS 6
32 162
 #else
33
-  #error "HAL: LPC1768: No defined pin-mapping"
163
+  #define NUM_ANALOG_INPUTS 8
34 164
 #endif
35 165
 
166
+constexpr pin_t adc_pin_table[] = { 
167
+  P0_23, P0_24, P0_25, P0_26, P1_30, P1_31,
168
+  #if SERIAL_PORT != 0
169
+    P0_3, P0_2
170
+  #endif
171
+};
172
+
173
+constexpr pin_t analogInputToDigitalPin(const uint8_t p) {
174
+  return (p < COUNT(adc_pin_table) ? adc_pin_table[p] : -1);
175
+}
176
+
177
+constexpr int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p) {
178
+  return (VALID_PIN(p) ? LPC1768_PIN_ADC(p) : -1);
179
+}
180
+
181
+// P0.6 thru P0.9 are for the onboard SD card
182
+// P0.29 and P0.30 are for the USB port
183
+#define HAL_SENSITIVE_PINS P0_6, P0_7, P0_8, P0_9, P0_29, P0_30
184
+
185
+// Pin map for M43 and M226
186
+const pin_t pin_map[] = {
187
+  #if SERIAL_PORT != 3
188
+    P0_0,  P0_1,
189
+  #endif
190
+  #if SERIAL_PORT != 0
191
+    P0_2,  P0_3,
192
+  #endif
193
+  P0_4,  P0_5,  P0_6,  P0_7,  P0_8,  P0_9,
194
+  #if SERIAL_PORT != 2
195
+    P0_10, P0_11,
196
+  #endif
197
+  #if SERIAL_PORT != 1
198
+    P0_15, P0_16,
199
+  #endif
200
+  P0_17, P0_18, P0_19, P0_20, P0_21, P0_22, P0_23, P0_24,
201
+  P0_25, P0_26, P0_27, P0_28, P0_29, P0_30,
202
+  P1_0,  P1_1,  P1_4,  P1_8,  P1_9,  P1_10, P1_14, P1_15,
203
+  P1_16, P1_17, P1_18, P1_19, P1_20, P1_21, P1_22, P1_23,
204
+  P1_24, P1_25, P1_26, P1_27, P1_28, P1_29, P1_30, P1_31,
205
+  P2_0,  P2_1,  P2_2,  P2_3,  P2_4,  P2_5,  P2_6,  P2_7,
206
+  P2_8,  P2_9,  P2_10, P2_11, P2_12, P2_13,
207
+  P3_25, P3_26,
208
+  P4_28, P4_29
209
+};
210
+
211
+#define NUM_DIGITAL_PINS COUNT(pin_map)
212
+
213
+#define GET_PIN_MAP_PIN(i) (WITHIN(i, 0, (int)NUM_DIGITAL_PINS - 1) ? pin_map[i] : -1)
214
+
215
+int16_t GET_PIN_MAP_INDEX(pin_t pin);
216
+int16_t PARSED_PIN_INDEX(char code, int16_t dval = 0);
217
+                           
36 218
 #endif // __HAL_PINMAPPING_H__

Marlin/src/HAL/HAL_LPC1768/pinsDebug_Re_ARM.h → Marlin/src/HAL/HAL_LPC1768/pinsDebug_LPC1768.h Целия файл

@@ -21,29 +21,27 @@
21 21
  */
22 22
 
23 23
 /**
24
- * Support routines for Re-ARM board
24
+ * Support routines for LPC1768
25 25
 */
26 26
 
27
-bool pin_Re_ARM_output;
28
-bool pin_Re_ARM_analog;
29
-int8_t pin_Re_ARM_pin;
30
-
31
-void get_pin_info(int8_t pin) {
27
+// active ADC function/mode/code values for PINSEL registers
28
+int8_t ADC_pin_mode(pin_t pin) {
29
+  uint8_t pin_port = LPC1768_PIN_PORT(pin);
30
+  uint8_t pin_port_pin = LPC1768_PIN_PIN(pin);
31
+  return (pin_port == 0 && pin_port_pin == 2  ? 2 :
32
+          pin_port == 0 && pin_port_pin == 3  ? 2 :
33
+          pin_port == 0 && pin_port_pin == 23 ? 1 :
34
+          pin_port == 0 && pin_port_pin == 24 ? 1 :
35
+          pin_port == 0 && pin_port_pin == 25 ? 1 :
36
+          pin_port == 0 && pin_port_pin == 26 ? 1 :
37
+          pin_port == 1 && pin_port_pin == 30 ? 3 :
38
+          pin_port == 1 && pin_port_pin == 31 ? 3 : -1);
39
+}
32 40
 
33
-if (pin == 7) return;
34
-  pin_Re_ARM_analog = 0;
35
-  pin_Re_ARM_pin = pin;
36
-  int8_t pin_port = pin_map[pin].port;
37
-  int8_t pin_port_pin = pin_map[pin].pin;
38
-  // active ADC function/mode/code values for PINSEL registers
39
-  int8_t ADC_pin_mode = pin_port == 0 && pin_port_pin == 2  ? 2 :
40
-                        pin_port == 0 && pin_port_pin == 3  ? 2 :
41
-                        pin_port == 0 && pin_port_pin == 23 ? 1 :
42
-                        pin_port == 0 && pin_port_pin == 24 ? 1 :
43
-                        pin_port == 0 && pin_port_pin == 25 ? 1 :
44
-                        pin_port == 0 && pin_port_pin == 26 ? 1 :
45
-                        pin_port == 1 && pin_port_pin == 30 ? 3 :
46
-                        pin_port == 1 && pin_port_pin == 31 ? 3 : -1;
41
+int8_t get_pin_mode(pin_t pin) {
42
+  if (!VALID_PIN(pin)) return -1;
43
+  uint8_t pin_port = LPC1768_PIN_PORT(pin);
44
+  uint8_t pin_port_pin = LPC1768_PIN_PIN(pin);
47 45
   //get appropriate PINSEL register
48 46
   volatile uint32_t * pinsel_reg = (pin_port == 0 && pin_port_pin <= 15) ? &LPC_PINCON->PINSEL0 :
49 47
                                    (pin_port == 0)                       ? &LPC_PINCON->PINSEL1 :
@@ -52,16 +50,22 @@ if (pin == 7) return;
52 50
                                     pin_port == 2                        ? &LPC_PINCON->PINSEL4 :
53 51
                                     pin_port == 3                        ? &LPC_PINCON->PINSEL7 : &LPC_PINCON->PINSEL9;
54 52
   uint8_t pinsel_start_bit = pin_port_pin > 15 ? 2 * (pin_port_pin - 16) : 2 * pin_port_pin;
55
-  uint8_t pin_mode = (uint8_t) ((*pinsel_reg >> pinsel_start_bit) & 0x3);
53
+  int8_t pin_mode = (int8_t) ((*pinsel_reg >> pinsel_start_bit) & 0x3);
54
+  return pin_mode;
55
+}
56
+
57
+bool GET_PINMODE(pin_t pin) {
58
+  int8_t pin_mode = get_pin_mode(pin);
59
+  if (pin_mode == -1 || (pin_mode && pin_mode == ADC_pin_mode(pin))) // found an invalid pin or active analog pin
60
+    return false;
61
+
56 62
   uint32_t * FIO_reg[5] PROGMEM = {(uint32_t*) 0x2009C000,(uint32_t*)  0x2009C020,(uint32_t*)  0x2009C040,(uint32_t*)  0x2009C060,(uint32_t*)  0x2009C080};
57
-  pin_Re_ARM_output = (*FIO_reg[pin_map[pin].port] >> pin_map[pin].pin) & 1; //input/output state except if active ADC
63
+  return ((*FIO_reg[LPC1768_PIN_PORT(pin)] >> LPC1768_PIN_PIN(pin) & 1) != 0); //input/output state
64
+}
58 65
 
59
-  if (pin_mode) {  // if function/mode/code value not 0 then could be an active analog channel
60
-    if (ADC_pin_mode == pin_mode) {  // found an active analog pin
61
-      pin_Re_ARM_output = 0;
62
-      pin_Re_ARM_analog = 1;
63
-    }
64
-  }
66
+bool GET_ARRAY_IS_DIGITAL(pin_t pin) {
67
+  int8_t pin_mode = get_pin_mode(pin);
68
+  return (pin_mode != -1 && (!get_pin_mode(pin) || pin_mode != ADC_pin_mode(pin)));
65 69
 }
66 70
 
67 71
 /**
@@ -70,9 +74,7 @@ if (pin == 7) return;
70 74
 
71 75
 #define pwm_details(pin) pin = pin    // do nothing  // print PWM details
72 76
 #define pwm_status(pin) false //Print a pin's PWM status. Return true if it's currently a PWM pin.
73
-#define GET_PIN_INFO(pin) get_pin_info(pin)
74 77
 #define IS_ANALOG(P) (DIGITAL_PIN_TO_ANALOG_PIN(P) >= 0 ? 1 : 0)
75
-#define GET_PINMODE(pin) pin_Re_ARM_output
76 78
 #define digitalRead_mod(p)  digitalRead(p)
77 79
 #define digitalPinToPort_DEBUG(p)  0
78 80
 #define digitalPinToBitMask_DEBUG(pin) 0
@@ -81,4 +83,4 @@ if (pin == 7) return;
81 83
 #define NAME_FORMAT(p) PSTR("%-##p##s")
82 84
 //  #define PRINT_ARRAY_NAME(x)  do {sprintf_P(buffer, NAME_FORMAT(MAX_NAME_LENGTH) , pin_array[x].name); SERIAL_ECHO(buffer);} while (0)
83 85
 #define PRINT_ARRAY_NAME(x)  do {sprintf_P(buffer, PSTR("%-35s") , pin_array[x].name); SERIAL_ECHO(buffer);} while (0)
84
-#define GET_ARRAY_IS_DIGITAL(x)  !pin_Re_ARM_analog
86
+#define PRINT_PIN(p) do {sprintf_P(buffer, PSTR("%d.%02d "), LPC1768_PIN_PORT(p), LPC1768_PIN_PIN(p)); SERIAL_ECHO(buffer);} while (0)

+ 5
- 5
Marlin/src/HAL/HAL_LPC1768/spi_pins.h Целия файл

@@ -31,13 +31,13 @@
31 31
 //#define MOSI_PIN          P0_9
32 32
 //#define SS_PIN            P0_6
33 33
 /** external */
34
-#define SCK_PIN           52 //P0_15
35
-#define MISO_PIN          50 //P0_17
36
-#define MOSI_PIN          51 //P0_18
37
-#define SS_PIN            53 //P1_23
34
+#define SCK_PIN           P0_15
35
+#define MISO_PIN          P0_17
36
+#define MOSI_PIN          P0_18
37
+#define SS_PIN            P1_23
38 38
 #define SDSS              SS_PIN
39 39
 
40
-#if (defined(IS_REARM) && !(defined(LPC_SOFTWARE_SPI)))   // signal LCDs that they need to use the hardware SPI
40
+#if (defined(TARGET_LPC1768) && !(defined(LPC_SOFTWARE_SPI)))   // signal LCDs that they need to use the hardware SPI
41 41
   #define SHARED_SPI
42 42
 #endif
43 43
 

+ 6
- 0
Marlin/src/HAL/HAL_STM32F1/HAL_Stm32f1.h Целия файл

@@ -98,6 +98,8 @@
98 98
 // Types
99 99
 // --------------------------------------------------------------------------
100 100
 
101
+typedef int8_t pin_t;
102
+
101 103
 // --------------------------------------------------------------------------
102 104
 // Public Variables
103 105
 // --------------------------------------------------------------------------
@@ -192,4 +194,8 @@ void HAL_enable_AdcFreerun(void);
192 194
 
193 195
 */
194 196
 
197
+#define GET_PIN_MAP_PIN(index) index
198
+#define GET_PIN_MAP_INDEX(pin) pin
199
+#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
200
+
195 201
 #endif // _HAL_STM32F1_H

+ 5
- 5
Marlin/src/HAL/HAL_STM32F1/HAL_timers_Stm32f1.h Целия файл

@@ -43,7 +43,7 @@
43 43
  */
44 44
 #define FORCE_INLINE __attribute__((always_inline)) inline
45 45
 
46
-#define HAL_TIMER_TYPE uint16_t
46
+typedef uint16_t timer_t;
47 47
 #define HAL_TIMER_TYPE_MAX 0xFFFF
48 48
 
49 49
 #define STEP_TIMER_NUM 5  // index of timer to use for stepper
@@ -126,8 +126,8 @@ static FORCE_INLINE void HAL_timer_set_count (uint8_t timer_num, uint32_t count)
126 126
   }
127 127
 }
128 128
 
129
-static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_count (uint8_t timer_num) {
130
-  HAL_TIMER_TYPE temp;
129
+static FORCE_INLINE timer_t HAL_timer_get_count (uint8_t timer_num) {
130
+  timer_t temp;
131 131
   switch (timer_num) {
132 132
   case STEP_TIMER_NUM:
133 133
     temp = StepperTimer.getCompare(STEP_TIMER_CHAN);
@@ -142,8 +142,8 @@ static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_count (uint8_t timer_num) {
142 142
   return temp;
143 143
 }
144 144
 
145
-static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_current_count(uint8_t timer_num) {
146
-  HAL_TIMER_TYPE temp;
145
+static FORCE_INLINE timer_t HAL_timer_get_current_count(uint8_t timer_num) {
146
+  timer_t temp;
147 147
   switch (timer_num) {
148 148
   case STEP_TIMER_NUM:
149 149
     temp = StepperTimer.getCount();

+ 6
- 0
Marlin/src/HAL/HAL_TEENSY35_36/HAL_Teensy.h Целия файл

@@ -64,6 +64,8 @@
64 64
 
65 65
 #define HAL_SERVO_LIB libServo
66 66
 
67
+typedef int8_t pin_t;
68
+
67 69
 #ifndef analogInputToDigitalPin
68 70
   #define analogInputToDigitalPin(p) ((p < 12u) ? (p) + 54u : -1)
69 71
 #endif
@@ -139,6 +141,10 @@ uint16_t HAL_adc_get_result(void);
139 141
   //void HAL_disable_AdcFreerun(uint8_t chan);
140 142
 */
141 143
 
144
+#define GET_PIN_MAP_PIN(index) index
145
+#define GET_PIN_MAP_INDEX(pin) pin
146
+#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
147
+
142 148
 // --------------------------------------------------------------------------
143 149
 //
144 150
 // --------------------------------------------------------------------------

+ 2
- 2
Marlin/src/HAL/HAL_TEENSY35_36/HAL_timers_Teensy.h Целия файл

@@ -40,7 +40,7 @@
40 40
 
41 41
 #define FORCE_INLINE __attribute__((always_inline)) inline
42 42
 
43
-#define HAL_TIMER_TYPE uint32_t
43
+typedef uint32_t timer_t;
44 44
 #define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
45 45
 
46 46
 #define STEP_TIMER_NUM 0
@@ -82,7 +82,7 @@ static FORCE_INLINE void HAL_timer_set_count(const uint8_t timer_num, const uint
82 82
   }
83 83
 }
84 84
 
85
-static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_count(const uint8_t timer_num) {
85
+static FORCE_INLINE timer_t HAL_timer_get_count(const uint8_t timer_num) {
86 86
   switch(timer_num) {
87 87
     case 0: return FTM0_C0V;
88 88
     case 1: return FTM1_C0V;

+ 1
- 1
Marlin/src/HAL/HAL_pinsDebug.h Целия файл

@@ -30,7 +30,7 @@
30 30
 #elif IS_32BIT_TEENSY
31 31
   #include "HAL_TEENSY35_36/HAL_pinsDebug_Teensy.h"
32 32
 #elif defined(TARGET_LPC1768)
33
-  #include "HAL_LPC1768/pinsDebug_Re_ARM.h"
33
+  #include "HAL_LPC1768/pinsDebug_LPC1768.h"
34 34
 #else
35 35
   #error Unsupported Platform!
36 36
 #endif

+ 7
- 4
Marlin/src/Marlin.cpp Целия файл

@@ -297,10 +297,13 @@ void setup_powerhold() {
297 297
 /**
298 298
  * Sensitive pin test for M42, M226
299 299
  */
300
-bool pin_is_protected(const int8_t pin) {
301
-  static const int8_t sensitive_pins[] PROGMEM = SENSITIVE_PINS;
302
-  for (uint8_t i = 0; i < COUNT(sensitive_pins); i++)
303
-    if (pin == (int8_t)pgm_read_byte(&sensitive_pins[i])) return true;
300
+bool pin_is_protected(const pin_t pin) {
301
+  static const pin_t sensitive_pins[] PROGMEM = SENSITIVE_PINS;
302
+  for (uint8_t i = 0; i < COUNT(sensitive_pins); i++) {
303
+    pin_t sensitive_pin;
304
+    memcpy_P(&sensitive_pin, &sensitive_pins[i], sizeof(pin_t));
305
+    if (pin == sensitive_pin) return true;
306
+  }
304 307
   return false;
305 308
 }
306 309
 

+ 1
- 1
Marlin/src/Marlin.h Целия файл

@@ -216,7 +216,7 @@ extern millis_t max_inactive_time, stepper_inactive_time;
216 216
   extern int lpq_len;
217 217
 #endif
218 218
 
219
-bool pin_is_protected(const int8_t pin);
219
+bool pin_is_protected(const pin_t pin);
220 220
 
221 221
 #if HAS_SUICIDE
222 222
   inline void suicide() { OUT_WRITE(SUICIDE_PIN, LOW); }

+ 1
- 0
Marlin/src/core/serial.cpp Целия файл

@@ -42,6 +42,7 @@ void serial_echopair_P(const char* s_P, int v)           { serialprintPGM(s_P);
42 42
 void serial_echopair_P(const char* s_P, long v)          { serialprintPGM(s_P); SERIAL_ECHO(v); }
43 43
 void serial_echopair_P(const char* s_P, float v)         { serialprintPGM(s_P); SERIAL_ECHO(v); }
44 44
 void serial_echopair_P(const char* s_P, double v)        { serialprintPGM(s_P); SERIAL_ECHO(v); }
45
+void serial_echopair_P(const char* s_P, unsigned int v)  { serialprintPGM(s_P); SERIAL_ECHO(v); }
45 46
 void serial_echopair_P(const char* s_P, unsigned long v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
46 47
 
47 48
 void serial_spaces(uint8_t count) { count *= (PROPORTIONAL_FONT_RATIO); while (count--) MYSERIAL.write(' '); }

+ 0
- 1
Marlin/src/core/serial.h Целия файл

@@ -106,7 +106,6 @@ void serial_echopair_P(const char* s_P, double v);
106 106
 void serial_echopair_P(const char* s_P, unsigned int v);
107 107
 void serial_echopair_P(const char* s_P, unsigned long v);
108 108
 FORCE_INLINE void serial_echopair_P(const char* s_P, uint8_t v) { serial_echopair_P(s_P, (int)v); }
109
-FORCE_INLINE void serial_echopair_P(const char* s_P, uint16_t v) { serial_echopair_P(s_P, (int)v); }
110 109
 FORCE_INLINE void serial_echopair_P(const char* s_P, bool v) { serial_echopair_P(s_P, (int)v); }
111 110
 FORCE_INLINE void serial_echopair_P(const char* s_P, void *v) { serial_echopair_P(s_P, (unsigned long)v); }
112 111
 

+ 15
- 10
Marlin/src/gcode/config/M43.cpp Целия файл

@@ -36,11 +36,12 @@
36 36
 inline void toggle_pins() {
37 37
   const bool I_flag = parser.boolval('I');
38 38
   const int repeat = parser.intval('R', 1),
39
-            start = parser.intval('S'),
40
-            end = parser.intval('E', NUM_DIGITAL_PINS - 1),
39
+            start = PARSED_PIN_INDEX('S', 0),
40
+            end = PARSED_PIN_INDEX('E', NUM_DIGITAL_PINS - 1),
41 41
             wait = parser.intval('W', 500);
42 42
 
43
-  for (uint8_t pin = start; pin <= end; pin++) {
43
+  for (uint8_t i = start; i <= end; i++) {
44
+    pin_t pin = GET_PIN_MAP_PIN(i);
44 45
     //report_pin_state_extended(pin, I_flag, false);
45 46
     if (!VALID_PIN(pin)) continue;
46 47
     if (!I_flag && pin_is_protected(pin)) {
@@ -258,7 +259,7 @@ void GcodeSuite::M43() {
258 259
   }
259 260
 
260 261
   // Get the range of pins to test or watch
261
-  const uint8_t first_pin = parser.byteval('P'),
262
+  const uint8_t first_pin = PARSED_PIN_INDEX('P', 0),
262 263
                 last_pin = parser.seenval('P') ? first_pin : NUM_DIGITAL_PINS - 1;
263 264
 
264 265
   if (first_pin > last_pin) return;
@@ -269,7 +270,8 @@ void GcodeSuite::M43() {
269 270
   if (parser.boolval('W')) {
270 271
     SERIAL_PROTOCOLLNPGM("Watching pins");
271 272
     uint8_t pin_state[last_pin - first_pin + 1];
272
-    for (int8_t pin = first_pin; pin <= last_pin; pin++) {
273
+    for (uint8_t i = first_pin; i <= last_pin; i++) {
274
+      pin_t pin = GET_PIN_MAP_PIN(i);
273 275
       if (!VALID_PIN(pin)) continue;
274 276
       if (pin_is_protected(pin) && !ignore_protection) continue;
275 277
       pinMode(pin, INPUT_PULLUP);
@@ -279,7 +281,7 @@ void GcodeSuite::M43() {
279 281
           pin_state[pin - first_pin] = analogRead(DIGITAL_PIN_TO_ANALOG_PIN(pin)); // int16_t pin_state[...]
280 282
         else
281 283
       //*/
282
-          pin_state[pin - first_pin] = digitalRead(pin);
284
+          pin_state[i - first_pin] = digitalRead(pin);
283 285
     }
284 286
 
285 287
     #if HAS_RESUME_CONTINUE
@@ -288,7 +290,8 @@ void GcodeSuite::M43() {
288 290
     #endif
289 291
 
290 292
     for (;;) {
291
-      for (int8_t pin = first_pin; pin <= last_pin; pin++) {
293
+      for (uint8_t i = first_pin; i <= last_pin; i++) {
294
+        pin_t pin = GET_PIN_MAP_PIN(i);
292 295
         if (!VALID_PIN(pin)) continue;
293 296
         if (pin_is_protected(pin) && !ignore_protection) continue;
294 297
         const byte val =
@@ -298,9 +301,9 @@ void GcodeSuite::M43() {
298 301
               :
299 302
           //*/
300 303
             digitalRead(pin);
301
-        if (val != pin_state[pin - first_pin]) {
304
+        if (val != pin_state[i - first_pin]) {
302 305
           report_pin_state_extended(pin, ignore_protection, false);
303
-          pin_state[pin - first_pin] = val;
306
+          pin_state[i - first_pin] = val;
304 307
         }
305 308
       }
306 309
 
@@ -317,8 +320,10 @@ void GcodeSuite::M43() {
317 320
   }
318 321
 
319 322
   // Report current state of selected pin(s)
320
-  for (uint8_t pin = first_pin; pin <= last_pin; pin++)
323
+  for (uint8_t i = first_pin; i <= last_pin; i++) {
324
+    pin_t pin = GET_PIN_MAP_PIN(i);
321 325
     if (VALID_PIN(pin)) report_pin_state_extended(pin, ignore_protection, true);
326
+  }
322 327
 }
323 328
 
324 329
 #endif // PINS_DEBUGGING

+ 7
- 6
Marlin/src/gcode/control/M226.cpp Целия файл

@@ -29,16 +29,17 @@
29 29
  */
30 30
 void GcodeSuite::M226() {
31 31
   if (parser.seen('P')) {
32
-    const int pin_number = parser.value_int(),
32
+    const int pin_number = PARSED_PIN_INDEX('P', 0),
33 33
               pin_state = parser.intval('S', -1); // required pin state - default is inverted
34
+    const pin_t pin = GET_PIN_MAP_PIN(pin_number);
34 35
 
35
-    if (WITHIN(pin_state, -1, 1) && pin_number > -1 && !pin_is_protected(pin_number)) {
36
+    if (WITHIN(pin_state, -1, 1) && pin > -1 && !pin_is_protected(pin)) {
36 37
 
37 38
       int target = LOW;
38 39
 
39 40
       stepper.synchronize();
40 41
 
41
-      pinMode(pin_number, INPUT);
42
+      pinMode(pin, INPUT);
42 43
       switch (pin_state) {
43 44
         case 1:
44 45
           target = HIGH;
@@ -47,12 +48,12 @@ void GcodeSuite::M226() {
47 48
           target = LOW;
48 49
           break;
49 50
         case -1:
50
-          target = !digitalRead(pin_number);
51
+          target = !digitalRead(pin);
51 52
           break;
52 53
       }
53 54
 
54
-      while (digitalRead(pin_number) != target) idle();
55
+      while (digitalRead(pin) != target) idle();
55 56
 
56
-    } // pin_state -1 0 1 && pin_number > -1
57
+    } // pin_state -1 0 1 && pin > -1
57 58
   } // parser.seen('P')
58 59
 }

+ 7
- 6
Marlin/src/gcode/control/M42.cpp Целия файл

@@ -34,21 +34,22 @@ void GcodeSuite::M42() {
34 34
   if (!parser.seenval('S')) return;
35 35
   const byte pin_status = parser.value_byte();
36 36
 
37
-  const int pin_number = parser.intval('P', LED_PIN);
37
+  int pin_number = PARSED_PIN_INDEX('P', GET_PIN_MAP_INDEX(LED_PIN));
38 38
   if (pin_number < 0) return;
39 39
 
40
-  if (pin_is_protected(pin_number)) {
40
+  const pin_t pin = GET_PIN_MAP_PIN(pin_number);
41
+  if (pin_is_protected(pin)) {
41 42
     SERIAL_ERROR_START();
42 43
     SERIAL_ERRORLNPGM(MSG_ERR_PROTECTED_PIN);
43 44
     return;
44 45
   }
45 46
 
46
-  pinMode(pin_number, OUTPUT);
47
-  digitalWrite(pin_number, pin_status);
48
-  analogWrite(pin_number, pin_status);
47
+  pinMode(pin, OUTPUT);
48
+  digitalWrite(pin, pin_status);
49
+  analogWrite(pin, pin_status);
49 50
 
50 51
   #if FAN_COUNT > 0
51
-    switch (pin_number) {
52
+    switch (pin) {
52 53
       #if HAS_FAN0
53 54
         case FAN_PIN: fanSpeeds[0] = pin_status; break;
54 55
       #endif

+ 10
- 9
Marlin/src/gcode/parser.h Целия файл

@@ -293,15 +293,16 @@ public:
293 293
   void unknown_command_error();
294 294
 
295 295
   // Provide simple value accessors with default option
296
-  FORCE_INLINE static float    floatval(const char c, const float dval=0.0)   { return seenval(c) ? value_float()        : dval; }
297
-  FORCE_INLINE static bool     boolval(const char c)                          { return seenval(c) ? value_bool()         : seen(c); }
298
-  FORCE_INLINE static uint8_t  byteval(const char c, const uint8_t dval=0)    { return seenval(c) ? value_byte()         : dval; }
299
-  FORCE_INLINE static int16_t  intval(const char c, const int16_t dval=0)     { return seenval(c) ? value_int()          : dval; }
300
-  FORCE_INLINE static uint16_t ushortval(const char c, const uint16_t dval=0) { return seenval(c) ? value_ushort()       : dval; }
301
-  FORCE_INLINE static int32_t  longval(const char c, const int32_t dval=0)    { return seenval(c) ? value_long()         : dval; }
302
-  FORCE_INLINE static uint32_t ulongval(const char c, const uint32_t dval=0)  { return seenval(c) ? value_ulong()        : dval; }
303
-  FORCE_INLINE static float    linearval(const char c, const float dval=0.0)  { return seenval(c) ? value_linear_units() : dval; }
304
-  FORCE_INLINE static float    celsiusval(const char c, const float dval=0.0) { return seenval(c) ? value_celsius()      : dval; }
296
+  FORCE_INLINE static float       floatval(const char c, const float dval=0.0)   { return seenval(c) ? value_float()        : dval; }
297
+  FORCE_INLINE static bool        boolval(const char c)                          { return seenval(c) ? value_bool()         : seen(c); }
298
+  FORCE_INLINE static uint8_t     byteval(const char c, const uint8_t dval=0)    { return seenval(c) ? value_byte()         : dval; }
299
+  FORCE_INLINE static int16_t     intval(const char c, const int16_t dval=0)     { return seenval(c) ? value_int()          : dval; }
300
+  FORCE_INLINE static uint16_t    ushortval(const char c, const uint16_t dval=0) { return seenval(c) ? value_ushort()       : dval; }
301
+  FORCE_INLINE static int32_t     longval(const char c, const int32_t dval=0)    { return seenval(c) ? value_long()         : dval; }
302
+  FORCE_INLINE static uint32_t    ulongval(const char c, const uint32_t dval=0)  { return seenval(c) ? value_ulong()        : dval; }
303
+  FORCE_INLINE static float       linearval(const char c, const float dval=0.0)  { return seenval(c) ? value_linear_units() : dval; }
304
+  FORCE_INLINE static float       celsiusval(const char c, const float dval=0.0) { return seenval(c) ? value_celsius()      : dval; }
305
+  FORCE_INLINE static const char* strval(const char c)                           { return seenval(c) ? value_ptr            : NULL; }
305 306
 
306 307
 };
307 308
 

+ 11
- 11
Marlin/src/module/stepper.cpp Целия файл

@@ -110,9 +110,9 @@ volatile uint32_t Stepper::step_events_completed = 0; // The number of step even
110 110
 
111 111
 #if ENABLED(LIN_ADVANCE)
112 112
 
113
-  constexpr HAL_TIMER_TYPE ADV_NEVER = HAL_TIMER_TYPE_MAX;
113
+  constexpr timer_t ADV_NEVER = HAL_TIMER_TYPE_MAX;
114 114
 
115
-  HAL_TIMER_TYPE Stepper::nextMainISR = 0,
115
+  timer_t Stepper::nextMainISR = 0,
116 116
          Stepper::nextAdvanceISR = ADV_NEVER,
117 117
          Stepper::eISR_Rate = ADV_NEVER;
118 118
 
@@ -127,9 +127,9 @@ volatile uint32_t Stepper::step_events_completed = 0; // The number of step even
127 127
    * This fix isn't perfect and may lose steps - but better than locking up completely
128 128
    * in future the planner should slow down if advance stepping rate would be too high
129 129
    */
130
-  FORCE_INLINE HAL_TIMER_TYPE adv_rate(const int steps, const HAL_TIMER_TYPE timer, const uint8_t loops) {
130
+  FORCE_INLINE timer_t adv_rate(const int steps, const timer_t timer, const uint8_t loops) {
131 131
     if (steps) {
132
-      const HAL_TIMER_TYPE rate = (timer * loops) / abs(steps);
132
+      const timer_t rate = (timer * loops) / abs(steps);
133 133
       //return constrain(rate, 1, ADV_NEVER - 1)
134 134
       return rate ? rate : 1;
135 135
     }
@@ -147,9 +147,9 @@ volatile signed char Stepper::count_direction[NUM_AXIS] = { 1, 1, 1, 1 };
147 147
   long Stepper::counter_m[MIXING_STEPPERS];
148 148
 #endif
149 149
 
150
-HAL_TIMER_TYPE Stepper::acc_step_rate; // needed for deceleration start point
150
+timer_t Stepper::acc_step_rate; // needed for deceleration start point
151 151
 uint8_t Stepper::step_loops, Stepper::step_loops_nominal;
152
-HAL_TIMER_TYPE Stepper::OCR1A_nominal;
152
+timer_t Stepper::OCR1A_nominal;
153 153
 
154 154
 volatile long Stepper::endstops_trigsteps[XYZ];
155 155
 
@@ -313,7 +313,7 @@ HAL_STEP_TIMER_ISR {
313 313
 
314 314
 void Stepper::isr() {
315 315
 
316
-  HAL_TIMER_TYPE ocr_val;
316
+  timer_t ocr_val;
317 317
 
318 318
   #define ENDSTOP_NOMINAL_OCR_VAL 1500 * HAL_TICKS_PER_US    // check endstops every 1.5ms to guarantee two stepper ISRs within 5ms for BLTouch
319 319
   #define OCR_VAL_TOLERANCE 500 * HAL_TICKS_PER_US           // First max delay is 2.0ms, last min delay is 0.5ms, all others 1.5ms
@@ -649,7 +649,7 @@ void Stepper::isr() {
649 649
     NOMORE(acc_step_rate, current_block->nominal_rate);
650 650
 
651 651
     // step_rate to timer interval
652
-    const HAL_TIMER_TYPE timer = calc_timer(acc_step_rate);
652
+    const timer_t timer = calc_timer(acc_step_rate);
653 653
 
654 654
     SPLIT(timer);  // split step into multiple ISRs if larger than  ENDSTOP_NOMINAL_OCR_VAL
655 655
     _NEXT_ISR(ocr_val);
@@ -671,7 +671,7 @@ void Stepper::isr() {
671 671
     #endif // LIN_ADVANCE
672 672
   }
673 673
   else if (step_events_completed > (uint32_t)current_block->decelerate_after) {
674
-    HAL_TIMER_TYPE step_rate;
674
+    timer_t step_rate;
675 675
     #ifdef CPU_32_BIT
676 676
       MultiU32X24toH32(step_rate, deceleration_time, current_block->acceleration_rate);
677 677
     #else
@@ -686,7 +686,7 @@ void Stepper::isr() {
686 686
       step_rate = current_block->final_rate;
687 687
 
688 688
     // step_rate to timer interval
689
-    const HAL_TIMER_TYPE timer = calc_timer(step_rate);
689
+    const timer_t timer = calc_timer(step_rate);
690 690
 
691 691
     SPLIT(timer);  // split step into multiple ISRs if larger than  ENDSTOP_NOMINAL_OCR_VAL
692 692
     _NEXT_ISR(ocr_val);
@@ -726,7 +726,7 @@ void Stepper::isr() {
726 726
   #if DISABLED(LIN_ADVANCE)
727 727
     #ifdef CPU_32_BIT
728 728
       // Make sure stepper interrupt does not monopolise CPU by adjusting count to give about 8 us room
729
-      HAL_TIMER_TYPE stepper_timer_count = HAL_timer_get_count(STEP_TIMER_NUM),
729
+      timer_t stepper_timer_count = HAL_timer_get_count(STEP_TIMER_NUM),
730 730
                      stepper_timer_current_count = HAL_timer_get_current_count(STEP_TIMER_NUM) + 8 * HAL_TICKS_PER_US;
731 731
       HAL_timer_set_count(STEP_TIMER_NUM, max(stepper_timer_count, stepper_timer_current_count));
732 732
     #else

+ 5
- 5
Marlin/src/module/stepper.h Целия файл

@@ -91,7 +91,7 @@ class Stepper {
91 91
     static volatile uint32_t step_events_completed; // The number of step events executed in the current block
92 92
 
93 93
     #if ENABLED(LIN_ADVANCE)
94
-      static HAL_TIMER_TYPE nextMainISR, nextAdvanceISR, eISR_Rate;
94
+      static timer_t nextMainISR, nextAdvanceISR, eISR_Rate;
95 95
       #define _NEXT_ISR(T) nextMainISR = T
96 96
 
97 97
       static volatile int e_steps[E_STEPPERS];
@@ -106,9 +106,9 @@ class Stepper {
106 106
 
107 107
     static long acceleration_time, deceleration_time;
108 108
     //unsigned long accelerate_until, decelerate_after, acceleration_rate, initial_rate, final_rate, nominal_rate;
109
-    static HAL_TIMER_TYPE acc_step_rate; // needed for deceleration start point
109
+    static timer_t acc_step_rate; // needed for deceleration start point
110 110
     static uint8_t step_loops, step_loops_nominal;
111
-    static HAL_TIMER_TYPE OCR1A_nominal;
111
+    static timer_t OCR1A_nominal;
112 112
 
113 113
     static volatile long endstops_trigsteps[XYZ];
114 114
     static volatile long endstops_stepsTotal, endstops_stepsDone;
@@ -259,8 +259,8 @@ class Stepper {
259 259
 
260 260
   private:
261 261
 
262
-    static FORCE_INLINE HAL_TIMER_TYPE calc_timer(HAL_TIMER_TYPE step_rate) {
263
-      HAL_TIMER_TYPE timer;
262
+    static FORCE_INLINE timer_t calc_timer(timer_t step_rate) {
263
+      timer_t timer;
264 264
 
265 265
       NOMORE(step_rate, MAX_STEP_FREQUENCY);
266 266
 

+ 7
- 2
Marlin/src/pins/pins.h Целия файл

@@ -665,7 +665,11 @@
665 665
   #define _Z2_PINS Z2_STEP_PIN, Z2_DIR_PIN, Z2_ENABLE_PIN,
666 666
 #endif
667 667
 
668
-#define SENSITIVE_PINS { 0, 1, \
668
+#ifndef HAL_SENSITIVE_PINS
669
+#define HAL_SENSITIVE_PINS
670
+#endif
671
+
672
+#define SENSITIVE_PINS { \
669 673
     X_STEP_PIN, X_DIR_PIN, X_ENABLE_PIN, X_MIN_PIN, X_MAX_PIN, \
670 674
     Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, Y_MIN_PIN, Y_MAX_PIN, \
671 675
     Z_STEP_PIN, Z_DIR_PIN, Z_ENABLE_PIN, Z_MIN_PIN, Z_MAX_PIN, Z_MIN_PROBE_PIN, \
@@ -673,7 +677,8 @@
673 677
     _E0_PINS _E1_PINS _E2_PINS _E3_PINS _E4_PINS BED_PINS \
674 678
     _H0_PINS _H1_PINS _H2_PINS _H3_PINS _H4_PINS \
675 679
     _X2_PINS _Y2_PINS _Z2_PINS \
676
-    X_MS1_PIN, X_MS2_PIN, Y_MS1_PIN, Y_MS2_PIN, Z_MS1_PIN, Z_MS2_PIN \
680
+    X_MS1_PIN, X_MS2_PIN, Y_MS1_PIN, Y_MS2_PIN, Z_MS1_PIN, Z_MS2_PIN, \
681
+    HAL_SENSITIVE_PINS \
677 682
   }
678 683
 
679 684
 #define HAS_DIGIPOTSS (PIN_EXISTS(DIGIPOTSS))

+ 6
- 5
Marlin/src/pins/pinsDebug.h Целия файл

@@ -68,7 +68,7 @@
68 68
 
69 69
 typedef struct {
70 70
   const char * const name;
71
-  uint8_t pin;
71
+  pin_t pin;
72 72
   bool is_digital;
73 73
 } PinInfo;
74 74
 
@@ -109,18 +109,18 @@ static void print_input_or_output(const bool isout) {
109 109
 
110 110
 
111 111
 // pretty report with PWM info
112
-inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = false, const char *start_string = "") {
112
+inline void report_pin_state_extended(pin_t pin, bool ignore, bool extended = false, const char *start_string = "") {
113 113
   char buffer[30];   // for the sprintf statements
114 114
   bool found = false, multi_name_pin = false;
115 115
 
116 116
   for (uint8_t x = 0; x < COUNT(pin_array); x++)  {    // scan entire array and report all instances of this pin
117 117
     if (GET_ARRAY_PIN(x) == pin) {
118
-      GET_PIN_INFO(pin);
119 118
       if (found) multi_name_pin = true;
120 119
       found = true;
121 120
       if (!multi_name_pin) {    // report digitial and analog pin number only on the first time through
122
-        sprintf_P(buffer, PSTR("%sPIN: %3d "), start_string, pin);     // digital pin number
121
+        sprintf_P(buffer, PSTR("%sPIN: "), start_string);     // digital pin number
123 122
         SERIAL_ECHO(buffer);
123
+        PRINT_PIN(pin);
124 124
         PRINT_PORT(pin);
125 125
         if (IS_ANALOG(pin)) {
126 126
           sprintf_P(buffer, PSTR(" (A%2d)  "), DIGITAL_PIN_TO_ANALOG_PIN(pin));    // analog pin number
@@ -180,8 +180,9 @@ inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = f
180 180
   } // end of for loop
181 181
 
182 182
   if (!found) {
183
-    sprintf_P(buffer, PSTR("%sPIN: %3d "), start_string, pin);
183
+    sprintf_P(buffer, PSTR("%sPIN: "), start_string);
184 184
     SERIAL_ECHO(buffer);
185
+    PRINT_PIN(pin);
185 186
     PRINT_PORT(pin);
186 187
     if (IS_ANALOG(pin)) {
187 188
       sprintf_P(buffer, PSTR(" (A%2d)  "), DIGITAL_PIN_TO_ANALOG_PIN(pin));    // analog pin number

+ 78
- 81
Marlin/src/pins/pins_MKS_SBASE.h Целия файл

@@ -25,9 +25,8 @@
25 25
  * MKS SBASE pin assignments
26 26
  */
27 27
 
28
-//#if !defined(TARGET_LPC1768)
29
-#if DISABLED(IS_REARM)
30
-  #error "Oops!  Make sure you have Re-Arm selected."
28
+#ifndef TARGET_LPC1768
29
+  #error "Oops!  Make sure you have LPC1768 selected."
31 30
 #endif
32 31
 
33 32
 #ifndef BOARD_NAME
@@ -39,46 +38,42 @@
39 38
 
40 39
 // unused
41 40
 /*
42
-#define D57               57
43
-#define D58               58
41
+#define PIN_P0_27         P0_27
42
+#define PIN_P0_28         P0_28
44 43
 */
45 44
 
46 45
 //
47 46
 // Limit Switches
48 47
 //
49
-#define X_MIN_PIN           3  //10k pullup to 3.3V, 1K series
50
-#define X_MAX_PIN           2  //10k pullup to 3.3V, 1K series
51
-#define Y_MIN_PIN          14  //10k pullup to 3.3V, 1K series
52
-#define Y_MAX_PIN          15  //10k pullup to 3.3V, 1K series
53
-#define Z_MIN_PIN          19  //The original Mks Sbase DIO19 has a 10k pullup to 3.3V or 5V, 1K series, so when using a Zprobe we must use DIO41 (J8 P1.22)
54
-#define Z_MAX_PIN          18  //10k pullup to 3.3V, 1K series
48
+#define X_MIN_PIN          P1_24  //10k pullup to 3.3V, 1K series
49
+#define X_MAX_PIN          P1_25  //10k pullup to 3.3V, 1K series
50
+#define Y_MIN_PIN          P1_26  //10k pullup to 3.3V, 1K series
51
+#define Y_MAX_PIN          P1_27  //10k pullup to 3.3V, 1K series
52
+#define Z_MIN_PIN          P1_28  //The original Mks Sbase DIO19 has a 10k pullup to 3.3V or 5V, 1K series, so when using a Zprobe we must use DIO41 (J8 P1.22)
53
+#define Z_MAX_PIN          P1_29  //10k pullup to 3.3V, 1K series
55 54
 
56 55
 //
57 56
 // Steppers
58 57
 //
59
-#define X_STEP_PIN         26
60
-#define X_DIR_PIN          28
61
-#define X_ENABLE_PIN       24
58
+#define X_STEP_PIN         P2_0
59
+#define X_DIR_PIN          P0_5
60
+#define X_ENABLE_PIN       P0_4
62 61
 
63
-#define Y_STEP_PIN         54
64
-#define Y_DIR_PIN          55
65
-#define Y_ENABLE_PIN       38
62
+#define Y_STEP_PIN         P2_1
63
+#define Y_DIR_PIN          P0_11
64
+#define Y_ENABLE_PIN       P0_10
66 65
 
67
-#define Z_STEP_PIN         60
68
-#define Z_DIR_PIN          61
69
-#define Z_ENABLE_PIN       56
66
+#define Z_STEP_PIN         P2_2
67
+#define Z_DIR_PIN          P0_20
68
+#define Z_ENABLE_PIN       P0_19
70 69
 
71
-#define E0_STEP_PIN        46
72
-#define E0_DIR_PIN         48
73
-#define E0_ENABLE_PIN      62
70
+#define E0_STEP_PIN        P2_3
71
+#define E0_DIR_PIN         P0_22
72
+#define E0_ENABLE_PIN      P0_21
74 73
 
75
-#define E1_STEP_PIN        36
76
-#define E1_DIR_PIN         34
77
-#define E1_ENABLE_PIN      30
78
-
79
-#define X2_STEP_PIN        36
80
-#define X2_DIR_PIN         34
81
-#define X2_ENABLE_PIN      30
74
+#define E1_STEP_PIN        P2_8
75
+#define E1_DIR_PIN         P2_13
76
+#define E1_ENABLE_PIN      P4_29
82 77
 
83 78
 //
84 79
 // Temperature Sensors
@@ -95,13 +90,13 @@
95 90
 // Heaters / Fans
96 91
 //
97 92
 
98
-#define HEATER_BED_PIN     10
99
-#define HEATER_0_PIN        8
100
-#define HEATER_1_PIN       59
101
-#define FAN_PIN             9
93
+#define HEATER_BED_PIN     P2_5
94
+#define HEATER_0_PIN       P2_7
95
+#define HEATER_1_PIN       P2_6
96
+#define FAN_PIN            P2_4
102 97
 
103 98
 
104
-#define PS_ON_PIN          69
99
+#define PS_ON_PIN          P0_25
105 100
 
106 101
 
107 102
 //
@@ -111,9 +106,9 @@
111 106
 // 5V
112 107
 // NC
113 108
 // GND
114
-#define PIN_P0_17          50
115
-#define PIN_P0_16          16
116
-#define PIN_P0_14          80
109
+#define PIN_P0_17          P0_17
110
+#define PIN_P0_16          P0_16
111
+#define PIN_P0_14          P0_14
117 112
 
118 113
 
119 114
 //
@@ -121,19 +116,21 @@
121 116
 //
122 117
 
123 118
 // GND
124
-#define PIN_P1_22          41
125
-#define PIN_P1_23          53
126
-#define PIN_P2_12          12
127
-#define PIN_P2_11          35
128
-#define PIN_P4_28          13
119
+#define PIN_P1_22          P1_22
120
+#define PIN_P1_23          P1_23
121
+#define PIN_P2_12          P2_12
122
+#define PIN_P2_11          P2_11
123
+#define PIN_P4_28          P4_28
129 124
 
130 125
 //
131 126
 // Prusa i3 MK2 Multi Material Multiplexer Support
132 127
 //
133 128
 
134
-#define E_MUX0_PIN         50   // J7-4
135
-#define E_MUX1_PIN         16   // J7-5
136
-#define E_MUX2_PIN         80   // J7-6
129
+#if ENABLED(MK2_MULTIPLEXER)
130
+  #define E_MUX0_PIN         P0_17   // J7-4
131
+  #define E_MUX1_PIN         P0_16   // J7-5
132
+  #define E_MUX2_PIN         P0_15   // J7-6
133
+#endif
137 134
 
138 135
 
139 136
 /**
@@ -150,32 +147,32 @@
150 147
  */
151 148
 
152 149
 #if ENABLED(ULTRA_LCD)
153
-  #define BEEPER_PIN       49  // EXP1.1
154
-  #define BTN_ENC          37  // EXP1.2
155
-  #define BTN_EN1          31  // EXP2.5
156
-  #define BTN_EN2          33  // EXP2.3
157
-  #define SD_DETECT_PIN    57  // EXP2.7
158
-  #define LCD_PINS_RS      16  // EXP1.4
159
-  #define LCD_SDSS         58  // EXP2.4
160
-  #define LCD_PINS_ENABLE  51  // EXP1.3
161
-  #define LCD_PINS_D4      80  // EXP1.5
150
+  #define BEEPER_PIN       P1_31  // EXP1.1
151
+  #define BTN_ENC          P1_30  // EXP1.2
152
+  #define BTN_EN1          P3_26  // EXP2.5
153
+  #define BTN_EN2          P3_25  // EXP2.3
154
+  #define SD_DETECT_PIN    P0_27  // EXP2.7
155
+  #define LCD_PINS_RS      P0_16  // EXP1.4
156
+  #define LCD_SDSS         P0_28  // EXP2.4
157
+  #define LCD_PINS_ENABLE  P0_18  // EXP1.3
158
+  #define LCD_PINS_D4      P0_14  // EXP1.5
162 159
 #endif // ULTRA_LCD
163 160
 
164 161
 //
165 162
 // Ethernet pins
166 163
 //
167 164
 #ifndef ULTIPANEL
168
-  #define ENET_MDIO        71  // J12-4
169
-  #define ENET_RX_ER       73  // J12-6
170
-  #define ENET_RXD1        75  // J12-8
165
+  #define ENET_MDIO        P1_17  // J12-4
166
+  #define ENET_RX_ER       P1_14  // J12-6
167
+  #define ENET_RXD1        P1_10  // J12-8
171 168
 #endif
172
-#define ENET_MOC           70  // J12-3
173
-#define REF_CLK            72  // J12-5
174
-#define ENET_RXD0          74  // J12-7
175
-#define ENET_CRS           76  // J12-9
176
-#define ENET_TX_EN         77  // J12-10
177
-#define ENET_TXD0          78  // J12-11
178
-#define ENET_TXD1          79  // J12-12
169
+#define ENET_MOC           P1_16  // J12-3
170
+#define REF_CLK            P1_15  // J12-5
171
+#define ENET_RXD0          P1_9   // J12-7
172
+#define ENET_CRS           P1_8   // J12-9
173
+#define ENET_TX_EN         P1_4   // J12-10
174
+#define ENET_TXD0          P1_0   // J12-11
175
+#define ENET_TXD1          P1_1   // J12-12
179 176
 
180 177
 /**
181 178
  *  PWMs
@@ -184,25 +181,25 @@
184 181
  *
185 182
  *  SERVO2 does NOT have a PWM assigned to it.
186 183
  *
187
- *  PWM1.1   DIO4    SERVO3_PIN       FIL_RUNOUT_PIN   5V output, PWM
188
- *  PWM1.1   DIO26   E0_STEP_PIN
189
- *  PWM1.2   DIO11   SERVO0_PIN
190
- *  PWM1.2   DIO54   X_STEP_PIN
191
- *  PWM1.3   DIO6    SERVO1_PIN       J5-1
192
- *  PWM1.3   DIO60   Y_STEP_PIN
193
- *  PWM1.4   DIO53   SDSS(SSEL0)      J3-5  AUX-3
194
- *  PWM1.4   DIO46   Z_STEP_PIN
195
- *  PWM1.5   DIO3    X_MIN_PIN        10K PULLUP TO 3.3v, 1K SERIES
196
- *  PWM1.5   DIO9    RAMPS_D9_PIN
197
- *  PWM1.6   DIO14   Y_MIN_PIN        10K PULLUP TO 3.3v, 1K SERIES
198
- *  PWM1.6   DIO10   RAMPS_D10_PIN
184
+ *  PWM1.1   P1_18   SERVO3_PIN       FIL_RUNOUT_PIN   5V output, PWM
185
+ *  PWM1.1   P2_0    E0_STEP_PIN
186
+ *  PWM1.2   P1_20   SERVO0_PIN
187
+ *  PWM1.2   P2_1    X_STEP_PIN
188
+ *  PWM1.3   P1_21   SERVO1_PIN       J5-1
189
+ *  PWM1.3   P2_2    Y_STEP_PIN
190
+ *  PWM1.4   P1_23   SDSS(SSEL0)      J3-5  AUX-3
191
+ *  PWM1.4   P2_3    Z_STEP_PIN
192
+ *  PWM1.5   P1_24   X_MIN_PIN        10K PULLUP TO 3.3v, 1K SERIES
193
+ *  PWM1.5   P2_4    RAMPS_D9_PIN
194
+ *  PWM1.6   P1_26   Y_MIN_PIN        10K PULLUP TO 3.3v, 1K SERIES
195
+ *  PWM1.6   P2_5    RAMPS_D10_PIN
199 196
  */
200 197
 
201 198
  /**
202 199
   * Special pins
203
-  *   D37 - not 5V tolerant
204
-  *   D49 - not 5V tolerant
205
-  *   D57 - open collector
206
-  *   D58 - open collector
200
+  *   P1_30 - not 5V tolerant
201
+  *   P1_31 - not 5V tolerant
202
+  *   P0_27 - open collector
203
+  *   P0_28 - open collector
207 204
   *
208 205
   */

+ 1
- 1
Marlin/src/pins/pins_RAMPS.h Целия файл

@@ -44,7 +44,7 @@
44 44
  *         7 | 11
45 45
  */
46 46
 
47
-#if ENABLED(IS_REARM)
47
+#if ENABLED(TARGET_LPC1768)
48 48
   #error "Oops!  Use 'BOARD_RAMPS_RE_ARM' to build for Re-ARM."
49 49
 #endif
50 50
 

+ 118
- 160
Marlin/src/pins/pins_RAMPS_RE_ARM.h Целия файл

@@ -34,9 +34,8 @@
34 34
  *
35 35
  */
36 36
 
37
-//#if !defined(TARGET_LPC1768)
38
-#if DISABLED(IS_REARM)
39
-  #error "Oops!  Make sure you have Re-Arm selected."
37
+#ifndef TARGET_LPC1768
38
+  #error "Oops!  Make sure you have LPC1768 selected."
40 39
 #endif
41 40
 
42 41
 #ifndef BOARD_NAME
@@ -45,56 +44,50 @@
45 44
 
46 45
 #define LARGE_FLASH true
47 46
 
48
-// unused
49
-#define D57               57
50
-#define D58               58
51
-
52 47
 //
53 48
 // Servos
54 49
 //
55
-#define SERVO0_PIN         11
56
-#define SERVO1_PIN          6  // also on J5-1
57
-#define SERVO2_PIN          5
58
-#define SERVO3_PIN          4  // 5V output - PWM capable
50
+#define SERVO0_PIN         P1_20
51
+#define SERVO1_PIN         P1_21  // also on J5-1
52
+#define SERVO2_PIN         P1_19
53
+#define SERVO3_PIN         P1_18  // 5V output - PWM capable
59 54
 
60 55
 //
61 56
 // Limit Switches
62 57
 //
63
-#define X_MIN_PIN           3  //10k pullup to 3.3V, 1K series
64
-#define X_MAX_PIN           2  //10k pullup to 3.3V, 1K series
65
-#define Y_MIN_PIN          14  //10k pullup to 3.3V, 1K series
66
-#define Y_MAX_PIN          15  //10k pullup to 3.3V, 1K series
67
-#define Z_MIN_PIN          18  //10k pullup to 3.3V, 1K series
68
-#define Z_MAX_PIN          19  //10k pullup to 3.3V, 1K series
69
-//#define Z_PROBE_PIN         1  // AUX-1
70
-
58
+#define X_MIN_PIN          P1_24  //10k pullup to 3.3V, 1K series
59
+#define X_MAX_PIN          P1_25  //10k pullup to 3.3V, 1K series
60
+#define Y_MIN_PIN          P1_26  //10k pullup to 3.3V, 1K series
61
+#define Y_MAX_PIN          P1_27  //10k pullup to 3.3V, 1K series
62
+#define Z_MIN_PIN          P1_29  //10k pullup to 3.3V, 1K series
63
+#define Z_MAX_PIN          P1_28  //10k pullup to 3.3V, 1K series
71 64
 
72 65
 //
73 66
 // Steppers
74 67
 //
75
-#define X_STEP_PIN         54
76
-#define X_DIR_PIN          55
77
-#define X_ENABLE_PIN       38
68
+#define X_STEP_PIN         P2_1
69
+#define X_DIR_PIN          P0_11
70
+#define X_ENABLE_PIN       P0_10
78 71
 
79
-#define Y_STEP_PIN         60
80
-#define Y_DIR_PIN          61
81
-#define Y_ENABLE_PIN       56
72
+#define Y_STEP_PIN         P2_2
73
+#define Y_DIR_PIN          P0_20
74
+#define Y_ENABLE_PIN       P0_19
82 75
 
83
-#define Z_STEP_PIN         46
84
-#define Z_DIR_PIN          48
85
-#define Z_ENABLE_PIN       62
76
+#define Z_STEP_PIN         P2_3
77
+#define Z_DIR_PIN          P0_22
78
+#define Z_ENABLE_PIN       P0_21
86 79
 
87
-#define E0_STEP_PIN        26
88
-#define E0_DIR_PIN         28
89
-#define E0_ENABLE_PIN      24
80
+#define E0_STEP_PIN        P2_0
81
+#define E0_DIR_PIN         P0_5
82
+#define E0_ENABLE_PIN      P0_4
90 83
 
91
-#define E1_STEP_PIN        36
92
-#define E1_DIR_PIN         34
93
-#define E1_ENABLE_PIN      30
84
+#define E1_STEP_PIN        P2_8
85
+#define E1_DIR_PIN         P2_13
86
+#define E1_ENABLE_PIN      P4_29
94 87
 
95
-#define E2_STEP_PIN        36
96
-#define E2_DIR_PIN         34
97
-#define E2_ENABLE_PIN      30
88
+#define E2_STEP_PIN        P2_8
89
+#define E2_DIR_PIN         P2_13
90
+#define E2_ENABLE_PIN      P4_29
98 91
 
99 92
 //
100 93
 // Temperature Sensors
@@ -131,16 +124,16 @@
131 124
 // Heaters / Fans
132 125
 //
133 126
 #ifndef MOSFET_D_PIN
134
-  #define MOSFET_D_PIN  -1
127
+  #define MOSFET_D_PIN   -1
135 128
 #endif
136 129
 #ifndef RAMPS_D8_PIN
137
-  #define RAMPS_D8_PIN   8
130
+  #define RAMPS_D8_PIN   P2_8
138 131
 #endif
139 132
 #ifndef RAMPS_D9_PIN
140
-  #define RAMPS_D9_PIN   9
133
+  #define RAMPS_D9_PIN   P2_4
141 134
 #endif
142 135
 #ifndef RAMPS_D10_PIN
143
-  #define RAMPS_D10_PIN 10
136
+  #define RAMPS_D10_PIN  P2_5
144 137
 #endif
145 138
 
146 139
 #define HEATER_0_PIN     RAMPS_D10_PIN
@@ -170,22 +163,22 @@
170 163
 #endif
171 164
 
172 165
 #ifndef FAN_PIN
173
-  #define FAN_PIN 4      // IO pin. Buffer needed
166
+  #define FAN_PIN         P1_18 // IO pin. Buffer needed
174 167
 #endif
175 168
 
176 169
 //
177 170
 // Misc. Functions
178 171
 //
179
-#define LED_PIN            13
172
+#define LED_PIN           P4_28
180 173
 
181 174
 // define digital pin 4 for the filament runout sensor. Use the RAMPS 1.4 digital input 4 on the servos connector
182
-#define FIL_RUNOUT_PIN      4
175
+#define FIL_RUNOUT_PIN    P1_18
183 176
 
184
-#define PS_ON_PIN          12
177
+#define PS_ON_PIN         P2_12
185 178
 
186 179
 #if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) && !defined(SPINDLE_LASER_ENABLE_PIN)
187 180
   #if !defined(NUM_SERVOS) || NUM_SERVOS < 4 // try to use servo connector
188
-    #define CASE_LIGHT_PIN    4      // MUST BE HARDWARE PWM
181
+    #define CASE_LIGHT_PIN    P1_18 // MUST BE HARDWARE PWM
189 182
   #endif
190 183
 #endif
191 184
 
@@ -197,17 +190,17 @@
197 190
     #undef  SERVO1
198 191
     #undef  SERVO2
199 192
     #undef  SERVO3
200
-    #define SPINDLE_LASER_ENABLE_PIN  6  // Pin should have a pullup/pulldown!
201
-    #define SPINDLE_LASER_PWM_PIN     4  // MUST BE HARDWARE PWM
202
-    #define SPINDLE_DIR_PIN           5
193
+    #define SPINDLE_LASER_ENABLE_PIN  P1_21  // Pin should have a pullup/pulldown!
194
+    #define SPINDLE_LASER_PWM_PIN     P1_18  // MUST BE HARDWARE PWM
195
+    #define SPINDLE_DIR_PIN           P1_19
203 196
   #endif
204 197
 #endif
205 198
 //
206 199
 // Průša i3 MK2 Multiplexer Support
207 200
 //
208
-#define E_MUX0_PIN          0   // Z_CS_PIN
209
-#define E_MUX1_PIN          1   // E0_CS_PIN
210
-#define E_MUX2_PIN         63   // E1_CS_PIN
201
+#define E_MUX0_PIN         P0_3    // Z_CS_PIN
202
+#define E_MUX1_PIN         P0_2    // E0_CS_PIN
203
+#define E_MUX2_PIN         P0_26   // E1_CS_PIN
211 204
 
212 205
 /**
213 206
  * LCD / Controller
@@ -230,89 +223,76 @@
230 223
 
231 224
 #if ENABLED(ULTRA_LCD)
232 225
 
233
-  #define BEEPER_PIN          37  // not 5V tolerant
226
+  #define BEEPER_PIN          P1_30  // not 5V tolerant
234 227
 
235
-  #define BTN_EN1             31  // J3-2 & AUX-4
236
-  #define BTN_EN2             33  // J3-4 & AUX-4
237
-  #define BTN_ENC             35  // J3-3 & AUX-4
228
+  #define BTN_EN1             P3_26  // J3-2 & AUX-4
229
+  #define BTN_EN2             P3_25  // J3-4 & AUX-4
230
+  #define BTN_ENC             P2_11  // J3-3 & AUX-4
238 231
 
239
-  #define SD_DETECT_PIN       49  // not 5V tolerant   J3-1 & AUX-3
240
-  #define KILL_PIN            41  // J5-4 & AUX-4
241
-  #define LCD_PINS_RS         16  // J3-7 & AUX-4
242
-  #define LCD_SDSS            16  // J3-7 & AUX-4
243
-  #define LCD_BACKLIGHT_PIN   16  // J3-7 & AUX-4 - only used on DOGLCD controllers
244
-  #define LCD_PINS_ENABLE     51  // (MOSI) J3-10 & AUX-3
245
-  #define LCD_PINS_D4         52  // (SCK)  J3-9 & AUX-3
232
+  #define SD_DETECT_PIN       P1_31  // not 5V tolerant   J3-1 & AUX-3
233
+  #define KILL_PIN            P1_22  // J5-4 & AUX-4
234
+  #define LCD_PINS_RS         P0_16  // J3-7 & AUX-4
235
+  #define LCD_SDSS            P0_16  // J3-7 & AUX-4
236
+  #define LCD_BACKLIGHT_PIN   P0_16  // J3-7 & AUX-4 - only used on DOGLCD controllers
237
+  #define LCD_PINS_ENABLE     P0_18  // (MOSI) J3-10 & AUX-3
238
+  #define LCD_PINS_D4         P0_15  // (SCK)  J3-9 & AUX-3
246 239
 
247
-  #define DOGLCD_A0           59  // J3-8 & AUX-2
248
-  #define DOGLCD_CS           63  // J5-3 & AUX-2
240
+  #define DOGLCD_A0           P2_6   // J3-8 & AUX-2
241
+  #define DOGLCD_CS           P0_26  // J5-3 & AUX-2
249 242
 
250 243
   #ifdef ULTIPANEL
251
-    #define LCD_PINS_D5       71  // ENET_MDIO
252
-    #define LCD_PINS_D6       73  // ENET_RX_ER
253
-    #define LCD_PINS_D7       75  // ENET_RXD1
244
+    #define LCD_PINS_D5       P1_17  // ENET_MDIO
245
+    #define LCD_PINS_D6       P1_14  // ENET_RX_ER
246
+    #define LCD_PINS_D7       P1_10  // ENET_RXD1
254 247
   #endif
255 248
 
256 249
   #if ENABLED(NEWPANEL)
257 250
     #if ENABLED(REPRAPWORLD_KEYPAD)
258
-      #define SHIFT_OUT         51  // (MOSI) J3-10 & AUX-3
259
-      #define SHIFT_CLK         52  // (SCK)  J3-9 & AUX-3
260
-      #define SHIFT_LD          49  // not 5V tolerant   J3-1 & AUX-3
251
+      #define SHIFT_OUT         P0_18  // (MOSI) J3-10 & AUX-3
252
+      #define SHIFT_CLK         P0_15  // (SCK)  J3-9 & AUX-3
253
+      #define SHIFT_LD          P1_31  // not 5V tolerant   J3-1 & AUX-3
261 254
     #endif
262 255
   #else
263
-    //#define SHIFT_CLK           31  // J3-2 & AUX-4
264
-    //#define SHIFT_LD            33  // J3-4 & AUX-4
265
-    //#define SHIFT_OUT           35  // J3-3 & AUX-4
266
-    //#define SHIFT_EN            41  // J5-4 & AUX-4
256
+    //#define SHIFT_CLK           P3_26  // J3-2 & AUX-4
257
+    //#define SHIFT_LD            P3_25  // J3-4 & AUX-4
258
+    //#define SHIFT_OUT           P2_11  // J3-3 & AUX-4
259
+    //#define SHIFT_EN            P1_22  // J5-4 & AUX-4
267 260
   #endif
268 261
 
269
-  #define SDCARD_SORT_ALPHA         // Using SORT feature to keep one directory level in RAM
270
-                                    // When going up/down directory levels the SD card is
271
-                                    // accessed but the garbage/lines are removed when the
272
-                                    // LCD updates
273
-
274
-  #define SDSORT_LIMIT       256    // Maximum number of sorted items (10-256). Costs 27 bytes each.
275
-  #define FOLDER_SORTING     -1     // -1=above  0=none  1=below
276
-  #define SDSORT_GCODE       false  // Allow turning sorting on/off with LCD and M34 g-code.
277
-  #define SDSORT_USES_RAM    true   // Pre-allocate a static array for faster pre-sorting.
278
-  #define SDSORT_USES_STACK  false  // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
279
-  #define SDSORT_CACHE_NAMES true   // Keep sorted items in RAM longer for speedy performance. Most expensive option.
280
-  #define SDSORT_DYNAMIC_RAM false  // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
281
-
282 262
   #if ENABLED(VIKI2) || ENABLED(miniVIKI)
283 263
     // #define LCD_SCREEN_ROT_180
284 264
 
285 265
     #undef  BEEPER_PIN
286
-    #define BEEPER_PIN          37  // may change if cable changes
266
+    #define BEEPER_PIN          P1_30  // may change if cable changes
287 267
 
288
-    #define BTN_EN1             31  // J3-2 & AUX-4
289
-    #define BTN_EN2             33  // J3-4 & AUX-4
290
-    #define BTN_ENC             35  // J3-3 & AUX-4
268
+    #define BTN_EN1             P3_26  // J3-2 & AUX-4
269
+    #define BTN_EN2             P3_25  // J3-4 & AUX-4
270
+    #define BTN_ENC             P2_11  // J3-3 & AUX-4
291 271
 
292
-    #define SD_DETECT_PIN       49  // not 5V tolerant   J3-1 & AUX-3
293
-    #define KILL_PIN            41  // J5-4 & AUX-4
272
+    #define SD_DETECT_PIN       P1_31  // not 5V tolerant   J3-1 & AUX-3
273
+    #define KILL_PIN            P1_22  // J5-4 & AUX-4
294 274
 
295 275
     #undef  DOGLCD_CS
296
-    #define DOGLCD_CS           16
297
-    #undef  LCD_BACKLIGHT_PIN   //16  // J3-7 & AUX-4 - only used on DOGLCD controllers
298
-    #undef  LCD_PINS_ENABLE     //51  // (MOSI) J3-10 & AUX-3
299
-    #undef  LCD_PINS_D4         //52  // (SCK)  J3-9 & AUX-3
300
-
301
-    #undef  LCD_PINS_D5         //59  // J3-8 & AUX-2
302
-    #define DOGLCD_A0           59  // J3-8 & AUX-2
303
-    #undef  LCD_PINS_D6         //63  // J5-3 & AUX-2
304
-    #undef  LCD_PINS_D7         // 6  // (SERVO1) J5-1 & SERVO connector
305
-    #define DOGLCD_SCK SCK_PIN
306
-    #define DOGLCD_MOSI MOSI_PIN
307
-
308
-    #define STAT_LED_BLUE_PIN   63  // may change if cable changes
309
-    #define STAT_LED_RED_PIN     6  // may change if cable changes
276
+    #define DOGLCD_CS           P0_16
277
+    #undef  LCD_BACKLIGHT_PIN   //P0_16  // J3-7 & AUX-4 - only used on DOGLCD controllers
278
+    #undef  LCD_PINS_ENABLE     //P0_18  // (MOSI) J3-10 & AUX-3
279
+    #undef  LCD_PINS_D4         //P0_15  // (SCK)  J3-9 & AUX-3
280
+
281
+    #undef  LCD_PINS_D5         //P2_6   // J3-8 & AUX-2
282
+    #define DOGLCD_A0           P2_6   // J3-8 & AUX-2
283
+    #undef  LCD_PINS_D6         //P0_26  // J5-3 & AUX-2
284
+    #undef  LCD_PINS_D7         //P1_21  // (SERVO1) J5-1 & SERVO connector
285
+    #define DOGLCD_SCK          SCK_PIN
286
+    #define DOGLCD_MOSI         MOSI_PIN
287
+
288
+    #define STAT_LED_BLUE_PIN   P0_26  // may change if cable changes
289
+    #define STAT_LED_RED_PIN    P1_21  // may change if cable changes
310 290
   #endif
311 291
 
312
-  //#define MISO_PIN            50  // system defined J3-10 & AUX-3
313
-  //#define MOSI_PIN            51  // system defined J3-10 & AUX-3
314
-  //#define SCK_PIN             52  // system defined J3-9 & AUX-3
315
-  //#define SS_PIN              53  // system defined J3-5 & AUX-3 - sometimes called SDSS
292
+  //#define MISO_PIN            P0_17  // system defined J3-10 & AUX-3
293
+  //#define MOSI_PIN            P0_18  // system defined J3-10 & AUX-3
294
+  //#define SCK_PIN             P0_15  // system defined J3-9 & AUX-3
295
+  //#define SS_PIN              P1_23  // system defined J3-5 & AUX-3 - sometimes called SDSS
316 296
 
317 297
   #if ENABLED(MINIPANEL)
318 298
     // GLCD features
@@ -329,17 +309,17 @@
329 309
 // Ethernet pins
330 310
 //
331 311
 #ifndef ULTIPANEL
332
-  #define ENET_MDIO   71  // J12-4
333
-  #define ENET_RX_ER  73  // J12-6
334
-  #define ENET_RXD1   75  // J12-8
312
+  #define ENET_MDIO   P1_17  // J12-4
313
+  #define ENET_RX_ER  P1_14  // J12-6
314
+  #define ENET_RXD1   P1_10  // J12-8
335 315
 #endif
336
-#define ENET_MOC      70  // J12-3
337
-#define REF_CLK       72  // J12-5
338
-#define ENET_RXD0     74  // J12-7
339
-#define ENET_CRS      76  // J12-9
340
-#define ENET_TX_EN    77  // J12-10
341
-#define ENET_TXD0     78  // J12-11
342
-#define ENET_TXD1     79  // J12-12
316
+#define ENET_MOC      P1_16  // J12-3
317
+#define REF_CLK       P1_15  // J12-5
318
+#define ENET_RXD0     P1_9   // J12-7
319
+#define ENET_CRS      P1_8   // J12-9
320
+#define ENET_TX_EN    P1_4   // J12-10
321
+#define ENET_TXD0     P1_0   // J12-11
322
+#define ENET_TXD1     P1_1   // J12-12
343 323
 
344 324
 /**
345 325
  *  PWMS
@@ -348,47 +328,25 @@
348 328
  *
349 329
  *  SERVO2 does NOT have a PWM assigned to it.
350 330
  *
351
- *  PWM1.1   DIO4    SERVO3_PIN       FIL_RUNOUT_PIN   5V output, PWM
352
- *  PWM1.1   DIO26   E0_STEP_PIN
353
- *  PWM1.2   DIO11   SERVO0_PIN
354
- *  PWM1.2   DIO54   X_STEP_PIN
355
- *  PWM1.3   DIO6    SERVO1_PIN       J5-1
356
- *  PWM1.3   DIO60   Y_STEP_PIN
357
- *  PWM1.4   DIO53   SDSS(SSEL0)      J3-5  AUX-3
358
- *  PWM1.4   DIO46   Z_STEP_PIN
359
- *  PWM1.5   DIO3    X_MIN_PIN        10K PULLUP TO 3.3v, 1K SERIES
360
- *  PWM1.5   DIO9    RAMPS_D9_PIN
361
- *  PWM1.6   DIO14   Y_MIN_PIN        10K PULLUP TO 3.3v, 1K SERIES
362
- *  PWM1.6   DIO10   RAMPS_D10_PIN
363
- */
364
-
365
-/**
366
- *  The following pins are NOT available in a Re-ARM system
367
- *  7
368
- *  17
369
- *  22
370
- *  23
371
- *  25
372
- *  27
373
- *  29
374
- *  32
375
- *  39
376
- *  40
377
- *  42
378
- *  43
379
- *  44
380
- *  45
381
- *  47
382
- *  64
383
- *  65
384
- *  66
331
+ *  PWM1.1   P0_18   SERVO3_PIN       FIL_RUNOUT_PIN   5V output, PWM
332
+ *  PWM1.1   P2_0    E0_STEP_PIN
333
+ *  PWM1.2   P1_20   SERVO0_PIN
334
+ *  PWM1.2   P2_1    X_STEP_PIN
335
+ *  PWM1.3   P1_21   SERVO1_PIN       J5-1
336
+ *  PWM1.3   P2_2    Y_STEP_PIN
337
+ *  PWM1.4   P1_23   SDSS(SSEL0)      J3-5  AUX-3
338
+ *  PWM1.4   P2_3    Z_STEP_PIN
339
+ *  PWM1.5   P1_24   X_MIN_PIN        10K PULLUP TO 3.3v, 1K SERIES
340
+ *  PWM1.5   P2_4    RAMPS_D9_PIN
341
+ *  PWM1.6   P1_26   Y_MIN_PIN        10K PULLUP TO 3.3v, 1K SERIES
342
+ *  PWM1.6   P2_5    RAMPS_D10_PIN
385 343
  */
386 344
 
387 345
  /**
388 346
   * special pins
389
-  *   D37 - not 5V tolerant
390
-  *   D49 - not 5V tolerant
391
-  *   D57 - open collector
392
-  *   D58 - open collector
347
+  *   P1_30 - not 5V tolerant
348
+  *   P1_31 - not 5V tolerant
349
+  *   P0_27 - open collector
350
+  *   P0_28 - open collector
393 351
   *
394 352
  */

+ 1
- 1
Marlin/src/sd/Sd2Card.cpp Целия файл

@@ -170,7 +170,7 @@ bool Sd2Card::eraseSingleBlockEnable() {
170 170
  * the value zero, false, is returned for failure.  The reason for failure
171 171
  * can be determined by calling errorCode() and errorData().
172 172
  */
173
-bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
173
+bool Sd2Card::init(uint8_t sckRateID, pin_t chipSelectPin) {
174 174
   errorCode_ = type_ = 0;
175 175
   chipSelectPin_ = chipSelectPin;
176 176
   // 16-bit init start time allows over a minute

+ 2
- 2
Marlin/src/sd/Sd2Card.h Целия файл

@@ -181,7 +181,7 @@ class Sd2Card {
181 181
    * \return true for success or false for failure.
182 182
    */
183 183
   bool init(uint8_t sckRateID = SPI_FULL_SPEED,
184
-            uint8_t chipSelectPin = SD_CHIP_SELECT_PIN);
184
+            pin_t chipSelectPin = SD_CHIP_SELECT_PIN);
185 185
   bool readBlock(uint32_t block, uint8_t* dst);
186 186
   /**
187 187
    * Read a card's CID register. The CID contains card identification
@@ -220,7 +220,7 @@ class Sd2Card {
220 220
   bool writeStop();
221 221
  private:
222 222
   //----------------------------------------------------------------------------
223
-  uint8_t chipSelectPin_;
223
+  pin_t chipSelectPin_;
224 224
   uint8_t errorCode_;
225 225
   uint8_t spiRate_;
226 226
   uint8_t status_;

+ 4
- 4
platformio.ini Целия файл

@@ -139,9 +139,9 @@ lib_ignore  = Adafruit NeoPixel
139 139
 src_filter  = ${common.default_src_filter}
140 140
 
141 141
 #
142
-# Re-ARM (NXP LPC1768 ARM Cortex-M3)
142
+# NXP LPC1768 ARM Cortex-M3
143 143
 #
144
-[env:Re-ARM]
144
+[env:LPC1768]
145 145
 platform        = nxplpc
146 146
 board_f_cpu     = 100000000L
147 147
 build_flags     = !python Marlin/src/HAL/HAL_LPC1768/lpc1768_flag_script.py
@@ -154,9 +154,9 @@ extra_scripts   = Marlin/src/HAL/HAL_LPC1768/lpc1768_flag_script.py
154 154
 src_filter      = ${common.default_src_filter}
155 155
 
156 156
 #
157
-# Re-ARM (for debugging and development)
157
+# LPC1768 (for debugging and development)
158 158
 #
159
-[env:Re-ARM_debug_and_upload]
159
+[env:LPC1768_debug_and_upload]
160 160
 # Segger JLink
161 161
 platform       = nxplpc
162 162
 #framework     = mbed

Loading…
Отказ
Запис