Quellcode durchsuchen

Merge pull request #6400 from thinkyhead/rc_interrupt_macros

Add and apply interrupt helper macros
Scott Lahteine vor 7 Jahren
Ursprung
Commit
b6ed69571a
6 geänderte Dateien mit 129 neuen und 111 gelöschten Zeilen
  1. 6
    16
      Marlin/Marlin_main.cpp
  2. 103
    71
      Marlin/fastio.h
  3. 14
    14
      Marlin/servo.cpp
  4. 4
    8
      Marlin/stepper.cpp
  5. 1
    1
      Marlin/ultralcd_impl_DOGM.h
  6. 1
    1
      Marlin/ultralcd_impl_HD44780.h

+ 6
- 16
Marlin/Marlin_main.cpp Datei anzeigen

@@ -5858,10 +5858,6 @@ inline void gcode_M42() {
5858 5858
 
5859 5859
     #else
5860 5860
 
5861
-      #if !defined(z_servo_angle)
5862
-        const int z_servo_angle[2] = Z_SERVO_ANGLES;
5863
-      #endif
5864
-
5865 5861
       const uint8_t probe_index = code_seen('P') ? code_value_byte() : Z_ENDSTOP_SERVO_NR;
5866 5862
 
5867 5863
       SERIAL_PROTOCOLLNPGM("Servo probe test");
@@ -11528,15 +11524,13 @@ void prepare_move_to_destination() {
11528 11524
       #ifdef TCCR0A
11529 11525
         case TIMER0A:
11530 11526
         case TIMER0B:
11531
-          // TCCR0B &= ~(_BV(CS00) | _BV(CS01) | _BV(CS02));
11532
-          // TCCR0B |= val;
11527
+          //SET_CS(0, val);
11533 11528
           break;
11534 11529
       #endif
11535 11530
       #ifdef TCCR1A
11536 11531
         case TIMER1A:
11537 11532
         case TIMER1B:
11538
-          // TCCR1B &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12));
11539
-          // TCCR1B |= val;
11533
+          //SET_CS(1, val);
11540 11534
           break;
11541 11535
       #endif
11542 11536
       #ifdef TCCR2
@@ -11549,32 +11543,28 @@ void prepare_move_to_destination() {
11549 11543
       #ifdef TCCR2A
11550 11544
         case TIMER2A:
11551 11545
         case TIMER2B:
11552
-          TCCR2B &= ~(_BV(CS20) | _BV(CS21) | _BV(CS22));
11553
-          TCCR2B |= val;
11546
+          SET_CS(2, val);
11554 11547
           break;
11555 11548
       #endif
11556 11549
       #ifdef TCCR3A
11557 11550
         case TIMER3A:
11558 11551
         case TIMER3B:
11559 11552
         case TIMER3C:
11560
-          TCCR3B &= ~(_BV(CS30) | _BV(CS31) | _BV(CS32));
11561
-          TCCR3B |= val;
11553
+          SET_CS(3, val);
11562 11554
           break;
11563 11555
       #endif
11564 11556
       #ifdef TCCR4A
11565 11557
         case TIMER4A:
11566 11558
         case TIMER4B:
11567 11559
         case TIMER4C:
11568
-          TCCR4B &= ~(_BV(CS40) | _BV(CS41) | _BV(CS42));
11569
-          TCCR4B |= val;
11560
+          SET_CS(4, val);
11570 11561
           break;
11571 11562
       #endif
11572 11563
       #ifdef TCCR5A
11573 11564
         case TIMER5A:
11574 11565
         case TIMER5B:
11575 11566
         case TIMER5C:
11576
-          TCCR5B &= ~(_BV(CS50) | _BV(CS51) | _BV(CS52));
11577
-          TCCR5B |= val;
11567
+          SET_CS(5, val);
11578 11568
           break;
11579 11569
       #endif
11580 11570
     }

+ 103
- 71
Marlin/fastio.h Datei anzeigen

@@ -21,99 +21,135 @@
21 21
  */
22 22
 
23 23
 /**
24
-  This code contributed by Triffid_Hunter and modified by Kliment
25
-  why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
26
-*/
24
+ * Contributed by Triffid_Hunter, modified by Kliment, extended by the Marlin team
25
+ * Why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
26
+ */
27 27
 
28 28
 #ifndef _FASTIO_ARDUINO_H
29 29
 #define _FASTIO_ARDUINO_H
30 30
 
31 31
 #include <avr/io.h>
32 32
 
33
-/**
34
-  utility functions
35
-*/
36
-
37
-#ifndef MASK
38
-  #define MASK(PIN)  (1 << PIN)
33
+#ifndef _BV
34
+  #define _BV(PIN) (1 << PIN)
39 35
 #endif
40 36
 
41 37
 /**
42
-  magic I/O routines
43
-  now you can simply SET_OUTPUT(STEP); WRITE(STEP, 1); WRITE(STEP, 0);
44
-*/
38
+ * Magic I/O routines
39
+ *
40
+ * Now you can simply SET_OUTPUT(PIN); WRITE(PIN, HIGH); WRITE(PIN, LOW);
41
+ */
42
+
43
+#define _READ(IO) ((bool)(DIO ## IO ## _RPORT & _BV(DIO ## IO ## _PIN)))
45 44
 
46
-/// Read a pin
47
-#define _READ(IO) ((bool)(DIO ## IO ## _RPORT & MASK(DIO ## IO ## _PIN)))
48
-/// write to a pin
49
-// On some boards pins > 0x100 are used. These are not converted to atomic actions. An critical section is needed.
45
+// On some boards pins > 0x100 are used. These are not converted to atomic actions. A critical section is needed.
50 46
 
51
-#define _WRITE_NC(IO, v)  do { if (v) {DIO ##  IO ## _WPORT |= MASK(DIO ## IO ## _PIN); } else {DIO ##  IO ## _WPORT &= ~MASK(DIO ## IO ## _PIN); }; } while (0)
47
+#define _WRITE_NC(IO, v)  do { if (v) {DIO ##  IO ## _WPORT |= _BV(DIO ## IO ## _PIN); } else {DIO ##  IO ## _WPORT &= ~_BV(DIO ## IO ## _PIN); }; } while (0)
52 48
 
53 49
 #define _WRITE_C(IO, v)   do { if (v) { \
54 50
                                          CRITICAL_SECTION_START; \
55
-                                         {DIO ##  IO ## _WPORT |= MASK(DIO ## IO ## _PIN); } \
51
+                                         {DIO ##  IO ## _WPORT |= _BV(DIO ## IO ## _PIN); } \
56 52
                                          CRITICAL_SECTION_END; \
57 53
                                        } \
58 54
                                        else { \
59 55
                                          CRITICAL_SECTION_START; \
60
-                                         {DIO ##  IO ## _WPORT &= ~MASK(DIO ## IO ## _PIN); } \
56
+                                         {DIO ##  IO ## _WPORT &= ~_BV(DIO ## IO ## _PIN); } \
61 57
                                          CRITICAL_SECTION_END; \
62 58
                                        } \
63 59
                                      } \
64 60
                                      while (0)
65 61
 
66
-#define _WRITE(IO, v)  do {  if (&(DIO ##  IO ## _RPORT) >= (uint8_t *)0x100) {_WRITE_C(IO, v); } else {_WRITE_NC(IO, v); }; } while (0)
62
+#define _WRITE(IO, v) do { if (&(DIO ## IO ## _RPORT) >= (uint8_t *)0x100) {_WRITE_C(IO, v); } else {_WRITE_NC(IO, v); }; } while (0)
67 63
 
68
-/// toggle a pin
69
-#define _TOGGLE(IO)  do {DIO ##  IO ## _RPORT ^= MASK(DIO ## IO ## _PIN); } while (0)
64
+#define _TOGGLE(IO) do {DIO ## IO ## _RPORT ^= _BV(DIO ## IO ## _PIN); } while (0)
70 65
 
71
-/// set pin as input
72
-#define _SET_INPUT(IO) do {DIO ##  IO ## _DDR &= ~MASK(DIO ## IO ## _PIN); } while (0)
73
-/// set pin as output
74
-#define _SET_OUTPUT(IO) do {DIO ##  IO ## _DDR |=  MASK(DIO ## IO ## _PIN); } while (0)
66
+#define _SET_INPUT(IO) do {DIO ## IO ## _DDR &= ~_BV(DIO ## IO ## _PIN); } while (0)
67
+#define _SET_OUTPUT(IO) do {DIO ## IO ## _DDR |= _BV(DIO ## IO ## _PIN); } while (0)
75 68
 
76
-/// check if pin is an input
77
-#define _GET_INPUT(IO)  ((DIO ## IO ## _DDR & MASK(DIO ## IO ## _PIN)) == 0)
78
-/// check if pin is an output
79
-#define _GET_OUTPUT(IO)  ((DIO ## IO ## _DDR & MASK(DIO ## IO ## _PIN)) != 0)
69
+#define _GET_INPUT(IO) ((DIO ## IO ## _DDR & _BV(DIO ## IO ## _PIN)) == 0)
70
+#define _GET_OUTPUT(IO) ((DIO ## IO ## _DDR & _BV(DIO ## IO ## _PIN)) != 0)
71
+#define _GET_TIMER(IO) (DIO ## IO ## _PWM)
80 72
 
81
-/// check if pin is an timer
82
-#define _GET_TIMER(IO)  (DIO ## IO ## _PWM)
73
+#define READ(IO) _READ(IO)
74
+#define WRITE(IO,V) _WRITE(IO,V)
75
+#define TOGGLE(IO) _TOGGLE(IO)
83 76
 
84
-//  why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
85
-
86
-/// Read a pin wrapper
87
-#define READ(IO)  _READ(IO)
88
-/// Write to a pin wrapper
89
-#define WRITE(IO, v)  _WRITE(IO, v)
90
-
91
-/// toggle a pin wrapper
92
-#define TOGGLE(IO)  _TOGGLE(IO)
93
-
94
-/// set pin as input wrapper
95
-#define SET_INPUT(IO)  _SET_INPUT(IO)
96
-/// set pin as input with pullup wrapper
77
+#define SET_INPUT(IO) _SET_INPUT(IO)
97 78
 #define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _WRITE(IO, HIGH); }while(0)
98
-/// set pin as output wrapper
99
-#define SET_OUTPUT(IO)  _SET_OUTPUT(IO)
79
+#define SET_OUTPUT(IO) _SET_OUTPUT(IO)
100 80
 
101
-/// check if pin is an input wrapper
102
-#define GET_INPUT(IO)  _GET_INPUT(IO)
103
-/// check if pin is an output wrapper
104
-#define GET_OUTPUT(IO)  _GET_OUTPUT(IO)
81
+#define GET_INPUT(IO) _GET_INPUT(IO)
82
+#define GET_OUTPUT(IO) _GET_OUTPUT(IO)
83
+#define GET_TIMER(IO) _GET_TIMER(IO)
105 84
 
106
-/// check if pin is an timer wrapper
107
-#define GET_TIMER(IO)  _GET_TIMER(IO)
108
-
109
-// Shorthand
110
-#define OUT_WRITE(IO, v) { SET_OUTPUT(IO); WRITE(IO, v); }
85
+#define OUT_WRITE(IO, v) do{ SET_OUTPUT(IO); WRITE(IO, v); }while(0)
111 86
 
112 87
 /**
113
-  ports and functions
88
+ * Interrupt Control
89
+ */
114 90
 
115
-  added as necessary or if I feel like it- not a comprehensive list!
116
-*/
91
+// Waveform Generation Modes
92
+typedef enum {
93
+  WGM_NORMAL,          //  0
94
+  WGM_PWM_PC_8,        //  1
95
+  WGM_PWM_PC_9,        //  2
96
+  WGM_PWM_PC_10,       //  3
97
+  WGM_CTC_OCRnA,       //  4  COM OCnx
98
+  WGM_FAST_PWM_8,      //  5
99
+  WGM_FAST_PWM_9,      //  6
100
+  WGM_FAST_PWM_10,     //  7
101
+  WGM_PWM_PC_FC_ICRn,  //  8
102
+  WGM_PWM_PC_FC_OCRnA, //  9  COM OCnA
103
+  WGM_PWM_PC_ICRn,     // 10
104
+  WGM_PWM_PC_OCRnA,    // 11  COM OCnA
105
+  WGM_CTC_ICRn,        // 12  COM OCnx
106
+  WGM_reserved,        // 13
107
+  WGM_FAST_PWM_ICRn,   // 14  COM OCnA
108
+  WGM_FAST_PWM_OCRnA   // 15  COM OCnA
109
+} WaveGenMode;
110
+
111
+// Compare Modes
112
+typedef enum {
113
+  COM_NORMAL,          //  0
114
+  COM_TOGGLE,          //  1  Non-PWM: OCnx ... Both PWM (WGM 9,11,14,15): OCnA only ... else NORMAL
115
+  COM_CLEAR_SET,       //  2  Non-PWM: OCnx ... Fast PWM: OCnx/Bottom ... PF-FC: OCnx Up/Down
116
+  COM_SET_CLEAR        //  3  Non-PWM: OCnx ... Fast PWM: OCnx/Bottom ... PF-FC: OCnx Up/Down
117
+} CompareMode;
118
+
119
+// Clock Sources
120
+typedef enum {
121
+  CS_NONE,             //  0
122
+  CS_PRESCALER_1,      //  1
123
+  CS_PRESCALER_8,      //  2
124
+  CS_PRESCALER_64,     //  3
125
+  CS_PRESCALER_256,    //  4
126
+  CS_PRESCALER_1024,   //  5
127
+  CS_EXT_FALLING,      //  6
128
+  CS_EXT_RISING        //  7
129
+} ClockSource;
130
+
131
+#define SET_WGM(T,V) do{ \
132
+    TCCR##T##A = (TCCR##T##A & ~(0x3 << WGM##T##0)) | (( int(V)       & 0x3) << WGM##T##0); \
133
+    TCCR##T##B = (TCCR##T##B & ~(0x3 << WGM##T##2)) | (((int(V) >> 2) & 0x3) << WGM##T##2); \
134
+  }while(0)
135
+
136
+#define SET_CS(T,V) do{ \
137
+    TCCR##T##B = (TCCR##T##B & ~(0x7 << CS10)) | ((int(V) & 0x7) << CS10); \
138
+  }while(0)
139
+
140
+#define SET_COM(T,Q,V) do{ \
141
+    TCCR##T##Q = (TCCR##T##Q & !(0x3 << COM1##Q##0) | (int(V) & 0x3) << COM1##Q##0); \
142
+  }while(0)
143
+#define SET_COMA(T,V) SET_COM(T,A,V)
144
+#define SET_COMB(T,V) SET_COM(T,B,V)
145
+#define SET_COMS(T,V1,V2) do{ SET_COMA(T,V1); SET_COMB(T,V2); }while(0)
146
+
147
+#define SET_ICNC(T,V) (TCCR##T##B = (TCCR##T##B & ~_BV(7) | ((V) & 1) << 7))
148
+#define SET_ICES(T,V) (TCCR##T##B = (TCCR##T##B & ~_BV(6) | ((V) & 1) << 6))
149
+
150
+/**
151
+ * Ports and Functions
152
+ */
117 153
 
118 154
 #if defined(__AVR_ATmega168__) || defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__)
119 155
   // UART
@@ -446,7 +482,7 @@
446 482
   #define PD7_WPORT   PORTD
447 483
   #define PD7_DDR     DDRD
448 484
   #define PD7_PWM     NULL
449
-#endif  /*  _AVR_ATmega{168,328,328P}__ */
485
+#endif // __AVR_ATmega(168|328|328P)__
450 486
 
451 487
 #if defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__)
452 488
   // UART
@@ -949,7 +985,7 @@
949 985
   #define PD7_WPORT   PORTD
950 986
   #define PD7_DDR     DDRD
951 987
   #define PD7_PWM     OCR2A
952
-#endif  /*  _AVR_ATmega{644,644P,644PA}__ */
988
+#endif // __AVR_ATmega(644|644P|644PA)__
953 989
 
954 990
 #if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
955 991
   // UART
@@ -2031,8 +2067,7 @@
2031 2067
   #define PL7_WPORT   PORTL
2032 2068
   #define PL7_DDR     DDRL
2033 2069
   #define PL7_PWM     NULL
2034
-
2035
-#endif
2070
+#endif // __AVR_ATmega(1280|2560)__
2036 2071
 
2037 2072
 #if defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB647__)
2038 2073
 
@@ -2040,8 +2075,8 @@
2040 2075
   #define DEBUG_LED   DIO31 /* led D5 red */
2041 2076
 
2042 2077
   /**
2043
-  pins
2044
-  */
2078
+   * pins
2079
+   */
2045 2080
 
2046 2081
   //#define AT90USBxx_TEENSYPP_ASSIGNMENTS // Use Teensy++ 2.0 assignments
2047 2082
   #ifndef AT90USBxx_TEENSYPP_ASSIGNMENTS // Use traditional Marlin pin assignments
@@ -3335,8 +3370,7 @@
3335 3370
     #define PF7_DDR     DDRF
3336 3371
 
3337 3372
   #endif // AT90USBxx_TEENSYPP_ASSIGNMENTS Teensyduino assignments
3338
-#endif // __AVR_AT90usbxxx__
3339
-
3373
+#endif // __AVR_AT90USB(1287|1286|646|647)__
3340 3374
 
3341 3375
 #if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)
3342 3376
   // UART
@@ -4027,12 +4061,10 @@
4027 4061
   #define PG5_WPORT   PORTG
4028 4062
   #define PG5_DDR     DDRG
4029 4063
   #define PG5_PWM     &OCR0B
4030
-
4031
-
4032
-#endif
4064
+#endif // __AVR_ATmega(1281|2561)__
4033 4065
 
4034 4066
 #ifndef DIO0_PIN
4035 4067
   #error "pins for this chip not defined in arduino.h! If you write an appropriate pin definition and have this firmware work on your chip, please submit a pull request"
4036 4068
 #endif
4037 4069
 
4038
-#endif /* _FASTIO_ARDUINO_H */
4070
+#endif // _FASTIO_ARDUINO_H

+ 14
- 14
Marlin/servo.cpp Datei anzeigen

@@ -168,8 +168,8 @@ static void initISR(timer16_Sequence_t timer) {
168 168
         SBI(TIFR, OCF3A);     // clear any pending interrupts;
169 169
         SBI(ETIMSK, OCIE3A);  // enable the output compare interrupt
170 170
       #else
171
-        TIFR3 = _BV(OCF3A);     // clear any pending interrupts;
172
-        TIMSK3 =  _BV(OCIE3A) ; // enable the output compare interrupt
171
+        SBI(TIFR3, OCF3A);   // clear any pending interrupts;
172
+        SBI(TIMSK3, OCIE3A); // enable the output compare interrupt
173 173
       #endif
174 174
       #ifdef WIRING
175 175
         timerAttach(TIMER3OUTCOMPAREA_INT, Timer3Service);  // for Wiring platform only
@@ -183,7 +183,7 @@ static void initISR(timer16_Sequence_t timer) {
183 183
       TCCR4B = _BV(CS41);     // set prescaler of 8
184 184
       TCNT4 = 0;              // clear the timer count
185 185
       TIFR4 = _BV(OCF4A);     // clear any pending interrupts;
186
-      TIMSK4 =  _BV(OCIE4A) ; // enable the output compare interrupt
186
+      TIMSK4 = _BV(OCIE4A);   // enable the output compare interrupt
187 187
     }
188 188
   #endif
189 189
 
@@ -193,7 +193,7 @@ static void initISR(timer16_Sequence_t timer) {
193 193
       TCCR5B = _BV(CS51);     // set prescaler of 8
194 194
       TCNT5 = 0;              // clear the timer count
195 195
       TIFR5 = _BV(OCF5A);     // clear any pending interrupts;
196
-      TIMSK5 =  _BV(OCIE5A) ; // enable the output compare interrupt
196
+      TIMSK5 = _BV(OCIE5A);   // enable the output compare interrupt
197 197
     }
198 198
   #endif
199 199
 }
@@ -203,21 +203,21 @@ static void finISR(timer16_Sequence_t timer) {
203 203
   #ifdef WIRING
204 204
     if (timer == _timer1) {
205 205
       CBI(
206
-      #if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)
207
-        TIMSK1
208
-      #else
209
-        TIMSK
210
-      #endif
206
+        #if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)
207
+          TIMSK1
208
+        #else
209
+          TIMSK
210
+        #endif
211 211
           , OCIE1A);    // disable timer 1 output compare interrupt
212 212
       timerDetach(TIMER1OUTCOMPAREA_INT);
213 213
     }
214 214
     else if (timer == _timer3) {
215 215
       CBI(
216
-      #if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)
217
-        TIMSK3
218
-      #else
219
-        ETIMSK
220
-      #endif
216
+        #if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)
217
+          TIMSK3
218
+        #else
219
+          ETIMSK
220
+        #endif
221 221
           , OCIE3A);    // disable the timer3 output compare A interrupt
222 222
       timerDetach(TIMER3OUTCOMPAREA_INT);
223 223
     }

+ 4
- 8
Marlin/stepper.cpp Datei anzeigen

@@ -271,7 +271,7 @@ volatile long Stepper::endstops_trigsteps[XYZ];
271 271
  *  The slope of acceleration is calculated using v = u + at where t is the accumulated timer values of the steps so far.
272 272
  */
273 273
 void Stepper::wake_up() {
274
-  //  TCNT1 = 0;
274
+  // TCNT1 = 0;
275 275
   ENABLE_STEPPER_DRIVER_INTERRUPT();
276 276
 }
277 277
 
@@ -1081,21 +1081,17 @@ void Stepper::init() {
1081 1081
   #endif
1082 1082
 
1083 1083
   // waveform generation = 0100 = CTC
1084
-  CBI(TCCR1B, WGM13);
1085
-  SBI(TCCR1B, WGM12);
1086
-  CBI(TCCR1A, WGM11);
1087
-  CBI(TCCR1A, WGM10);
1084
+  SET_WGM(1, WGM_CTC_OCRnA);
1088 1085
 
1089 1086
   // output mode = 00 (disconnected)
1090
-  TCCR1A &= ~(3 << COM1A0);
1091
-  TCCR1A &= ~(3 << COM1B0);
1087
+  SET_COMS(1, COM_NORMAL, COM_NORMAL);
1092 1088
 
1093 1089
   // Set the timer pre-scaler
1094 1090
   // Generally we use a divider of 8, resulting in a 2MHz timer
1095 1091
   // frequency on a 16MHz MCU. If you are going to change this, be
1096 1092
   // sure to regenerate speed_lookuptable.h with
1097 1093
   // create_speed_lookuptable.py
1098
-  TCCR1B = (TCCR1B & ~(0x07 << CS10)) | (2 << CS10);
1094
+  SET_CS(1, CS_PRESCALER_8);  //  CS 2 = 1/8 prescaler
1099 1095
 
1100 1096
   // Init Stepper ISR to 122 Hz for quick starting
1101 1097
   OCR1A = 0x4000;

+ 1
- 1
Marlin/ultralcd_impl_DOGM.h Datei anzeigen

@@ -791,7 +791,7 @@ static void lcd_implementation_status_screen() {
791 791
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float51, ftostr51sign);
792 792
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float52, ftostr52sign);
793 793
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float62, ftostr62rj);
794
-  DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(long, long5, ftostr5rj);
794
+  DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(unsigned long, long5, ftostr5rj);
795 795
 
796 796
   #define lcd_implementation_drawmenu_setting_edit_bool(sel, row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))
797 797
   #define lcd_implementation_drawmenu_setting_edit_callback_bool(sel, row, pstr, pstr2, data, callback) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))

+ 1
- 1
Marlin/ultralcd_impl_HD44780.h Datei anzeigen

@@ -894,7 +894,7 @@ static void lcd_implementation_status_screen() {
894 894
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float51, ftostr51sign);
895 895
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float52, ftostr52sign);
896 896
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float62, ftostr62rj);
897
-  DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(long, long5, ftostr5rj);
897
+  DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(unsigned long, long5, ftostr5rj);
898 898
 
899 899
   #define lcd_implementation_drawmenu_setting_edit_bool(sel, row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, '>', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))
900 900
   #define lcd_implementation_drawmenu_setting_edit_callback_bool(sel, row, pstr, pstr2, data, callback) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, '>', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))

Laden…
Abbrechen
Speichern