Browse Source

2.0 compile issues

Bob-the-Kuhn 7 years ago
parent
commit
62054af6eb
2 changed files with 563 additions and 258 deletions
  1. 561
    256
      Marlin/src/HAL/HAL_LPC1768/HardwareSerial.cpp
  2. 2
    2
      Marlin/src/HAL/HAL_LPC1768/include/arduino.h

+ 561
- 256
Marlin/src/HAL/HAL_LPC1768/HardwareSerial.cpp View File

@@ -35,301 +35,606 @@ volatile uint32_t UART0RxQueueWritePos = 0, UART1RxQueueWritePos = 0, UART2RxQue
35 35
 volatile uint32_t UART0RxQueueReadPos = 0, UART1RxQueueReadPos = 0, UART2RxQueueReadPos = 0, UART3RxQueueReadPos = 0;
36 36
 volatile uint8_t dummy;
37 37
 
38
-void HardwareSerial::begin(uint32_t baudrate) {
39
-  uint32_t Fdiv, pclkdiv, pclk;
40
-
41
-  if (PortNum == 0) {
42
-    LPC_PINCON->PINSEL0 &= ~0x000000F0;
43
-    LPC_PINCON->PINSEL0 |= 0x00000050;  /* RxD0 is P0.3 and TxD0 is P0.2 */
44
-    /* By default, the PCLKSELx value is zero, thus, the PCLK for
45
-       all the peripherals is 1/4 of the SystemFrequency. */
46
-    /* Bit 6~7 is for UART0 */
47
-    pclkdiv = (LPC_SC->PCLKSEL0 >> 6) & 0x03;
48
-    switch (pclkdiv) {
49
-      case 0x00:
50
-      default:
51
-        pclk = SystemCoreClock / 4;
52
-        break;
53
-      case 0x01:
54
-        pclk = SystemCoreClock;
55
-        break;
56
-      case 0x02:
57
-        pclk = SystemCoreClock / 2;
58
-        break;
59
-      case 0x03:
60
-        pclk = SystemCoreClock / 8;
61
-        break;
62
-    }
38
+  void HardwareSerial::begin(uint32_t baudrate) {
39
+    uint32_t Fdiv;
40
+     uint32_t pclkdiv, pclk;
63 41
 
64
-    LPC_UART0->LCR = 0x83;       /* 8 bits, no Parity, 1 Stop bit */
65
-    Fdiv = ( pclk / 16 ) / baudrate ;   /*baud rate */
66
-    LPC_UART0->DLM = Fdiv / 256;
67
-    LPC_UART0->DLL = Fdiv % 256;
68
-    LPC_UART0->LCR = 0x03;      /* DLAB = 0 */
69
-    LPC_UART0->FCR = 0x07;       /* Enable and reset TX and RX FIFO. */
42
+     if ( PortNum == 0 )
43
+     {
44
+   	LPC_PINCON->PINSEL0 &= ~0x000000F0;
45
+   	LPC_PINCON->PINSEL0 |= 0x00000050;  /* RxD0 is P0.3 and TxD0 is P0.2 */
46
+   	/* By default, the PCLKSELx value is zero, thus, the PCLK for
47
+   	all the peripherals is 1/4 of the SystemFrequency. */
48
+   	/* Bit 6~7 is for UART0 */
49
+   	pclkdiv = (LPC_SC->PCLKSEL0 >> 6) & 0x03;
50
+   	switch ( pclkdiv )
51
+   	{
52
+   	  case 0x00:
53
+   	  default:
54
+   		pclk = SystemCoreClock/4;
55
+   		break;
56
+   	  case 0x01:
57
+   		pclk = SystemCoreClock;
58
+   		break;
59
+   	  case 0x02:
60
+   		pclk = SystemCoreClock/2;
61
+   		break;
62
+   	  case 0x03:
63
+   		pclk = SystemCoreClock/8;
64
+   		break;
65
+   	}
70 66
 
71
-    NVIC_EnableIRQ(UART0_IRQn);
67
+       LPC_UART0->LCR = 0x83;		/* 8 bits, no Parity, 1 Stop bit */
68
+   	Fdiv = ( pclk / 16 ) / baudrate ;	/*baud rate */
69
+       LPC_UART0->DLM = Fdiv / 256;
70
+       LPC_UART0->DLL = Fdiv % 256;
71
+   	LPC_UART0->LCR = 0x03;		/* DLAB = 0 */
72
+       LPC_UART0->FCR = 0x07;		/* Enable and reset TX and RX FIFO. */
72 73
 
73
-    LPC_UART0->IER = IER_RBR | IER_THRE | IER_RLS;   /* Enable UART0 interrupt */
74
-  }
75
-  else if (PortNum == 1) {
76
-    LPC_PINCON->PINSEL4 &= ~0x0000000F;
77
-    LPC_PINCON->PINSEL4 |= 0x0000000A;  /* Enable RxD1 P2.1, TxD1 P2.0 */
78
-
79
-    /* By default, the PCLKSELx value is zero, thus, the PCLK for
80
-    all the peripherals is 1/4 of the SystemFrequency. */
81
-    /* Bit 8,9 are for UART1 */
82
-    pclkdiv = (LPC_SC->PCLKSEL0 >> 8) & 0x03;
83
-    switch (pclkdiv) {
84
-      case 0x00:
85
-      default:
86
-        pclk = SystemCoreClock / 4;
87
-        break;
88
-      case 0x01:
89
-        pclk = SystemCoreClock;
90
-        break;
91
-      case 0x02:
92
-        pclk = SystemCoreClock / 2;
93
-        break;
94
-      case 0x03:
95
-        pclk = SystemCoreClock / 8;
96
-        break;
97
-    }
74
+      	NVIC_EnableIRQ(UART0_IRQn);
75
+
76
+       LPC_UART0->IER = IER_RBR | IER_THRE | IER_RLS;	/* Enable UART0 interrupt */
77
+     }
78
+     else if ( PortNum == 1 )
79
+     {
80
+   	LPC_PINCON->PINSEL4 &= ~0x0000000F;
81
+   	LPC_PINCON->PINSEL4 |= 0x0000000A;	/* Enable RxD1 P2.1, TxD1 P2.0 */
82
+
83
+   	/* By default, the PCLKSELx value is zero, thus, the PCLK for
84
+   	all the peripherals is 1/4 of the SystemFrequency. */
85
+   	/* Bit 8,9 are for UART1 */
86
+   	pclkdiv = (LPC_SC->PCLKSEL0 >> 8) & 0x03;
87
+   	switch ( pclkdiv )
88
+   	{
89
+   	  case 0x00:
90
+   	  default:
91
+   		pclk = SystemCoreClock/4;
92
+   		break;
93
+   	  case 0x01:
94
+   		pclk = SystemCoreClock;
95
+   		break;
96
+   	  case 0x02:
97
+   		pclk = SystemCoreClock/2;
98
+   		break;
99
+   	  case 0x03:
100
+   		pclk = SystemCoreClock/8;
101
+   		break;
102
+   	}
103
+
104
+       LPC_UART1->LCR = 0x83;		/* 8 bits, no Parity, 1 Stop bit */
105
+   	Fdiv = ( pclk / 16 ) / baudrate ;	/*baud rate */
106
+       LPC_UART1->DLM = Fdiv / 256;
107
+       LPC_UART1->DLL = Fdiv % 256;
108
+   	LPC_UART1->LCR = 0x03;		/* DLAB = 0 */
109
+       LPC_UART1->FCR = 0x07;		/* Enable and reset TX and RX FIFO. */
110
+
111
+      	NVIC_EnableIRQ(UART1_IRQn);
112
+
113
+       LPC_UART1->IER = IER_RBR | IER_THRE | IER_RLS;	/* Enable UART1 interrupt */
114
+     }
115
+     else if ( PortNum == 2 )
116
+     {
117
+   	  //LPC_PINCON->PINSEL4 &= ~0x000F0000;  /*Pinsel4 Bits 16-19*/
118
+   	  //LPC_PINCON->PINSEL4 |=  0x000A0000;  /* RxD2 is P2.9 and TxD2 is P2.8, value 10*/
119
+   	  LPC_PINCON->PINSEL0 &= ~0x00F00000;  /*Pinsel0 Bits 20-23*/
120
+   	  LPC_PINCON->PINSEL0 |=  0x00500000;  /* RxD2 is P0.11 and TxD2 is P0.10, value 01*/
121
+
122
+   	  LPC_SC->PCONP |= 1<<24; //Enable PCUART2
123
+   	  /* By default, the PCLKSELx value is zero, thus, the PCLK for
124
+   		all the peripherals is 1/4 of the SystemFrequency. */
125
+   	  /* Bit 6~7 is for UART3 */
126
+   	  pclkdiv = (LPC_SC->PCLKSEL1 >> 16) & 0x03;
127
+   	  switch ( pclkdiv )
128
+   	  {
129
+   	  case 0x00:
130
+   	  default:
131
+   		  pclk = SystemCoreClock/4;
132
+   		  break;
133
+   	  case 0x01:
134
+   		  pclk = SystemCoreClock;
135
+   		  break;
136
+   	  case 0x02:
137
+   		  pclk = SystemCoreClock/2;
138
+   		  break;
139
+   	  case 0x03:
140
+   		  pclk = SystemCoreClock/8;
141
+   		  break;
142
+   	  }
143
+   	  LPC_UART2->LCR = 0x83;		/* 8 bits, no Parity, 1 Stop bit */
144
+   	  Fdiv = ( pclk / 16 ) / baudrate ;	/*baud rate */
145
+   	  LPC_UART2->DLM = Fdiv / 256;
146
+   	  LPC_UART2->DLL = Fdiv % 256;
147
+   	  LPC_UART2->LCR = 0x03;		/* DLAB = 0 */
148
+   	  LPC_UART2->FCR = 0x07;		/* Enable and reset TX and RX FIFO. */
98 149
 
99
-    LPC_UART1->LCR = 0x83;       /* 8 bits, no Parity, 1 Stop bit */
100
-    Fdiv = ( pclk / 16 ) / baudrate ;   /*baud rate */
101
-    LPC_UART1->DLM = Fdiv / 256;
102
-    LPC_UART1->DLL = Fdiv % 256;
103
-    LPC_UART1->LCR = 0x03;      /* DLAB = 0 */
104
-    LPC_UART1->FCR = 0x07;       /* Enable and reset TX and RX FIFO. */
150
+   	  NVIC_EnableIRQ(UART2_IRQn);
105 151
 
106
-    NVIC_EnableIRQ(UART1_IRQn);
152
+   	  LPC_UART2->IER = IER_RBR | IER_THRE | IER_RLS;	/* Enable UART3 interrupt */
153
+     }
154
+     else if ( PortNum == 3 )
155
+     {
156
+   	  LPC_PINCON->PINSEL0 &= ~0x0000000F;
157
+   	  LPC_PINCON->PINSEL0 |=  0x0000000A;  /* RxD3 is P0.1 and TxD3 is P0.0 */
158
+   	  LPC_SC->PCONP |= 1<<4 | 1<<25; //Enable PCUART1
159
+   	  /* By default, the PCLKSELx value is zero, thus, the PCLK for
160
+   		all the peripherals is 1/4 of the SystemFrequency. */
161
+   	  /* Bit 6~7 is for UART3 */
162
+   	  pclkdiv = (LPC_SC->PCLKSEL1 >> 18) & 0x03;
163
+   	  switch ( pclkdiv )
164
+   	  {
165
+   	  case 0x00:
166
+   	  default:
167
+   		  pclk = SystemCoreClock/4;
168
+   		  break;
169
+   	  case 0x01:
170
+   		  pclk = SystemCoreClock;
171
+   		  break;
172
+   	  case 0x02:
173
+   		  pclk = SystemCoreClock/2;
174
+   		  break;
175
+   	  case 0x03:
176
+   		  pclk = SystemCoreClock/8;
177
+   		  break;
178
+   	  }
179
+   	  LPC_UART3->LCR = 0x83;		/* 8 bits, no Parity, 1 Stop bit */
180
+   	  Fdiv = ( pclk / 16 ) / baudrate ;	/*baud rate */
181
+   	  LPC_UART3->DLM = Fdiv / 256;
182
+   	  LPC_UART3->DLL = Fdiv % 256;
183
+   	  LPC_UART3->LCR = 0x03;		/* DLAB = 0 */
184
+   	  LPC_UART3->FCR = 0x07;		/* Enable and reset TX and RX FIFO. */
107 185
 
108
-    LPC_UART1->IER = IER_RBR | IER_THRE | IER_RLS;   /* Enable UART1 interrupt */
186
+   	  NVIC_EnableIRQ(UART3_IRQn);
187
+
188
+   	  LPC_UART3->IER = IER_RBR | IER_THRE | IER_RLS;	/* Enable UART3 interrupt */
189
+     }
109 190
   }
110
-  else if (PortNum == 2) {
111
-    //LPC_PINCON->PINSEL4 &= ~0x000F0000;  /*Pinsel4 Bits 16-19*/
112
-    //LPC_PINCON->PINSEL4 |=  0x000A0000;  /* RxD2 is P2.9 and TxD2 is P2.8, value 10*/
113
-    LPC_PINCON->PINSEL0 &= ~0x00F00000;  /*Pinsel0 Bits 20-23*/
114
-    LPC_PINCON->PINSEL0 |=  0x00500000;  /* RxD2 is P0.11 and TxD2 is P0.10, value 01*/
115
-
116
-    LPC_SC->PCONP |= 1 << 24; //Enable PCUART2
117
-    /* By default, the PCLKSELx value is zero, thus, the PCLK for
118
-      all the peripherals is 1/4 of the SystemFrequency. */
119
-    /* Bit 6~7 is for UART3 */
120
-    pclkdiv = (LPC_SC->PCLKSEL1 >> 16) & 0x03;
121
-    switch (pclkdiv) {
122
-      case 0x00:
123
-      default:
124
-          pclk = SystemCoreClock / 4;
125
-          break;
126
-      case 0x01:
127
-          pclk = SystemCoreClock;
128
-          break;
129
-      case 0x02:
130
-          pclk = SystemCoreClock / 2;
131
-          break;
132
-      case 0x03:
133
-          pclk = SystemCoreClock / 8;
134
-          break;
135
-    }
136
-    LPC_UART2->LCR = 0x83;        /* 8 bits, no Parity, 1 Stop bit */
137
-    Fdiv = (pclk / 16) / baudrate; /*baud rate */
138
-    LPC_UART2->DLM = Fdiv >> 8;
139
-    LPC_UART2->DLL = Fdiv & 0xFF;
140
-    LPC_UART2->LCR = 0x03;        /* DLAB = 0 */
141
-    LPC_UART2->FCR = 0x07;        /* Enable and reset TX and RX FIFO. */
142 191
 
143
-    NVIC_EnableIRQ(UART2_IRQn);
192
+  int HardwareSerial::read() {
193
+    uint8_t rx;
194
+  	if ( PortNum == 0 )
195
+  	  {
196
+  		  if (UART0RxQueueReadPos == UART0RxQueueWritePos)
197
+  		    return -1;
198
+
199
+  		  // Read from "head"
200
+  		  rx = UART0Buffer[UART0RxQueueReadPos]; // grab next byte
201
+  		  UART0RxQueueReadPos = (UART0RxQueueReadPos + 1) % UARTRXQUEUESIZE;
202
+  		  return rx;
203
+  	  }
204
+  	  if ( PortNum == 1 )
205
+  	  {
206
+  		  if (UART1RxQueueReadPos == UART1RxQueueWritePos)
207
+  		    return -1;
208
+
209
+  		  // Read from "head"
210
+  		  rx = UART1Buffer[UART1RxQueueReadPos]; // grab next byte
211
+  		  UART1RxQueueReadPos = (UART1RxQueueReadPos + 1) % UARTRXQUEUESIZE;
212
+  		  return rx;
213
+  	  }
214
+  	  if ( PortNum == 2 )
215
+  	  {
216
+  		  if (UART2RxQueueReadPos == UART2RxQueueWritePos)
217
+  		    return -1;
218
+
219
+  		  // Read from "head"
220
+  		  rx = UART2Buffer[UART2RxQueueReadPos]; // grab next byte
221
+  		  UART2RxQueueReadPos = (UART2RxQueueReadPos + 1) % UARTRXQUEUESIZE;
222
+  		  return rx;
223
+  	  }
224
+  	  if ( PortNum == 3 )
225
+  	  {
226
+  		  if (UART3RxQueueReadPos == UART3RxQueueWritePos)
227
+  		    return -1;
144 228
 
145
-    LPC_UART2->IER = IER_RBR | IER_THRE | IER_RLS;    /* Enable UART3 interrupt */
229
+  		  // Read from "head"
230
+  		  rx = UART3Buffer[UART3RxQueueReadPos]; // grab next byte
231
+  		  UART3RxQueueReadPos = (UART3RxQueueReadPos + 1) % UARTRXQUEUESIZE;
232
+  		  return rx;
233
+  	  }
234
+  	  return 0;
146 235
   }
147
-  else if (PortNum == 3) {
148
-    LPC_PINCON->PINSEL0 &= ~0x0000000F;
149
-    LPC_PINCON->PINSEL0 |=  0x0000000A;  /* RxD3 is P0.1 and TxD3 is P0.0 */
150
-    LPC_SC->PCONP |= 1 << 4 | 1 << 25; //Enable PCUART1
151
-    /* By default, the PCLKSELx value is zero, thus, the PCLK for
152
-      all the peripherals is 1/4 of the SystemFrequency. */
153
-    /* Bit 6~7 is for UART3 */
154
-    pclkdiv = (LPC_SC->PCLKSEL1 >> 18) & 0x03;
155
-    switch (pclkdiv) {
156
-      case 0x00:
157
-      default:
158
-        pclk = SystemCoreClock / 4;
159
-        break;
160
-      case 0x01:
161
-        pclk = SystemCoreClock;
162
-        break;
163
-      case 0x02:
164
-        pclk = SystemCoreClock / 2;
165
-        break;
166
-      case 0x03:
167
-        pclk = SystemCoreClock / 8;
168
-        break;
169
-    }
170
-    LPC_UART3->LCR = 0x83;        /* 8 bits, no Parity, 1 Stop bit */
171
-    Fdiv = (pclk / 16) / baudrate ; /*baud rate */
172
-    LPC_UART3->DLM = Fdiv >> 8;
173
-    LPC_UART3->DLL = Fdiv & 0xFF;
174
-    LPC_UART3->LCR = 0x03;        /* DLAB = 0 */
175
-    LPC_UART3->FCR = 0x07;        /* Enable and reset TX and RX FIFO. */
176 236
 
177
-    NVIC_EnableIRQ(UART3_IRQn);
237
+  size_t HardwareSerial::write(uint8_t send) {
238
+    if ( PortNum == 0 )
239
+     {
240
+   	  /* THRE status, contain valid data */
241
+   	  while ( !(UART0TxEmpty & 0x01) );
242
+   	  LPC_UART0->THR = send;
243
+   	  UART0TxEmpty = 0;	/* not empty in the THR until it shifts out */
244
+     }
245
+     else if (PortNum == 1)
246
+     {
247
+
248
+   	  /* THRE status, contain valid data */
249
+   	  while ( !(UART1TxEmpty & 0x01) );
250
+   	  LPC_UART1->THR = send;
251
+   	  UART1TxEmpty = 0;	/* not empty in the THR until it shifts out */
252
+
253
+
254
+     }
255
+     else if ( PortNum == 2 )
256
+     {
257
+   	  /* THRE status, contain valid data */
258
+   	  while ( !(UART2TxEmpty & 0x01) );
259
+   	  LPC_UART2->THR = send;
260
+   	  UART2TxEmpty = 0;	/* not empty in the THR until it shifts out */
178 261
 
179
-    LPC_UART3->IER = IER_RBR | IER_THRE | IER_RLS;    /* Enable UART3 interrupt */
262
+     }
263
+     else if ( PortNum == 3 )
264
+     {
265
+   	  /* THRE status, contain valid data */
266
+   	  while ( !(UART3TxEmpty & 0x01) );
267
+   	  LPC_UART3->THR = send;
268
+   	  UART3TxEmpty = 0;	/* not empty in the THR until it shifts out */
269
+
270
+     }
271
+     return 0;
180 272
   }
273
+
274
+  int HardwareSerial::available() {
275
+    if ( PortNum == 0 )
276
+{
277
+  return (UART0RxQueueWritePos + UARTRXQUEUESIZE - UART0RxQueueReadPos) % UARTRXQUEUESIZE;
278
+}
279
+if ( PortNum == 1 )
280
+{
281
+  return (UART1RxQueueWritePos + UARTRXQUEUESIZE - UART1RxQueueReadPos) % UARTRXQUEUESIZE;
282
+}
283
+if ( PortNum == 2 )
284
+{
285
+  return (UART2RxQueueWritePos + UARTRXQUEUESIZE - UART2RxQueueReadPos) % UARTRXQUEUESIZE;
286
+}
287
+if ( PortNum == 3 )
288
+{
289
+  return (UART3RxQueueWritePos + UARTRXQUEUESIZE - UART3RxQueueReadPos) % UARTRXQUEUESIZE;
181 290
 }
291
+return 0;
292
+  }
293
+
294
+  void HardwareSerial::flush() {
295
+    if ( PortNum == 0 )
296
+{
297
+  UART0RxQueueWritePos = 0;
298
+  UART0RxQueueReadPos = 0;
182 299
 
183
-int HardwareSerial::read() {
184
-  uint8_t rx;
185
-  if (PortNum == 0) {
186
-    if (UART0RxQueueReadPos == UART0RxQueueWritePos) return -1;
187
-    // Read from "head"
188
-    rx = UART0Buffer[UART0RxQueueReadPos]; // grab next byte
189
-    UART0RxQueueReadPos = (UART0RxQueueReadPos + 1) % UARTRXQUEUESIZE;
190
-    return rx;
300
+}
301
+if ( PortNum == 1 )
302
+{
303
+  UART1RxQueueWritePos = 0;
304
+  UART1RxQueueReadPos = 0;
305
+}
306
+if ( PortNum == 2 )
307
+{
308
+  UART2RxQueueWritePos = 0;
309
+  UART2RxQueueReadPos = 0;
310
+}
311
+if ( PortNum == 3 )
312
+{
313
+  UART3RxQueueWritePos = 0;
314
+  UART3RxQueueReadPos = 0;
315
+}
316
+return;
191 317
   }
192
-  if (PortNum == 1) {
193
-    if (UART1RxQueueReadPos == UART1RxQueueWritePos) return -1;
194
-    rx = UART1Buffer[UART1RxQueueReadPos];
195
-    UART1RxQueueReadPos = (UART1RxQueueReadPos + 1) % UARTRXQUEUESIZE;
196
-    return rx;
318
+
319
+  void HardwareSerial::printf(const char *format, ...) {
320
+    static char buffer[256];
321
+    va_list vArgs;
322
+    va_start(vArgs, format);
323
+    int length = vsnprintf((char *) buffer, 256, (char const *) format, vArgs);
324
+    va_end(vArgs);
325
+    if (length > 0 && length < 256) {
326
+        for (int i = 0; i < length;) {
327
+          write(buffer[i]);
328
+            ++i;
329
+          }
330
+        }
331
+    }
332
+
333
+#ifdef __cplusplus
334
+extern "C" {
335
+#endif
336
+
337
+/*****************************************************************************
338
+** Function name:		UART0_IRQHandler
339
+**
340
+** Descriptions:		UART0 interrupt handler
341
+**
342
+** parameters:			None
343
+** Returned value:		None
344
+**
345
+*****************************************************************************/
346
+void UART0_IRQHandler (void)
347
+{
348
+  uint8_t IIRValue, LSRValue;
349
+  uint8_t Dummy = Dummy;
350
+
351
+  IIRValue = LPC_UART0->IIR;
352
+
353
+  IIRValue >>= 1;			/* skip pending bit in IIR */
354
+  IIRValue &= 0x07;			/* check bit 1~3, interrupt identification */
355
+  if ( IIRValue == IIR_RLS )		/* Receive Line Status */
356
+  {
357
+	LSRValue = LPC_UART0->LSR;
358
+	/* Receive Line Status */
359
+	if ( LSRValue & (LSR_OE|LSR_PE|LSR_FE|LSR_RXFE|LSR_BI) )
360
+	{
361
+	  /* There are errors or break interrupt */
362
+	  /* Read LSR will clear the interrupt */
363
+	  UART0Status = LSRValue;
364
+	  Dummy = LPC_UART0->RBR;		/* Dummy read on RX to clear
365
+							interrupt, then bail out */
366
+	  return;
367
+	}
368
+	if ( LSRValue & LSR_RDR )	/* Receive Data Ready */
369
+	{
370
+	  /* If no error on RLS, normal ready, save into the data buffer. */
371
+	  /* Note: read RBR will clear the interrupt */
372
+		  if ((UART0RxQueueWritePos+1) % UARTRXQUEUESIZE != UART0RxQueueReadPos)
373
+		  {
374
+			  UART0Buffer[UART0RxQueueWritePos] = LPC_UART0->RBR;
375
+			  UART0RxQueueWritePos = (UART0RxQueueWritePos+1) % UARTRXQUEUESIZE;
376
+		  }
377
+		  else
378
+			  dummy = LPC_UART0->RBR;;
379
+	}
380
+  }
381
+  else if ( IIRValue == IIR_RDA )	/* Receive Data Available */
382
+  {
383
+	/* Receive Data Available */
384
+	  if ((UART0RxQueueWritePos+1) % UARTRXQUEUESIZE != UART0RxQueueReadPos)
385
+	  {
386
+		  UART0Buffer[UART0RxQueueWritePos] = LPC_UART0->RBR;
387
+		  UART0RxQueueWritePos = (UART0RxQueueWritePos+1) % UARTRXQUEUESIZE;
388
+	  }
389
+	  else
390
+		  dummy = LPC_UART1->RBR;;
197 391
   }
198
-  if (PortNum == 2) {
199
-    if (UART2RxQueueReadPos == UART2RxQueueWritePos) return -1;
200
-    rx = UART2Buffer[UART2RxQueueReadPos];
201
-    UART2RxQueueReadPos = (UART2RxQueueReadPos + 1) % UARTRXQUEUESIZE;
202
-    return rx;
392
+  else if ( IIRValue == IIR_CTI )	/* Character timeout indicator */
393
+  {
394
+	/* Character Time-out indicator */
395
+	UART0Status |= 0x100;		/* Bit 9 as the CTI error */
203 396
   }
204
-  if (PortNum == 3) {
205
-    if (UART3RxQueueReadPos == UART3RxQueueWritePos) return -1;
206
-    rx = UART3Buffer[UART3RxQueueReadPos];
207
-    UART3RxQueueReadPos = (UART3RxQueueReadPos + 1) % UARTRXQUEUESIZE;
208
-    return rx;
397
+  else if ( IIRValue == IIR_THRE )	/* THRE, transmit holding register empty */
398
+  {
399
+	/* THRE interrupt */
400
+	LSRValue = LPC_UART0->LSR;		/* Check status in the LSR to see if
401
+									valid data in U0THR or not */
402
+	if ( LSRValue & LSR_THRE )
403
+	{
404
+	  UART0TxEmpty = 1;
405
+	}
406
+	else
407
+	{
408
+	  UART0TxEmpty = 0;
409
+	}
209 410
   }
210
-  return 0;
211 411
 }
212 412
 
213
-size_t HardwareSerial::write(uint8_t send) {
214
-  if (PortNum == 0) {
215
-    /* THRE status, contain valid data */
216
-    while (!(UART0TxEmpty & 0x01));
217
-    LPC_UART0->THR = send;
218
-    UART0TxEmpty = 0; /* not empty in the THR until it shifts out */
413
+/*****************************************************************************
414
+** Function name:		UART1_IRQHandler
415
+**
416
+** Descriptions:		UART1 interrupt handler
417
+**
418
+** parameters:			None
419
+** Returned value:		None
420
+**
421
+*****************************************************************************/
422
+void UART1_IRQHandler (void)
423
+{
424
+  uint8_t IIRValue, LSRValue;
425
+  uint8_t Dummy = Dummy;
426
+
427
+  IIRValue = LPC_UART1->IIR;
428
+
429
+  IIRValue >>= 1;			/* skip pending bit in IIR */
430
+  IIRValue &= 0x07;			/* check bit 1~3, interrupt identification */
431
+  if ( IIRValue == IIR_RLS )		/* Receive Line Status */
432
+  {
433
+	LSRValue = LPC_UART1->LSR;
434
+	/* Receive Line Status */
435
+	if ( LSRValue & (LSR_OE|LSR_PE|LSR_FE|LSR_RXFE|LSR_BI) )
436
+	{
437
+	  /* There are errors or break interrupt */
438
+	  /* Read LSR will clear the interrupt */
439
+	  UART1Status = LSRValue;
440
+	  Dummy = LPC_UART1->RBR;		/* Dummy read on RX to clear
441
+								interrupt, then bail out */
442
+	  return;
443
+	}
444
+	if ( LSRValue & LSR_RDR )	/* Receive Data Ready */
445
+	{
446
+	  /* If no error on RLS, normal ready, save into the data buffer. */
447
+	  /* Note: read RBR will clear the interrupt */
448
+	  if ((UART1RxQueueWritePos+1) % UARTRXQUEUESIZE != UART1RxQueueReadPos)
449
+	  {
450
+		  UART1Buffer[UART1RxQueueWritePos] = LPC_UART1->RBR;
451
+		  UART1RxQueueWritePos =(UART1RxQueueWritePos+1) % UARTRXQUEUESIZE;
452
+	  }
453
+	  else
454
+		  dummy = LPC_UART1->RBR;;
455
+	}
219 456
   }
220
-  else if (PortNum == 1) {
221
-    while (!(UART1TxEmpty & 0x01));
222
-    LPC_UART1->THR = send;
223
-    UART1TxEmpty = 0;
457
+  else if ( IIRValue == IIR_RDA )	/* Receive Data Available */
458
+  {
459
+	/* Receive Data Available */
460
+	  if ((UART1RxQueueWritePos+1) % UARTRXQUEUESIZE != UART1RxQueueReadPos)
461
+	  {
462
+		  UART1Buffer[UART1RxQueueWritePos] = LPC_UART1->RBR;
463
+		  UART1RxQueueWritePos = (UART1RxQueueWritePos+1) % UARTRXQUEUESIZE;
464
+	  }
465
+	  else
466
+		  dummy = LPC_UART1->RBR;;
224 467
   }
225
-  else if (PortNum == 2) {
226
-    while (!(UART2TxEmpty & 0x01));
227
-    LPC_UART2->THR = send;
228
-    UART2TxEmpty = 0;
468
+  else if ( IIRValue == IIR_CTI )	/* Character timeout indicator */
469
+  {
470
+	/* Character Time-out indicator */
471
+	UART1Status |= 0x100;		/* Bit 9 as the CTI error */
229 472
   }
230
-  else if (PortNum == 3) {
231
-    while (!(UART3TxEmpty & 0x01));
232
-    LPC_UART3->THR = send;
233
-    UART3TxEmpty = 0;
473
+  else if ( IIRValue == IIR_THRE )	/* THRE, transmit holding register empty */
474
+  {
475
+	/* THRE interrupt */
476
+	LSRValue = LPC_UART1->LSR;		/* Check status in the LSR to see if
477
+								valid data in U0THR or not */
478
+	if ( LSRValue & LSR_THRE )
479
+	{
480
+	  UART1TxEmpty = 1;
481
+	}
482
+	else
483
+	{
484
+	  UART1TxEmpty = 0;
485
+	}
234 486
   }
235
-  return 0;
236
-}
237 487
 
238
-int HardwareSerial::available() {
239
-  if (PortNum == 0)
240
-    return (UART0RxQueueWritePos + UARTRXQUEUESIZE - UART0RxQueueReadPos) % UARTRXQUEUESIZE;
241
-  if (PortNum == 1)
242
-    return (UART1RxQueueWritePos + UARTRXQUEUESIZE - UART1RxQueueReadPos) % UARTRXQUEUESIZE;
243
-  if (PortNum == 2)
244
-    return (UART2RxQueueWritePos + UARTRXQUEUESIZE - UART2RxQueueReadPos) % UARTRXQUEUESIZE;
245
-  if (PortNum == 3)
246
-    return (UART3RxQueueWritePos + UARTRXQUEUESIZE - UART3RxQueueReadPos) % UARTRXQUEUESIZE;
247
-  return 0;
248 488
 }
489
+/*****************************************************************************
490
+** Function name:		UART2_IRQHandler
491
+**
492
+** Descriptions:		UART2 interrupt handler
493
+**
494
+** parameters:			None
495
+** Returned value:		None
496
+**
497
+*****************************************************************************/
498
+void UART2_IRQHandler (void)
499
+{
500
+  uint8_t IIRValue, LSRValue;
501
+  uint8_t Dummy = Dummy;
249 502
 
250
-void HardwareSerial::flush() {
251
-  if (PortNum == 0)
252
-    UART0RxQueueWritePos = UART0RxQueueReadPos = 0;
253
-  if (PortNum == 1)
254
-    UART1RxQueueWritePos = UART1RxQueueReadPos = 0;
255
-  if (PortNum == 2)
256
-    UART2RxQueueWritePos = UART2RxQueueReadPos = 0;
257
-  if (PortNum == 3)
258
-    UART3RxQueueWritePos = UART3RxQueueReadPos = 0;
259
-}
503
+  IIRValue = LPC_UART2->IIR;
260 504
 
261
-void HardwareSerial::printf(const char *format, ...) {
262
-  static char buffer[256];
263
-  va_list vArgs;
264
-  va_start(vArgs, format);
265
-  int length = vsnprintf((char *) buffer, 256, (char const *) format, vArgs);
266
-  va_end(vArgs);
267
-  if (length > 0 && length < 256)
268
-    for (int i = 0; i < length; ++i)
269
-      write(buffer[i]);
505
+  IIRValue >>= 1;			/* skip pending bit in IIR */
506
+  IIRValue &= 0x07;			/* check bit 1~3, interrupt identification */
507
+  if ( IIRValue == IIR_RLS )		/* Receive Line Status */
508
+  {
509
+	LSRValue = LPC_UART2->LSR;
510
+	/* Receive Line Status */
511
+	if ( LSRValue & (LSR_OE|LSR_PE|LSR_FE|LSR_RXFE|LSR_BI) )
512
+	{
513
+	  /* There are errors or break interrupt */
514
+	  /* Read LSR will clear the interrupt */
515
+	  UART2Status = LSRValue;
516
+	  Dummy = LPC_UART2->RBR;		/* Dummy read on RX to clear
517
+							interrupt, then bail out */
518
+	  return;
519
+	}
520
+	if ( LSRValue & LSR_RDR )	/* Receive Data Ready */
521
+	{
522
+	  /* If no error on RLS, normal ready, save into the data buffer. */
523
+	  /* Note: read RBR will clear the interrupt */
524
+		 if ((UART2RxQueueWritePos+1) % UARTRXQUEUESIZE != UART2RxQueueReadPos)
525
+		  {
526
+			  UART2Buffer[UART2RxQueueWritePos] = LPC_UART2->RBR;
527
+			  UART2RxQueueWritePos = (UART2RxQueueWritePos+1) % UARTRXQUEUESIZE;
528
+		  }
529
+	}
530
+  }
531
+  else if ( IIRValue == IIR_RDA )	/* Receive Data Available */
532
+  {
533
+	/* Receive Data Available */
534
+	  if ((UART2RxQueueWritePos+1) % UARTRXQUEUESIZE != UART2RxQueueReadPos)
535
+	  {
536
+		  UART2Buffer[UART2RxQueueWritePos] = LPC_UART2->RBR;
537
+		  UART2RxQueueWritePos = (UART2RxQueueWritePos+1) % UARTRXQUEUESIZE;
538
+	  }
539
+	  else
540
+		  dummy = LPC_UART2->RBR;;
541
+  }
542
+  else if ( IIRValue == IIR_CTI )	/* Character timeout indicator */
543
+  {
544
+	/* Character Time-out indicator */
545
+	UART2Status |= 0x100;		/* Bit 9 as the CTI error */
546
+  }
547
+  else if ( IIRValue == IIR_THRE )	/* THRE, transmit holding register empty */
548
+  {
549
+	/* THRE interrupt */
550
+	LSRValue = LPC_UART2->LSR;		/* Check status in the LSR to see if
551
+									valid data in U0THR or not */
552
+	if ( LSRValue & LSR_THRE )
553
+	{
554
+	  UART2TxEmpty = 1;
555
+	}
556
+	else
557
+	{
558
+	  UART2TxEmpty = 0;
559
+	}
560
+  }
270 561
 }
271
-
272 562
 /*****************************************************************************
273
-** Function name:       UARTn_IRQHandler
563
+** Function name:		UART3_IRQHandler
274 564
 **
275
-** Descriptions:        UARTn interrupt handler
565
+** Descriptions:		UART0 interrupt handler
276 566
 **
277
-** parameters:          None
278
-** Returned value:      None
567
+** parameters:			None
568
+** Returned value:		None
279 569
 **
280 570
 *****************************************************************************/
281
-#define DEFINE_UART_HANDLER(NUM)                                                                    \
282
-  void UART3_IRQHandler(void) {                                                                     \
283
-    uint8_t IIRValue, LSRValue;                                                                     \
284
-    uint8_t Dummy = Dummy;                                                                          \
285
-    IIRValue = LPC_UART ##NUM## ->IIR;                                                              \
286
-    IIRValue >>= 1;                                                                                 \
287
-    IIRValue &= 0x07;                                                                               \
288
-    switch (IIRValue) {                                                                             \
289
-      case IIR_RLS:                                                                                 \
290
-        LSRValue = LPC_UART ##NUM## ->LSR;                                                          \
291
-        if (LSRValue & (LSR_OE|LSR_PE|LSR_FE|LSR_RXFE|LSR_BI)) {                                    \
292
-          UART ##NUM## Status = LSRValue;                                                           \
293
-          Dummy = LPC_UART ##NUM## ->RBR;                                                           \
294
-          return;                                                                                   \
295
-        }                                                                                           \
296
-        if (LSRValue & LSR_RDR) {                                                                   \
297
-          if ((UART ##NUM## RxQueueWritePos+1) % UARTRXQUEUESIZE != UART ##NUM## RxQueueReadPos) {  \
298
-            UART ##NUM## Buffer[UART ##NUM## RxQueueWritePos] = LPC_UART ##NUM## ->RBR;             \
299
-            UART ##NUM## RxQueueWritePos = (UART ##NUM## RxQueueWritePos+1) % UARTRXQUEUESIZE;      \
300
-          }                                                                                         \
301
-        }                                                                                           \
302
-        break;                                                                                      \
303
-      case IIR_RDA:                                                                                 \
304
-        if ((UART ##NUM## RxQueueWritePos+1) % UARTRXQUEUESIZE != UART ##NUM## RxQueueReadPos) {    \
305
-          UART ##NUM## Buffer[UART ##NUM## RxQueueWritePos] = LPC_UART ##NUM## ->RBR;               \
306
-          UART ##NUM## RxQueueWritePos = (UART ##NUM## RxQueueWritePos+1) % UARTRXQUEUESIZE;        \
307
-        }                                                                                           \
308
-        else                                                                                        \
309
-          dummy = LPC_UART ##NUM## ->RBR;;                                                          \
310
-        break;                                                                                      \
311
-      case IIR_CTI:                                                                                 \
312
-        UART ##NUM## Status |= 0x100;                                                               \
313
-        break;                                                                                      \
314
-      case IIR_THRE:                                                                                \
315
-        LSRValue = LPC_UART ##NUM## ->LSR;                                                          \
316
-        UART ##NUM## TxEmpty = (LSRValue & LSR_THRE) ? 1 : 0;                                       \
317
-        break;                                                                                      \
318
-    }                                                                                               \
319
-  }                                                                                                 \
320
-  typedef void _uart_ ## NUM
571
+void UART3_IRQHandler (void)
572
+{
573
+  uint8_t IIRValue, LSRValue;
574
+  uint8_t Dummy = Dummy;
321 575
 
322
-#ifdef __cplusplus
323
-  extern "C" {
324
-#endif
576
+  IIRValue = LPC_UART3->IIR;
325 577
 
326
-    DEFINE_UART_HANDLER(0);
327
-    DEFINE_UART_HANDLER(1);
328
-    DEFINE_UART_HANDLER(2);
329
-    DEFINE_UART_HANDLER(3);
578
+  IIRValue >>= 1;			/* skip pending bit in IIR */
579
+  IIRValue &= 0x07;			/* check bit 1~3, interrupt identification */
580
+  if ( IIRValue == IIR_RLS )		/* Receive Line Status */
581
+  {
582
+	LSRValue = LPC_UART3->LSR;
583
+	/* Receive Line Status */
584
+	if ( LSRValue & (LSR_OE|LSR_PE|LSR_FE|LSR_RXFE|LSR_BI) )
585
+	{
586
+	  /* There are errors or break interrupt */
587
+	  /* Read LSR will clear the interrupt */
588
+	  UART3Status = LSRValue;
589
+	  Dummy = LPC_UART3->RBR;		/* Dummy read on RX to clear
590
+							interrupt, then bail out */
591
+	  return;
592
+	}
593
+	if ( LSRValue & LSR_RDR )	/* Receive Data Ready */
594
+	{
595
+	  /* If no error on RLS, normal ready, save into the data buffer. */
596
+	  /* Note: read RBR will clear the interrupt */
597
+		 if ((UART3RxQueueWritePos+1) % UARTRXQUEUESIZE != UART3RxQueueReadPos)
598
+		  {
599
+			  UART3Buffer[UART3RxQueueWritePos] = LPC_UART3->RBR;
600
+			  UART3RxQueueWritePos = (UART3RxQueueWritePos+1) % UARTRXQUEUESIZE;
601
+		  }
602
+	}
603
+  }
604
+  else if ( IIRValue == IIR_RDA )	/* Receive Data Available */
605
+  {
606
+	/* Receive Data Available */
607
+	  if ((UART3RxQueueWritePos+1) % UARTRXQUEUESIZE != UART3RxQueueReadPos)
608
+	  {
609
+		  UART3Buffer[UART3RxQueueWritePos] = LPC_UART3->RBR;
610
+		  UART3RxQueueWritePos = (UART3RxQueueWritePos+1) % UARTRXQUEUESIZE;
611
+	  }
612
+	  else
613
+		  dummy = LPC_UART3->RBR;;
614
+  }
615
+  else if ( IIRValue == IIR_CTI )	/* Character timeout indicator */
616
+  {
617
+	/* Character Time-out indicator */
618
+	UART3Status |= 0x100;		/* Bit 9 as the CTI error */
619
+  }
620
+  else if ( IIRValue == IIR_THRE )	/* THRE, transmit holding register empty */
621
+  {
622
+	/* THRE interrupt */
623
+	LSRValue = LPC_UART3->LSR;		/* Check status in the LSR to see if
624
+									valid data in U0THR or not */
625
+	if ( LSRValue & LSR_THRE )
626
+	{
627
+	  UART3TxEmpty = 1;
628
+	}
629
+	else
630
+	{
631
+	  UART3TxEmpty = 0;
632
+	}
633
+  }
634
+}
330 635
 
331 636
 #ifdef __cplusplus
332
-  }
637
+}
333 638
 #endif
334 639
 
335 640
 #endif // TARGET_LPC1768

+ 2
- 2
Marlin/src/HAL/HAL_LPC1768/include/arduino.h View File

@@ -101,9 +101,9 @@ uint32_t millis();
101 101
 //IO functions
102 102
 void pinMode(uint8_t, uint8_t);
103 103
 void digitalWrite(uint8_t, uint8_t);
104
-int digitalRead(uint8_t);
104
+bool digitalRead(uint8_t);
105 105
 void analogWrite(uint8_t, int);
106
-int analogRead(uint8_t);
106
+uint16_t analogRead(uint8_t);
107 107
 
108 108
 // EEPROM
109 109
 void eeprom_write_byte(unsigned char *pos, unsigned char value);

Loading…
Cancel
Save