Przeglądaj źródła

Merge pull request #7770 from thinkyhead/bf2_HAL_cleanups_etc

Some HAL formatting cleanup
Scott Lahteine 7 lat temu
rodzic
commit
baf0bd2b24
52 zmienionych plików z 608 dodań i 992 usunięć
  1. 1
    1
      Marlin/src/HAL/HAL_AVR/HAL_AVR.cpp
  2. 1
    1
      Marlin/src/HAL/HAL_AVR/HAL_AVR.h
  3. 1
    1
      Marlin/src/HAL/HAL_AVR/HAL_spi_AVR.cpp
  4. 1
    1
      Marlin/src/HAL/HAL_AVR/pinsDebug_AVR_8_bit.h
  5. 4
    4
      Marlin/src/HAL/HAL_DUE/HAL_Due.cpp
  6. 2
    2
      Marlin/src/HAL/HAL_DUE/HAL_Due.h
  7. 2
    2
      Marlin/src/HAL/HAL_DUE/HAL_spi_Due.cpp
  8. 1
    1
      Marlin/src/HAL/HAL_DUE/watchdog_Due.cpp
  9. 1
    1
      Marlin/src/HAL/HAL_LPC1768/HAL.cpp
  10. 1
    1
      Marlin/src/HAL/HAL_LPC1768/HAL.h
  11. 256
    561
      Marlin/src/HAL/HAL_LPC1768/HardwareSerial.cpp
  12. 43
    84
      Marlin/src/HAL/HAL_LPC1768/HardwareSerial.h
  13. 46
    46
      Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.h
  14. 5
    5
      Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.cpp
  15. 5
    5
      Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.h
  16. 6
    6
      Marlin/src/HAL/HAL_LPC1768/SoftwareSerial.cpp
  17. 13
    14
      Marlin/src/HAL/HAL_LPC1768/arduino.cpp
  18. 7
    7
      Marlin/src/HAL/HAL_LPC1768/include/arduino.h
  19. 1
    1
      Marlin/src/HAL/HAL_SanityCheck.h
  20. 7
    10
      Marlin/src/HAL/HAL_TEENSY35_36/HAL_Servo_Teensy.cpp
  21. 4
    4
      Marlin/src/HAL/HAL_TEENSY35_36/HAL_Servo_Teensy.h
  22. 2
    2
      Marlin/src/HAL/HAL_TEENSY35_36/HAL_Teensy.cpp
  23. 2
    2
      Marlin/src/HAL/HAL_TEENSY35_36/HAL_Teensy.h
  24. 2
    2
      Marlin/src/HAL/HAL_TEENSY35_36/HAL_pinsDebug_Teensy.h
  25. 13
    13
      Marlin/src/HAL/HAL_TEENSY35_36/HAL_spi_Teensy.cpp
  26. 2
    2
      Marlin/src/HAL/HAL_TEENSY35_36/HAL_timers_Teensy.cpp
  27. 1
    1
      Marlin/src/HAL/HAL_TEENSY35_36/HAL_timers_Teensy.h
  28. 20
    54
      Marlin/src/HAL/HAL_TEENSY35_36/fastio_Teensy.h
  29. 4
    4
      Marlin/src/HAL/HAL_TEENSY35_36/spi_pins.h
  30. 11
    11
      Marlin/src/HAL/HAL_TEENSY35_36/watchdog_Teensy.cpp
  31. 3
    3
      Marlin/src/config/examples/gCreate/gMax1.5+/Configuration_adv.h
  32. 1
    1
      Marlin/src/feature/caselight.cpp
  33. 1
    1
      Marlin/src/feature/dac/dac_dac084s085.cpp
  34. 1
    1
      Marlin/src/gcode/calibrate/G33.cpp
  35. 8
    8
      Marlin/src/lcd/dogm/ultralcd_st7565_u8glib_VIKI.h
  36. 3
    3
      Marlin/src/lcd/ultralcd_impl_DOGM.h
  37. 1
    1
      Marlin/src/module/stepper.h
  38. 1
    1
      Marlin/src/pins/pins.h
  39. 1
    1
      Marlin/src/pins/pinsDebug_list.h
  40. 3
    3
      Marlin/src/pins/pins_DUE3DOM.h
  41. 3
    3
      Marlin/src/pins/pins_DUE3DOM_MINI.h
  42. 2
    2
      Marlin/src/pins/pins_RAMPS.h
  43. 10
    10
      Marlin/src/pins/pins_RAMPS_RE_ARM.h
  44. 12
    12
      Marlin/src/pins/pins_TEENSY35_36.h
  45. 13
    13
      frameworks/CMSIS/LPC1768/Re-ARM/startup_LPC17xx.S
  46. 23
    23
      frameworks/CMSIS/LPC1768/driver/lpc17xx_i2c.c
  47. 2
    2
      frameworks/CMSIS/LPC1768/driver/lpc17xx_i2s.c
  48. 32
    32
      frameworks/CMSIS/LPC1768/include/arm_common_tables.h
  49. 11
    11
      frameworks/CMSIS/LPC1768/include/core_cmFunc.h
  50. 3
    3
      frameworks/CMSIS/LPC1768/include/lpc17xx_iap.h
  51. 6
    6
      frameworks/CMSIS/LPC1768/include/system_LPC17xx.h
  52. 3
    3
      frameworks/CMSIS/library.json

+ 1
- 1
Marlin/src/HAL/HAL_AVR/HAL_AVR.cpp Wyświetl plik

4
  Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
  Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
 
5
 
6
  Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
6
  Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
7
- 
7
+
8
  This program is free software: you can redistribute it and/or modify
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
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
10
  the Free Software Foundation, either version 3 of the License, or

+ 1
- 1
Marlin/src/HAL/HAL_AVR/HAL_AVR.h Wyświetl plik

83
 
83
 
84
 //void cli(void);
84
 //void cli(void);
85
 
85
 
86
-//void _delay_ms(int delay);
86
+//void _delay_ms(const int delay);
87
 
87
 
88
 inline void HAL_clear_reset_source(void) { MCUSR = 0; }
88
 inline void HAL_clear_reset_source(void) { MCUSR = 0; }
89
 inline uint8_t HAL_get_reset_source(void) { return MCUSR; }
89
 inline uint8_t HAL_get_reset_source(void) { return MCUSR; }

+ 1
- 1
Marlin/src/HAL/HAL_AVR/HAL_spi_AVR.cpp Wyświetl plik

24
  * Originally from Arduino Sd2Card Library
24
  * Originally from Arduino Sd2Card Library
25
  * Copyright (C) 2009 by William Greiman
25
  * Copyright (C) 2009 by William Greiman
26
  */
26
  */
27
- 
27
+
28
 /**
28
 /**
29
  * Description: HAL for AVR - SPI functions
29
  * Description: HAL for AVR - SPI functions
30
  *
30
  *

+ 1
- 1
Marlin/src/HAL/HAL_AVR/pinsDebug_AVR_8_bit.h Wyświetl plik

393
       SERIAL_PROTOCOL_SP(10);
393
       SERIAL_PROTOCOL_SP(10);
394
     #endif
394
     #endif
395
   }
395
   }
396
-  
396
+
397
   #define PRINT_PORT(p) print_port(p)
397
   #define PRINT_PORT(p) print_port(p)
398
 
398
 
399
 #endif
399
 #endif

+ 4
- 4
Marlin/src/HAL/HAL_DUE/HAL_Due.cpp Wyświetl plik

1
 /* **************************************************************************
1
 /* **************************************************************************
2
- 
2
+
3
  Marlin 3D Printer Firmware
3
  Marlin 3D Printer Firmware
4
  Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
  Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
  Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
5
  Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
6
-   
6
+
7
  This program is free software: you can redistribute it and/or modify
7
  This program is free software: you can redistribute it and/or modify
8
  it under the terms of the GNU General Public License as published by
8
  it under the terms of the GNU General Public License as published by
9
  the Free Software Foundation, either version 3 of the License, or
9
  the Free Software Foundation, either version 3 of the License, or
93
   }
93
   }
94
 }
94
 }
95
 
95
 
96
-void _delay_ms(int delay_ms) {
96
+void _delay_ms(const int delay_ms) {
97
   // todo: port for Due?
97
   // todo: port for Due?
98
   delay(delay_ms);
98
   delay(delay_ms);
99
 }
99
 }
112
 // ADC
112
 // ADC
113
 // --------------------------------------------------------------------------
113
 // --------------------------------------------------------------------------
114
 
114
 
115
-void HAL_adc_start_conversion(uint8_t adc_pin) {
115
+void HAL_adc_start_conversion(const uint8_t adc_pin) {
116
   HAL_adc_result = analogRead(adc_pin);
116
   HAL_adc_result = analogRead(adc_pin);
117
 }
117
 }
118
 
118
 

+ 2
- 2
Marlin/src/HAL/HAL_DUE/HAL_Due.h Wyświetl plik

120
 /** reset reason */
120
 /** reset reason */
121
 uint8_t HAL_get_reset_source (void);
121
 uint8_t HAL_get_reset_source (void);
122
 
122
 
123
-void _delay_ms(int delay);
123
+void _delay_ms(const int delay);
124
 
124
 
125
 int freeMemory(void);
125
 int freeMemory(void);
126
 
126
 
150
 #define HAL_READ_ADC        HAL_adc_result
150
 #define HAL_READ_ADC        HAL_adc_result
151
 
151
 
152
 
152
 
153
-void HAL_adc_start_conversion (uint8_t adc_pin);
153
+void HAL_adc_start_conversion(const uint8_t adc_pin);
154
 
154
 
155
 uint16_t HAL_adc_get_result(void);
155
 uint16_t HAL_adc_get_result(void);
156
 
156
 

+ 2
- 2
Marlin/src/HAL/HAL_DUE/HAL_spi_Due.cpp Wyświetl plik

199
       if(spiRate > 6) spiRate = 1;
199
       if(spiRate > 6) spiRate = 1;
200
 
200
 
201
       #if MB(ALLIGATOR)
201
       #if MB(ALLIGATOR)
202
-        // Set SPI mode 1, clock, select not active after transfer, with delay between transfers  
202
+        // Set SPI mode 1, clock, select not active after transfer, with delay between transfers
203
         SPI_ConfigureNPCS(SPI0, SPI_CHAN_DAC,
203
         SPI_ConfigureNPCS(SPI0, SPI_CHAN_DAC,
204
                           SPI_CSR_CSAAT | SPI_CSR_SCBR(spiDueDividors[spiRate]) |
204
                           SPI_CSR_CSAAT | SPI_CSR_SCBR(spiDueDividors[spiRate]) |
205
                           SPI_CSR_DLYBCT(1));
205
                           SPI_CSR_DLYBCT(1));
206
-        // Set SPI mode 0, clock, select not active after transfer, with delay between transfers 
206
+        // Set SPI mode 0, clock, select not active after transfer, with delay between transfers
207
         SPI_ConfigureNPCS(SPI0, SPI_CHAN_EEPROM1, SPI_CSR_NCPHA |
207
         SPI_ConfigureNPCS(SPI0, SPI_CHAN_EEPROM1, SPI_CSR_NCPHA |
208
                           SPI_CSR_CSAAT | SPI_CSR_SCBR(spiDueDividors[spiRate]) |
208
                           SPI_CSR_CSAAT | SPI_CSR_SCBR(spiDueDividors[spiRate]) |
209
                           SPI_CSR_DLYBCT(1));
209
                           SPI_CSR_DLYBCT(1));

+ 1
- 1
Marlin/src/HAL/HAL_DUE/watchdog_Due.cpp Wyświetl plik

21
  */
21
  */
22
 
22
 
23
 #ifdef ARDUINO_ARCH_SAM
23
 #ifdef ARDUINO_ARCH_SAM
24
- 
24
+
25
 #include "../../inc/MarlinConfig.h"
25
 #include "../../inc/MarlinConfig.h"
26
 
26
 
27
 #if ENABLED(USE_WATCHDOG)
27
 #if ENABLED(USE_WATCHDOG)

+ 1
- 1
Marlin/src/HAL/HAL_LPC1768/HAL.cpp Wyświetl plik

113
   };
113
   };
114
 }
114
 }
115
 
115
 
116
-void HAL_adc_start_conversion(uint8_t adc_pin) {
116
+void HAL_adc_start_conversion(const uint8_t adc_pin) {
117
   if (adc_pin >= (NUM_ANALOG_INPUTS) || adc_pin_map[adc_pin].port == 0xFF) {
117
   if (adc_pin >= (NUM_ANALOG_INPUTS) || adc_pin_map[adc_pin].port == 0xFF) {
118
     usb_serial.printf("HAL: HAL_adc_start_conversion: no pinmap for %d\n", adc_pin);
118
     usb_serial.printf("HAL: HAL_adc_start_conversion: no pinmap for %d\n", adc_pin);
119
     return;
119
     return;

+ 1
- 1
Marlin/src/HAL/HAL_LPC1768/HAL.h Wyświetl plik

91
 
91
 
92
 void HAL_adc_init(void);
92
 void HAL_adc_init(void);
93
 void HAL_adc_enable_channel(int pin);
93
 void HAL_adc_enable_channel(int pin);
94
-void HAL_adc_start_conversion (uint8_t adc_pin);
94
+void HAL_adc_start_conversion(const uint8_t adc_pin);
95
 uint16_t HAL_adc_get_result(void);
95
 uint16_t HAL_adc_get_result(void);
96
 
96
 
97
 #endif // _HAL_LPC1768_H
97
 #endif // _HAL_LPC1768_H

+ 256
- 561
Marlin/src/HAL/HAL_LPC1768/HardwareSerial.cpp Wyświetl plik

35
 volatile uint32_t UART0RxQueueReadPos = 0, UART1RxQueueReadPos = 0, UART2RxQueueReadPos = 0, UART3RxQueueReadPos = 0;
35
 volatile uint32_t UART0RxQueueReadPos = 0, UART1RxQueueReadPos = 0, UART2RxQueueReadPos = 0, UART3RxQueueReadPos = 0;
36
 volatile uint8_t dummy;
36
 volatile uint8_t dummy;
37
 
37
 
38
-  void HardwareSerial::begin(uint32_t baudrate) {
39
-    uint32_t Fdiv;
40
-     uint32_t pclkdiv, pclk;
41
-
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
-   	}
66
-
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. */
73
-
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. */
149
-
150
-   	  NVIC_EnableIRQ(UART2_IRQn);
151
-
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. */
185
-
186
-   	  NVIC_EnableIRQ(UART3_IRQn);
187
-
188
-   	  LPC_UART3->IER = IER_RBR | IER_THRE | IER_RLS;	/* Enable UART3 interrupt */
189
-     }
190
-  }
191
-
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;
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
+    }
208
 
63
 
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;
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. */
218
 
70
 
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;
71
+    NVIC_EnableIRQ(UART0_IRQn);
228
 
72
 
229
-  		  // Read from "head"
230
-  		  rx = UART3Buffer[UART3RxQueueReadPos]; // grab next byte
231
-  		  UART3RxQueueReadPos = (UART3RxQueueReadPos + 1) % UARTRXQUEUESIZE;
232
-  		  return rx;
233
-  	  }
234
-  	  return 0;
73
+    LPC_UART0->IER = IER_RBR | IER_THRE | IER_RLS;   /* Enable UART0 interrupt */
235
   }
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
+    }
236
 
98
 
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 */
261
-
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 */
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. */
269
 
105
 
270
-     }
271
-     return 0;
272
-  }
106
+    NVIC_EnableIRQ(UART1_IRQn);
273
 
107
 
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;
290
-}
291
-return 0;
108
+    LPC_UART1->IER = IER_RBR | IER_THRE | IER_RLS;   /* Enable UART1 interrupt */
292
   }
109
   }
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. */
293
 
142
 
294
-  void HardwareSerial::flush() {
295
-    if ( PortNum == 0 )
296
-{
297
-  UART0RxQueueWritePos = 0;
298
-  UART0RxQueueReadPos = 0;
143
+    NVIC_EnableIRQ(UART2_IRQn);
299
 
144
 
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;
145
+    LPC_UART2->IER = IER_RBR | IER_THRE | IER_RLS;    /* Enable UART3 interrupt */
317
   }
146
   }
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
-        }
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;
331
     }
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. */
332
 
176
 
333
-#ifdef __cplusplus
334
-extern "C" {
335
-#endif
177
+    NVIC_EnableIRQ(UART3_IRQn);
336
 
178
 
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;
179
+    LPC_UART3->IER = IER_RBR | IER_THRE | IER_RLS;    /* Enable UART3 interrupt */
180
+  }
181
+}
352
 
182
 
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
-	}
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;
380
   }
191
   }
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;;
192
+  if (PortNum == 1) {
193
+    if (UART1RxQueueReadPos == UART1RxQueueWritePos) return -1;
194
+    rx = UART1Buffer[UART1RxQueueReadPos];
195
+    UART1RxQueueReadPos = (UART1RxQueueReadPos + 1) % UARTRXQUEUESIZE;
196
+    return rx;
391
   }
197
   }
392
-  else if ( IIRValue == IIR_CTI )	/* Character timeout indicator */
393
-  {
394
-	/* Character Time-out indicator */
395
-	UART0Status |= 0x100;		/* Bit 9 as the CTI error */
198
+  if (PortNum == 2) {
199
+    if (UART2RxQueueReadPos == UART2RxQueueWritePos) return -1;
200
+    rx = UART2Buffer[UART2RxQueueReadPos];
201
+    UART2RxQueueReadPos = (UART2RxQueueReadPos + 1) % UARTRXQUEUESIZE;
202
+    return rx;
396
   }
203
   }
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
-	}
204
+  if (PortNum == 3) {
205
+    if (UART3RxQueueReadPos == UART3RxQueueWritePos) return -1;
206
+    rx = UART3Buffer[UART3RxQueueReadPos];
207
+    UART3RxQueueReadPos = (UART3RxQueueReadPos + 1) % UARTRXQUEUESIZE;
208
+    return rx;
410
   }
209
   }
210
+  return 0;
411
 }
211
 }
412
 
212
 
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
-	}
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 */
456
   }
219
   }
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;;
220
+  else if (PortNum == 1) {
221
+    while (!(UART1TxEmpty & 0x01));
222
+    LPC_UART1->THR = send;
223
+    UART1TxEmpty = 0;
467
   }
224
   }
468
-  else if ( IIRValue == IIR_CTI )	/* Character timeout indicator */
469
-  {
470
-	/* Character Time-out indicator */
471
-	UART1Status |= 0x100;		/* Bit 9 as the CTI error */
225
+  else if (PortNum == 2) {
226
+    while (!(UART2TxEmpty & 0x01));
227
+    LPC_UART2->THR = send;
228
+    UART2TxEmpty = 0;
472
   }
229
   }
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
-	}
230
+  else if (PortNum == 3) {
231
+    while (!(UART3TxEmpty & 0x01));
232
+    LPC_UART3->THR = send;
233
+    UART3TxEmpty = 0;
486
   }
234
   }
235
+  return 0;
236
+}
487
 
237
 
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;
488
 }
248
 }
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;
502
 
249
 
503
-  IIRValue = LPC_UART2->IIR;
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
+}
504
 
260
 
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
-  }
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]);
561
 }
270
 }
271
+
562
 /*****************************************************************************
272
 /*****************************************************************************
563
-** Function name:		UART3_IRQHandler
273
+** Function name:       UARTn_IRQHandler
564
 **
274
 **
565
-** Descriptions:		UART0 interrupt handler
275
+** Descriptions:        UARTn interrupt handler
566
 **
276
 **
567
-** parameters:			None
568
-** Returned value:		None
277
+** parameters:          None
278
+** Returned value:      None
569
 **
279
 **
570
 *****************************************************************************/
280
 *****************************************************************************/
571
-void UART3_IRQHandler (void)
572
-{
573
-  uint8_t IIRValue, LSRValue;
574
-  uint8_t Dummy = Dummy;
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
575
 
321
 
576
-  IIRValue = LPC_UART3->IIR;
322
+#ifdef __cplusplus
323
+  extern "C" {
324
+#endif
577
 
325
 
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
-}
326
+    DEFINE_UART_HANDLER(0);
327
+    DEFINE_UART_HANDLER(1);
328
+    DEFINE_UART_HANDLER(2);
329
+    DEFINE_UART_HANDLER(3);
635
 
330
 
636
 #ifdef __cplusplus
331
 #ifdef __cplusplus
637
-}
332
+  }
638
 #endif
333
 #endif
639
 
334
 
640
 #endif // TARGET_LPC1768
335
 #endif // TARGET_LPC1768

+ 43
- 84
Marlin/src/HAL/HAL_LPC1768/HardwareSerial.h Wyświetl plik

29
 
29
 
30
 extern "C" {
30
 extern "C" {
31
   #include <debug_frmwrk.h>
31
   #include <debug_frmwrk.h>
32
-
33
-//#include <lpc17xx_uart.h>
32
+  //#include <lpc17xx_uart.h>
34
 }
33
 }
35
 
34
 
36
-#define IER_RBR		0x01
37
-#define IER_THRE	0x02
38
-#define IER_RLS		0x04
35
+#define IER_RBR   0x01
36
+#define IER_THRE  0x02
37
+#define IER_RLS   0x04
39
 
38
 
40
-#define IIR_PEND	0x01
41
-#define IIR_RLS		0x03
42
-#define IIR_RDA		0x02
43
-#define IIR_CTI		0x06
44
-#define IIR_THRE	0x01
39
+#define IIR_PEND  0x01
40
+#define IIR_RLS   0x03
41
+#define IIR_RDA   0x02
42
+#define IIR_CTI   0x06
43
+#define IIR_THRE  0x01
45
 
44
 
46
-#define LSR_RDR		0x01
47
-#define LSR_OE		0x02
48
-#define LSR_PE		0x04
49
-#define LSR_FE		0x08
50
-#define LSR_BI		0x10
51
-#define LSR_THRE	0x20
52
-#define LSR_TEMT	0x40
53
-#define LSR_RXFE	0x80
45
+#define LSR_RDR   0x01
46
+#define LSR_OE    0x02
47
+#define LSR_PE    0x04
48
+#define LSR_FE    0x08
49
+#define LSR_BI    0x10
50
+#define LSR_THRE  0x20
51
+#define LSR_TEMT  0x40
52
+#define LSR_RXFE  0x80
54
 
53
 
55
-#define UARTRXQUEUESIZE		0x10
54
+#define UARTRXQUEUESIZE   0x10
56
 
55
 
57
 class HardwareSerial : public Stream {
56
 class HardwareSerial : public Stream {
58
 private:
57
 private:
75
     return 0;
74
     return 0;
76
   };
75
   };
77
 
76
 
78
-
79
-  operator bool() {
80
-    return true;
81
-  }
82
-
83
-    void print(const char value[]) {
84
-      printf("%s" , value);
85
-    }
86
-    void print(char value, int = 0) {
87
-      printf("%c" , value);
88
-    }
89
-    void print(unsigned char value, int = 0) {
90
-      printf("%u" , value);
91
-    }
92
-    void print(int value, int = 0) {
93
-      printf("%d" , value);
94
-    }
95
-    void print(unsigned int value, int = 0) {
96
-      printf("%u" , value);
97
-    }
98
-    void print(long value, int = 0) {
99
-      printf("%ld" , value);
100
-    }
101
-    void print(unsigned long value, int = 0) {
102
-      printf("%lu" , value);
103
-    }
104
-
105
-    void print(float value, int round = 6) {
106
-      printf("%f" , value);
107
-    }
108
-    void print(double value, int round = 6) {
109
-      printf("%f" , value );
110
-    }
111
-
112
-    void println(const char value[]) {
113
-      printf("%s\n" , value);
114
-    }
115
-    void println(char value, int = 0) {
116
-      printf("%c\n" , value);
117
-    }
118
-    void println(unsigned char value, int = 0) {
119
-      printf("%u\r\n" , value);
120
-    }
121
-    void println(int value, int = 0) {
122
-      printf("%d\n" , value);
123
-    }
124
-    void println(unsigned int value, int = 0) {
125
-      printf("%u\n" , value);
126
-    }
127
-    void println(long value, int = 0) {
128
-      printf("%ld\n" , value);
129
-    }
130
-    void println(unsigned long value, int = 0) {
131
-      printf("%lu\n" , value);
132
-    }
133
-    void println(float value, int round = 6) {
134
-      printf("%f\n" , value );
135
-    }
136
-    void println(double value, int round = 6) {
137
-      printf("%f\n" , value );
138
-    }
139
-    void println(void) {
140
-      print('\n');
141
-    }
77
+  operator bool() { return true; }
78
+
79
+  void print(const char value[])              { printf("%s" , value); }
80
+  void print(char value, int = 0)             { printf("%c" , value); }
81
+  void print(unsigned char value, int = 0)    { printf("%u" , value); }
82
+  void print(int value, int = 0)              { printf("%d" , value); }
83
+  void print(unsigned int value, int = 0)     { printf("%u" , value); }
84
+  void print(long value, int = 0)             { printf("%ld" , value); }
85
+  void print(unsigned long value, int = 0)    { printf("%lu" , value); }
86
+
87
+  void print(float value, int round = 6)      { printf("%f" , value); }
88
+  void print(double value, int round = 6)     { printf("%f" , value ); }
89
+
90
+  void println(const char value[])            { printf("%s\n" , value); }
91
+  void println(char value, int = 0)           { printf("%c\n" , value); }
92
+  void println(unsigned char value, int = 0)  { printf("%u\r\n" , value); }
93
+  void println(int value, int = 0)            { printf("%d\n" , value); }
94
+  void println(unsigned int value, int = 0)   { printf("%u\n" , value); }
95
+  void println(long value, int = 0)           { printf("%ld\n" , value); }
96
+  void println(unsigned long value, int = 0)  { printf("%lu\n" , value); }
97
+  void println(float value, int round = 6)    { printf("%f\n" , value ); }
98
+  void println(double value, int round = 6)   { printf("%f\n" , value ); }
99
+  void println(void)                          { print('\n'); }
142
 
100
 
143
 };
101
 };
102
+
144
 //extern HardwareSerial Serial0;
103
 //extern HardwareSerial Serial0;
145
 //extern HardwareSerial Serial1;
104
 //extern HardwareSerial Serial1;
146
 //extern HardwareSerial Serial2;
105
 //extern HardwareSerial Serial2;
147
 extern HardwareSerial Serial3;
106
 extern HardwareSerial Serial3;
148
 
107
 
149
-#endif /* MARLIN_SRC_HAL_HAL_SERIAL_H_ */
108
+#endif // MARLIN_SRC_HAL_HAL_SERIAL_H_

+ 46
- 46
Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.h Wyświetl plik

27
 */
27
 */
28
 
28
 
29
 /**
29
 /**
30
- * This is a hybrid system.  
30
+ * This is a hybrid system.
31
  *
31
  *
32
  * The PWM1 module is used to directly control the Servo 0, 1 & 3 pins.  This keeps
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.
33
  * the pulse width jitter to under a microsecond.
34
  *
34
  *
35
- * For all other pins the PWM1 module is used to generate interrupts.  The ISR 
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
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
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
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
39
  * prempt the PWM ISR.  Writing to the SD card can add 20 microseconds to the pulse
40
  * width.
40
  * width.
41
  */
41
  */
42
- 
42
+
43
 /**
43
 /**
44
  * The data structures are setup to minimize the computation done by the ISR which
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.
45
  * minimizes ISR execution time.  Execution times are 2.2 - 3.7 microseconds.
72
     uint16_t PWM_mask;       // MASK TO CHECK/WRITE THE IR REGISTER
72
     uint16_t PWM_mask;       // MASK TO CHECK/WRITE THE IR REGISTER
73
     volatile uint32_t* set_register;
73
     volatile uint32_t* set_register;
74
     volatile uint32_t* clr_register;
74
     volatile uint32_t* clr_register;
75
-    uint32_t write_mask;     // USED BY SET/CLEAR COMMANDS 
75
+    uint32_t write_mask;     // USED BY SET/CLEAR COMMANDS
76
     uint32_t microseconds;   // value written to MR register
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
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
78
     uint32_t max;            // upper value limit checked by WRITE routine before writing to the MR register
180
 
180
 
181
 
181
 
182
 bool PWM_table_swap = false;  // flag to tell the ISR that the tables have been swapped
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 
183
+bool PWM_MR0_wait = false;  // flag to ensure don't delay MR0 interrupt
184
 
184
 
185
 
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) {
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) {
209
   //swap tables
209
   //swap tables
210
   PWM_MR0_wait = true;
210
   PWM_MR0_wait = true;
211
   while (PWM_MR0_wait) delay(5);  //wait until MR0 interrupt has happend so don't delay it.
211
   while (PWM_MR0_wait) delay(5);  //wait until MR0 interrupt has happend so don't delay it.
212
-  
212
+
213
   NVIC_DisableIRQ(PWM1_IRQn);
213
   NVIC_DisableIRQ(PWM1_IRQn);
214
   PWM_map *pointer_swap = active_table;
214
   PWM_map *pointer_swap = active_table;
215
   active_table = work_table;
215
   active_table = work_table;
235
     uint32_t PINSEL3_bits;              // PINSEL3 register bits to set pin mode to PWM1 control
235
     uint32_t PINSEL3_bits;              // PINSEL3 register bits to set pin mode to PWM1 control
236
 } MR_map;
236
 } MR_map;
237
 
237
 
238
-MR_map map_MR[NUM_PWMS];  
239
- 
238
+MR_map map_MR[NUM_PWMS];
239
+
240
 void LPC1768_PWM_update_map_MR(void) {
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};
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};
242
   map_MR[1] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_11_PWM_channel) ? 1 : 0), 11, &LPC_PWM1->MR2, 0, 0};
244
   map_MR[3] = {0, 0,  0, &LPC_PWM1->MR4, 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};
245
   map_MR[4] = {0, 0,  0, &LPC_PWM1->MR5, 0, 0};
246
   map_MR[5] = {0, 0,  0, &LPC_PWM1->MR6, 0, 0};
246
   map_MR[5] = {0, 0,  0, &LPC_PWM1->MR6, 0, 0};
247
-}  
247
+}
248
 
248
 
249
 
249
 
250
 uint32_t LPC1768_PWM_interrupt_mask = 1;
250
 uint32_t LPC1768_PWM_interrupt_mask = 1;
265
   }
265
   }
266
 
266
 
267
   LPC1768_PWM_interrupt_mask = 0;                          // set match registers to new values, build IRQ mask
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++) { 
268
+  for (uint8_t i = 0; i < NUM_PWMS; i++) {
269
     if (work_table[i].active_flag == true) {
269
     if (work_table[i].active_flag == true) {
270
       work_table[i].sequence = i + 1;
270
       work_table[i].sequence = i + 1;
271
-      
271
+
272
       // first see if there is a PWM1 controlled pin for this entry
272
       // first see if there is a PWM1 controlled pin for this entry
273
       bool found = false;
273
       bool found = false;
274
-      for (uint8_t j = 0; (j < NUM_PWMS) && !found; j++) {      
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 ) {
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
276
           *map_MR[j].MR_register = work_table[i].microseconds;  // found one of the PWM pins
277
           work_table[i].PWM_mask = 0;
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
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;
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;
280
           map_MR[j].map_used = 2;
281
-          work_table[i].assigned_MR = j +1;                    // only used to help in debugging                                                                  
281
+          work_table[i].assigned_MR = j +1;                    // only used to help in debugging
282
           found = true;
282
           found = true;
283
         }
283
         }
284
-      } 
285
-      
284
+      }
285
+
286
       // didn't find a PWM1 pin so get an interrupt
286
       // didn't find a PWM1 pin so get an interrupt
287
-      for (uint8_t k = 0; (k < NUM_PWMS) && !found; k++) {     
287
+      for (uint8_t k = 0; (k < NUM_PWMS) && !found; k++) {
288
         if ( !(map_MR[k].map_PWM_INT || map_MR[k].map_used)) {
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
289
           *map_MR[k].MR_register = work_table[i].microseconds;  // found one for an interrupt pin
290
           map_MR[k].map_used = 1;
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
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
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 
293
+          work_table[i].assigned_MR = k +1;                // only used to help in debugging
294
           found = true;
294
           found = true;
295
-        }  
295
+        }
296
       }
296
       }
297
     }
297
     }
298
     else
298
     else
299
       work_table[i].sequence = 0;
299
       work_table[i].sequence = 0;
300
-  }      
300
+  }
301
   LPC1768_PWM_interrupt_mask |= (uint32_t) _BV(0);  // add in MR0 interrupt
301
   LPC1768_PWM_interrupt_mask |= (uint32_t) _BV(0);  // add in MR0 interrupt
302
 
302
 
303
    // swap tables
303
    // swap tables
304
-   
304
+
305
   PWM_MR0_wait = true;
305
   PWM_MR0_wait = true;
306
   while (PWM_MR0_wait) delay(5);  //wait until MR0 interrupt has happend so don't delay it.
306
   while (PWM_MR0_wait) delay(5);  //wait until MR0 interrupt has happend so don't delay it.
307
-  
307
+
308
   NVIC_DisableIRQ(PWM1_IRQn);
308
   NVIC_DisableIRQ(PWM1_IRQn);
309
   LPC_PWM1->LER = 0x07E;  // Set the latch Enable Bits to load the new Match Values for MR1 - MR6
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;
310
   PWM_map *pointer_swap = active_table;
324
   if (slot == 0xFF) return false;    // return error if pin not found
324
   if (slot == 0xFF) return false;    // return error if pin not found
325
 
325
 
326
   LPC1768_PWM_update_map_MR();
326
   LPC1768_PWM_update_map_MR();
327
-  
327
+
328
   switch(pin) {
328
   switch(pin) {
329
     case 11:                        // Servo 0, PWM1 channel 2 (Pin 11  P1.20 PWM1.2)
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
330
       map_MR[pin_11_PWM_channel - 1].PCR_bit = _BV(8 + pin_11_PWM_channel);  // enable PWM1 module control of this pin
337
       map_MR[pin_6_PWM_channel - 1].PINSEL3_bits = 0x2 << 10;       // ISR must do this AFTER setting PCR
337
       map_MR[pin_6_PWM_channel - 1].PINSEL3_bits = 0x2 << 10;       // ISR must do this AFTER setting PCR
338
       break;
338
       break;
339
     case  4:                        // Servo 3, PWM1 channel 1 (Pin 4  P1.18 PWM1.1)
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 
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
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
342
       map_MR[pin_4_PWM_channel - 1].PINSEL3_bits =  0x2 <<  4;       // ISR must do this AFTER setting PCR
343
       break;
343
       break;
344
-    default:                                                        // ISR pins 
344
+    default:                                                        // ISR pins
345
       pinMode(pin, OUTPUT);  // set pin to output but don't write anything in case it's already in use
345
       pinMode(pin, OUTPUT);  // set pin to output but don't write anything in case it's already in use
346
       break;
346
       break;
347
-  }      
348
-    
347
+  }
348
+
349
   work_table[slot].microseconds = MAX(MIN(value, work_table[slot].max), work_table[slot].min);
349
   work_table[slot].microseconds = MAX(MIN(value, work_table[slot].max), work_table[slot].min);
350
   work_table[slot].active_flag = true;
350
   work_table[slot].active_flag = true;
351
 
351
 
352
   LPC1768_PWM_update();
352
   LPC1768_PWM_update();
353
 
353
 
354
   return 1;
354
   return 1;
355
-}  
355
+}
356
 
356
 
357
 
357
 
358
 bool LPC1768_PWM_detach_pin(uint8_t pin) {
358
 bool LPC1768_PWM_detach_pin(uint8_t pin) {
382
       map_MR[pin_6_PWM_channel - 1].map_PWM_INT = 0;                // 0 - available for interrupts, 1 - in use by PWM
382
       map_MR[pin_6_PWM_channel - 1].map_PWM_INT = 0;                // 0 - available for interrupts, 1 - in use by PWM
383
       break;
383
       break;
384
     case  4:                        // Servo 3, PWM1 channel 1 (Pin 4  P1.18 PWM1.1)
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 
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;
386
       map_MR[pin_4_PWM_channel - 1].PCR_bit =  0;
387
       LPC_PINCON->PINSEL3 &= ~(0x3 <<  4);  // return pin to general purpose I/O
387
       LPC_PINCON->PINSEL3 &= ~(0x3 <<  4);  // return pin to general purpose I/O
388
       map_MR[pin_4_PWM_channel - 1].PINSEL3_bits =  0;
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
389
       map_MR[pin_4_PWM_channel - 1].map_PWM_INT = 0;                // 0 - available for interrupts, 1 - in use by PWM
390
       break;
390
       break;
391
-  } 
392
-  
391
+  }
392
+
393
   pinMode(pin, INPUT);
393
   pinMode(pin, INPUT);
394
-  
394
+
395
   work_table[slot] = PWM_MAP_INIT_ROW;
395
   work_table[slot] = PWM_MAP_INIT_ROW;
396
 
396
 
397
   LPC1768_PWM_update();
397
   LPC1768_PWM_update();
411
  * Changes to PINSEL3, PCR and MCR are only done during the MR0 interrupt otherwise
411
  * Changes to PINSEL3, PCR and MCR are only done during the MR0 interrupt otherwise
412
  * the wrong pin may be toggled or even have the system hang.
412
  * the wrong pin may be toggled or even have the system hang.
413
  */
413
  */
414
-  
415
-  
414
+
415
+
416
 HAL_PWM_LPC1768_ISR {
416
 HAL_PWM_LPC1768_ISR {
417
   if (PWM_table_swap) ISR_table = work_table;   // use old table if a swap was just done
417
   if (PWM_table_swap) ISR_table = work_table;   // use old table if a swap was just done
418
   else ISR_table = active_table;
418
   else ISR_table = active_table;
422
     if (PWM_table_swap) LPC_PWM1->MCR = LPC1768_PWM_interrupt_mask; // enable new PWM individual channel interrupts
422
     if (PWM_table_swap) LPC_PWM1->MCR = LPC1768_PWM_interrupt_mask; // enable new PWM individual channel interrupts
423
 
423
 
424
     for (uint8_t i = 0; (i < NUM_PWMS) ; i++) {
424
     for (uint8_t i = 0; (i < NUM_PWMS) ; i++) {
425
-      if(ISR_table[i].active_flag && !((ISR_table[i].logical_pin ==  11) || 
426
-                                       (ISR_table[i].logical_pin ==  4) || 
427
-                                       (ISR_table[i].logical_pin ==  6))) 
425
+      if(ISR_table[i].active_flag && !((ISR_table[i].logical_pin ==  11) ||
426
+                                       (ISR_table[i].logical_pin ==  4) ||
427
+                                       (ISR_table[i].logical_pin ==  6)))
428
         *ISR_table[i].set_register = ISR_table[i].write_mask;       // set pins for all enabled interrupt channels active
428
         *ISR_table[i].set_register = ISR_table[i].write_mask;       // set pins for all enabled interrupt channels active
429
       if (PWM_table_swap && ISR_table[i].PCR_bit) {
429
       if (PWM_table_swap && ISR_table[i].PCR_bit) {
430
         LPC_PWM1->PCR |= ISR_table[i].PCR_bit;              // enable PWM1 module control of this pin
430
         LPC_PWM1->PCR |= ISR_table[i].PCR_bit;              // enable PWM1 module control of this pin
431
-        LPC_PINCON->PINSEL3 |= ISR_table[i].PINSEL3_bits;   // set pin mode to PWM1 control - must be done after PCR 
431
+        LPC_PINCON->PINSEL3 |= ISR_table[i].PINSEL3_bits;   // set pin mode to PWM1 control - must be done after PCR
432
       }
432
       }
433
     }
433
     }
434
     PWM_table_swap = false;
434
     PWM_table_swap = false;
442
         *ISR_table[i].clr_register = ISR_table[i].write_mask;   // set channel to inactive
442
         *ISR_table[i].clr_register = ISR_table[i].write_mask;   // set channel to inactive
443
       }
443
       }
444
   }
444
   }
445
- 
445
+
446
   LPC_PWM1->IR = 0x70F;  // guarantees all interrupt flags are cleared which, if there is an unexpected
446
   LPC_PWM1->IR = 0x70F;  // guarantees all interrupt flags are cleared which, if there is an unexpected
447
                            // PWM interrupt, will keep the ISR from hanging which will crash the controller
447
                            // PWM interrupt, will keep the ISR from hanging which will crash the controller
448
 
448
 
457
 /**
457
 /**
458
  *  Almost all changes to the hardware registers must be coordinated with the Match Register 0 (MR0)
458
  *  Almost all changes to the hardware registers must be coordinated with the Match Register 0 (MR0)
459
  *  interrupt.  The only exception is detaching pins.  It doesn't matter when they go
459
  *  interrupt.  The only exception is detaching pins.  It doesn't matter when they go
460
- *  tristate.  
460
+ *  tristate.
461
  *
461
  *
462
- *  The LPC1768_PWM_init routine kicks off the MR0 interrupt.  This interrupt is never disabled or 
463
- *  delayed. 
462
+ *  The LPC1768_PWM_init routine kicks off the MR0 interrupt.  This interrupt is never disabled or
463
+ *  delayed.
464
  *
464
  *
465
  *  The PWM_table_swap flag is set when the firmware has swapped in an updated table.  It is
465
  *  The PWM_table_swap flag is set when the firmware has swapped in an updated table.  It is
466
  *  cleared by the ISR during the MR0 interrupt as it completes the swap and accompanying updates.
466
  *  cleared by the ISR during the MR0 interrupt as it completes the swap and accompanying updates.
467
  *  It serves two purposes:
467
  *  It serves two purposes:
468
  *    1) Tells the ISR that the tables have been swapped
468
  *    1) Tells the ISR that the tables have been swapped
469
- *    2) Keeps the firmware from starting a new update until the previous one has been completed. 
469
+ *    2) Keeps the firmware from starting a new update until the previous one has been completed.
470
  *
470
  *
471
- *  The PWM_MR0_wait flag is set when the firmware is ready to swap in an updated table and cleared by 
471
+ *  The PWM_MR0_wait flag is set when the firmware is ready to swap in an updated table and cleared by
472
  *  the ISR during the MR0 interrupt.  It is used to avoid delaying the MR0 interrupt when swapping in
472
  *  the ISR during the MR0 interrupt.  It is used to avoid delaying the MR0 interrupt when swapping in
473
- *  an updated table.  This avoids glitches in pulse width and/or repetition rate. 
473
+ *  an updated table.  This avoids glitches in pulse width and/or repetition rate.
474
  *
474
  *
475
  *  The sequence of events during a write to a PWM channel is:
475
  *  The sequence of events during a write to a PWM channel is:
476
  *    1) Waits until PWM_table_swap flag is false before starting
476
  *    1) Waits until PWM_table_swap flag is false before starting
489
  *          writes to the LER register
489
  *          writes to the LER register
490
  *          sets the PWM_table_swap flag active
490
  *          sets the PWM_table_swap flag active
491
  *          re-enables the ISR
491
  *          re-enables the ISR
492
- *     7) On the next interrupt the ISR changes its pointer to the work table which is now the old, 
492
+ *     7) On the next interrupt the ISR changes its pointer to the work table which is now the old,
493
  *        unmodified, active table.
493
  *        unmodified, active table.
494
  *     8) On the next MR0 interrupt the ISR:
494
  *     8) On the next MR0 interrupt the ISR:
495
  *          switches over to the active table
495
  *          switches over to the active table
500
  *             NOTE - PCR must be set before PINSEL
500
  *             NOTE - PCR must be set before PINSEL
501
  *          sets the pins controlled by the ISR to their active states
501
  *          sets the pins controlled by the ISR to their active states
502
  */
502
  */
503
- 
503
+

+ 5
- 5
Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.cpp Wyświetl plik

89
     this->servoIndex = INVALID_SERVO;  // too many servos
89
     this->servoIndex = INVALID_SERVO;  // too many servos
90
   }
90
   }
91
 
91
 
92
-  int8_t Servo::attach(int pin) {
92
+  int8_t Servo::attach(const int pin) {
93
     return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
93
     return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
94
   }
94
   }
95
 
95
 
96
-  int8_t Servo::attach(int pin, int min, int max) {
96
+  int8_t Servo::attach(const int pin, const int min, const int max) {
97
 
97
 
98
     if (this->servoIndex >= MAX_SERVOS) return -1;
98
     if (this->servoIndex >= MAX_SERVOS) return -1;
99
 
99
 
113
     servo_info[this->servoIndex].Pin.isActive = false;
113
     servo_info[this->servoIndex].Pin.isActive = false;
114
   }
114
   }
115
 
115
 
116
-  void Servo::write(int value) {
116
+  void Servo::write(const int value) {
117
     if (value < MIN_PULSE_WIDTH) { // treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds)
117
     if (value < MIN_PULSE_WIDTH) { // treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds)
118
       value = map(constrain(value, 0, 180), 0, 180, SERVO_MIN(), SERVO_MAX());
118
       value = map(constrain(value, 0, 180), 0, 180, SERVO_MIN(), SERVO_MAX());
119
         // odd - this sets zero degrees to 544 and 180 degrees to 2400 microseconds but the literature says
119
         // odd - this sets zero degrees to 544 and 180 degrees to 2400 microseconds but the literature says
122
     this->writeMicroseconds(value);
122
     this->writeMicroseconds(value);
123
   }
123
   }
124
 
124
 
125
-  void Servo::writeMicroseconds(int value) {
125
+  void Servo::writeMicroseconds(const int value) {
126
     // calculate and store the values for the given channel
126
     // calculate and store the values for the given channel
127
     byte channel = this->servoIndex;
127
     byte channel = this->servoIndex;
128
     if (channel < MAX_SERVOS) {  // ensure channel is valid
128
     if (channel < MAX_SERVOS) {  // ensure channel is valid
146
 
146
 
147
   bool Servo::attached() { return servo_info[this->servoIndex].Pin.isActive; }
147
   bool Servo::attached() { return servo_info[this->servoIndex].Pin.isActive; }
148
 
148
 
149
-  void Servo::move(int value) {
149
+  void Servo::move(const int value) {
150
     if (this->attach(0) >= 0) {    // notice the pin number is zero here
150
     if (this->attach(0) >= 0) {    // notice the pin number is zero here
151
       this->write(value);
151
       this->write(value);
152
       delay(SERVO_DELAY);
152
       delay(SERVO_DELAY);

+ 5
- 5
Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.h Wyświetl plik

39
   class Servo {
39
   class Servo {
40
     public:
40
     public:
41
       Servo();
41
       Servo();
42
-      int8_t attach(int pin);            // attach the given pin to the next free channel, set pinMode, return channel number (-1 on fail)
43
-      int8_t attach(int pin, int min, int max); // as above but also sets min and max values for writes.
42
+      int8_t attach(const int pin);            // attach the given pin to the next free channel, set pinMode, return channel number (-1 on fail)
43
+      int8_t attach(const int pin, const int min, const int max); // as above but also sets min and max values for writes.
44
       void detach();
44
       void detach();
45
-      void write(int value);             // if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds
46
-      void writeMicroseconds(int value); // write pulse width in microseconds
47
-      void move(int value);              // attach the servo, then move to value
45
+      void write(const int value);             // if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds
46
+      void writeMicroseconds(const int value); // write pulse width in microseconds
47
+      void move(const int value);              // attach the servo, then move to value
48
                                          // if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds
48
                                          // if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds
49
                                          // if DEACTIVATE_SERVOS_AFTER_MOVE wait SERVO_DELAY, then detach
49
                                          // if DEACTIVATE_SERVOS_AFTER_MOVE wait SERVO_DELAY, then detach
50
       int read();                        // returns current pulse width as an angle between 0 and 180 degrees
50
       int read();                        // returns current pulse width as an angle between 0 and 180 degrees

+ 6
- 6
Marlin/src/HAL/HAL_LPC1768/SoftwareSerial.cpp Wyświetl plik

88
 /* static */
88
 /* static */
89
 inline void SoftwareSerial::tunedDelay(uint32_t count) {
89
 inline void SoftwareSerial::tunedDelay(uint32_t count) {
90
 
90
 
91
-	asm volatile(
91
+  asm volatile(
92
 
92
 
93
     "mov r3, %[loopsPerMicrosecond] \n\t" //load the initial loop counter
93
     "mov r3, %[loopsPerMicrosecond] \n\t" //load the initial loop counter
94
     "1: \n\t"
94
     "1: \n\t"
163
     // Read each of the 8 bits
163
     // Read each of the 8 bits
164
     for (uint8_t i=8; i > 0; --i)
164
     for (uint8_t i=8; i > 0; --i)
165
     {
165
     {
166
-	  tunedDelay(_rx_delay_intrabit);
166
+    tunedDelay(_rx_delay_intrabit);
167
       d >>= 1;
167
       d >>= 1;
168
       if (rx_pin_read())
168
       if (rx_pin_read())
169
         d |= 0x80;
169
         d |= 0x80;
184
     {
184
     {
185
       _buffer_overflow = true;
185
       _buffer_overflow = true;
186
     }
186
     }
187
-	tunedDelay(_rx_delay_stopbit);
187
+  tunedDelay(_rx_delay_stopbit);
188
     // Re-enable interrupts when we're sure to be inside the stop bit
188
     // Re-enable interrupts when we're sure to be inside the stop bit
189
-	setRxIntMsk(true);//__enable_irq();//
189
+  setRxIntMsk(true);//__enable_irq();//
190
 
190
 
191
   }
191
   }
192
 }
192
 }
339
   uint16_t delay = _tx_delay;
339
   uint16_t delay = _tx_delay;
340
 
340
 
341
   if(inv)
341
   if(inv)
342
-	  b = ~b;
342
+    b = ~b;
343
 
343
 
344
   cli();  // turn off interrupts for a clean txmit
344
   cli();  // turn off interrupts for a clean txmit
345
 
345
 
369
   else
369
   else
370
     digitalWrite(_transmitPin, 1);
370
     digitalWrite(_transmitPin, 1);
371
 
371
 
372
-	sei(); // turn interrupts back on
372
+  sei(); // turn interrupts back on
373
   tunedDelay(delay);
373
   tunedDelay(delay);
374
 
374
 
375
   return 1;
375
   return 1;

+ 13
- 14
Marlin/src/HAL/HAL_LPC1768/arduino.cpp Wyświetl plik

25
 #include <lpc17xx_pinsel.h>
25
 #include <lpc17xx_pinsel.h>
26
 #include "HAL.h"
26
 #include "HAL.h"
27
 #include "../../core/macros.h"
27
 #include "../../core/macros.h"
28
+#include "../../core/types.h"
28
 
29
 
29
 // Interrupts
30
 // Interrupts
30
 void cli(void) { __disable_irq(); } // Disable
31
 void cli(void) { __disable_irq(); } // Disable
31
 void sei(void) { __enable_irq(); }  // Enable
32
 void sei(void) { __enable_irq(); }  // Enable
32
 
33
 
33
 // Time functions
34
 // Time functions
34
-void _delay_ms(int delay_ms) {
35
-  delay (delay_ms);
35
+void _delay_ms(const int delay_ms) {
36
+  delay(delay_ms);
36
 }
37
 }
37
 
38
 
38
 uint32_t millis() {
39
 uint32_t millis() {
72
   }
73
   }
73
 }
74
 }
74
 
75
 
75
-extern "C" void delay(int msec) {
76
-   volatile int32_t end = _millis + msec;
77
-   SysTick->VAL = SysTick->LOAD; // reset systick counter so next systick is in exactly 1ms
78
-                                 // this could extend the time between systicks by upto 1ms
79
-   while (_millis < end) __WFE();
76
+extern "C" void delay(const int msec) {
77
+  volatile millis_t end = _millis + msec;
78
+  SysTick->VAL = SysTick->LOAD; // reset systick counter so next systick is in exactly 1ms
79
+                                // this could extend the time between systicks by upto 1ms
80
+  while PENDING(_millis, end) __WFE();
80
 }
81
 }
81
 
82
 
82
 // IO functions
83
 // IO functions
83
 // As defined by Arduino INPUT(0x0), OUPUT(0x1), INPUT_PULLUP(0x2)
84
 // As defined by Arduino INPUT(0x0), OUPUT(0x1), INPUT_PULLUP(0x2)
84
-void pinMode(int pin, int mode) {
85
+void pinMode(uint8_t pin, uint8_t mode) {
85
   if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
86
   if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
86
     return;
87
     return;
87
 
88
 
109
   }
110
   }
110
 }
111
 }
111
 
112
 
112
-void digitalWrite(int pin, int pin_status) {
113
+void digitalWrite(uint8_t pin, uint8_t pin_status) {
113
   if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
114
   if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
114
     return;
115
     return;
115
 
116
 
129
      */
130
      */
130
 }
131
 }
131
 
132
 
132
-bool digitalRead(int pin) {
133
+bool digitalRead(uint8_t pin) {
133
   if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF) {
134
   if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF) {
134
     return false;
135
     return false;
135
   }
136
   }
136
   return LPC_GPIO(pin_map[pin].port)->FIOPIN & LPC_PIN(pin_map[pin].pin) ? 1 : 0;
137
   return LPC_GPIO(pin_map[pin].port)->FIOPIN & LPC_PIN(pin_map[pin].pin) ? 1 : 0;
137
 }
138
 }
138
 
139
 
139
-
140
-
141
-void analogWrite(int pin, int pwm_value) {  // 1 - 254: pwm_value, 0: LOW, 255: HIGH
140
+void analogWrite(uint8_t pin, int pwm_value) {  // 1 - 254: pwm_value, 0: LOW, 255: HIGH
142
 
141
 
143
   extern bool LPC1768_PWM_attach_pin(uint8_t, uint32_t, uint32_t, uint8_t);
142
   extern bool LPC1768_PWM_attach_pin(uint8_t, uint32_t, uint32_t, uint8_t);
144
   extern bool LPC1768_PWM_write(uint8_t, uint32_t);
143
   extern bool LPC1768_PWM_write(uint8_t, uint32_t);
168
 
167
 
169
 extern bool HAL_adc_finished();
168
 extern bool HAL_adc_finished();
170
 
169
 
171
-uint16_t analogRead(int adc_pin) {
170
+uint16_t analogRead(uint8_t adc_pin) {
172
   HAL_adc_start_conversion(adc_pin);
171
   HAL_adc_start_conversion(adc_pin);
173
   while (!HAL_adc_finished());  // Wait for conversion to finish
172
   while (!HAL_adc_finished());  // Wait for conversion to finish
174
   return HAL_adc_get_result();
173
   return HAL_adc_get_result();

+ 7
- 7
Marlin/src/HAL/HAL_LPC1768/include/arduino.h Wyświetl plik

92
 
92
 
93
 // Time functions
93
 // Time functions
94
 extern "C" {
94
 extern "C" {
95
-void delay(int milis);
95
+  void delay(const int milis);
96
 }
96
 }
97
-void _delay_ms(int delay);
97
+void _delay_ms(const int delay);
98
 void delayMicroseconds(unsigned long);
98
 void delayMicroseconds(unsigned long);
99
 uint32_t millis();
99
 uint32_t millis();
100
 
100
 
101
 //IO functions
101
 //IO functions
102
-void pinMode(int pin_number, int mode);
103
-void digitalWrite(int pin_number, int pin_status);
104
-bool digitalRead(int pin);
105
-void analogWrite(int pin_number, int pin_status);
106
-uint16_t analogRead(int adc_pin);
102
+void pinMode(uint8_t, uint8_t);
103
+void digitalWrite(uint8_t, uint8_t);
104
+int digitalRead(uint8_t);
105
+void analogWrite(uint8_t, int);
106
+int analogRead(uint8_t);
107
 
107
 
108
 // EEPROM
108
 // EEPROM
109
 void eeprom_write_byte(unsigned char *pos, unsigned char value);
109
 void eeprom_write_byte(unsigned char *pos, unsigned char value);

+ 1
- 1
Marlin/src/HAL/HAL_SanityCheck.h Wyświetl plik

33
 #else
33
 #else
34
   #error Unsupported Platform!
34
   #error Unsupported Platform!
35
 #endif
35
 #endif
36
- 
36
+
37
 #endif
37
 #endif

+ 7
- 10
Marlin/src/HAL/HAL_TEENSY35_36/HAL_Servo_Teensy.cpp Wyświetl plik

1
 #if defined(__MK64FX512__) || defined(__MK66FX1M0__)
1
 #if defined(__MK64FX512__) || defined(__MK66FX1M0__)
2
 
2
 
3
-
4
 #include "HAL_Servo_Teensy.h"
3
 #include "HAL_Servo_Teensy.h"
5
 #include "../../inc/MarlinConfig.h"
4
 #include "../../inc/MarlinConfig.h"
6
 
5
 
7
-
8
-int8_t libServo::attach(int pin) {
9
-	if (this->servoIndex >= MAX_SERVOS) return -1;
10
-	return Servo::attach(pin);
6
+int8_t libServo::attach(const int pin) {
7
+  if (this->servoIndex >= MAX_SERVOS) return -1;
8
+  return Servo::attach(pin);
11
 }
9
 }
12
 
10
 
13
-int8_t libServo::attach(int pin, int min, int max) {
14
-	return Servo::attach(pin, min, max);
11
+int8_t libServo::attach(const int pin, const int min, const int max) {
12
+  return Servo::attach(pin, min, max);
15
 }
13
 }
16
 
14
 
17
-void libServo::move(int value) {
15
+void libServo::move(const int value) {
18
   if (this->attach(0) >= 0) {
16
   if (this->attach(0) >= 0) {
19
     this->write(value);
17
     this->write(value);
20
     delay(SERVO_DELAY);
18
     delay(SERVO_DELAY);
24
   }
22
   }
25
 }
23
 }
26
 
24
 
27
-
28
-#endif
25
+#endif // __MK64FX512__ || __MK66FX1M0__

+ 4
- 4
Marlin/src/HAL/HAL_TEENSY35_36/HAL_Servo_Teensy.h Wyświetl plik

6
 // Inherit and expand on the official library
6
 // Inherit and expand on the official library
7
 class libServo : public Servo {
7
 class libServo : public Servo {
8
 	public:
8
 	public:
9
-		int8_t attach(int pin);
10
-		int8_t attach(int pin, int min, int max);
11
-		void move(int value);
9
+		int8_t attach(const int pin);
10
+		int8_t attach(const int pin, const int min, const int max);
11
+		void move(const int value);
12
 	private:
12
 	private:
13
 	   uint16_t min_ticks;
13
 	   uint16_t min_ticks;
14
 	   uint16_t max_ticks;
14
 	   uint16_t max_ticks;
15
 	   uint8_t servoIndex;               // index into the channel data for this servo
15
 	   uint8_t servoIndex;               // index into the channel data for this servo
16
 };
16
 };
17
 
17
 
18
-#endif
18
+#endif // HAL_Servo_Teensy_h

+ 2
- 2
Marlin/src/HAL/HAL_TEENSY35_36/HAL_Teensy.cpp Wyświetl plik

1
 /* **************************************************************************
1
 /* **************************************************************************
2
- 
2
+
3
  Marlin 3D Printer Firmware
3
  Marlin 3D Printer Firmware
4
  Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
  Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
  Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
5
  Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
6
-   
6
+
7
  This program is free software: you can redistribute it and/or modify
7
  This program is free software: you can redistribute it and/or modify
8
  it under the terms of the GNU General Public License as published by
8
  it under the terms of the GNU General Public License as published by
9
  the Free Software Foundation, either version 3 of the License, or
9
  the Free Software Foundation, either version 3 of the License, or

+ 2
- 2
Marlin/src/HAL/HAL_TEENSY35_36/HAL_Teensy.h Wyświetl plik

1
 /* **************************************************************************
1
 /* **************************************************************************
2
- 
2
+
3
  Marlin 3D Printer Firmware
3
  Marlin 3D Printer Firmware
4
  Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
  Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
  Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
5
  Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
122
 
122
 
123
 #define HAL_ANALOG_SELECT(pin) NOOP;
123
 #define HAL_ANALOG_SELECT(pin) NOOP;
124
 
124
 
125
-void HAL_adc_start_conversion(uint8_t adc_pin);
125
+void HAL_adc_start_conversion(const uint8_t adc_pin);
126
 
126
 
127
 uint16_t HAL_adc_get_result(void);
127
 uint16_t HAL_adc_get_result(void);
128
 
128
 

+ 2
- 2
Marlin/src/HAL/HAL_TEENSY35_36/HAL_pinsDebug_Teensy.h Wyświetl plik

50
 #define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(0) && (P) <= analogInputToDigitalPin(9)) || ((P) >= analogInputToDigitalPin(12) && (P) <= analogInputToDigitalPin(20))
50
 #define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(0) && (P) <= analogInputToDigitalPin(9)) || ((P) >= analogInputToDigitalPin(12) && (P) <= analogInputToDigitalPin(20))
51
 
51
 
52
 void HAL_print_analog_pin(char buffer[], int8_t pin) {
52
 void HAL_print_analog_pin(char buffer[], int8_t pin) {
53
-	if (pin <= 23)      sprintf(buffer, "(A%2d)  ", int(pin - 14));
54
-	else if (pin <= 39) sprintf(buffer, "(A%2d)  ", int(pin - 19));
53
+  if (pin <= 23)      sprintf(buffer, "(A%2d)  ", int(pin - 14));
54
+  else if (pin <= 39) sprintf(buffer, "(A%2d)  ", int(pin - 19));
55
 }
55
 }
56
 
56
 
57
 void HAL_analog_pin_state(char buffer[], int8_t pin) {
57
 void HAL_analog_pin_state(char buffer[], int8_t pin) {

+ 13
- 13
Marlin/src/HAL/HAL_TEENSY35_36/HAL_spi_Teensy.cpp Wyświetl plik

33
 
33
 
34
 /** Configure SPI for specified SPI speed */
34
 /** Configure SPI for specified SPI speed */
35
 void spiInit(uint8_t spiRate) {
35
 void spiInit(uint8_t spiRate) {
36
-	// Use datarates Marlin uses
37
-	uint32_t clock;
38
-	switch (spiRate) {
39
-  case SPI_FULL_SPEED:		clock = 10000000;	break;
40
-  case SPI_HALF_SPEED:		clock =  5000000;	break;
41
-  case SPI_QUARTER_SPEED:	clock =  2500000;	break;
42
-  case SPI_EIGHTH_SPEED:	clock =  1250000;	break;
43
-  case SPI_SPEED_5:				clock =   625000;	break;
44
-  case SPI_SPEED_6:				clock =   312500;	break;
36
+  // Use datarates Marlin uses
37
+  uint32_t clock;
38
+  switch (spiRate) {
39
+  case SPI_FULL_SPEED:    clock = 10000000; break;
40
+  case SPI_HALF_SPEED:    clock =  5000000; break;
41
+  case SPI_QUARTER_SPEED: clock =  2500000; break;
42
+  case SPI_EIGHTH_SPEED:  clock =  1250000; break;
43
+  case SPI_SPEED_5:       clock =   625000; break;
44
+  case SPI_SPEED_6:       clock =   312500; break;
45
   default:
45
   default:
46
-		clock = 4000000; // Default from the SPI libarary
47
-	}
48
-	spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0);
49
-	SPI.begin();
46
+    clock = 4000000; // Default from the SPI libarary
47
+  }
48
+  spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0);
49
+  SPI.begin();
50
 }
50
 }
51
 
51
 
52
 //------------------------------------------------------------------------------
52
 //------------------------------------------------------------------------------

+ 2
- 2
Marlin/src/HAL/HAL_TEENSY35_36/HAL_timers_Teensy.cpp Wyświetl plik

1
 /* **************************************************************************
1
 /* **************************************************************************
2
- 
2
+
3
  Marlin 3D Printer Firmware
3
  Marlin 3D Printer Firmware
4
  Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
  Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
  Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
5
  Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
6
-   
6
+
7
  This program is free software: you can redistribute it and/or modify
7
  This program is free software: you can redistribute it and/or modify
8
  it under the terms of the GNU General Public License as published by
8
  it under the terms of the GNU General Public License as published by
9
  the Free Software Foundation, either version 3 of the License, or
9
  the Free Software Foundation, either version 3 of the License, or

+ 1
- 1
Marlin/src/HAL/HAL_TEENSY35_36/HAL_timers_Teensy.h Wyświetl plik

1
 /* **************************************************************************
1
 /* **************************************************************************
2
- 
2
+
3
  Marlin 3D Printer Firmware
3
  Marlin 3D Printer Firmware
4
  Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
  Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
  Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
5
  Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com

+ 20
- 54
Marlin/src/HAL/HAL_TEENSY35_36/fastio_Teensy.h Wyświetl plik

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
-*/
27
-
28
-/**
29
- * Description: Fast IO functions for Teensy 3.5 and Teensy 3.6
24
+ * Fast I/O Routines for Teensy 3.5 and Teensy 3.6
25
+ * Use direct port manipulation to save scads of processor time.
26
+ * Contributed by Triffid_Hunter. Modified by Kliment and the Marlin team.
30
  */
27
  */
31
 
28
 
32
-#ifndef	_FASTIO_TEENSY_H
33
-#define	_FASTIO_TEENSY_H
34
-
35
-/**
36
-  utility functions
37
-*/
29
+#ifndef _FASTIO_TEENSY_H
30
+#define _FASTIO_TEENSY_H
38
 
31
 
39
 #ifndef MASK
32
 #ifndef MASK
40
   #define MASK(PIN)  (1 << PIN)
33
   #define MASK(PIN)  (1 << PIN)
44
 #define GPIO_BITBAND(reg, bit) (*(uint32_t *)GPIO_BITBAND_ADDR((reg), (bit)))
37
 #define GPIO_BITBAND(reg, bit) (*(uint32_t *)GPIO_BITBAND_ADDR((reg), (bit)))
45
 
38
 
46
 /**
39
 /**
47
-  magic I/O routines
48
-  now you can simply SET_OUTPUT(STEP); WRITE(STEP, 1); WRITE(STEP, 0);
49
-*/
40
+ * Magic I/O routines
41
+ *
42
+ * Now you can simply SET_OUTPUT(PIN); WRITE(PIN, HIGH); WRITE(PIN, LOW);
43
+ *
44
+ * Why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
45
+ */
50
 
46
 
51
-/// Read a pin
52
 #define _READ(p) ((bool)(CORE_PIN ## p ## _PINREG & CORE_PIN ## p ## _BITMASK))
47
 #define _READ(p) ((bool)(CORE_PIN ## p ## _PINREG & CORE_PIN ## p ## _BITMASK))
53
-
54
-/// Write to a pin
55
 #define _WRITE(p, v) do { if (v) CORE_PIN ## p ## _PORTSET = CORE_PIN ## p ## _BITMASK; \
48
 #define _WRITE(p, v) do { if (v) CORE_PIN ## p ## _PORTSET = CORE_PIN ## p ## _BITMASK; \
56
                             else CORE_PIN ## p ## _PORTCLEAR = CORE_PIN ## p ## _BITMASK; } while (0)
49
                             else CORE_PIN ## p ## _PORTCLEAR = CORE_PIN ## p ## _BITMASK; } while (0)
57
-
58
-/// toggle a pin
59
 #define _TOGGLE(p)  (*(&(CORE_PIN ## p ## _PORTCLEAR)+1) = CORE_PIN ## p ## _BITMASK)
50
 #define _TOGGLE(p)  (*(&(CORE_PIN ## p ## _PORTCLEAR)+1) = CORE_PIN ## p ## _BITMASK)
51
+#define _SET_INPUT(p)   do { CORE_PIN ## p ## _CONFIG = PORT_PCR_MUX(1); \
52
+                          GPIO_BITBAND(CORE_PIN ## p ## _DDRREG , CORE_PIN ## p ## _BIT) = 0; \
53
+                          } while (0)
54
+#define _SET_OUTPUT(p)  do { CORE_PIN ## p ## _CONFIG = PORT_PCR_MUX(1)|PORT_PCR_SRE|PORT_PCR_DSE; \
55
+                          GPIO_BITBAND(CORE_PIN ## p ## _DDRREG , CORE_PIN ## p ## _BIT) = 1; \
56
+                          } while (0)
60
 
57
 
61
-/// set pin as input
62
-  #define _SET_INPUT(p)   do { CORE_PIN ## p ## _CONFIG = PORT_PCR_MUX(1); \
63
-                            GPIO_BITBAND(CORE_PIN ## p ## _DDRREG , CORE_PIN ## p ## _BIT) = 0; \
64
-                            } while (0)
65
-/// set pin as output
66
-  #define _SET_OUTPUT(p)  do { CORE_PIN ## p ## _CONFIG = PORT_PCR_MUX(1)|PORT_PCR_SRE|PORT_PCR_DSE; \
67
-                            GPIO_BITBAND(CORE_PIN ## p ## _DDRREG , CORE_PIN ## p ## _BIT) = 1; \
68
-                            } while (0)
69
-
70
-/// set pin as input with pullup mode
71
 //#define _PULLUP(IO, v)  { pinMode(IO, (v!=LOW ? INPUT_PULLUP : INPUT)); }
58
 //#define _PULLUP(IO, v)  { pinMode(IO, (v!=LOW ? INPUT_PULLUP : INPUT)); }
72
 
59
 
73
-/// check if pin is an input
74
 #define _GET_INPUT(p)   ((CORE_PIN ## p ## _DDRREG & CORE_PIN ## p ## _BITMASK) == 0)
60
 #define _GET_INPUT(p)   ((CORE_PIN ## p ## _DDRREG & CORE_PIN ## p ## _BITMASK) == 0)
75
-/// check if pin is an output
76
 #define _GET_OUTPUT(p)  ((CORE_PIN ## p ## _DDRREG & CORE_PIN ## p ## _BITMASK) == 0)
61
 #define _GET_OUTPUT(p)  ((CORE_PIN ## p ## _DDRREG & CORE_PIN ## p ## _BITMASK) == 0)
77
 
62
 
78
-/// check if pin is an timer
79
 //#define _GET_TIMER(IO)
63
 //#define _GET_TIMER(IO)
80
 
64
 
81
-//  why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
82
-
83
-/// Read a pin wrapper
84
 #define READ(IO)  _READ(IO)
65
 #define READ(IO)  _READ(IO)
85
 
66
 
86
-/// Write to a pin wrapper
87
 #define WRITE_VAR(IO, v)  _WRITE_VAR(IO, v)
67
 #define WRITE_VAR(IO, v)  _WRITE_VAR(IO, v)
88
 #define WRITE(IO, v)  _WRITE(IO, v)
68
 #define WRITE(IO, v)  _WRITE(IO, v)
89
-
90
-/// toggle a pin wrapper
91
 #define TOGGLE(IO)  _TOGGLE(IO)
69
 #define TOGGLE(IO)  _TOGGLE(IO)
92
 
70
 
93
-/// set pin as input wrapper
94
 #define SET_INPUT(IO)  _SET_INPUT(IO)
71
 #define SET_INPUT(IO)  _SET_INPUT(IO)
95
-/// set pin as input with pullup wrapper
96
 #define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _WRITE(IO, HIGH); }while(0)
72
 #define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _WRITE(IO, HIGH); }while(0)
97
-/// set pin as output wrapper
98
 #define SET_OUTPUT(IO)  _SET_OUTPUT(IO)
73
 #define SET_OUTPUT(IO)  _SET_OUTPUT(IO)
99
 
74
 
100
-/// check if pin is an input wrapper
101
 #define GET_INPUT(IO)  _GET_INPUT(IO)
75
 #define GET_INPUT(IO)  _GET_INPUT(IO)
102
-/// check if pin is an output wrapper
103
 #define GET_OUTPUT(IO)  _GET_OUTPUT(IO)
76
 #define GET_OUTPUT(IO)  _GET_OUTPUT(IO)
104
 
77
 
105
-// Shorthand
106
 #define OUT_WRITE(IO, v) { SET_OUTPUT(IO); WRITE(IO, v); }
78
 #define OUT_WRITE(IO, v) { SET_OUTPUT(IO); WRITE(IO, v); }
107
 
79
 
108
 /**
80
 /**
109
-  ports and functions
110
-
111
-  added as necessary or if I feel like it- not a comprehensive list!
112
-*/
113
-
114
-/**
115
-pins
116
-*/
81
+ * Ports, functions, and pins
82
+ */
117
 
83
 
118
 #define DIO0_PIN 8
84
 #define DIO0_PIN 8
119
 
85
 
120
-#endif	/* _FASTIO_TEENSY_H */
86
+#endif  /* _FASTIO_TEENSY_H */

+ 4
- 4
Marlin/src/HAL/HAL_TEENSY35_36/spi_pins.h Wyświetl plik

23
 #ifndef SPI_PINS_H_
23
 #ifndef SPI_PINS_H_
24
 #define SPI_PINS_H_
24
 #define SPI_PINS_H_
25
 
25
 
26
-#define SCK_PIN		13
27
-#define MISO_PIN	12
28
-#define MOSI_PIN	11
29
-#define SS_PIN		20 //SDSS // A.28, A.29, B.21, C.26, C.29
26
+#define SCK_PIN   13
27
+#define MISO_PIN  12
28
+#define MOSI_PIN  11
29
+#define SS_PIN    20 //SDSS // A.28, A.29, B.21, C.26, C.29
30
 
30
 
31
 #endif /* SPI_PINS_H_ */
31
 #endif /* SPI_PINS_H_ */

+ 11
- 11
Marlin/src/HAL/HAL_TEENSY35_36/watchdog_Teensy.cpp Wyświetl plik

21
  */
21
  */
22
 
22
 
23
 #if defined(__MK64FX512__) || defined(__MK66FX1M0__)
23
 #if defined(__MK64FX512__) || defined(__MK66FX1M0__)
24
- 
25
-  #include "../../Marlin.h"
26
 
24
 
27
-  #if ENABLED(USE_WATCHDOG)
25
+#include "../../inc/MarlinConfig.h"
28
 
26
 
29
-    #include "watchdog_Teensy.h"
27
+#if ENABLED(USE_WATCHDOG)
30
 
28
 
31
-    void watchdog_init() {
32
-      WDOG_TOVALH = 0;
33
-      WDOG_TOVALL = 4000;
34
-      WDOG_STCTRLH = WDOG_STCTRLH_WDOGEN;
35
-    }
29
+#include "watchdog_Teensy.h"
36
 
30
 
37
-  #endif //USE_WATCHDOG
31
+void watchdog_init() {
32
+  WDOG_TOVALH = 0;
33
+  WDOG_TOVALL = 4000;
34
+  WDOG_STCTRLH = WDOG_STCTRLH_WDOGEN;
35
+}
38
 
36
 
39
-#endif
37
+#endif // USE_WATCHDOG
38
+
39
+#endif // __MK64FX512__ || __MK66FX1M0__

+ 3
- 3
Marlin/src/config/examples/gCreate/gMax1.5+/Configuration_adv.h Wyświetl plik

1392
 
1392
 
1393
 #define MAX7219_DEBUG
1393
 #define MAX7219_DEBUG
1394
 #if ENABLED(MAX7219_DEBUG)
1394
 #if ENABLED(MAX7219_DEBUG)
1395
-  #define MAX7219_CLK_PIN   64  // 77 on Re-ARM       // Configuration of the 3 pins to control the display 
1396
-  #define MAX7219_DIN_PIN 57  // 78 on Re-ARM
1397
-  #define MAX7219_LOAD_PIN    44  // 79 on Re-ARM
1395
+  #define MAX7219_CLK_PIN   64  // 77 on Re-ARM       // Configuration of the 3 pins to control the display
1396
+  #define MAX7219_DIN_PIN   57  // 78 on Re-ARM
1397
+  #define MAX7219_LOAD_PIN  44  // 79 on Re-ARM
1398
 
1398
 
1399
   /**
1399
   /**
1400
    * Sample debug features
1400
    * Sample debug features

+ 1
- 1
Marlin/src/feature/caselight.cpp Wyświetl plik

26
 
26
 
27
 uint8_t case_light_brightness = CASE_LIGHT_DEFAULT_BRIGHTNESS;
27
 uint8_t case_light_brightness = CASE_LIGHT_DEFAULT_BRIGHTNESS;
28
 bool case_light_on = CASE_LIGHT_DEFAULT_ON;
28
 bool case_light_on = CASE_LIGHT_DEFAULT_ON;
29
-    
29
+
30
 #ifndef INVERT_CASE_LIGHT
30
 #ifndef INVERT_CASE_LIGHT
31
   #define INVERT_CASE_LIGHT false
31
   #define INVERT_CASE_LIGHT false
32
 #endif
32
 #endif

+ 1
- 1
Marlin/src/feature/dac/dac_dac084s085.cpp Wyświetl plik

74
 
74
 
75
   externalDac_buf[0] |= (value >> 4);
75
   externalDac_buf[0] |= (value >> 4);
76
   externalDac_buf[1] |= (value << 4);
76
   externalDac_buf[1] |= (value << 4);
77
-  
77
+
78
   // All SPI chip-select HIGH
78
   // All SPI chip-select HIGH
79
   digitalWrite( DAC0_SYNC , HIGH );
79
   digitalWrite( DAC0_SYNC , HIGH );
80
   #if EXTRUDERS > 1
80
   #if EXTRUDERS > 1

+ 1
- 1
Marlin/src/gcode/calibrate/G33.cpp Wyświetl plik

375
       float a_sum = 0.0;
375
       float a_sum = 0.0;
376
       LOOP_XYZ(axis) a_sum += delta_tower_angle_trim[axis];
376
       LOOP_XYZ(axis) a_sum += delta_tower_angle_trim[axis];
377
       LOOP_XYZ(axis) delta_tower_angle_trim[axis] -= a_sum / 3.0;
377
       LOOP_XYZ(axis) delta_tower_angle_trim[axis] -= a_sum / 3.0;
378
-      
378
+
379
       // adjust delta_height and endstops by the max amount
379
       // adjust delta_height and endstops by the max amount
380
       const float z_temp = MAX3(delta_endstop_adj[A_AXIS], delta_endstop_adj[B_AXIS], delta_endstop_adj[C_AXIS]);
380
       const float z_temp = MAX3(delta_endstop_adj[A_AXIS], delta_endstop_adj[B_AXIS], delta_endstop_adj[C_AXIS]);
381
       home_offset[Z_AXIS] -= z_temp;
381
       home_offset[Z_AXIS] -= z_temp;

+ 8
- 8
Marlin/src/lcd/dogm/ultralcd_st7565_u8glib_VIKI.h Wyświetl plik

142
       ST7565_WRITE_BYTE(0x40);          // Display start line for Displaytech 64128N
142
       ST7565_WRITE_BYTE(0x40);          // Display start line for Displaytech 64128N
143
 
143
 
144
       ST7565_WRITE_BYTE(0x28 | 0x04);   // power control: turn on voltage converter
144
       ST7565_WRITE_BYTE(0x28 | 0x04);   // power control: turn on voltage converter
145
-      //U8G_ESC_DLY(50);                  // delay 50 ms - hangs after a reset if used 
145
+      //U8G_ESC_DLY(50);                  // delay 50 ms - hangs after a reset if used
146
 
146
 
147
       ST7565_WRITE_BYTE(0x28 | 0x06);   // power control: turn on voltage regulator
147
       ST7565_WRITE_BYTE(0x28 | 0x06);   // power control: turn on voltage regulator
148
-      //U8G_ESC_DLY(50);                  // delay 50 ms - hangs after a reset if used 
148
+      //U8G_ESC_DLY(50);                  // delay 50 ms - hangs after a reset if used
149
 
149
 
150
       ST7565_WRITE_BYTE(0x28 | 0x07);   // power control: turn on voltage follower
150
       ST7565_WRITE_BYTE(0x28 | 0x07);   // power control: turn on voltage follower
151
-      //U8G_ESC_DLY(50);                  // delay 50 ms - hangs after a reset if used 
151
+      //U8G_ESC_DLY(50);                  // delay 50 ms - hangs after a reset if used
152
 
152
 
153
       ST7565_WRITE_BYTE(0x10);          // Set V0 voltage resistor ratio. Setting for controlling brightness of Displaytech 64128N
153
       ST7565_WRITE_BYTE(0x10);          // Set V0 voltage resistor ratio. Setting for controlling brightness of Displaytech 64128N
154
 
154
 
228
 
228
 
229
 class U8GLIB_ST7565_64128n_2x_VIKI : public U8GLIB {
229
 class U8GLIB_ST7565_64128n_2x_VIKI : public U8GLIB {
230
   public:
230
   public:
231
-  U8GLIB_ST7565_64128n_2x_VIKI(uint8_t dummy) 
232
-    : U8GLIB(&u8g_dev_st7565_64128n_2x_VIKI_sw_spi) 
231
+  U8GLIB_ST7565_64128n_2x_VIKI(uint8_t dummy)
232
+    : U8GLIB(&u8g_dev_st7565_64128n_2x_VIKI_sw_spi)
233
+    {  }
234
+  U8GLIB_ST7565_64128n_2x_VIKI(uint8_t sck, uint8_t mosi, uint8_t cs, uint8_t a0, uint8_t reset = U8G_PIN_NONE)
235
+    : U8GLIB(&u8g_dev_st7565_64128n_2x_VIKI_sw_spi)
233
     {  }
236
     {  }
234
-  U8GLIB_ST7565_64128n_2x_VIKI(uint8_t sck, uint8_t mosi, uint8_t cs, uint8_t a0, uint8_t reset = U8G_PIN_NONE) 
235
-    : U8GLIB(&u8g_dev_st7565_64128n_2x_VIKI_sw_spi) 
236
-    {  }  
237
 };
237
 };
238
 
238
 
239
 #pragma GCC reset_options
239
 #pragma GCC reset_options

+ 3
- 3
Marlin/src/lcd/ultralcd_impl_DOGM.h Wyświetl plik

176
   //U8GLIB_LM6059 u8g(DOGLCD_CS, DOGLCD_A0);  // 8 stripes
176
   //U8GLIB_LM6059 u8g(DOGLCD_CS, DOGLCD_A0);  // 8 stripes
177
   U8GLIB_LM6059_2X u8g(DOGLCD_CS, DOGLCD_A0); // 4 stripes
177
   U8GLIB_LM6059_2X u8g(DOGLCD_CS, DOGLCD_A0); // 4 stripes
178
 #elif ENABLED(U8GLIB_ST7565_64128N)
178
 #elif ENABLED(U8GLIB_ST7565_64128N)
179
-  // The MaKrPanel, Mini Viki, and Viki 2.0, ST7565 controller 
180
-  //U8GLIB_ST7565_64128n_2x_VIKI u8g(0);  // using SW-SPI DOGLCD_MOSI != -1 && DOGLCD_SCK 
181
-  U8GLIB_ST7565_64128n_2x_VIKI u8g(DOGLCD_SCK, DOGLCD_MOSI, DOGLCD_CS, DOGLCD_A0);  // using SW-SPI 
179
+  // The MaKrPanel, Mini Viki, and Viki 2.0, ST7565 controller
180
+  //U8GLIB_ST7565_64128n_2x_VIKI u8g(0);  // using SW-SPI DOGLCD_MOSI != -1 && DOGLCD_SCK
181
+  U8GLIB_ST7565_64128n_2x_VIKI u8g(DOGLCD_SCK, DOGLCD_MOSI, DOGLCD_CS, DOGLCD_A0);  // using SW-SPI
182
   //U8GLIB_NHD_C12864 u8g(DOGLCD_CS, DOGLCD_A0);  // 8 stripes
182
   //U8GLIB_NHD_C12864 u8g(DOGLCD_CS, DOGLCD_A0);  // 8 stripes
183
   //U8GLIB_NHD_C12864_2X u8g(DOGLCD_CS, DOGLCD_A0); // 4 stripes  HWSPI
183
   //U8GLIB_NHD_C12864_2X u8g(DOGLCD_CS, DOGLCD_A0); // 4 stripes  HWSPI
184
 #elif ENABLED(U8GLIB_SSD1306)
184
 #elif ENABLED(U8GLIB_SSD1306)

+ 1
- 1
Marlin/src/module/stepper.h Wyświetl plik

302
       #endif
302
       #endif
303
 
303
 
304
       #ifdef CPU_32_BIT
304
       #ifdef CPU_32_BIT
305
-        // In case of high-performance processor, it is able to calculate in real-time 
305
+        // In case of high-performance processor, it is able to calculate in real-time
306
         timer = (uint32_t)(HAL_STEPPER_TIMER_RATE) / step_rate;
306
         timer = (uint32_t)(HAL_STEPPER_TIMER_RATE) / step_rate;
307
         if (timer < (HAL_STEPPER_TIMER_RATE / (STEP_DOUBLER_FREQUENCY * 2))) { // (STEP_DOUBLER_FREQUENCY * 2 kHz - this should never happen)
307
         if (timer < (HAL_STEPPER_TIMER_RATE / (STEP_DOUBLER_FREQUENCY * 2))) { // (STEP_DOUBLER_FREQUENCY * 2 kHz - this should never happen)
308
           timer = (HAL_STEPPER_TIMER_RATE / (STEP_DOUBLER_FREQUENCY * 2));
308
           timer = (HAL_STEPPER_TIMER_RATE / (STEP_DOUBLER_FREQUENCY * 2));

+ 1
- 1
Marlin/src/pins/pins.h Wyświetl plik

45
   #define IS_RAMPS_EFF
45
   #define IS_RAMPS_EFF
46
 #elif MB(RAMPS_13_EEF) || MB(RAMPS_14_EEF) || MB(RAMPS_14_RE_ARM_EEF) || MB(RAMPS_SMART_EEF) || MB(RAMPS_DUO_EEF) || MB(RAMPS4DUE_EEF)
46
 #elif MB(RAMPS_13_EEF) || MB(RAMPS_14_EEF) || MB(RAMPS_14_RE_ARM_EEF) || MB(RAMPS_SMART_EEF) || MB(RAMPS_DUO_EEF) || MB(RAMPS4DUE_EEF)
47
   #define IS_RAMPS_EEF
47
   #define IS_RAMPS_EEF
48
-#elif MB(RAMPS_13_SF)  || MB(RAMPS_14_SF)  || MB(RAMPS_14_RE_ARM_SF)  || MB(RAMPS_SMART_SF)  || MB(RAMPS_DUO_SF)  || MB(RAMPS4DUE_SF) 
48
+#elif MB(RAMPS_13_SF)  || MB(RAMPS_14_SF)  || MB(RAMPS_14_RE_ARM_SF)  || MB(RAMPS_SMART_SF)  || MB(RAMPS_DUO_SF)  || MB(RAMPS4DUE_SF)
49
   #define IS_RAMPS_SF
49
   #define IS_RAMPS_SF
50
 #endif
50
 #endif
51
 
51
 

+ 1
- 1
Marlin/src/pins/pinsDebug_list.h Wyświetl plik

358
 #endif
358
 #endif
359
 #if PIN_EXISTS(FAN)
359
 #if PIN_EXISTS(FAN)
360
   REPORT_NAME_DIGITAL(FAN_PIN, __LINE__ )
360
   REPORT_NAME_DIGITAL(FAN_PIN, __LINE__ )
361
-#endif 
361
+#endif
362
 #if PIN_EXISTS(FAN1)
362
 #if PIN_EXISTS(FAN1)
363
   REPORT_NAME_DIGITAL(FAN1_PIN, __LINE__ )
363
   REPORT_NAME_DIGITAL(FAN1_PIN, __LINE__ )
364
 #endif
364
 #endif

+ 3
- 3
Marlin/src/pins/pins_DUE3DOM.h Wyświetl plik

123
 
123
 
124
     #define BTN_EN1         50
124
     #define BTN_EN1         50
125
     #define BTN_EN2         52
125
     #define BTN_EN2         52
126
-    #define BTN_ENC         48    
126
+    #define BTN_ENC         48
127
 
127
 
128
     #define SDSS             4
128
     #define SDSS             4
129
     #define SD_DETECT_PIN   14
129
     #define SD_DETECT_PIN   14
135
     #define BTN_EN1         50
135
     #define BTN_EN1         50
136
     #define BTN_EN2         52
136
     #define BTN_EN2         52
137
     #define BTN_ENC         48
137
     #define BTN_ENC         48
138
-      
138
+
139
     #define BTN_BACK        71
139
     #define BTN_BACK        71
140
-    
140
+
141
     #undef SDSS
141
     #undef SDSS
142
     #define SDSS             4
142
     #define SDSS             4
143
     #define SD_DETECT_PIN   14
143
     #define SD_DETECT_PIN   14

+ 3
- 3
Marlin/src/pins/pins_DUE3DOM_MINI.h Wyświetl plik

115
 
115
 
116
     #define BTN_EN1         50
116
     #define BTN_EN1         50
117
     #define BTN_EN2         52
117
     #define BTN_EN2         52
118
-    #define BTN_ENC         48    
118
+    #define BTN_ENC         48
119
 
119
 
120
     #define SDSS             4
120
     #define SDSS             4
121
     #define SD_DETECT_PIN   14
121
     #define SD_DETECT_PIN   14
127
     #define BTN_EN1         50
127
     #define BTN_EN1         50
128
     #define BTN_EN2         52
128
     #define BTN_EN2         52
129
     #define BTN_ENC         48
129
     #define BTN_ENC         48
130
-      
130
+
131
     #define BTN_BACK        71
131
     #define BTN_BACK        71
132
-    
132
+
133
     #undef SDSS
133
     #undef SDSS
134
     #define SDSS             4
134
     #define SDSS             4
135
     #define SD_DETECT_PIN   14
135
     #define SD_DETECT_PIN   14

+ 2
- 2
Marlin/src/pins/pins_RAMPS.h Wyświetl plik

46
 
46
 
47
 #if ENABLED(IS_REARM)
47
 #if ENABLED(IS_REARM)
48
   #error "Oops!  use 'pins_RAMPS_RE_ARM.h' when Re-Arm is used."
48
   #error "Oops!  use 'pins_RAMPS_RE_ARM.h' when Re-Arm is used."
49
-#endif 
50
- 
49
+#endif
50
+
51
 #if !ENABLED(IS_RAMPS_SMART) && !ENABLED(IS_RAMPS_DUO) && !ENABLED(IS_RAMPS4DUE) && !ENABLED(TARGET_LPC1768)
51
 #if !ENABLED(IS_RAMPS_SMART) && !ENABLED(IS_RAMPS_DUO) && !ENABLED(IS_RAMPS4DUE) && !ENABLED(TARGET_LPC1768)
52
   #if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__)
52
   #if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__)
53
     #error "Oops!  Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu."
53
     #error "Oops!  Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu."

+ 10
- 10
Marlin/src/pins/pins_RAMPS_RE_ARM.h Wyświetl plik

248
   #define DOGLCD_CS           63  // J5-3 & AUX-2
248
   #define DOGLCD_CS           63  // J5-3 & AUX-2
249
 
249
 
250
 #ifdef ULTIPANEL
250
 #ifdef ULTIPANEL
251
-  
251
+
252
   #define LCD_PINS_D5         71  // ENET_MDIO
252
   #define LCD_PINS_D5         71  // ENET_MDIO
253
   #define LCD_PINS_D6         73  // ENET_RX_ER
253
   #define LCD_PINS_D6         73  // ENET_RX_ER
254
   #define LCD_PINS_D7         75  // ENET_RXD1
254
   #define LCD_PINS_D7         75  // ENET_RXD1
255
 #endif
255
 #endif
256
- 
256
+
257
   #if ENABLED(NEWPANEL)
257
   #if ENABLED(NEWPANEL)
258
     #if ENABLED(REPRAPWORLD_KEYPAD)
258
     #if ENABLED(REPRAPWORLD_KEYPAD)
259
       #define SHIFT_OUT         51  // (MOSI) J3-10 & AUX-3
259
       #define SHIFT_OUT         51  // (MOSI) J3-10 & AUX-3
287
 
287
 
288
  #if ENABLED(VIKI2) || ENABLED(miniVIKI)
288
  #if ENABLED(VIKI2) || ENABLED(miniVIKI)
289
 //    #define LCD_SCREEN_ROT_180
289
 //    #define LCD_SCREEN_ROT_180
290
-    
290
+
291
     #define SOFTWARE_SPI  // temp to see if it fixes the  "not found" error
291
     #define SOFTWARE_SPI  // temp to see if it fixes the  "not found" error
292
-    
292
+
293
     #undef  BEEPER_PIN
293
     #undef  BEEPER_PIN
294
     #define BEEPER_PIN          37  // may change if cable changes
294
     #define BEEPER_PIN          37  // may change if cable changes
295
-    
295
+
296
     #define BTN_EN1             31  // J3-2 & AUX-4
296
     #define BTN_EN1             31  // J3-2 & AUX-4
297
     #define BTN_EN2             33  // J3-4 & AUX-4
297
     #define BTN_EN2             33  // J3-4 & AUX-4
298
     #define BTN_ENC             35  // J3-3 & AUX-4
298
     #define BTN_ENC             35  // J3-3 & AUX-4
301
     #define KILL_PIN            41  // J5-4 & AUX-4
301
     #define KILL_PIN            41  // J5-4 & AUX-4
302
 
302
 
303
     #undef  DOGLCD_CS
303
     #undef  DOGLCD_CS
304
-    #define DOGLCD_CS           16 
304
+    #define DOGLCD_CS           16
305
     #undef  LCD_BACKLIGHT_PIN   //16  // J3-7 & AUX-4 - only used on DOGLCD controllers
305
     #undef  LCD_BACKLIGHT_PIN   //16  // J3-7 & AUX-4 - only used on DOGLCD controllers
306
     #undef  LCD_PINS_ENABLE     //51  // (MOSI) J3-10 & AUX-3
306
     #undef  LCD_PINS_ENABLE     //51  // (MOSI) J3-10 & AUX-3
307
     #undef  LCD_PINS_D4         //52  // (SCK)  J3-9 & AUX-3
307
     #undef  LCD_PINS_D4         //52  // (SCK)  J3-9 & AUX-3
310
     #define DOGLCD_A0           59  // J3-8 & AUX-2
310
     #define DOGLCD_A0           59  // J3-8 & AUX-2
311
     #undef  LCD_PINS_D6         //63  // J5-3 & AUX-2
311
     #undef  LCD_PINS_D6         //63  // J5-3 & AUX-2
312
     #undef  LCD_PINS_D7          //6  // (SERVO1) J5-1 & SERVO connector
312
     #undef  LCD_PINS_D7          //6  // (SERVO1) J5-1 & SERVO connector
313
-    #define DOGLCD_SCK SCK_PIN 
313
+    #define DOGLCD_SCK SCK_PIN
314
     #define DOGLCD_MOSI MOSI_PIN
314
     #define DOGLCD_MOSI MOSI_PIN
315
- 
315
+
316
     #define STAT_LED_BLUE_PIN   63  // may change if cable changes
316
     #define STAT_LED_BLUE_PIN   63  // may change if cable changes
317
     #define STAT_LED_RED_PIN     6  // may change if cable changes
317
     #define STAT_LED_RED_PIN     6  // may change if cable changes
318
   #endif
318
   #endif
320
   //#define MOSI_PIN            51  // system defined J3-10 & AUX-3
320
   //#define MOSI_PIN            51  // system defined J3-10 & AUX-3
321
   //#define SCK_PIN             52  // system defined J3-9 & AUX-3
321
   //#define SCK_PIN             52  // system defined J3-9 & AUX-3
322
   //#define SS_PIN              53  // system defined J3-5 & AUX-3 - sometimes called SDSS
322
   //#define SS_PIN              53  // system defined J3-5 & AUX-3 - sometimes called SDSS
323
-  
324
-  
323
+
324
+
325
   #if ENABLED(MINIPANEL)
325
   #if ENABLED(MINIPANEL)
326
     // GLCD features
326
     // GLCD features
327
     //#define LCD_CONTRAST   190
327
     //#define LCD_CONTRAST   190

+ 12
- 12
Marlin/src/pins/pins_TEENSY35_36.h Wyświetl plik

2
 * Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0) Breadboard pin assignments
2
 * Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0) Breadboard pin assignments
3
 * Requires the Teensyduino software with Teensy 3.5 or Teensy 3.6 selected in Arduino IDE!
3
 * Requires the Teensyduino software with Teensy 3.5 or Teensy 3.6 selected in Arduino IDE!
4
 * http://www.pjrc.com/teensy/teensyduino.html
4
 * http://www.pjrc.com/teensy/teensyduino.html
5
-* 
5
+*
6
 ****************************************************************************************/
6
 ****************************************************************************************/
7
 #if MOTHERBOARD == 841 // BOARD_TEENSY35_36
7
 #if MOTHERBOARD == 841 // BOARD_TEENSY35_36
8
 #define KNOWN_BOARD 1
8
 #define KNOWN_BOARD 1
21
 #define LARGE_FLASH        true
21
 #define LARGE_FLASH        true
22
 #define USBCON //1286  // Disable MarlinSerial etc.
22
 #define USBCON //1286  // Disable MarlinSerial etc.
23
 
23
 
24
-/* 
24
+/*
25
 teemuatlut plan for Teensy3.5 and Teensy3.6:
25
 teemuatlut plan for Teensy3.5 and Teensy3.6:
26
 
26
 
27
                                                      USB
27
                                                      USB
109
 #define SOL1_PIN           28
109
 #define SOL1_PIN           28
110
 
110
 
111
 #ifndef SDSUPPORT
111
 #ifndef SDSUPPORT
112
-// these pins are defined in the SD library if building with SD support
112
+  // these are defined in the SD library if building with SD support
113
   #define SCK_PIN          13
113
   #define SCK_PIN          13
114
   #define MISO_PIN         12
114
   #define MISO_PIN         12
115
   #define MOSI_PIN         11
115
   #define MOSI_PIN         11
116
 #endif
116
 #endif
117
 
117
 
118
 #ifdef ULTRA_LCD
118
 #ifdef ULTRA_LCD
119
-  #define LCD_PINS_RS        40
120
-  #define LCD_PINS_ENABLE    41
121
-  #define LCD_PINS_D4        42
122
-  #define LCD_PINS_D5        43
123
-  #define LCD_PINS_D6        44
124
-  #define LCD_PINS_D7        45
125
-  #define BTN_EN1            46
126
-  #define BTN_EN2            47
127
-  #define BTN_ENC            48
119
+  #define LCD_PINS_RS      40
120
+  #define LCD_PINS_ENABLE  41
121
+  #define LCD_PINS_D4      42
122
+  #define LCD_PINS_D5      43
123
+  #define LCD_PINS_D6      44
124
+  #define LCD_PINS_D7      45
125
+  #define BTN_EN1          46
126
+  #define BTN_EN2          47
127
+  #define BTN_ENC          48
128
 #endif
128
 #endif
129
 
129
 
130
 #endif  // MOTHERBOARD == 841 (Teensy3.5 and Teensy3.6)
130
 #endif  // MOTHERBOARD == 841 (Teensy3.5 and Teensy3.6)

+ 13
- 13
frameworks/CMSIS/LPC1768/Re-ARM/startup_LPC17xx.S Wyświetl plik

1
 /* File: startup_ARMCM3.s
1
 /* File: startup_ARMCM3.s
2
- * Purpose: startup file for Cortex-M3/M4 devices. Should use with 
2
+ * Purpose: startup file for Cortex-M3/M4 devices. Should use with
3
  *   GNU Tools for ARM Embedded Processors
3
  *   GNU Tools for ARM Embedded Processors
4
  * Version: V1.1
4
  * Version: V1.1
5
  * Date: 17 June 2011
5
  * Date: 17 June 2011
6
- * 
6
+ *
7
  * Copyright (C) 2011 ARM Limited. All rights reserved.
7
  * Copyright (C) 2011 ARM Limited. All rights reserved.
8
- * ARM Limited (ARM) is supplying this software for use with Cortex-M3/M4 
9
- * processor based microcontrollers.  This file can be freely distributed 
10
- * within development tools that are supporting such ARM based processors. 
8
+ * ARM Limited (ARM) is supplying this software for use with Cortex-M3/M4
9
+ * processor based microcontrollers.  This file can be freely distributed
10
+ * within development tools that are supporting such ARM based processors.
11
  *
11
  *
12
  * THIS SOFTWARE IS PROVIDED "AS IS".  NO WARRANTIES, WHETHER EXPRESS, IMPLIED
12
  * THIS SOFTWARE IS PROVIDED "AS IS".  NO WARRANTIES, WHETHER EXPRESS, IMPLIED
13
  * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
13
  * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
20
 
20
 
21
 /* Memory Model
21
 /* Memory Model
22
    The HEAP starts at the end of the DATA section and grows upward.
22
    The HEAP starts at the end of the DATA section and grows upward.
23
-   
23
+
24
    The STACK starts at the end of the RAM and grows downward.
24
    The STACK starts at the end of the RAM and grows downward.
25
-   
25
+
26
    The HEAP and stack STACK are only checked at compile time:
26
    The HEAP and stack STACK are only checked at compile time:
27
    (DATA_SIZE + HEAP_SIZE + STACK_SIZE) < RAM_SIZE
27
    (DATA_SIZE + HEAP_SIZE + STACK_SIZE) < RAM_SIZE
28
-   
28
+
29
    This is just a check for the bare minimum for the Heap+Stack area before
29
    This is just a check for the bare minimum for the Heap+Stack area before
30
    aborting compilation, it is not the run time limit:
30
    aborting compilation, it is not the run time limit:
31
    Heap_Size + Stack_Size = 0x80 + 0x80 = 0x100
31
    Heap_Size + Stack_Size = 0x80 + 0x80 = 0x100
59
     .size __HeapBase, . - __HeapBase
59
     .size __HeapBase, . - __HeapBase
60
 __HeapLimit:
60
 __HeapLimit:
61
     .size __HeapLimit, . - __HeapLimit
61
     .size __HeapLimit, . - __HeapLimit
62
-    
62
+
63
     .section .isr_vector
63
     .section .isr_vector
64
     .align 2
64
     .align 2
65
     .globl __isr_vector
65
     .globl __isr_vector
128
     .type    Reset_Handler, %function
128
     .type    Reset_Handler, %function
129
 Reset_Handler:
129
 Reset_Handler:
130
 /*     Loop to copy data from read only memory to RAM. The ranges
130
 /*     Loop to copy data from read only memory to RAM. The ranges
131
- *      of copy from/to are specified by following symbols evaluated in 
131
+ *      of copy from/to are specified by following symbols evaluated in
132
  *      linker script.
132
  *      linker script.
133
  *      _etext: End of code section, i.e., begin of data sections to copy from.
133
  *      _etext: End of code section, i.e., begin of data sections to copy from.
134
  *      __data_start__/__data_end__: RAM address range that data should be
134
  *      __data_start__/__data_end__: RAM address range that data should be
153
     bx    r0
153
     bx    r0
154
     .pool
154
     .pool
155
     .size Reset_Handler, . - Reset_Handler
155
     .size Reset_Handler, . - Reset_Handler
156
-    
156
+
157
 /*    Macro to define default handlers. Default handler
157
 /*    Macro to define default handlers. Default handler
158
  *    will be weak symbol and just dead loops. They can be
158
  *    will be weak symbol and just dead loops. They can be
159
  *    overwritten by other handlers */
159
  *    overwritten by other handlers */
166
     b    .
166
     b    .
167
     .size    \handler_name, . - \handler_name
167
     .size    \handler_name, . - \handler_name
168
     .endm
168
     .endm
169
-    
169
+
170
     def_default_handler    NMI_Handler
170
     def_default_handler    NMI_Handler
171
     def_default_handler    HardFault_Handler
171
     def_default_handler    HardFault_Handler
172
     def_default_handler    MemManage_Handler
172
     def_default_handler    MemManage_Handler
177
     def_default_handler    PendSV_Handler
177
     def_default_handler    PendSV_Handler
178
     def_default_handler    SysTick_Handler
178
     def_default_handler    SysTick_Handler
179
     def_default_handler    Default_Handler
179
     def_default_handler    Default_Handler
180
-    
180
+
181
     def_default_handler     WDT_IRQHandler
181
     def_default_handler     WDT_IRQHandler
182
     def_default_handler     TIMER0_IRQHandler
182
     def_default_handler     TIMER0_IRQHandler
183
     def_default_handler     TIMER1_IRQHandler
183
     def_default_handler     TIMER1_IRQHandler

+ 23
- 23
frameworks/CMSIS/LPC1768/driver/lpc17xx_i2c.c Wyświetl plik

188
 	{
188
 	{
189
 		return CodeStatus;
189
 		return CodeStatus;
190
 	}
190
 	}
191
-	
191
+
192
 	/* Make sure start bit is not active */
192
 	/* Make sure start bit is not active */
193
 	if (I2Cx->I2CONSET & I2C_I2CONSET_STA)
193
 	if (I2Cx->I2CONSET & I2C_I2CONSET_STA)
194
 	{
194
 	{
216
 static uint32_t I2C_GetByte (LPC_I2C_TypeDef *I2Cx, uint8_t *retdat, Bool ack)
216
 static uint32_t I2C_GetByte (LPC_I2C_TypeDef *I2Cx, uint8_t *retdat, Bool ack)
217
 {
217
 {
218
 	*retdat = (uint8_t) (I2Cx->I2DAT & I2C_I2DAT_BITMASK);
218
 	*retdat = (uint8_t) (I2Cx->I2DAT & I2C_I2DAT_BITMASK);
219
-	
219
+
220
 	if (ack == TRUE)
220
 	if (ack == TRUE)
221
 	{
221
 	{
222
 		I2Cx->I2CONSET = I2C_I2CONSET_AA;
222
 		I2Cx->I2CONSET = I2C_I2CONSET_AA;
227
 	}
227
 	}
228
 
228
 
229
 	I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
229
 	I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
230
-	
230
+
231
 	return (I2Cx->I2STAT & I2C_STAT_CODE_BITMASK);
231
 	return (I2Cx->I2STAT & I2C_STAT_CODE_BITMASK);
232
 }
232
 }
233
 
233
 
454
 	uint8_t *rxdat;
454
 	uint8_t *rxdat;
455
 	uint8_t tmp;
455
 	uint8_t tmp;
456
 	int32_t Ret = I2C_OK;
456
 	int32_t Ret = I2C_OK;
457
-	
457
+
458
 	//get buffer to send/receive
458
 	//get buffer to send/receive
459
 	txdat = (uint8_t *) &TransferCfg->tx_data[TransferCfg->tx_count];
459
 	txdat = (uint8_t *) &TransferCfg->tx_data[TransferCfg->tx_count];
460
 	rxdat = (uint8_t *) &TransferCfg->rx_data[TransferCfg->rx_count];
460
 	rxdat = (uint8_t *) &TransferCfg->rx_data[TransferCfg->rx_count];
481
 			break;
481
 			break;
482
 		case I2C_I2STAT_M_TX_SLAW_ACK:
482
 		case I2C_I2STAT_M_TX_SLAW_ACK:
483
 		case I2C_I2STAT_M_TX_DAT_ACK:
483
 		case I2C_I2STAT_M_TX_DAT_ACK:
484
-			
484
+
485
 			if(TransferCfg->tx_count < TransferCfg->tx_length)
485
 			if(TransferCfg->tx_count < TransferCfg->tx_length)
486
 			{
486
 			{
487
 				I2C_SendByte(I2Cx, *txdat);
487
 				I2C_SendByte(I2Cx, *txdat);
488
-				
488
+
489
 				txdat++;
489
 				txdat++;
490
 
490
 
491
 				TransferCfg->tx_count++;
491
 				TransferCfg->tx_count++;
497
 				I2C_Stop(I2Cx);
497
 				I2C_Stop(I2Cx);
498
 
498
 
499
 				Ret = I2C_SEND_END;
499
 				Ret = I2C_SEND_END;
500
-				
500
+
501
 			}
501
 			}
502
 			break;
502
 			break;
503
 		case I2C_I2STAT_M_TX_DAT_NACK:
503
 		case I2C_I2STAT_M_TX_DAT_NACK:
537
 			 {
537
 			 {
538
 				Ret = I2C_RECV_END;
538
 				Ret = I2C_RECV_END;
539
 			}
539
 			}
540
-			
540
+
541
 			break;
541
 			break;
542
 		case I2C_I2STAT_M_RX_DAT_NACK:
542
 		case I2C_I2STAT_M_RX_DAT_NACK:
543
 			I2C_GetByte(I2Cx, &tmp, FALSE);
543
 			I2C_GetByte(I2Cx, &tmp, FALSE);
559
 			I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
559
 			I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
560
 			break;
560
 			break;
561
 	}
561
 	}
562
-	
562
+
563
 	return Ret;
563
 	return Ret;
564
 }
564
 }
565
 
565
 
592
 	//get buffer to send/receive
592
 	//get buffer to send/receive
593
 	txdat = (uint8_t *) &TransferCfg->tx_data[TransferCfg->tx_count];
593
 	txdat = (uint8_t *) &TransferCfg->tx_data[TransferCfg->tx_count];
594
 	rxdat = (uint8_t *) &TransferCfg->rx_data[TransferCfg->rx_count];
594
 	rxdat = (uint8_t *) &TransferCfg->rx_data[TransferCfg->rx_count];
595
-	
595
+
596
 	switch (CodeStatus)
596
 	switch (CodeStatus)
597
 	{
597
 	{
598
 		/* Reading phase -------------------------------------------------------- */
598
 		/* Reading phase -------------------------------------------------------- */
636
 				I2Cx->I2CONSET = I2C_I2CONSET_AA;
636
 				I2Cx->I2CONSET = I2C_I2CONSET_AA;
637
 				I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
637
 				I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
638
 			}
638
 			}
639
-			
639
+
640
 			break;
640
 			break;
641
 		/* DATA has been received, Only the first data byte will be received with ACK. Additional
641
 		/* DATA has been received, Only the first data byte will be received with ACK. Additional
642
 				data will be received with NOT ACK. */
642
 				data will be received with NOT ACK. */
688
 			I2Cx->I2CONSET = I2C_I2CONSET_AA|I2C_I2CONSET_STA;
688
 			I2Cx->I2CONSET = I2C_I2CONSET_AA|I2C_I2CONSET_STA;
689
 			I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
689
 			I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
690
 			break;
690
 			break;
691
-			
691
+
692
 		case I2C_I2STAT_S_TX_LAST_DAT_ACK:
692
 		case I2C_I2STAT_S_TX_LAST_DAT_ACK:
693
 		/* Data has been transmitted, NACK has been received,
693
 		/* Data has been transmitted, NACK has been received,
694
 		 * that means there's no more data to send, exit now */
694
 		 * that means there's no more data to send, exit now */
729
 			I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
729
 			I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
730
 			Ret = I2C_STA_STO_RECV;
730
 			Ret = I2C_STA_STO_RECV;
731
 			break;
731
 			break;
732
-		
732
+
733
 		/* No status information */
733
 		/* No status information */
734
 		case I2C_I2STAT_NO_INF:
734
 		case I2C_I2STAT_NO_INF:
735
 		/* Other status must be captured */
735
 		/* Other status must be captured */
737
 			I2Cx->I2CONSET = I2C_I2CONSET_AA;
737
 			I2Cx->I2CONSET = I2C_I2CONSET_AA;
738
 			I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
738
 			I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
739
 			break;
739
 			break;
740
-		
740
+
741
 	}
741
 	}
742
 
742
 
743
 	return Ret;
743
 	return Ret;
787
 	else if (Ret & I2C_SEND_END)
787
 	else if (Ret & I2C_SEND_END)
788
 	{
788
 	{
789
 		// If no need to wait for data from Slave
789
 		// If no need to wait for data from Slave
790
-		if(txrx_setup->rx_count >= (txrx_setup->rx_length)) 
790
+		if(txrx_setup->rx_count >= (txrx_setup->rx_length))
791
 		{
791
 		{
792
 			goto s_int_end;
792
 			goto s_int_end;
793
 		}
793
 		}
799
 	       		return;
799
 	       		return;
800
 		}
800
 		}
801
 	}
801
 	}
802
-	else if (Ret & I2C_RECV_END) 
802
+	else if (Ret & I2C_RECV_END)
803
 	{
803
 	{
804
 		goto s_int_end;
804
 		goto s_int_end;
805
 	}
805
 	}
815
 	I2Cx->I2CONCLR = I2C_I2CONCLR_AAC | I2C_I2CONCLR_SIC | I2C_I2CONCLR_STAC;
815
 	I2Cx->I2CONCLR = I2C_I2CONCLR_AAC | I2C_I2CONCLR_SIC | I2C_I2CONCLR_STAC;
816
 
816
 
817
 	I2C_MasterComplete[i2cId] = TRUE;
817
 	I2C_MasterComplete[i2cId] = TRUE;
818
-		
818
+
819
 }
819
 }
820
 
820
 
821
 
821
 
874
 					goto s_int_end;
874
 					goto s_int_end;
875
 				}
875
 				}
876
 			}
876
 			}
877
-		}	
877
+		}
878
 	}
878
 	}
879
 	else if(Ret &I2C_SEND_END)
879
 	else if(Ret &I2C_SEND_END)
880
 	{
880
 	{
937
 
937
 
938
 		// Start command
938
 		// Start command
939
 		CodeStatus = I2C_Start(I2Cx);
939
 		CodeStatus = I2C_Start(I2Cx);
940
-		
940
+
941
 		while(1)	// send data first and then receive data from Slave.
941
 		while(1)	// send data first and then receive data from Slave.
942
 		{
942
 		{
943
 			Ret = I2C_MasterHanleStates(I2Cx, CodeStatus, TransferCfg);
943
 			Ret = I2C_MasterHanleStates(I2Cx, CodeStatus, TransferCfg);
955
 			else if( (Ret & I2C_BYTE_SENT) ||
955
 			else if( (Ret & I2C_BYTE_SENT) ||
956
 					(Ret & I2C_BYTE_RECV))
956
 					(Ret & I2C_BYTE_RECV))
957
 			{
957
 			{
958
-				// Wait for sending ends				
958
+				// Wait for sending ends
959
 				while (!(I2Cx->I2CONSET & I2C_I2CONSET_SI));
959
 				while (!(I2Cx->I2CONSET & I2C_I2CONSET_SI));
960
 			}
960
 			}
961
 			else if (Ret & I2C_SEND_END) // already send all data
961
 			else if (Ret & I2C_SEND_END) // already send all data
962
 			{
962
 			{
963
 				// If no need to wait for data from Slave
963
 				// If no need to wait for data from Slave
964
-				if(TransferCfg->rx_count >= (TransferCfg->rx_length)) 
964
+				if(TransferCfg->rx_count >= (TransferCfg->rx_length))
965
 				{
965
 				{
966
 					break;
966
 					break;
967
 				}
967
 				}
1037
 								I2C_TRANSFER_OPT_Type Opt)
1037
 								I2C_TRANSFER_OPT_Type Opt)
1038
 {
1038
 {
1039
 	int32_t   Ret = I2C_OK;
1039
 	int32_t   Ret = I2C_OK;
1040
-	
1040
+
1041
 	uint32_t CodeStatus;
1041
 	uint32_t CodeStatus;
1042
 	uint32_t timeout;
1042
 	uint32_t timeout;
1043
 	int32_t time_en;
1043
 	int32_t time_en;
1052
 	{
1052
 	{
1053
 		/* Set AA bit to ACK command on I2C bus */
1053
 		/* Set AA bit to ACK command on I2C bus */
1054
 		I2Cx->I2CONSET = I2C_I2CONSET_AA;
1054
 		I2Cx->I2CONSET = I2C_I2CONSET_AA;
1055
-		
1055
+
1056
 		/* Clear SI bit to be ready ... */
1056
 		/* Clear SI bit to be ready ... */
1057
 		I2Cx->I2CONCLR = (I2C_I2CONCLR_SIC | I2C_I2CONCLR_STAC|I2C_I2CONCLR_STOC);
1057
 		I2Cx->I2CONCLR = (I2C_I2CONCLR_SIC | I2C_I2CONCLR_STAC|I2C_I2CONCLR_STOC);
1058
 
1058
 

+ 2
- 2
frameworks/CMSIS/LPC1768/driver/lpc17xx_i2s.c Wyświetl plik

331
 	uint16_t dif;
331
 	uint16_t dif;
332
 	uint16_t x_divide, y_divide;
332
 	uint16_t x_divide, y_divide;
333
 	uint16_t err, ErrorOptimal = 0xFFFF;
333
 	uint16_t err, ErrorOptimal = 0xFFFF;
334
-	
334
+
335
 	uint32_t N;
335
 	uint32_t N;
336
 
336
 
337
 	CHECK_PARAM(PARAM_I2Sx(I2Sx));
337
 	CHECK_PARAM(PARAM_I2Sx(I2Sx));
360
 	 * The formula is:
360
 	 * The formula is:
361
 	 * 		I2S_MCLK = PCLK_I2S * (X/Y) / 2
361
 	 * 		I2S_MCLK = PCLK_I2S * (X/Y) / 2
362
      * In that, Y must be greater than or equal to X. X should divides evenly
362
      * In that, Y must be greater than or equal to X. X should divides evenly
363
-     * into Y. 
363
+     * into Y.
364
 	 * We have:
364
 	 * We have:
365
 	 * 		I2S_MCLK = Freq * channel*wordwidth * (I2STXBITRATE+1);
365
 	 * 		I2S_MCLK = Freq * channel*wordwidth * (I2STXBITRATE+1);
366
 	 * So: (X/Y) = (Freq * channel*wordwidth * (I2STXBITRATE+1))*2/PCLK_I2S
366
 	 * So: (X/Y) = (Freq * channel*wordwidth * (I2STXBITRATE+1))*2/PCLK_I2S

+ 32
- 32
frameworks/CMSIS/LPC1768/include/arm_common_tables.h Wyświetl plik

1
-/* ---------------------------------------------------------------------- 
2
-* Copyright (C) 2010 ARM Limited. All rights reserved. 
3
-* 
4
-* $Date:        11. November 2010  
5
-* $Revision: 	V1.0.2  
6
-* 
7
-* Project: 	    CMSIS DSP Library 
8
-* Title:	    arm_common_tables.h 
9
-* 
10
-* Description:	This file has extern declaration for common tables like Bitreverse, reciprocal etc which are used across different functions 
11
-* 
1
+/* ----------------------------------------------------------------------
2
+* Copyright (C) 2010 ARM Limited. All rights reserved.
3
+*
4
+* $Date:        11. November 2010
5
+* $Revision: 	V1.0.2
6
+*
7
+* Project: 	    CMSIS DSP Library
8
+* Title:	    arm_common_tables.h
9
+*
10
+* Description:	This file has extern declaration for common tables like Bitreverse, reciprocal etc which are used across different functions
11
+*
12
 * Target Processor: Cortex-M4/Cortex-M3
12
 * Target Processor: Cortex-M4/Cortex-M3
13
-*  
14
-* Version 1.0.2 2010/11/11 
15
-*    Documentation updated.  
16
-* 
17
-* Version 1.0.1 2010/10/05  
18
-*    Production release and review comments incorporated. 
19
-* 
20
-* Version 1.0.0 2010/09/20  
21
-*    Production release and review comments incorporated. 
22
-* -------------------------------------------------------------------- */ 
23
- 
24
-#ifndef _ARM_COMMON_TABLES_H 
25
-#define _ARM_COMMON_TABLES_H 
26
- 
27
-#include "arm_math.h" 
28
- 
29
-extern uint16_t armBitRevTable[256]; 
30
-extern q15_t armRecipTableQ15[64]; 
31
-extern q31_t armRecipTableQ31[64]; 
13
+*
14
+* Version 1.0.2 2010/11/11
15
+*    Documentation updated.
16
+*
17
+* Version 1.0.1 2010/10/05
18
+*    Production release and review comments incorporated.
19
+*
20
+* Version 1.0.0 2010/09/20
21
+*    Production release and review comments incorporated.
22
+* -------------------------------------------------------------------- */
23
+
24
+#ifndef _ARM_COMMON_TABLES_H
25
+#define _ARM_COMMON_TABLES_H
26
+
27
+#include "arm_math.h"
28
+
29
+extern uint16_t armBitRevTable[256];
30
+extern q15_t armRecipTableQ15[64];
31
+extern q31_t armRecipTableQ31[64];
32
 extern const q31_t realCoefAQ31[1024];
32
 extern const q31_t realCoefAQ31[1024];
33
 extern const q31_t realCoefBQ31[1024];
33
 extern const q31_t realCoefBQ31[1024];
34
- 
35
-#endif /*  ARM_COMMON_TABLES_H */ 
34
+
35
+#endif /*  ARM_COMMON_TABLES_H */

+ 11
- 11
frameworks/CMSIS/LPC1768/include/core_cmFunc.h Wyświetl plik

8
  * Copyright (C) 2009-2011 ARM Limited. All rights reserved.
8
  * Copyright (C) 2009-2011 ARM Limited. All rights reserved.
9
  *
9
  *
10
  * @par
10
  * @par
11
- * ARM Limited (ARM) is supplying this software for use with Cortex-M 
12
- * processor based microcontrollers.  This file can be freely distributed 
13
- * within development tools that are supporting such ARM based processors. 
11
+ * ARM Limited (ARM) is supplying this software for use with Cortex-M
12
+ * processor based microcontrollers.  This file can be freely distributed
13
+ * within development tools that are supporting such ARM based processors.
14
  *
14
  *
15
  * @par
15
  * @par
16
  * THIS SOFTWARE IS PROVIDED "AS IS".  NO WARRANTIES, WHETHER EXPRESS, IMPLIED
16
  * THIS SOFTWARE IS PROVIDED "AS IS".  NO WARRANTIES, WHETHER EXPRESS, IMPLIED
26
 
26
 
27
 
27
 
28
 /* ###########################  Core Function Access  ########################### */
28
 /* ###########################  Core Function Access  ########################### */
29
-/** \ingroup  CMSIS_Core_FunctionInterface   
29
+/** \ingroup  CMSIS_Core_FunctionInterface
30
     \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions
30
     \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions
31
   @{
31
   @{
32
  */
32
  */
182
   register uint32_t __regPriMask         __ASM("primask");
182
   register uint32_t __regPriMask         __ASM("primask");
183
   __regPriMask = (priMask);
183
   __regPriMask = (priMask);
184
 }
184
 }
185
- 
185
+
186
 
186
 
187
 #if       (__CORTEX_M >= 0x03)
187
 #if       (__CORTEX_M >= 0x03)
188
 
188
 
226
   register uint32_t __regBasePri         __ASM("basepri");
226
   register uint32_t __regBasePri         __ASM("basepri");
227
   __regBasePri = (basePri & 0xff);
227
   __regBasePri = (basePri & 0xff);
228
 }
228
 }
229
- 
229
+
230
 
230
 
231
 /** \brief  Get Fault Mask
231
 /** \brief  Get Fault Mask
232
 
232
 
407
   __ASM volatile ("MRS %0, psp\n"  : "=r" (result) );
407
   __ASM volatile ("MRS %0, psp\n"  : "=r" (result) );
408
   return(result);
408
   return(result);
409
 }
409
 }
410
- 
410
+
411
 
411
 
412
 /** \brief  Set Process Stack Pointer
412
 /** \brief  Set Process Stack Pointer
413
 
413
 
434
   __ASM volatile ("MRS %0, msp\n" : "=r" (result) );
434
   __ASM volatile ("MRS %0, msp\n" : "=r" (result) );
435
   return(result);
435
   return(result);
436
 }
436
 }
437
- 
437
+
438
 
438
 
439
 /** \brief  Set Main Stack Pointer
439
 /** \brief  Set Main Stack Pointer
440
 
440
 
473
 {
473
 {
474
   __ASM volatile ("MSR primask, %0" : : "r" (priMask) );
474
   __ASM volatile ("MSR primask, %0" : : "r" (priMask) );
475
 }
475
 }
476
- 
476
+
477
 
477
 
478
 #if       (__CORTEX_M >= 0x03)
478
 #if       (__CORTEX_M >= 0x03)
479
 
479
 
508
 __attribute__( ( always_inline ) ) static __INLINE uint32_t __get_BASEPRI(void)
508
 __attribute__( ( always_inline ) ) static __INLINE uint32_t __get_BASEPRI(void)
509
 {
509
 {
510
   uint32_t result;
510
   uint32_t result;
511
-  
511
+
512
   __ASM volatile ("MRS %0, basepri_max" : "=r" (result) );
512
   __ASM volatile ("MRS %0, basepri_max" : "=r" (result) );
513
   return(result);
513
   return(result);
514
 }
514
 }
535
 __attribute__( ( always_inline ) ) static __INLINE uint32_t __get_FAULTMASK(void)
535
 __attribute__( ( always_inline ) ) static __INLINE uint32_t __get_FAULTMASK(void)
536
 {
536
 {
537
   uint32_t result;
537
   uint32_t result;
538
-  
538
+
539
   __ASM volatile ("MRS %0, faultmask" : "=r" (result) );
539
   __ASM volatile ("MRS %0, faultmask" : "=r" (result) );
540
   return(result);
540
   return(result);
541
 }
541
 }

+ 3
- 3
frameworks/CMSIS/LPC1768/include/lpc17xx_iap.h Wyświetl plik

7
 * @version	1.0
7
 * @version	1.0
8
 * @date		18. April. 2012
8
 * @date		18. April. 2012
9
 * @author	NXP MCU SW Application Team
9
 * @author	NXP MCU SW Application Team
10
-* 
10
+*
11
 * Copyright(C) 2011, NXP Semiconductor
11
 * Copyright(C) 2011, NXP Semiconductor
12
 * All rights reserved.
12
 * All rights reserved.
13
 *
13
 *
112
 /**
112
 /**
113
  * @}
113
  * @}
114
  */
114
  */
115
- 
115
+
116
 /* Public Functions ----------------------------------------------------------- */
116
 /* Public Functions ----------------------------------------------------------- */
117
 /** @defgroup IAP_Public_Functions IAP Public Functions
117
 /** @defgroup IAP_Public_Functions IAP Public Functions
118
  * @{
118
  * @{
128
 IAP_STATUS_CODE EraseSector(uint32_t start_sec, uint32_t end_sec);
128
 IAP_STATUS_CODE EraseSector(uint32_t start_sec, uint32_t end_sec);
129
 /**  Blank check sectors */
129
 /**  Blank check sectors */
130
 IAP_STATUS_CODE BlankCheckSector(uint32_t start_sec, uint32_t end_sec,
130
 IAP_STATUS_CODE BlankCheckSector(uint32_t start_sec, uint32_t end_sec,
131
-                                 uint32_t *first_nblank_loc, 
131
+                                 uint32_t *first_nblank_loc,
132
 								 uint32_t *first_nblank_val);
132
 								 uint32_t *first_nblank_val);
133
 /**  Read part identification number */
133
 /**  Read part identification number */
134
 IAP_STATUS_CODE ReadPartID(uint32_t *partID);
134
 IAP_STATUS_CODE ReadPartID(uint32_t *partID);

+ 6
- 6
frameworks/CMSIS/LPC1768/include/system_LPC17xx.h Wyświetl plik

1
 /******************************************************************************
1
 /******************************************************************************
2
  * @file:    system_LPC17xx.h
2
  * @file:    system_LPC17xx.h
3
  * @purpose: CMSIS Cortex-M3 Device Peripheral Access Layer Header File
3
  * @purpose: CMSIS Cortex-M3 Device Peripheral Access Layer Header File
4
- *           for the NXP LPC17xx Device Series 
4
+ *           for the NXP LPC17xx Device Series
5
  * @version: V1.02
5
  * @version: V1.02
6
  * @date:    27. July 2009
6
  * @date:    27. July 2009
7
  *----------------------------------------------------------------------------
7
  *----------------------------------------------------------------------------
8
  *
8
  *
9
  * Copyright (C) 2009 ARM Limited. All rights reserved.
9
  * Copyright (C) 2009 ARM Limited. All rights reserved.
10
  *
10
  *
11
- * ARM Limited (ARM) is supplying this software for use with Cortex-M3 
12
- * processor based microcontrollers.  This file can be freely distributed 
13
- * within development tools that are supporting such ARM based processors. 
11
+ * ARM Limited (ARM) is supplying this software for use with Cortex-M3
12
+ * processor based microcontrollers.  This file can be freely distributed
13
+ * within development tools that are supporting such ARM based processors.
14
  *
14
  *
15
  * THIS SOFTWARE IS PROVIDED "AS IS".  NO WARRANTIES, WHETHER EXPRESS, IMPLIED
15
  * THIS SOFTWARE IS PROVIDED "AS IS".  NO WARRANTIES, WHETHER EXPRESS, IMPLIED
16
  * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
16
  * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
26
 
26
 
27
 #ifdef __cplusplus
27
 #ifdef __cplusplus
28
  extern "C" {
28
  extern "C" {
29
-#endif 
29
+#endif
30
 
30
 
31
 extern uint32_t SystemCoreClock;     /*!< System Clock Frequency (Core Clock)  */
31
 extern uint32_t SystemCoreClock;     /*!< System Clock Frequency (Core Clock)  */
32
 
32
 
48
  * @param  none
48
  * @param  none
49
  * @return none
49
  * @return none
50
  *
50
  *
51
- * @brief  Updates the SystemCoreClock with current core Clock 
51
+ * @brief  Updates the SystemCoreClock with current core Clock
52
  *         retrieved from cpu registers.
52
  *         retrieved from cpu registers.
53
  */
53
  */
54
 extern void SystemCoreClockUpdate (void);
54
 extern void SystemCoreClockUpdate (void);

+ 3
- 3
frameworks/CMSIS/library.json Wyświetl plik

1
 {
1
 {
2
-  "name": "CMSIS-LPC1768", 
2
+  "name": "CMSIS-LPC1768",
3
   "version": "0.0.0",
3
   "version": "0.0.0",
4
-  "frameworks": [], 
4
+  "frameworks": [],
5
   "platforms": [
5
   "platforms": [
6
-      "nxplpc", 
6
+      "nxplpc",
7
       "ststm32"
7
       "ststm32"
8
   ],
8
   ],
9
   "description": "CMSIS library for LPC1768",
9
   "description": "CMSIS library for LPC1768",

Ładowanie…
Anuluj
Zapisz