Просмотр исходного кода

[HAL][LPC176x] Pull out framework into separate repository

Framework and build platform now located at https://github.com/p3p/pio-framework-arduino-lpc176x and https://github.com/p3p/pio-nxplpc-arduino-lpc176x respectively

fix mkssbase leds

move hardware serial

remove hardware/software serial

Hardware Serial extraction

HardwareSerial ISRs

fix disabled serial2 causing Serial object to link

move usb devices out to framework

separate out adc/pwm peripheral function from hal.cpp

fix includes

remove unused pwm init

move adc

HAL header update

templated filtered adc

LPC1769 platform
Christopher Pepper 5 лет назад
Родитель
Сommit
5ddf52d58e
100 измененных файлов: 248 добавлений и 37686 удалений
  1. 6
    227
      Marlin/src/HAL/HAL_LPC1768/HAL.cpp
  2. 37
    57
      Marlin/src/HAL/HAL_LPC1768/HAL.h
  3. 0
    1
      Marlin/src/HAL/HAL_LPC1768/HAL_temp.h
  4. 1
    2
      Marlin/src/HAL/HAL_LPC1768/HAL_timers.h
  5. 0
    576
      Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.cpp
  6. 0
    79
      Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.h
  7. 0
    163
      Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.cpp
  8. 0
    62
      Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.h
  9. 56
    0
      Marlin/src/HAL/HAL_LPC1768/MarlinSerial.cpp
  10. 71
    0
      Marlin/src/HAL/HAL_LPC1768/MarlinSerial.h
  11. 0
    90
      Marlin/src/HAL/HAL_LPC1768/SoftwareSPI.cpp
  12. 0
    50
      Marlin/src/HAL/HAL_LPC1768/SoftwareSPI.h
  13. 0
    162
      Marlin/src/HAL/HAL_LPC1768/WInterrupts.cpp
  14. 0
    179
      Marlin/src/HAL/HAL_LPC1768/arduino.cpp
  15. 0
    21
      Marlin/src/HAL/HAL_LPC1768/debug_extra_script.py
  16. 11
    15
      Marlin/src/HAL/HAL_LPC1768/fastio.h
  17. 0
    125
      Marlin/src/HAL/HAL_LPC1768/include/Arduino.h
  18. 0
    335
      Marlin/src/HAL/HAL_LPC1768/include/HardwareSerial.cpp
  19. 0
    91
      Marlin/src/HAL/HAL_LPC1768/include/HardwareSerial.h
  20. 0
    329
      Marlin/src/HAL/HAL_LPC1768/include/SoftwareSerial.cpp
  21. 0
    120
      Marlin/src/HAL/HAL_LPC1768/include/SoftwareSerial.h
  22. 0
    219
      Marlin/src/HAL/HAL_LPC1768/include/Wire.cpp
  23. 0
    67
      Marlin/src/HAL/HAL_LPC1768/include/Wire.h
  24. 0
    74
      Marlin/src/HAL/HAL_LPC1768/include/pinmapping.cpp
  25. 0
    294
      Marlin/src/HAL/HAL_LPC1768/include/pinmapping.h
  26. 0
    161
      Marlin/src/HAL/HAL_LPC1768/include/serial.h
  27. 0
    60
      Marlin/src/HAL/HAL_LPC1768/lpc1768_flag_script.py
  28. 28
    77
      Marlin/src/HAL/HAL_LPC1768/main.cpp
  29. 17
    26
      Marlin/src/HAL/HAL_LPC1768/servo_private.h
  30. 1
    1
      Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp
  31. 1
    1
      Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp
  32. 0
    0
      Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_sw_i2c.cpp under construction
  33. 2
    2
      Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp
  34. 2
    2
      Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_sw_spi.cpp
  35. 1
    1
      Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp
  36. 13
    0
      Marlin/src/HAL/HAL_LPC1768/usb_serial.cpp
  37. 0
    0
      Marlin/src/HAL/HAL_LPC1768/win_usb_driver/lpc176x_usb_driver.inf
  38. 1
    1
      Marlin/src/HAL/shared/servo.h
  39. 0
    306
      frameworks/CMSIS/LPC1768/driver/debug_frmwrk.c
  40. 0
    358
      frameworks/CMSIS/LPC1768/driver/lpc17xx_adc.c
  41. 0
    1936
      frameworks/CMSIS/LPC1768/driver/lpc17xx_can.c
  42. 0
    350
      frameworks/CMSIS/LPC1768/driver/lpc17xx_clkpwr.c
  43. 0
    151
      frameworks/CMSIS/LPC1768/driver/lpc17xx_dac.c
  44. 0
    963
      frameworks/CMSIS/LPC1768/driver/lpc17xx_emac.c
  45. 0
    171
      frameworks/CMSIS/LPC1768/driver/lpc17xx_exti.c
  46. 0
    463
      frameworks/CMSIS/LPC1768/driver/lpc17xx_gpdma.c
  47. 0
    762
      frameworks/CMSIS/LPC1768/driver/lpc17xx_gpio.c
  48. 0
    1344
      frameworks/CMSIS/LPC1768/driver/lpc17xx_i2c.c
  49. 0
    663
      frameworks/CMSIS/LPC1768/driver/lpc17xx_i2s.c
  50. 0
    308
      frameworks/CMSIS/LPC1768/driver/lpc17xx_iap.c
  51. 0
    76
      frameworks/CMSIS/LPC1768/driver/lpc17xx_libcfg_default.c
  52. 0
    509
      frameworks/CMSIS/LPC1768/driver/lpc17xx_mcpwm.c
  53. 0
    148
      frameworks/CMSIS/LPC1768/driver/lpc17xx_nvic.c
  54. 0
    318
      frameworks/CMSIS/LPC1768/driver/lpc17xx_pinsel.c
  55. 0
    588
      frameworks/CMSIS/LPC1768/driver/lpc17xx_pwm.c
  56. 0
    514
      frameworks/CMSIS/LPC1768/driver/lpc17xx_qei.c
  57. 0
    199
      frameworks/CMSIS/LPC1768/driver/lpc17xx_rit.c
  58. 0
    783
      frameworks/CMSIS/LPC1768/driver/lpc17xx_rtc.c
  59. 0
    443
      frameworks/CMSIS/LPC1768/driver/lpc17xx_spi.c
  60. 0
    694
      frameworks/CMSIS/LPC1768/driver/lpc17xx_ssp.c
  61. 0
    193
      frameworks/CMSIS/LPC1768/driver/lpc17xx_systick.c
  62. 0
    609
      frameworks/CMSIS/LPC1768/driver/lpc17xx_timer.c
  63. 0
    1382
      frameworks/CMSIS/LPC1768/driver/lpc17xx_uart.c
  64. 0
    274
      frameworks/CMSIS/LPC1768/driver/lpc17xx_wdt.c
  65. 0
    1078
      frameworks/CMSIS/LPC1768/include/LPC17xx.h
  66. 0
    35
      frameworks/CMSIS/LPC1768/include/arm_common_tables.h
  67. 0
    7064
      frameworks/CMSIS/LPC1768/include/arm_math.h
  68. 0
    1227
      frameworks/CMSIS/LPC1768/include/core_cm3.h
  69. 0
    609
      frameworks/CMSIS/LPC1768/include/core_cmFunc.h
  70. 0
    586
      frameworks/CMSIS/LPC1768/include/core_cmInstr.h
  71. 0
    80
      frameworks/CMSIS/LPC1768/include/debug_frmwrk.h
  72. 0
    302
      frameworks/CMSIS/LPC1768/include/lpc17xx_adc.h
  73. 0
    872
      frameworks/CMSIS/LPC1768/include/lpc17xx_can.h
  74. 0
    406
      frameworks/CMSIS/LPC1768/include/lpc17xx_clkpwr.h
  75. 0
    154
      frameworks/CMSIS/LPC1768/include/lpc17xx_dac.h
  76. 0
    711
      frameworks/CMSIS/LPC1768/include/lpc17xx_emac.h
  77. 0
    155
      frameworks/CMSIS/LPC1768/include/lpc17xx_exti.h
  78. 0
    429
      frameworks/CMSIS/LPC1768/include/lpc17xx_gpdma.h
  79. 0
    177
      frameworks/CMSIS/LPC1768/include/lpc17xx_gpio.h
  80. 0
    434
      frameworks/CMSIS/LPC1768/include/lpc17xx_i2c.h
  81. 0
    384
      frameworks/CMSIS/LPC1768/include/lpc17xx_i2s.h
  82. 0
    153
      frameworks/CMSIS/LPC1768/include/lpc17xx_iap.h
  83. 0
    181
      frameworks/CMSIS/LPC1768/include/lpc17xx_libcfg_default.h
  84. 0
    329
      frameworks/CMSIS/LPC1768/include/lpc17xx_mcpwm.h
  85. 0
    76
      frameworks/CMSIS/LPC1768/include/lpc17xx_nvic.h
  86. 0
    203
      frameworks/CMSIS/LPC1768/include/lpc17xx_pinsel.h
  87. 0
    348
      frameworks/CMSIS/LPC1768/include/lpc17xx_pwm.h
  88. 0
    424
      frameworks/CMSIS/LPC1768/include/lpc17xx_qei.h
  89. 0
    112
      frameworks/CMSIS/LPC1768/include/lpc17xx_rit.h
  90. 0
    314
      frameworks/CMSIS/LPC1768/include/lpc17xx_rtc.h
  91. 0
    328
      frameworks/CMSIS/LPC1768/include/lpc17xx_spi.h
  92. 0
    472
      frameworks/CMSIS/LPC1768/include/lpc17xx_ssp.h
  93. 0
    119
      frameworks/CMSIS/LPC1768/include/lpc17xx_systick.h
  94. 0
    348
      frameworks/CMSIS/LPC1768/include/lpc17xx_timer.h
  95. 0
    656
      frameworks/CMSIS/LPC1768/include/lpc17xx_uart.h
  96. 0
    154
      frameworks/CMSIS/LPC1768/include/lpc17xx_wdt.h
  97. 0
    205
      frameworks/CMSIS/LPC1768/include/lpc_types.h
  98. 0
    60
      frameworks/CMSIS/LPC1768/include/system_LPC17xx.h
  99. 0
    326
      frameworks/CMSIS/LPC1768/lib/LiquidCrystal.cpp
  100. 0
    0
      frameworks/CMSIS/LPC1768/lib/LiquidCrystal.h

+ 6
- 227
Marlin/src/HAL/HAL_LPC1768/HAL.cpp Просмотреть файл

@@ -22,8 +22,7 @@
22 22
 
23 23
 #include "../../inc/MarlinConfig.h"
24 24
 #include "../shared/Delay.h"
25
-
26
-HalSerial usb_serial;
25
+#include "../../../gcode/parser.h"
27 26
 
28 27
 // U8glib required functions
29 28
 extern "C" void u8g_xMicroDelay(uint16_t val) {
@@ -51,231 +50,11 @@ int freeMemory() {
51 50
   return result;
52 51
 }
53 52
 
54
-// --------------------------------------------------------------------------
55
-// ADC
56
-// --------------------------------------------------------------------------
57
-
58
-#define ADC_DONE      0x80000000
59
-#define ADC_OVERRUN   0x40000000
60
-
61
-void HAL_adc_init(void) {
62
-  LPC_SC->PCONP |= (1 << 12);      // Enable CLOCK for internal ADC controller
63
-  LPC_SC->PCLKSEL0 &= ~(0x3 << 24);
64
-  LPC_SC->PCLKSEL0 |= (0x1 << 24); // 0: 25MHz, 1: 100MHz, 2: 50MHz, 3: 12.5MHZ to ADC clock divider
65
-  LPC_ADC->ADCR = (0 << 0)         // SEL: 0 = no channels selected
66
-                | (0xFF << 8)      // select slowest clock for A/D conversion 150 - 190 uS for a complete conversion
67
-                | (0 << 16)        // BURST: 0 = software control
68
-                | (0 << 17)        // CLKS: not applicable
69
-                | (1 << 21)        // PDN: 1 = operational
70
-                | (0 << 24)        // START: 0 = no start
71
-                | (0 << 27);       // EDGE: not applicable
72
-}
73
-
74
-// externals need to make the call to KILL compile
75
-#include "../../core/language.h"
76
-
77
-extern void kill(PGM_P);
78
-
79
-void HAL_adc_enable_channel(int ch) {
80
-  pin_t pin = analogInputToDigitalPin(ch);
81
-
82
-  if (pin == -1) {
83
-    serial_error_start();
84
-    SERIAL_PRINTF("INVALID ANALOG PORT:%d\n", ch);
85
-    kill(MSG_KILLED);
86
-  }
87
-
88
-  int8_t pin_port = LPC1768_PIN_PORT(pin),
89
-         pin_port_pin = LPC1768_PIN_PIN(pin),
90
-         pinsel_start_bit = pin_port_pin > 15 ? 2 * (pin_port_pin - 16) : 2 * pin_port_pin;
91
-  uint8_t pin_sel_register = (pin_port == 0 && pin_port_pin <= 15) ? 0 :
92
-                              pin_port == 0                        ? 1 :
93
-                              pin_port == 1                        ? 3 : 10;
94
-
95
-  switch (pin_sel_register) {
96
-    case 1:
97
-      LPC_PINCON->PINSEL1 &= ~(0x3 << pinsel_start_bit);
98
-      LPC_PINCON->PINSEL1 |=  (0x1 << pinsel_start_bit);
99
-      break;
100
-    case 3:
101
-      LPC_PINCON->PINSEL3 &= ~(0x3 << pinsel_start_bit);
102
-      LPC_PINCON->PINSEL3 |=  (0x3 << pinsel_start_bit);
103
-      break;
104
-    case 0:
105
-      LPC_PINCON->PINSEL0 &= ~(0x3 << pinsel_start_bit);
106
-      LPC_PINCON->PINSEL0 |=  (0x2 << pinsel_start_bit);
107
-      break;
108
-  };
109
-}
110
-
111
-void HAL_adc_start_conversion(const uint8_t ch) {
112
-  if (analogInputToDigitalPin(ch) == -1) {
113
-    SERIAL_PRINTF("HAL: HAL_adc_start_conversion: invalid channel %d\n", ch);
114
-    return;
115
-  }
116
-
117
-  LPC_ADC->ADCR &= ~0xFF; // Reset
118
-  SBI(LPC_ADC->ADCR, ch); // Select Channel
119
-  SBI(LPC_ADC->ADCR, 24); // Start conversion
120
-}
121
-
122
-bool HAL_adc_finished(void) {
123
-  return LPC_ADC->ADGDR & ADC_DONE;
124
-}
125
-
126
-// possible config options if something similar is extended to more platforms.
127
-#define ADC_USE_MEDIAN_FILTER          // Filter out erroneous readings
128
-#define ADC_MEDIAN_FILTER_SIZE     23  // Higher values increase step delay (phase shift),
129
-                                       // (ADC_MEDIAN_FILTER_SIZE + 1) / 2 sample step delay (12 samples @ 500Hz: 24ms phase shift)
130
-                                       // Memory usage per ADC channel (bytes): (6 * ADC_MEDIAN_FILTER_SIZE) + 16
131
-                                       // 8 * ((6 * 23) + 16 ) = 1232 Bytes for 8 channels
132
-
133
-#define ADC_USE_LOWPASS_FILTER         // Filter out high frequency noise
134
-#define ADC_LOWPASS_K_VALUE         6  // Higher values increase rise time
135
-                                       // Rise time sample delays for 100% signal convergence on full range step
136
-                                       // (1 : 13, 2 : 32, 3 : 67, 4 : 139, 5 : 281, 6 : 565, 7 : 1135, 8 : 2273)
137
-                                       // K = 6, 565 samples, 500Hz sample rate, 1.13s convergence on full range step
138
-                                       // Memory usage per ADC channel (bytes): 4 (32 Bytes for 8 channels)
139
-
140
-
141
-// Sourced from https://embeddedgurus.com/stack-overflow/tag/median-filter/
142
-struct MedianFilter {
143
-  #define STOPPER 0                // Smaller than any datum
144
-  struct Pair {
145
-    Pair   *point;                 // Pointers forming list linked in sorted order
146
-    uint16_t  value;               // Values to sort
147
-  };
148
-
149
-  Pair buffer[ADC_MEDIAN_FILTER_SIZE] = {}; // Buffer of nwidth pairs
150
-  Pair *datpoint = buffer;                  // Pointer into circular buffer of data
151
-  Pair small = {NULL, STOPPER};             // Chain stopper
152
-  Pair big = {&small, 0};                   // Pointer to head (largest) of linked list.
153
-
154
-  uint16_t update(uint16_t datum) {
155
-    Pair *successor;                        // Pointer to successor of replaced data item
156
-    Pair *scan;                             // Pointer used to scan down the sorted list
157
-    Pair *scanold;                          // Previous value of scan
158
-    Pair *median;                           // Pointer to median
159
-    uint16_t i;
160
-
161
-    if (datum == STOPPER) {
162
-      datum = STOPPER + 1;                  // No stoppers allowed.
163
-    }
164
-
165
-    if ( (++datpoint - buffer) >= (ADC_MEDIAN_FILTER_SIZE)) {
166
-      datpoint = buffer;                    // Increment and wrap data in pointer.
167
-    }
168
-
169
-    datpoint->value = datum;                // Copy in new datum
170
-    successor = datpoint->point;            // Save pointer to old value's successor
171
-    median = &big;                          // Median initially to first in chain
172
-    scanold = NULL;                         // Scanold initially null.
173
-    scan = &big;                            // Points to pointer to first (largest) datum in chain
174
-
175
-    // Handle chain-out of first item in chain as special case
176
-    if (scan->point == datpoint) {
177
-      scan->point = successor;
178
-    }
179
-    scanold = scan;                         // Save this pointer and
180
-    scan = scan->point ;                    // step down chain
181
-
182
-    // Loop through the chain, normal loop exit via break.
183
-    for (i = 0 ; i < ADC_MEDIAN_FILTER_SIZE; ++i) {
184
-      // Handle odd-numbered item in chain
185
-      if (scan->point == datpoint) {
186
-        scan->point = successor;            // Chain out the old datum
187
-      }
188
-
189
-      if (scan->value < datum) {            // If datum is larger than scanned value
190
-        datpoint->point = scanold->point;   // Chain it in here
191
-        scanold->point = datpoint;          // Mark it chained in
192
-        datum = STOPPER;
193
-      }
194
-
195
-      // Step median pointer down chain after doing odd-numbered element
196
-      median = median->point;               // Step median pointer
197
-      if (scan == &small) {
198
-        break;                              // Break at end of chain
199
-      }
200
-      scanold = scan;                       // Save this pointer and
201
-      scan = scan->point;                   // step down chain
202
-
203
-      // Handle even-numbered item in chain.
204
-      if (scan->point == datpoint) {
205
-        scan->point = successor;
206
-      }
207
-
208
-      if (scan->value < datum) {
209
-        datpoint->point = scanold->point;
210
-        scanold->point = datpoint;
211
-        datum = STOPPER;
212
-      }
213
-
214
-      if (scan == &small) {
215
-        break;
216
-      }
217
-
218
-      scanold = scan;
219
-      scan = scan->point;
220
-    }
221
-    return median->value;
222
-  }
223
-};
224
-
225
-struct LowpassFilter {
226
-  uint32_t data_delay = 0;
227
-  uint16_t update(const uint16_t value) {
228
-    data_delay -= (data_delay >> (ADC_LOWPASS_K_VALUE)) - value;
229
-    return (uint16_t)(data_delay >> (ADC_LOWPASS_K_VALUE));
230
-  }
231
-};
232
-
233
-uint16_t HAL_adc_get_result(void) {
234
-  uint32_t adgdr = LPC_ADC->ADGDR;
235
-  CBI(LPC_ADC->ADCR, 24);                    // Stop conversion
236
-
237
-  if (adgdr & ADC_OVERRUN) return 0;
238
-  uint16_t data = (adgdr >> 4) & 0xFFF;      // copy the 12bit data value
239
-  uint8_t adc_channel = (adgdr >> 24) & 0x7; // copy the  3bit used channel
240
-
241
-  #ifdef ADC_USE_MEDIAN_FILTER
242
-    static MedianFilter median_filter[NUM_ANALOG_INPUTS];
243
-    data = median_filter[adc_channel].update(data);
244
-  #endif
245
-
246
-  #ifdef ADC_USE_LOWPASS_FILTER
247
-    static LowpassFilter lowpass_filter[NUM_ANALOG_INPUTS];
248
-    data = lowpass_filter[adc_channel].update(data);
249
-  #endif
250
-
251
-  return ((data >> 2) & 0x3FF);    // return 10bit value as Marlin expects
252
-}
253
-
254
-#define SBIT_CNTEN     0
255
-#define SBIT_PWMEN     2
256
-#define SBIT_PWMMR0R   1
257
-
258
-#define PWM_1          0  //P2_00 (0-1 Bits of PINSEL4)
259
-#define PWM_2          2  //P2_01 (2-3 Bits of PINSEL4)
260
-#define PWM_3          4  //P2_02 (4-5 Bits of PINSEL4)
261
-#define PWM_4          6  //P2_03 (6-7 Bits of PINSEL4)
262
-#define PWM_5          8  //P2_04 (8-9 Bits of PINSEL4)
263
-#define PWM_6          10 //P2_05 (10-11 Bits of PINSEL4)
264
-
265
-void HAL_pwm_init(void) {
266
-  LPC_PINCON->PINSEL4 = _BV(PWM_5) | _BV(PWM_6);
267
-
268
-  LPC_PWM1->TCR = _BV(SBIT_CNTEN) | _BV(SBIT_PWMEN);
269
-  LPC_PWM1->PR  =  0x0;               // No prescalar
270
-  LPC_PWM1->MCR = _BV(SBIT_PWMMR0R);  // Reset on PWMMR0, reset TC if it matches MR0
271
-  LPC_PWM1->MR0 = 255;                // set PWM cycle(Ton+Toff)=255)
272
-  LPC_PWM1->MR5 = 0;                  // Set 50% Duty Cycle for the channels
273
-  LPC_PWM1->MR6 = 0;
274
-
275
-  // Trigger the latch Enable Bits to load the new Match Values MR0, MR5, MR6
276
-  LPC_PWM1->LER = _BV(0) | _BV(5) | _BV(6);
277
-  // Enable the PWM output pins for PWM_5-PWM_6(P2_04 - P2_05)
278
-  LPC_PWM1->PCR = _BV(13) | _BV(14);
53
+int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) {
54
+  const uint16_t val = (uint16_t)parser.intval(code), port = val / 100, pin = val % 100;
55
+  const  int16_t ind = (port < (NUM_DIGITAL_PINS >> 5) && (pin < 32))
56
+                      ? GET_PIN_MAP_INDEX(port << 5 | pin) : -2;
57
+  return ind > -2 ? ind : dval;
279 58
 }
280 59
 
281 60
 #endif // TARGET_LPC1768

+ 37
- 57
Marlin/src/HAL/HAL_LPC1768/HAL.h Просмотреть файл

@@ -29,42 +29,27 @@
29 29
 #define _HAL_LPC1768_H_
30 30
 
31 31
 #define CPU_32_BIT
32
+#define HAL_INIT
32 33
 
33
-// --------------------------------------------------------------------------
34
-// Includes
35
-// --------------------------------------------------------------------------
34
+void HAL_init();
36 35
 
37 36
 #include <stdint.h>
38 37
 #include <stdarg.h>
39
-
40
-#undef min
41
-#undef max
42
-
43 38
 #include <algorithm>
44 39
 
45
-void _printf (const  char *format, ...);
46
-void _putc(uint8_t c);
47
-uint8_t _getc();
48
-
49 40
 extern "C" volatile uint32_t _millis;
50 41
 
51
-//arduino: Print.h
52
-#define DEC 10
53
-#define HEX 16
54
-#define OCT 8
55
-#define BIN 2
56
-//arduino: binary.h (weird defines)
57
-#define B01 1
58
-#define B10 2
59
-
60 42
 #include <Arduino.h>
61 43
 #include <pinmapping.h>
44
+#include <CDCSerial.h>
62 45
 
63 46
 #include "../shared/math_32bit.h"
64 47
 #include "../shared/HAL_SPI.h"
65 48
 #include "fastio.h"
49
+#include <adc.h>
66 50
 #include "watchdog.h"
67 51
 #include "HAL_timers.h"
52
+#include "MarlinSerial.h"
68 53
 
69 54
 //
70 55
 // Default graphical display delays
@@ -79,32 +64,20 @@ extern "C" volatile uint32_t _millis;
79 64
   #define ST7920_DELAY_3 DELAY_NS(750)
80 65
 #endif
81 66
 
82
-//
83
-// Arduino-style serial ports
84
-//
85
-#include "serial.h"
86
-#include "HardwareSerial.h"
87
-
88
-extern HalSerial usb_serial;
89
-
90 67
 #if !WITHIN(SERIAL_PORT, -1, 3)
91 68
   #error "SERIAL_PORT must be from -1 to 3"
92 69
 #endif
93 70
 
94 71
 #if SERIAL_PORT == -1
95
-  #define MYSERIAL0 usb_serial
72
+  #define MYSERIAL0 UsbSerial
96 73
 #elif SERIAL_PORT == 0
97
-  extern HardwareSerial Serial;
98
-  #define MYSERIAL0 Serial
74
+  #define MYSERIAL0 MSerial
99 75
 #elif SERIAL_PORT == 1
100
-  extern HardwareSerial Serial1;
101
-  #define MYSERIAL0 Serial1
76
+  #define MYSERIAL0 MSerial1
102 77
 #elif SERIAL_PORT == 2
103
-  extern HardwareSerial Serial2;
104
-  #define MYSERIAL0 Serial2
78
+  #define MYSERIAL0 MSerial2
105 79
 #elif SERIAL_PORT == 3
106
-  #define MYSERIAL0 Serial3
107
-  extern HardwareSerial Serial3;
80
+  #define MYSERIAL0 MSerial3
108 81
 #endif
109 82
 
110 83
 #ifdef SERIAL_PORT_2
@@ -115,19 +88,15 @@ extern HalSerial usb_serial;
115 88
   #endif
116 89
   #define NUM_SERIAL 2
117 90
   #if SERIAL_PORT_2 == -1
118
-    #define MYSERIAL1 usb_serial
91
+    #define MYSERIAL1 UsbSerial
119 92
   #elif SERIAL_PORT_2 == 0
120
-    extern HardwareSerial Serial;
121
-    #define MYSERIAL1 Serial
93
+    #define MYSERIAL1 MSerial
122 94
   #elif SERIAL_PORT_2 == 1
123
-    extern HardwareSerial Serial1;
124
-    #define MYSERIAL1 Serial1
95
+    #define MYSERIAL1 MSerial1
125 96
   #elif SERIAL_PORT_2 == 2
126
-    extern HardwareSerial Serial2;
127
-    #define MYSERIAL1 Serial2
97
+    #define MYSERIAL1 MSerial2
128 98
   #elif SERIAL_PORT_2 == 3
129
-    extern HardwareSerial Serial3;
130
-    #define MYSERIAL1 Serial3
99
+    #define MYSERIAL1 MSerial3
131 100
   #endif
132 101
 #else
133 102
   #define NUM_SERIAL 1
@@ -159,17 +128,28 @@ void spiSend(uint32_t chan, const uint8_t* buf, size_t n);
159 128
 uint8_t spiRec(uint32_t chan);
160 129
 
161 130
 //
162
-// ADC
131
+// ADC API
163 132
 //
164
-#define HAL_ANALOG_SELECT(pin) HAL_adc_enable_channel(pin)
165
-#define HAL_START_ADC(pin)     HAL_adc_start_conversion(pin)
166
-#define HAL_READ_ADC()         HAL_adc_get_result()
167
-#define HAL_ADC_READY()        HAL_adc_finished()
168
-
169
-void HAL_adc_init(void);
170
-void HAL_adc_enable_channel(int pin);
171
-void HAL_adc_start_conversion(const uint8_t adc_pin);
172
-uint16_t HAL_adc_get_result(void);
173
-bool HAL_adc_finished(void);
133
+
134
+#define ADC_MEDIAN_FILTER_SIZE (23) // Higher values increase step delay (phase shift),
135
+                                    // (ADC_MEDIAN_FILTER_SIZE + 1) / 2 sample step delay (12 samples @ 500Hz: 24ms phase shift)
136
+                                    // Memory usage per ADC channel (bytes): (6 * ADC_MEDIAN_FILTER_SIZE) + 16
137
+                                    // 8 * ((6 * 23) + 16 ) = 1232 Bytes for 8 channels
138
+
139
+#define ADC_LOWPASS_K_VALUE    (6)  // Higher values increase rise time
140
+                                    // Rise time sample delays for 100% signal convergence on full range step
141
+                                    // (1 : 13, 2 : 32, 3 : 67, 4 : 139, 5 : 281, 6 : 565, 7 : 1135, 8 : 2273)
142
+                                    // K = 6, 565 samples, 500Hz sample rate, 1.13s convergence on full range step
143
+                                    // Memory usage per ADC channel (bytes): 4 (32 Bytes for 8 channels)
144
+
145
+using FilteredADC = LPC176x::ADC<ADC_LOWPASS_K_VALUE, ADC_MEDIAN_FILTER_SIZE>;
146
+#define HAL_adc_init()         FilteredADC::init()
147
+#define HAL_ANALOG_SELECT(pin) FilteredADC::enable_channel(pin)
148
+#define HAL_START_ADC(pin)     FilteredADC::start_conversion(pin)
149
+#define HAL_READ_ADC()         FilteredADC::get_result()
150
+#define HAL_ADC_READY()        FilteredADC::finished_conversion()
151
+
152
+// Parse a G-code word into a pin index
153
+int16_t PARSED_PIN_INDEX(const char code, const int16_t dval);
174 154
 
175 155
 #endif // _HAL_LPC1768_H_

+ 0
- 1
Marlin/src/HAL/HAL_LPC1768/HAL_temp.h Просмотреть файл

@@ -1 +0,0 @@
1
-// blank file needed until I get platformio to update it's copy of U8Glib-HAL

+ 1
- 2
Marlin/src/HAL/HAL_LPC1768/HAL_timers.h Просмотреть файл

@@ -20,9 +20,8 @@
20 20
  */
21 21
 
22 22
 /**
23
- * HAL for Arduino Due and compatible (SAM3X8E)
24 23
  *
25
- * For ARDUINO_ARCH_SAM
24
+ * HAL For LPC1768
26 25
  */
27 26
 
28 27
 #ifndef _HAL_TIMERS_H

+ 0
- 576
Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.cpp Просмотреть файл

@@ -1,576 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (C) 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
- *
21
- */
22
-
23
-/**
24
- * The class Servo uses the PWM class to implement its functions
25
- *
26
- * All PWMs use the same repetition rate - 20mS because that's the normal servo rate
27
- */
28
-
29
-/**
30
- * This is a hybrid system.
31
- *
32
- * The PWM1 module is used to directly control the Servo 0, 1 & 3 pins and D9 & D10 pins.  This keeps
33
- * the pulse width jitter to under a microsecond.
34
- *
35
- * For all other pins a timer is used to generate interrupts.  The ISR
36
- * routine does the actual setting/clearing of pins.  The upside is that any pin can
37
- * have a PWM channel assigned to it.  The downside is that there is more pulse width
38
- * jitter. The jitter depends on what else is happening in the system and what ISRs
39
- * pre-empt the PWM ISR.
40
- */
41
-
42
-/**
43
- * The data structures are set up to minimize the computation done by the ISR which
44
- * minimizes ISR execution time.  Execution times are 5-14µs depending on how full the
45
- * ISR table is.  14uS is for a 20 element ISR table.
46
- *
47
- * Two tables are used.  One table contains the data used by the ISR to update/control
48
- * the PWM pins.  The other is used as an aid when updating the ISR table.
49
- *
50
- * See the end of this file for details on the hardware/firmware interaction
51
- */
52
-
53
-/**
54
- * Directly controlled PWM pins (
55
- *   NA means not being used as a directly controlled PWM pin
56
- *
57
- *                   Re-ARM              MKS Sbase
58
- *  PWM1.1   P1_18   SERVO3_PIN           NA(no connection)
59
- *  PWM1.1   P2_00    NA(E0_STEP_PIN)     NA(X stepper)
60
- *  PWM1.2   P1_20   SERVO0_PIN           NA(no connection)
61
- *  PWM1.2   P2_01    NA(X_STEP_PIN)      NA(Y stepper)
62
- *  PWM1.3   P1_21   SERVO1_PIN           NA(no connection)
63
- *  PWM1.3   P2_02    NA(Y_STEP_PIN)      NA(Z stepper)
64
- *  PWM1.4   P1_23    NA(SDSS(SSEL0))    SERVO0_PIN
65
- *  PWM1.4   P2_03    NA(Z_STEP_PIN)      NA(E0 stepper)
66
- *  PWM1.5   P1_24    NA(X_MIN_PIN)       NA(X_MIN_pin)
67
- *  PWM1.5   P2_04   RAMPS_D9_PIN        FAN_PIN
68
- *  PWM1.6   P1_26    NA(Y_MIN_PIN)       NA(Y_MIN_pin)
69
- *  PWM1.6   P2_05   RAMPS_D10_PIN       HEATER_BED_PIN
70
- */
71
-
72
-#ifdef TARGET_LPC1768
73
-
74
-#include "../../inc/MarlinConfig.h"
75
-#include <lpc17xx_pinsel.h>
76
-#include "LPC1768_PWM.h"
77
-#include <Arduino.h>
78
-
79
-#define NUM_ISR_PWMS 20
80
-
81
-#define HAL_PWM_TIMER      LPC_TIM3
82
-#define HAL_PWM_TIMER_ISR  extern "C" void TIMER3_IRQHandler(void)
83
-#define HAL_PWM_TIMER_IRQn TIMER3_IRQn
84
-
85
-#define LPC_PORT_OFFSET         (0x0020)
86
-#define LPC_PIN(pin)            (1UL << pin)
87
-#define LPC_GPIO(port)          ((volatile LPC_GPIO_TypeDef *)(LPC_GPIO0_BASE + LPC_PORT_OFFSET * port))
88
-
89
-typedef struct {            // holds all data needed to control/init one of the PWM channels
90
-  bool                active_flag;    // THIS TABLE ENTRY IS ACTIVELY TOGGLING A PIN
91
-  pin_t               pin;
92
-  volatile uint32_t*  set_register;
93
-  volatile uint32_t*  clr_register;
94
-  uint32_t            write_mask;     // USED BY SET/CLEAR COMMANDS
95
-  uint32_t            microseconds;   // value written to MR register
96
-  uint32_t            min;            // lower value limit checked by WRITE routine before writing to the MR register
97
-  uint32_t            max;            // upper value limit checked by WRITE routine before writing to the MR register
98
-  uint8_t             servo_index;    // 0 - MAX_SERVO -1 : servo index,  0xFF : PWM channel
99
-} PWM_map;
100
-
101
-PWM_map PWM1_map_A[NUM_ISR_PWMS];  // compiler will initialize to all zeros
102
-PWM_map PWM1_map_B[NUM_ISR_PWMS];  // compiler will initialize to all zeros
103
-
104
-PWM_map *active_table = PWM1_map_A;
105
-PWM_map *work_table = PWM1_map_B;
106
-PWM_map *temp_table;
107
-
108
-#define P1_18_PWM_channel  1  // servo 3
109
-#define P1_20_PWM_channel  2  // servo 0
110
-#define P1_21_PWM_channel  3  // servo 1
111
-#define P1_23_PWM_channel  4  // servo 0 for MKS Sbase
112
-#define P2_04_PWM_channel  5  // D9
113
-#define P2_05_PWM_channel  6  // D10
114
-
115
-typedef struct {
116
-  uint32_t min;
117
-  uint32_t max;
118
-  bool     assigned;
119
-} table_direct;
120
-
121
-table_direct direct_table[6];  // compiler will initialize to all zeros
122
-
123
-/**
124
- *  Prescale register and MR0 register values
125
- *
126
- *               100MHz PCLK          50MHz PCLK          25MHz PCLK         12.5MHz PCLK
127
- *             -----------------   -----------------   -----------------   -----------------
128
- *  desired    prescale  MR0       prescale  MR0       prescale  MR0       prescale  MR0        resolution
129
- *  prescale   register  register  register  register  register  register  register  register   in degrees
130
- *  freq       value     value     value     value     value     value     value     value
131
- *
132
- *      8        11.5    159,999      5.25   159,999       2.13  159,999    0.5625   159,999    0.023
133
- *      4        24       79,999     11.5     79,999       5.25   79,999    2.125     79,999    0.045
134
- *      2        49       39,999     24       39,999      11.5    39,999    5.25      39,999    0.090
135
- *      1        99       19,999     49       19,999      24      19,999   11.5       19,999    0.180
136
- *    0.5       199        9,999     99        9,999      49       9,999   24          9,999    0.360
137
- *   0.25       399        4,999    199        4,999      99       4,999   49          4,999    0.720
138
- *  0.125       799        2,499    399        2,499     199       2,499   99          2,499    1.440
139
- *
140
- *  The desired prescale frequency column comes from an input in the range of 544 - 2400 microseconds
141
- *  and the desire to just shift the input left or right as needed.
142
- *
143
- *  A resolution of 0.2 degrees seems reasonable so a prescale frequency output of 1MHz is being used.
144
- *  It also means we don't need to scale the input.
145
- *
146
- *  The PCLK is set to 25MHz because that's the slowest one that gives whole numbers for prescale and
147
- *  MR0 registers.
148
- *
149
- *  Final settings:
150
- *   PCLKSEL0: 0x0
151
- *   PWM1PR:   0x018 (24)
152
- *   PWM1MR0:  0x04E1F (19,999)
153
- *
154
- */
155
-
156
-void LPC1768_PWM_init(void) {
157
-
158
-  /////  directly controlled PWM pins (interrupts not used for these)
159
-
160
-  #define SBIT_CNTEN      0  // PWM1 counter & pre-scaler enable/disable
161
-  #define SBIT_CNTRST     1  // reset counters to known state
162
-  #define SBIT_PWMEN      3  // 1 - PWM, 0 - timer
163
-  #define SBIT_PWMMR0R    1
164
-  #define PCPWM1          6
165
-  #define PCLK_PWM1      12
166
-
167
-  SBI(LPC_SC->PCONP, PCPWM1);                                             // Enable PWM1 controller (enabled on power up)
168
-  LPC_SC->PCLKSEL0 &= ~(0x3 << PCLK_PWM1);
169
-  LPC_SC->PCLKSEL0 |= (LPC_PWM1_PCLKSEL0 << PCLK_PWM1);
170
-
171
-  uint32_t PR = (CLKPWR_GetPCLK(CLKPWR_PCLKSEL_PWM1) / 1000000) - 1;      // Prescalar to create 1 MHz output
172
-
173
-  LPC_PWM1->MR0  = LPC_PWM1_MR0;                                          // TC resets every 19,999 + 1 cycles - sets PWM cycle(Ton+Toff) to 20 mS
174
-  // MR0 must be set before TCR enables the PWM
175
-  LPC_PWM1->TCR  = _BV(SBIT_CNTEN) | _BV(SBIT_CNTRST) | _BV(SBIT_PWMEN);  // Enable counters, reset counters, set mode to PWM
176
-  CBI(LPC_PWM1->TCR, SBIT_CNTRST);                                        // Take counters out of reset
177
-  LPC_PWM1->PR   = PR;
178
-  LPC_PWM1->MCR  = _BV(SBIT_PWMMR0R) | _BV(0);                            // Reset TC if it matches MR0, disable all interrupts except for MR0
179
-  LPC_PWM1->CTCR = 0;                                                     // Disable counter mode (enable PWM mode)
180
-  LPC_PWM1->LER  = 0x07F;                                                 // Set the latch Enable Bits to load the new Match Values for MR0 - MR6
181
-  LPC_PWM1->PCR  = 0;                                                     // Single edge mode for all channels, PWM1 control of outputs off
182
-
183
-  ////  interrupt controlled PWM setup
184
-
185
-  LPC_SC->PCONP |= 1 << 23;  // power on timer3
186
-  HAL_PWM_TIMER->PR = PR;
187
-  HAL_PWM_TIMER->MCR = 0x0B;              // Interrupt on MR0 & MR1, reset on MR0
188
-  HAL_PWM_TIMER->MR0 = LPC_PWM1_MR0;
189
-  HAL_PWM_TIMER->MR1 = 0;
190
-  HAL_PWM_TIMER->TCR = _BV(0);       // enable
191
-  NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn);
192
-  NVIC_SetPriority(HAL_PWM_TIMER_IRQn, NVIC_EncodePriority(0, 4, 0));
193
-}
194
-
195
-
196
-bool ISR_table_update = false;  // flag to tell the ISR that the tables need to be updated & swapped
197
-uint8_t ISR_index = 0;          // index used by ISR to skip already actioned entries
198
-#define COPY_ACTIVE_TABLE    for (uint8_t i = 0; i < NUM_ISR_PWMS ; i++) work_table[i] = active_table[i]
199
-uint32_t first_MR1_value = LPC_PWM1_MR0 + 1;
200
-
201
-void LPC1768_PWM_sort(void) {
202
-
203
-  for (uint8_t i = NUM_ISR_PWMS; --i;) {  // (bubble) sort table by microseconds
204
-    bool didSwap = false;
205
-    PWM_map temp;
206
-    for (uint16_t j = 0; j < i; ++j) {
207
-      if (work_table[j].microseconds > work_table[j + 1].microseconds) {
208
-        temp = work_table[j + 1];
209
-        work_table[j + 1] = work_table[j];
210
-        work_table[j] = temp;
211
-        didSwap = true;
212
-      }
213
-    }
214
-    if (!didSwap) break;
215
-  }
216
-}
217
-
218
-bool LPC1768_PWM_attach_pin(pin_t pin, uint32_t min /* = 1 */, uint32_t max /* = (LPC_PWM1_MR0 - 1) */, uint8_t servo_index /* = 0xFF */) {
219
-
220
-  pin = GET_PIN_MAP_PIN(GET_PIN_MAP_INDEX(pin & 0xFF));  // Sometimes the upper byte is garbled
221
-
222
-////  direct control PWM code
223
-  switch (pin) {
224
-    case P1_23:                                       // MKS Sbase Servo 0, PWM1 channel 4  (J3-8 PWM1.4)
225
-      direct_table[P1_23_PWM_channel - 1].min = min;
226
-      direct_table[P1_23_PWM_channel - 1].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
227
-      direct_table[P1_23_PWM_channel - 1].assigned = true;
228
-      return true;
229
-    case P1_20:                                       // Servo 0, PWM1 channel 2  (Pin 11  P1.20 PWM1.2)
230
-      direct_table[P1_20_PWM_channel - 1].min = min;
231
-      direct_table[P1_20_PWM_channel - 1].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
232
-      direct_table[P1_20_PWM_channel - 1].assigned = true;
233
-      return true;
234
-    case P1_21:                                       // Servo 1, PWM1 channel 3  (Pin 6  P1.21 PWM1.3)
235
-      direct_table[P1_21_PWM_channel - 1].min = min;
236
-      direct_table[P1_21_PWM_channel - 1].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
237
-      direct_table[P1_21_PWM_channel - 1].assigned = true;
238
-      return true;
239
-    case P1_18:                                       // Servo 3, PWM1 channel 1 (Pin 4  P1.18 PWM1.1)
240
-      direct_table[P1_18_PWM_channel - 1].min = min;
241
-      direct_table[P1_18_PWM_channel - 1].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
242
-      direct_table[P1_18_PWM_channel - 1].assigned = true;
243
-      return true;
244
-    case P2_04:                                       // D9 FET, PWM1 channel 5  (Pin 9  P2_04 PWM1.5)
245
-      direct_table[P2_04_PWM_channel - 1].min = min;
246
-      direct_table[P2_04_PWM_channel - 1].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
247
-      direct_table[P2_04_PWM_channel - 1].assigned = true;
248
-      return true;
249
-    case P2_05:                                       // D10 FET, PWM1 channel 6 (Pin 10  P2_05 PWM1.6)
250
-      direct_table[P2_05_PWM_channel - 1].min = min;
251
-      direct_table[P2_05_PWM_channel - 1].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
252
-      direct_table[P2_05_PWM_channel - 1].assigned = true;
253
-      return true;
254
-  }
255
-
256
-////  interrupt controlled PWM code
257
-  NVIC_DisableIRQ(HAL_PWM_TIMER_IRQn);    // make it safe to update the active table
258
-                                 // OK to update the active table because the
259
-                                 // ISR doesn't use any of the changed items
260
-
261
-  // We NEED memory barriers to ensure Interrupts are actually disabled!
262
-  // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
263
-  __DSB();
264
-  __ISB();
265
-
266
-  if (ISR_table_update) //use work table if that's the newest
267
-    temp_table = work_table;
268
-  else
269
-    temp_table = active_table;
270
-
271
-  uint8_t slot = 0;
272
-  for (uint8_t i = 0; i < NUM_ISR_PWMS; i++)         // see if already in table
273
-    if (temp_table[i].pin == pin) {
274
-      NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn);  // re-enable PWM interrupts
275
-      return 1;
276
-    }
277
-
278
-  for (uint8_t i = 1; (i < NUM_ISR_PWMS + 1) && !slot; i++)         // find empty slot
279
-    if ( !(temp_table[i - 1].set_register)) { slot = i; break; }  // any item that can't be zero when active or just attached is OK
280
-
281
-  if (!slot) {
282
-    NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn);  // re-enable PWM interrupts
283
-    return 0;
284
-  }
285
-
286
-  slot--;  // turn it into array index
287
-
288
-  temp_table[slot].pin          = pin;     // init slot
289
-  temp_table[slot].set_register = &LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOSET;
290
-  temp_table[slot].clr_register = &LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOCLR;
291
-  temp_table[slot].write_mask   = LPC_PIN(LPC1768_PIN_PIN(pin));
292
-  temp_table[slot].min          = min;
293
-  temp_table[slot].max          = max;                // different max for ISR PWMs than for direct PWMs
294
-  temp_table[slot].servo_index  = servo_index;
295
-  temp_table[slot].active_flag  = false;
296
-
297
-  NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn);  // re-enable PWM interrupts
298
-
299
-  return 1;
300
-}
301
-
302
-
303
-bool LPC1768_PWM_detach_pin(pin_t pin) {
304
-
305
-  pin = GET_PIN_MAP_PIN(GET_PIN_MAP_INDEX(pin & 0xFF));
306
-
307
-////  direct control PWM code
308
-  switch (pin) {
309
-    case P1_23:                                       // MKS Sbase Servo 0, PWM1 channel 4  (J3-8 PWM1.4)
310
-      if (!direct_table[P1_23_PWM_channel - 1].assigned) return false;
311
-      CBI(LPC_PWM1->PCR, 8 + P1_23_PWM_channel);      // disable PWM1 module control of this pin
312
-      LPC_PINCON->PINSEL3 &= ~(0x3 <<  14);           // return pin to general purpose I/O
313
-      direct_table[P1_23_PWM_channel - 1].assigned = false;
314
-      return true;
315
-    case P1_20:                                       // Servo 0, PWM1 channel 2  (Pin 11  P1.20 PWM1.2)
316
-      if (!direct_table[P1_20_PWM_channel - 1].assigned) return false;
317
-      CBI(LPC_PWM1->PCR, 8 + P1_20_PWM_channel);      // disable PWM1 module control of this pin
318
-      LPC_PINCON->PINSEL3 &= ~(0x3 <<  8);            // return pin to general purpose I/O
319
-      direct_table[P1_20_PWM_channel - 1].assigned = false;
320
-      return true;
321
-    case P1_21:                                       // Servo 1, PWM1 channel 3  (Pin 6  P1.21 PWM1.3)
322
-      if (!direct_table[P1_21_PWM_channel - 1].assigned) return false;
323
-      CBI(LPC_PWM1->PCR, 8 + P1_21_PWM_channel);      // disable PWM1 module control of this pin
324
-      LPC_PINCON->PINSEL3 &= ~(0x3 << 10);            // return pin to general purpose I/O
325
-      direct_table[P1_21_PWM_channel - 1].assigned = false;
326
-      return true;
327
-    case P1_18:                                       // Servo 3, PWM1 channel 1 (Pin 4  P1.18 PWM1.1)
328
-      if (!direct_table[P1_18_PWM_channel - 1].assigned) return false;
329
-      CBI(LPC_PWM1->PCR, 8 + P1_18_PWM_channel);      // disable PWM1 module control of this pin
330
-      LPC_PINCON->PINSEL3 &= ~(0x3 <<  4);            // return pin to general purpose I/O
331
-      direct_table[P1_18_PWM_channel - 1].assigned = false;
332
-      return true;
333
-    case P2_04:                                       // D9 FET, PWM1 channel 5  (Pin 9  P2_04 PWM1.5)
334
-      if (!direct_table[P2_04_PWM_channel - 1].assigned) return false;
335
-      CBI(LPC_PWM1->PCR, 8 + P2_04_PWM_channel);      // disable PWM1 module control of this pin
336
-      LPC_PINCON->PINSEL4 &= ~(0x3 << 10);            // return pin to general purpose I/O
337
-      direct_table[P2_04_PWM_channel - 1].assigned = false;
338
-      return true;
339
-    case P2_05:                                       // D10 FET, PWM1 channel 6 (Pin 10  P2_05 PWM1.6)
340
-      if (!direct_table[P2_05_PWM_channel - 1].assigned) return false;
341
-      CBI(LPC_PWM1->PCR, 8 + P2_05_PWM_channel);      // disable PWM1 module control of this pin
342
-      LPC_PINCON->PINSEL4 &= ~(0x3 <<  4);            // return pin to general purpose I/O
343
-      direct_table[P2_05_PWM_channel - 1].assigned = false;
344
-      return true;
345
-  }
346
-
347
-////  interrupt controlled PWM code
348
-  NVIC_DisableIRQ(HAL_PWM_TIMER_IRQn);
349
-
350
-  // We NEED memory barriers to ensure Interrupts are actually disabled!
351
-  // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
352
-  __DSB();
353
-  __ISB();
354
-
355
-  if (ISR_table_update) {
356
-    ISR_table_update = false;    // don't update yet - have another update to do
357
-    NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn);  // re-enable PWM interrupts
358
-  }
359
-  else {
360
-    NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn);  // re-enable PWM interrupts
361
-    COPY_ACTIVE_TABLE;  // copy active table into work table
362
-  }
363
-
364
-  uint8_t slot = 0xFF;
365
-  for (uint8_t i = 0; i < NUM_ISR_PWMS; i++) {        // find slot
366
-    if (work_table[i].pin == pin) {
367
-      slot = i;
368
-      break;
369
-    }
370
-  }
371
-  if (slot == 0xFF)    // return error if pin not found
372
-    return false;
373
-
374
-  work_table[slot] = {0, 0, 0, 0, 0, 0, 0, 0, 0};
375
-
376
-  LPC1768_PWM_sort();    // sort table by microseconds
377
-  ISR_table_update = true;
378
-  return true;
379
-}
380
-
381
-// value is 0-20,000 microseconds (0% to 100% duty cycle)
382
-// servo routine provides values in the 544 - 2400 range
383
-bool LPC1768_PWM_write(pin_t pin, uint32_t value) {
384
-
385
-  pin = GET_PIN_MAP_PIN(GET_PIN_MAP_INDEX(pin & 0xFF));
386
-
387
-////  direct control PWM code
388
-  switch (pin) {
389
-    case P1_23:                                                           // MKS Sbase Servo 0, PWM1 channel 4  (J3-8 PWM1.4)
390
-      if (!direct_table[P1_23_PWM_channel - 1].assigned) return false;
391
-      LPC_PWM1->PCR |=  _BV(8 + P1_23_PWM_channel); // enable PWM1 module control of this pin
392
-      LPC_PINCON->PINSEL3 = 0x2 <<  14;             // must set pin function AFTER setting PCR
393
-      // load the new time value
394
-      LPC_PWM1->MR4 = MAX(MIN(value, direct_table[P1_23_PWM_channel - 1].max), direct_table[P1_23_PWM_channel - 1].min);
395
-      LPC_PWM1->LER = 0x1 << P1_23_PWM_channel; // Set the latch Enable Bit to load the new Match Value on the next MR0
396
-      return true;
397
-    case P1_20:                                                           // Servo 0, PWM1 channel 2 (Pin 11  P1.20 PWM1.2)
398
-      if (!direct_table[P1_20_PWM_channel - 1].assigned) return false;
399
-      LPC_PWM1->PCR |=  _BV(8 + P1_20_PWM_channel); // enable PWM1 module control of this pin
400
-      LPC_PINCON->PINSEL3 |= 0x2 <<  8;             // must set pin function AFTER setting PCR
401
-      // load the new time value
402
-      LPC_PWM1->MR2 = MAX(MIN(value, direct_table[P1_20_PWM_channel - 1].max), direct_table[P1_20_PWM_channel - 1].min);
403
-      LPC_PWM1->LER = 0x1 << P1_20_PWM_channel; // Set the latch Enable Bit to load the new Match Value on the next MR0
404
-      return true;
405
-    case P1_21:                                                           // Servo 1, PWM1 channel 3 (Pin 6  P1.21 PWM1.3)
406
-      if (!direct_table[P1_21_PWM_channel - 1].assigned) return false;
407
-      LPC_PWM1->PCR |=  _BV(8 + P1_21_PWM_channel); // enable PWM1 module control of this pin
408
-      LPC_PINCON->PINSEL3 |= 0x2 << 10;              // must set pin function AFTER setting PCR
409
-      // load the new time value
410
-      LPC_PWM1->MR3 = MAX(MIN(value, direct_table[P1_21_PWM_channel - 1].max), direct_table[P1_21_PWM_channel - 1].min);
411
-      LPC_PWM1->LER = 0x1 << P1_21_PWM_channel; // Set the latch Enable Bit to load the new Match Value on the next MR0
412
-      return true;
413
-    case P1_18:                                                           // Servo 3, PWM1 channel 1 (Pin 4  P1.18 PWM1.1)
414
-      if (!direct_table[P1_18_PWM_channel - 1].assigned) return false;
415
-      LPC_PWM1->PCR |=  _BV(8 + P1_18_PWM_channel); // enable PWM1 module control of this pin
416
-      LPC_PINCON->PINSEL3 |= 0x2 <<  4;             // must set pin function AFTER setting PCR
417
-      // load the new time value
418
-      LPC_PWM1->MR1 = MAX(MIN(value, direct_table[P1_18_PWM_channel - 1].max), direct_table[P1_18_PWM_channel - 1].min);
419
-      LPC_PWM1->LER = 0x1 << P1_18_PWM_channel; // Set the latch Enable Bit to load the new Match Value on the next MR0
420
-      return true;
421
-    case P2_04:                                                           // D9 FET, PWM1 channel 5 (Pin 9  P2_04 PWM1.5)
422
-      if (!direct_table[P2_04_PWM_channel - 1].assigned) return false;
423
-      LPC_PWM1->PCR |=  _BV(8 + P2_04_PWM_channel); // enable PWM1 module control of this pin
424
-      LPC_PINCON->PINSEL4 |= 0x1 <<  8;             // must set pin function AFTER setting PCR
425
-      // load the new time value
426
-      LPC_PWM1->MR5 = MAX(MIN(value, direct_table[P2_04_PWM_channel - 1].max), direct_table[P2_04_PWM_channel - 1].min);
427
-      LPC_PWM1->LER = 0x1 << P2_04_PWM_channel; // Set the latch Enable Bit to load the new Match Value on the next MR0
428
-      return true;
429
-    case P2_05:                                                           // D10 FET, PWM1 channel 6 (Pin 10  P2_05 PWM1.6)
430
-      if (!direct_table[P2_05_PWM_channel - 1].assigned) return false;
431
-      LPC_PWM1->PCR |=  _BV(8 + P2_05_PWM_channel); // enable PWM1 module control of this pin
432
-      LPC_PINCON->PINSEL4 |= 0x1 << 10;             // must set pin function AFTER setting PCR
433
-      // load the new time value
434
-      LPC_PWM1->MR6 = MAX(MIN(value, direct_table[P2_05_PWM_channel - 1].max), direct_table[P2_05_PWM_channel - 1].min);
435
-      LPC_PWM1->LER = 0x1 << P2_05_PWM_channel; // Set the latch Enable Bit to load the new Match Value on the next MR0
436
-      return true;
437
-  }
438
-
439
-////  interrupt controlled PWM code
440
-  NVIC_DisableIRQ(HAL_PWM_TIMER_IRQn);
441
-
442
-  // We NEED memory barriers to ensure Interrupts are actually disabled!
443
-  // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
444
-  __DSB();
445
-  __ISB();
446
-
447
-  if (!ISR_table_update)   // use the most up to date table
448
-    COPY_ACTIVE_TABLE;  // copy active table into work table
449
-
450
-  uint8_t slot = 0xFF;
451
-  for (uint8_t i = 0; i < NUM_ISR_PWMS; i++)         // find slot
452
-    if (work_table[i].pin == pin) { slot = i; break; }
453
-  if (slot == 0xFF) {   // return error if pin not found
454
-    NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn);
455
-    return false;
456
-  }
457
-
458
-  work_table[slot].microseconds = MAX(MIN(value, work_table[slot].max), work_table[slot].min);;
459
-  work_table[slot].active_flag  = true;
460
-
461
-  LPC1768_PWM_sort();    // sort table by microseconds
462
-  ISR_table_update = true;
463
-
464
-  NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn);  // re-enable PWM interrupts
465
-  return 1;
466
-}
467
-
468
-
469
-bool useable_hardware_PWM(pin_t pin) {
470
-
471
-  pin = GET_PIN_MAP_PIN(GET_PIN_MAP_INDEX(pin & 0xFF));
472
-
473
-  NVIC_DisableIRQ(HAL_PWM_TIMER_IRQn);
474
-
475
-  // We NEED memory barriers to ensure Interrupts are actually disabled!
476
-  // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
477
-  __DSB();
478
-  __ISB();
479
-
480
-  bool return_flag = false;
481
-  for (uint8_t i = 0; i < NUM_ISR_PWMS; i++)         // see if it's already setup
482
-    if (active_table[i].pin == pin) return_flag = true;
483
-  for (uint8_t i = 0; i < NUM_ISR_PWMS; i++)         // see if there is an empty slot
484
-    if (!active_table[i].set_register) return_flag = true;
485
-  NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn);  // re-enable PWM interrupts
486
-  return return_flag;
487
-}
488
-
489
-
490
-////////////////////////////////////////////////////////////////////////////////
491
-
492
-
493
-#define PWM_LPC1768_ISR_SAFETY_FACTOR 5  // amount of time needed to guarantee MR1 count will be above TC
494
-volatile bool in_PWM_isr = false;
495
-
496
-HAL_PWM_TIMER_ISR {
497
-  bool first_active_entry = true;
498
-  uint32_t next_MR1_val;
499
-
500
-  if (in_PWM_isr) goto exit_PWM_ISR;  // prevent re-entering this ISR
501
-  in_PWM_isr = true;
502
-
503
-  if (HAL_PWM_TIMER->IR & 0x01) {  // MR0 interrupt
504
-    next_MR1_val = first_MR1_value;               // only used if have a blank ISR table
505
-    if (ISR_table_update) {                       // new values have been loaded so swap tables
506
-      temp_table = active_table;
507
-      active_table = work_table;
508
-      work_table = temp_table;
509
-      ISR_table_update = false;
510
-    }
511
-  }
512
-  HAL_PWM_TIMER->IR = 0x3F;  // clear all interrupts
513
-
514
-  for (uint8_t i = 0; i < NUM_ISR_PWMS; i++) {
515
-    if (active_table[i].active_flag) {
516
-      if (first_active_entry) {
517
-        first_active_entry = false;
518
-        next_MR1_val = active_table[i].microseconds;
519
-      }
520
-      if (HAL_PWM_TIMER->TC < active_table[i].microseconds) {
521
-        *active_table[i].set_register = active_table[i].write_mask;   // set pin high
522
-      }
523
-      else {
524
-        *active_table[i].clr_register = active_table[i].write_mask;   // set pin low
525
-        next_MR1_val = (i == NUM_ISR_PWMS -1)
526
-          ? LPC_PWM1_MR0 + 1                  // done with table, wait for MR0
527
-          : active_table[i + 1].microseconds; // set next MR1 interrupt?
528
-      }
529
-    }
530
-  }
531
-  if (first_active_entry) next_MR1_val = LPC_PWM1_MR0 + 1;  // empty table so disable MR1 interrupt
532
-  HAL_PWM_TIMER->MR1 = MAX(next_MR1_val, HAL_PWM_TIMER->TC + PWM_LPC1768_ISR_SAFETY_FACTOR); // set next
533
-  in_PWM_isr = false;
534
-
535
-  exit_PWM_ISR:
536
-  return;
537
-}
538
-#endif
539
-
540
-
541
-/////////////////////////////////////////////////////////////////
542
-/////////////////  HARDWARE FIRMWARE INTERACTION ////////////////
543
-/////////////////////////////////////////////////////////////////
544
-
545
-/**
546
- *  There are two distinct systems used for PWMs:
547
- *    directly controlled pins
548
- *    ISR controlled pins.
549
- *
550
- *  The two systems are independent of each other.  The use the same counter frequency so there's no
551
- *  translation needed when setting the time values.  The init, attach, detach and write routines all
552
- *  start with the direct pin code which is followed by the ISR pin code.
553
- *
554
- *  The PMW1 module handles the directly controlled pins.  Each directly controlled pin is associated
555
- *  with a match register (MR1 - MR6).  When the associated MR equals the module's TIMER/COUNTER (TC)
556
- *  then the pins is set to low.  The MR0 register controls the repetition rate.  When the TC equals
557
- *  MR0 then the TC is reset and ALL directly controlled pins are set high.  The resulting pulse widths
558
- *  are almost immune to system loading and ISRs.  No PWM1 interrupts are used.
559
- *
560
- *  The ISR controlled pins use the TIMER/COUNTER, MR0 and MR1 registers from one timer.  MR0 controls
561
- *  period of the controls the repetition rate.  When the TC equals MR0 then the TC is reset and an
562
- *  interrupt is generated. When the TC equals MR1 then an interrupt is generated.
563
- *
564
- *  Each interrupt does the following:
565
- *    1) Swaps the tables if it's a MR0 interrupt and the swap flag is set.  It then clears the swap flag.
566
- *    2) Scans the entire ISR table (it's been sorted low to high time)
567
- *         a. If its the first active entry then it grabs the time as a tentative time for MR1
568
- *         b. If active and TC is less than the time then it sets the pin high
569
- *         c. If active and TC is more than the time it sets the pin high
570
- *         d. On every entry that sets a pin low it grabs the NEXT entry's time for use as the next MR1.
571
- *            This results in MR1 being set to the time in the first active entry that does NOT set a
572
- *            pin low.
573
- *         e. If it's setting the last entry's pin low then it sets MR1 to a value bigger than MR0
574
- *         f. If no value has been grabbed for the next MR1 then it's an empty table and MR1 is set to a
575
- *            value greater than MR0
576
- */

+ 0
- 79
Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.h Просмотреть файл

@@ -1,79 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (C) 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
- *
21
- */
22
-
23
-/**
24
- * The class Servo uses the PWM class to implement its functions
25
- *
26
- * All PWMs use the same repetition rate - 20mS because that's the normal servo rate
27
- */
28
-
29
-/**
30
- * This is a hybrid system.
31
- *
32
- * The PWM1 module is used to directly control the Servo 0, 1 & 3 pins.  This keeps
33
- * the pulse width jitter to under a microsecond.
34
- *
35
- * For all other pins the PWM1 module is used to generate interrupts.  The ISR
36
- * routine does the actual setting/clearing of pins.  The upside is that any pin can
37
- * have a PWM channel assigned to it.  The downside is that there is more pulse width
38
- * jitter. The jitter depends on what else is happening in the system and what ISRs
39
- * prempt the PWM ISR.  Writing to the SD card can add 20 microseconds to the pulse
40
- * width.
41
- */
42
-
43
-/**
44
- * The data structures are setup to minimize the computation done by the ISR which
45
- * minimizes ISR execution time.  Execution times are 2.2 - 3.7 microseconds.
46
- *
47
- * Two tables are used.  active_table is used by the ISR.  Changes to the table are
48
- * are done by copying the active_table into the work_table, updating the work_table
49
- * and then swapping the two tables.  Swapping is done by manipulating pointers.
50
- *
51
- * Immediately after the swap the ISR uses the work_table until the start of the
52
- * next 20mS cycle. During this transition the "work_table" is actually the table
53
- * that was being used before the swap.  The "active_table" contains the data that
54
- * will start being used at the start of the next 20mS period.  This keeps the pins
55
- * well behaved during the transition.
56
- *
57
- * The ISR's priority is set to the maximum otherwise other ISRs can cause considerable
58
- * jitter in the PWM high time.
59
- *
60
- * See the end of this file for details on the hardware/firmware interaction
61
- */
62
-
63
-#ifndef _LPC1768_PWM_H_
64
-#define _LPC1768_PWM_H_
65
-
66
-#include <pinmapping.h>
67
-#include <lpc17xx_clkpwr.h>
68
-
69
-#define LPC_PWM1_MR0 19999  // base repetition rate minus one count - 20mS
70
-#define LPC_PWM1_PCLKSEL0 CLKPWR_PCLKSEL_CCLK_DIV_4 // select clock divider for prescaler - defaults to 4 on power up
71
-#define MR0_MARGIN 200      // if channel value too close to MR0 the system locks up
72
-
73
-void LPC1768_PWM_init(void);
74
-bool LPC1768_PWM_attach_pin(pin_t pin, uint32_t min=1, uint32_t max=(LPC_PWM1_MR0 - (MR0_MARGIN)), uint8_t servo_index=0xFF);
75
-bool LPC1768_PWM_write(pin_t pin, uint32_t value);
76
-bool LPC1768_PWM_detach_pin(pin_t pin);
77
-bool useable_hardware_PWM(pin_t pin);
78
-
79
-#endif // _LPC1768_PWM_H_

+ 0
- 163
Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.cpp Просмотреть файл

@@ -1,163 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
- *
21
- */
22
-
23
-/**
24
- * Based on servo.cpp - Interrupt driven Servo library for Arduino using 16 bit
25
- * timers- Version 2  Copyright (c) 2009 Michael Margolis.  All right reserved.
26
- */
27
-
28
-/**
29
- * A servo is activated by creating an instance of the Servo class passing the desired pin to the attach() method.
30
- * The servos are pulsed in the background using the value most recently written using the write() method
31
- *
32
- * Note that analogWrite of PWM on pins associated with the timer are disabled when the first servo is attached.
33
- * Timers are seized as needed in groups of 12 servos - 24 servos use two timers, 48 servos will use four.
34
- *
35
- * The methods are:
36
- *
37
- * Servo - Class for manipulating servo motors connected to Arduino pins.
38
- *
39
- * attach(pin)           - Attach a servo motor to an i/o pin.
40
- * attach(pin, min, max) - Attach to a pin, setting min and max values in microseconds
41
- *                         Default min is 544, max is 2400
42
- *
43
- * write()               - Set the servo angle in degrees. (Invalid angles —over MIN_PULSE_WIDTH— are treated as µs.)
44
- * writeMicroseconds()   - Set the servo pulse width in microseconds.
45
- * move(pin, angle)      - Sequence of attach(pin), write(angle), safe_delay(servo_delay[servoIndex]).
46
- *                         With DEACTIVATE_SERVOS_AFTER_MOVE it detaches after servo_delay[servoIndex].
47
- * read()                - Get the last-written servo pulse width as an angle between 0 and 180.
48
- * readMicroseconds()    - Get the last-written servo pulse width in microseconds.
49
- * attached()            - Return true if a servo is attached.
50
- * detach()              - Stop an attached servo from pulsing its i/o pin.
51
- *
52
- */
53
-
54
-/**
55
- * The only time that this library wants physical movement is when a WRITE
56
- * command is issued.  Before that all the attach & detach activity is solely
57
- * within the data base.
58
- *
59
- * The PWM output is inactive until the first WRITE.  After that it stays active
60
- * unless DEACTIVATE_SERVOS_AFTER_MOVE is enabled and a MOVE command was issued.
61
- */
62
-
63
-#ifdef TARGET_LPC1768
64
-
65
-#include "../../inc/MarlinConfig.h"
66
-
67
-#if HAS_SERVOS
68
-
69
-  #include "LPC1768_PWM.h"
70
-  #include "LPC1768_Servo.h"
71
-  #include "servo_private.h"
72
-
73
-  ServoInfo_t servo_info[MAX_SERVOS];                  // static array of servo info structures
74
-  uint8_t ServoCount = 0;                              // the total number of attached servos
75
-
76
-  #define US_TO_PULSE_WIDTH(p) p
77
-  #define PULSE_WIDTH_TO_US(p) p
78
-  #define TRIM_DURATION 0
79
-  #define SERVO_MIN() MIN_PULSE_WIDTH  // minimum value in uS for this servo
80
-  #define SERVO_MAX() MAX_PULSE_WIDTH  // maximum value in uS for this servo
81
-
82
-  Servo::Servo() {
83
-    if (ServoCount < MAX_SERVOS) {
84
-      this->servoIndex = ServoCount++;                    // assign a servo index to this instance
85
-      servo_info[this->servoIndex].pulse_width = US_TO_PULSE_WIDTH(DEFAULT_PULSE_WIDTH);   // store default values  - 12 Aug 2009
86
-    }
87
-    else
88
-    this->servoIndex = INVALID_SERVO;  // too many servos
89
-  }
90
-
91
-  int8_t Servo::attach(const int pin) {
92
-    return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
93
-  }
94
-
95
-  int8_t Servo::attach(const int pin, const int min, const int max) {
96
-
97
-    if (this->servoIndex >= MAX_SERVOS) return -1;
98
-
99
-    if (pin > 0) servo_info[this->servoIndex].Pin.nbr = pin;  // only assign a pin value if the pin info is
100
-                                                              // greater than zero. This way the init routine can
101
-                                                              // assign the pin and the MOVE command only needs the value.
102
-
103
-    this->min = MIN_PULSE_WIDTH; //resolution of min/max is 1 uS
104
-    this->max = MAX_PULSE_WIDTH;
105
-
106
-    servo_info[this->servoIndex].Pin.isActive = true;
107
-
108
-    return this->servoIndex;
109
-  }
110
-
111
-  void Servo::detach() {
112
-    servo_info[this->servoIndex].Pin.isActive = false;
113
-  }
114
-
115
-  void Servo::write(int value) {
116
-    if (value < MIN_PULSE_WIDTH) { // treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds)
117
-      value = map(constrain(value, 0, 180), 0, 180, SERVO_MIN(), SERVO_MAX());
118
-        // odd - this sets zero degrees to 544 and 180 degrees to 2400 microseconds but the literature says
119
-        //          zero degrees should be 500 microseconds and 180 should be 2500
120
-    }
121
-    this->writeMicroseconds(value);
122
-  }
123
-
124
-  void Servo::writeMicroseconds(int value) {
125
-    // calculate and store the values for the given channel
126
-    byte channel = this->servoIndex;
127
-    if (channel < MAX_SERVOS) {  // ensure channel is valid
128
-      // ensure pulse width is valid
129
-      value = constrain(value, SERVO_MIN(), SERVO_MAX()) - (TRIM_DURATION);
130
-      value = US_TO_PULSE_WIDTH(value);  // convert to pulse_width after compensating for interrupt overhead - 12 Aug 2009
131
-
132
-      servo_info[channel].pulse_width = value;
133
-      LPC1768_PWM_attach_pin(servo_info[this->servoIndex].Pin.nbr, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH, this->servoIndex);
134
-      LPC1768_PWM_write(servo_info[this->servoIndex].Pin.nbr, value);
135
-
136
-    }
137
-  }
138
-
139
-  // return the value as degrees
140
-  int Servo::read() { return map(this->readMicroseconds() + 1, SERVO_MIN(), SERVO_MAX(), 0, 180); }
141
-
142
-  int Servo::readMicroseconds() {
143
-    return (this->servoIndex == INVALID_SERVO) ? 0 : PULSE_WIDTH_TO_US(servo_info[this->servoIndex].pulse_width) + TRIM_DURATION;
144
-  }
145
-
146
-  bool Servo::attached() { return servo_info[this->servoIndex].Pin.isActive; }
147
-
148
-  void Servo::move(const int value) {
149
-    constexpr uint16_t servo_delay[] = SERVO_DELAY;
150
-    static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
151
-    if (this->attach(0) >= 0) {    // notice the pin number is zero here
152
-      this->write(value);
153
-      safe_delay(servo_delay[this->servoIndex]);
154
-      #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
155
-        this->detach();
156
-        LPC1768_PWM_detach_pin(servo_info[this->servoIndex].Pin.nbr);  // shut down the PWM signal
157
-        LPC1768_PWM_attach_pin(servo_info[this->servoIndex].Pin.nbr, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH, this->servoIndex);  // make sure no one else steals the slot
158
-      #endif
159
-    }
160
-  }
161
-
162
-#endif // HAS_SERVOS
163
-#endif // TARGET_LPC1768

+ 0
- 62
Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.h Просмотреть файл

@@ -1,62 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (C) 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
- *
21
- */
22
-
23
-/**
24
- * The class Servo uses the PWM class to implement its functions
25
- *
26
- * The PWM1 module is only used to generate interrups at specified times. It
27
- * is NOT used to directly toggle pins. The ISR writes to the pin assigned to
28
- * that interrupt
29
- *
30
- * All PWMs use the same repetition rate - 20mS because that's the normal servo rate
31
- *
32
- */
33
-
34
-#ifndef LPC1768_SERVO_H
35
-#define LPC1768_SERVO_H
36
-
37
-#include <stdint.h>
38
-
39
-  class Servo {
40
-    public:
41
-      Servo();
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();
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(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
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
51
-      int readMicroseconds();            // returns current pulse width in microseconds for this servo (was read_us() in first release)
52
-      bool attached();                   // return true if this servo is attached, otherwise false
53
-
54
-    private:
55
-      uint8_t servoIndex;               // index into the channel data for this servo
56
-      int min;
57
-      int max;
58
-  };
59
-
60
-  #define HAL_SERVO_LIB Servo
61
-
62
-#endif // LPC1768_SERVO_H

+ 56
- 0
Marlin/src/HAL/HAL_LPC1768/MarlinSerial.cpp Просмотреть файл

@@ -0,0 +1,56 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+#ifdef TARGET_LPC1768
24
+
25
+#include "../../inc/MarlinConfigPre.h"
26
+#include "MarlinSerial.h"
27
+
28
+#if (defined(SERIAL_PORT) && SERIAL_PORT == 0) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 0)
29
+  MarlinSerial MSerial(LPC_UART0);
30
+  extern "C" void UART0_IRQHandler(void) {
31
+    MSerial.IRQHandler();
32
+  }
33
+#endif
34
+
35
+#if (defined(SERIAL_PORT) && SERIAL_PORT == 1) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 1)
36
+  MarlinSerial MSerial1((LPC_UART_TypeDef *) LPC_UART1);
37
+  extern "C" void UART1_IRQHandler(void) {
38
+    MSerial1.IRQHandler();
39
+  }
40
+#endif
41
+
42
+#if (defined(SERIAL_PORT) && SERIAL_PORT == 2) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 2)
43
+  MarlinSerial MSerial2(LPC_UART2);
44
+  extern "C" void UART2_IRQHandler(void) {
45
+    MSerial2.IRQHandler();
46
+  }
47
+#endif
48
+
49
+#if (defined(SERIAL_PORT) && SERIAL_PORT == 3) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 3)
50
+  MarlinSerial MSerial3(LPC_UART3);
51
+  extern "C" void UART3_IRQHandler(void) {
52
+    MSerial3.IRQHandler();
53
+  }
54
+#endif
55
+
56
+#endif // TARGET_LPC1768

+ 71
- 0
Marlin/src/HAL/HAL_LPC1768/MarlinSerial.h Просмотреть файл

@@ -0,0 +1,71 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+#ifndef MARLINSERIAL_H
24
+#define MARLINSERIAL_H
25
+#include <HardwareSerial.h>
26
+#include <WString.h>
27
+
28
+#include "../../inc/MarlinConfigPre.h"
29
+#if ENABLED(EMERGENCY_PARSER)
30
+  #include "../../feature/emergency_parser.h"
31
+#endif
32
+
33
+#ifndef SERIAL_PORT
34
+  #define SERIAL_PORT 0
35
+#endif
36
+
37
+#ifndef RX_BUFFER_SIZE
38
+  #define RX_BUFFER_SIZE 128
39
+#endif
40
+#ifndef TX_BUFFER_SIZE
41
+  #define TX_BUFFER_SIZE 32
42
+#endif
43
+
44
+class MarlinSerial : public HardwareSerial<RX_BUFFER_SIZE, TX_BUFFER_SIZE> {
45
+public:
46
+  MarlinSerial(LPC_UART_TypeDef *UARTx) :
47
+    HardwareSerial<RX_BUFFER_SIZE, TX_BUFFER_SIZE>(UARTx)
48
+    #if ENABLED(EMERGENCY_PARSER)
49
+       , emergency_state(EmergencyParser::State::EP_RESET)
50
+    #endif
51
+    {
52
+    }
53
+
54
+  #if ENABLED(EMERGENCY_PARSER)
55
+    bool recv_callback(const char c) override {
56
+      emergency_parser.update(emergency_state, c);
57
+      return true; // do not discard character
58
+    }
59
+  #endif
60
+
61
+  #if ENABLED(EMERGENCY_PARSER)
62
+    EmergencyParser::State emergency_state;
63
+  #endif
64
+};
65
+
66
+extern MarlinSerial MSerial;
67
+extern MarlinSerial MSerial1;
68
+extern MarlinSerial MSerial2;
69
+extern MarlinSerial MSerial3;
70
+
71
+#endif // MARLINSERIAL_H

+ 0
- 90
Marlin/src/HAL/HAL_LPC1768/SoftwareSPI.cpp Просмотреть файл

@@ -1,90 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016, 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
- *
21
- */
22
-
23
-/**
24
- * Software SPI functions originally from Arduino Sd2Card Library
25
- * Copyright (C) 2009 by William Greiman
26
- */
27
-
28
-/**
29
- * For TARGET_LPC1768
30
- */
31
-
32
-#ifdef TARGET_LPC1768
33
-
34
-#include "../../inc/MarlinConfig.h"
35
-
36
-// --------------------------------------------------------------------------
37
-// Software SPI
38
-// --------------------------------------------------------------------------
39
-
40
-/**
41
- * This software SPI runs at multiple rates. The SD software provides an index
42
- * (spiRate) of 0-6. The mapping is:
43
- *     0 - about 5 MHz peak (6 MHz on LPC1769)
44
- *     1-2 - about 2 MHz peak
45
- *     3 - about 1 MHz peak
46
- *     4 - about 500 kHz peak
47
- *     5 - about 250 kHz peak
48
- *     6 - about 125 kHz peak
49
- */
50
-
51
-uint8_t swSpiTransfer(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin) {
52
-  for (uint8_t i = 0; i < 8; i++) {
53
-    if (spi_speed == 0) {
54
-      WRITE(mosi_pin, !!(b & 0x80));
55
-      WRITE(sck_pin, HIGH);
56
-      b <<= 1;
57
-      if (miso_pin >= 0 && READ(miso_pin)) b |= 1;
58
-      WRITE(sck_pin, LOW);
59
-    }
60
-    else {
61
-      const uint8_t state = (b & 0x80) ? HIGH : LOW;
62
-      for (uint8_t j = 0; j < spi_speed; j++)
63
-        WRITE(mosi_pin, state);
64
-
65
-      for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); j++)
66
-        WRITE(sck_pin, HIGH);
67
-
68
-      b <<= 1;
69
-      if (miso_pin >= 0 && READ(miso_pin)) b |= 1;
70
-
71
-      for (uint8_t j = 0; j < spi_speed; j++)
72
-        WRITE(sck_pin, LOW);
73
-    }
74
-  }
75
-  return b;
76
-}
77
-
78
-void swSpiBegin(const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin) {
79
-  SET_OUTPUT(sck_pin);
80
-  if (VALID_PIN(miso_pin)) SET_INPUT(miso_pin);
81
-  SET_OUTPUT(mosi_pin);
82
-}
83
-
84
-uint8_t swSpiInit(const uint8_t spiRate, const pin_t sck_pin, const pin_t mosi_pin) {
85
-  WRITE(mosi_pin, HIGH);
86
-  WRITE(sck_pin, LOW);
87
-  return (SystemCoreClock == 120000000 ? 44 : 38) / POW(2, 6 - MIN(spiRate, 6));
88
-}
89
-
90
-#endif // TARGET_LPC1768

+ 0
- 50
Marlin/src/HAL/HAL_LPC1768/SoftwareSPI.h Просмотреть файл

@@ -1,50 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
- *
21
- */
22
-
23
-#ifndef _SOFTWARE_SPI_H_
24
-#define _SOFTWARE_SPI_H_
25
-
26
-#include <pinmapping.h>
27
-
28
-// --------------------------------------------------------------------------
29
-// Software SPI
30
-// --------------------------------------------------------------------------
31
-
32
-/**
33
- * This software SPI runs at multiple rates. The SD software provides an index
34
- * (spiRate) of 0-6. The mapping is:
35
- *     0 - about 5 MHz peak (6 MHz on LPC1769)
36
- *     1-2 - about 2 MHz peak
37
- *     3 - about 1 MHz peak
38
- *     4 - about 500 kHz peak
39
- *     5 - about 250 kHz peak
40
- *     6 - about 125 kHz peak
41
- */
42
-
43
-void swSpiBegin(const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin);
44
-
45
-// Returns the spi_speed value to be passed to swSpiTransfer
46
-uint8_t swSpiInit(const uint8_t spiRate, const pin_t sck_pin, const pin_t mosi_pin);
47
-
48
-uint8_t swSpiTransfer(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin);
49
-
50
-#endif // _SOFTWARE_SPI_H_

+ 0
- 162
Marlin/src/HAL/HAL_LPC1768/WInterrupts.cpp Просмотреть файл

@@ -1,162 +0,0 @@
1
-/**
2
- * Copyright (c) 2011-2012 Arduino.  All right reserved.
3
- *
4
- * This library is free software; you can redistribute it and/or
5
- * modify it under the terms of the GNU Lesser General Public
6
- * License as published by the Free Software Foundation; either
7
- * version 2.1 of the License, or (at your option) any later version.
8
- *
9
- * This library is distributed in the hope that it will be useful,
10
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
11
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
12
- * See the GNU Lesser General Public License for more details.
13
- *
14
- * You should have received a copy of the GNU Lesser General Public
15
- * License along with this library; if not, write to the Free Software
16
- * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
17
- */
18
-
19
-#ifdef TARGET_LPC1768
20
-
21
-#include "../../inc/MarlinConfig.h"
22
-
23
-#define GNUM 31
24
-
25
-typedef void (*interruptCB)(void);
26
-
27
-static interruptCB callbacksP0[GNUM] = {};
28
-static interruptCB callbacksP2[GNUM] = {};
29
-
30
-extern "C" void GpioEnableInt(const uint32_t port, const uint32_t pin, const uint32_t mode);
31
-extern "C" void GpioDisableInt(const uint32_t port, const uint32_t pin);
32
-
33
-
34
-static void __initialize() {
35
-  NVIC_SetPriority(EINT3_IRQn, NVIC_EncodePriority(0, 1, 0));
36
-  NVIC_EnableIRQ(EINT3_IRQn);
37
-}
38
-
39
-void attachInterrupt(const pin_t pin, void (*callback)(void), uint32_t mode) {
40
-  static int enabled = 0;
41
-
42
-  if (!INTERRUPT_PIN(pin)) return;
43
-
44
-  if (!enabled) {
45
-    __initialize();
46
-    ++enabled;
47
-  }
48
-
49
-  uint8_t myport = LPC1768_PIN_PORT(pin),
50
-          mypin = LPC1768_PIN_PIN(pin);
51
-
52
-  if (myport == 0)
53
-    callbacksP0[mypin] = callback;
54
-  else
55
-    callbacksP2[mypin] = callback;
56
-
57
-  // Enable interrupt
58
-  GpioEnableInt(myport,mypin,mode);
59
-}
60
-
61
-void detachInterrupt(const pin_t pin) {
62
-  if (!INTERRUPT_PIN(pin)) return;
63
-
64
-  const uint8_t myport = LPC1768_PIN_PORT(pin),
65
-                mypin = LPC1768_PIN_PIN(pin);
66
-
67
-  // Disable interrupt
68
-  GpioDisableInt(myport, mypin);
69
-
70
-  // unset callback
71
-  if (myport == 0)
72
-    callbacksP0[mypin] = 0;
73
-  else //if (myport == 2 )
74
-    callbacksP2[mypin] = 0;
75
-}
76
-
77
-
78
-extern "C" void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode) {
79
-  //pin here is the processor pin, not logical pin
80
-  if (port == 0) {
81
-    LPC_GPIOINT->IO0IntClr = _BV(pin);
82
-    if (mode == RISING) {
83
-      SBI(LPC_GPIOINT->IO0IntEnR, pin);
84
-      CBI(LPC_GPIOINT->IO0IntEnF, pin);
85
-    }
86
-    else if (mode == FALLING) {
87
-      SBI(LPC_GPIOINT->IO0IntEnF, pin);
88
-      CBI(LPC_GPIOINT->IO0IntEnR, pin);
89
-    }
90
-    else if (mode == CHANGE) {
91
-      SBI(LPC_GPIOINT->IO0IntEnR, pin);
92
-      SBI(LPC_GPIOINT->IO0IntEnF, pin);
93
-    }
94
-  }
95
-  else {
96
-    LPC_GPIOINT->IO2IntClr = _BV(pin);
97
-    if (mode == RISING) {
98
-      SBI(LPC_GPIOINT->IO2IntEnR, pin);
99
-      CBI(LPC_GPIOINT->IO2IntEnF, pin);
100
-    }
101
-    else if (mode == FALLING) {
102
-      SBI(LPC_GPIOINT->IO2IntEnF, pin);
103
-      CBI(LPC_GPIOINT->IO2IntEnR, pin);
104
-    }
105
-    else if (mode == CHANGE) {
106
-      SBI(LPC_GPIOINT->IO2IntEnR, pin);
107
-      SBI(LPC_GPIOINT->IO2IntEnF, pin);
108
-    }
109
-  }
110
-}
111
-
112
-extern "C" void GpioDisableInt(const uint32_t port, const uint32_t pin) {
113
-  if (port == 0) {
114
-    CBI(LPC_GPIOINT->IO0IntEnR, pin);
115
-    CBI(LPC_GPIOINT->IO0IntEnF, pin);
116
-    LPC_GPIOINT->IO0IntClr = _BV(pin);
117
-  }
118
-  else {
119
-    CBI(LPC_GPIOINT->IO2IntEnR, pin);
120
-    CBI(LPC_GPIOINT->IO2IntEnF, pin);
121
-    LPC_GPIOINT->IO2IntClr = _BV(pin);
122
-  }
123
-}
124
-
125
-extern "C" void EINT3_IRQHandler(void) {
126
-  // Read in all current interrupt registers. We do this once as the
127
-  // GPIO interrupt registers are on the APB bus, and this is slow.
128
-  uint32_t rise0 = LPC_GPIOINT->IO0IntStatR,
129
-           fall0 = LPC_GPIOINT->IO0IntStatF,
130
-           rise2 = LPC_GPIOINT->IO2IntStatR,
131
-           fall2 = LPC_GPIOINT->IO2IntStatF;
132
-
133
-  // Clear the interrupts ASAP
134
-  LPC_GPIOINT->IO0IntClr = LPC_GPIOINT->IO2IntClr = 0xFFFFFFFF;
135
-  NVIC_ClearPendingIRQ(EINT3_IRQn);
136
-
137
-  while (rise0 > 0) {                                       // If multiple pins changes happened continue as long as there are interrupts pending
138
-    const uint8_t bitloc = 31 - __CLZ(rise0);               // CLZ returns number of leading zeros, 31 minus that is location of first pending interrupt
139
-    if (callbacksP0[bitloc] != NULL) callbacksP0[bitloc]();
140
-    rise0 -= _BV(bitloc);
141
-  }
142
-
143
-  while (fall0 > 0) {
144
-    const uint8_t bitloc = 31 - __CLZ(fall0);
145
-    if (callbacksP0[bitloc] != NULL) callbacksP0[bitloc]();
146
-    fall0 -= _BV(bitloc);
147
-  }
148
-
149
-  while(rise2 > 0) {
150
-    const uint8_t bitloc = 31 - __CLZ(rise2);
151
-    if (callbacksP2[bitloc] != NULL) callbacksP2[bitloc]();
152
-    rise2 -= _BV(bitloc);
153
-  }
154
-
155
-  while (fall2 > 0) {
156
-    const uint8_t bitloc = 31 - __CLZ(fall2);
157
-    if (callbacksP2[bitloc] != NULL) callbacksP2[bitloc]();
158
-    fall2 -= _BV(bitloc);
159
-  }
160
-}
161
-
162
-#endif // TARGET_LPC1768

+ 0
- 179
Marlin/src/HAL/HAL_LPC1768/arduino.cpp Просмотреть файл

@@ -1,179 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
- *
21
- */
22
-
23
-#ifdef TARGET_LPC1768
24
-
25
-#include "LPC1768_PWM.h"
26
-#include <lpc17xx_pinsel.h>
27
-
28
-#include "../../inc/MarlinConfig.h"
29
-#include "../shared/Delay.h"
30
-
31
-// Interrupts
32
-void cli(void) { __disable_irq(); } // Disable
33
-void sei(void) { __enable_irq(); }  // Enable
34
-
35
-// Time functions
36
-void _delay_ms(const int delay_ms) {
37
-  delay(delay_ms);
38
-}
39
-
40
-uint32_t millis() {
41
-  return _millis;
42
-}
43
-
44
-// This is required for some Arduino libraries we are using
45
-void delayMicroseconds(uint32_t us) {
46
-  DELAY_US(us);
47
-}
48
-
49
-extern "C" void delay(const int msec) {
50
-  volatile millis_t end = _millis + msec;
51
-  SysTick->VAL = SysTick->LOAD; // reset systick counter so next systick is in exactly 1ms
52
-                                // this could extend the time between systicks by upto 1ms
53
-  while PENDING(_millis, end) __WFE();
54
-}
55
-
56
-// IO functions
57
-// As defined by Arduino INPUT(0x0), OUTPUT(0x1), INPUT_PULLUP(0x2)
58
-void pinMode(const pin_t pin, const uint8_t mode) {
59
-  if (!VALID_PIN(pin)) return;
60
-
61
-  PINSEL_CFG_Type config = { LPC1768_PIN_PORT(pin),
62
-                             LPC1768_PIN_PIN(pin),
63
-                             PINSEL_FUNC_0,
64
-                             PINSEL_PINMODE_TRISTATE,
65
-                             PINSEL_PINMODE_NORMAL };
66
-  switch (mode) {
67
-    case INPUT:
68
-      LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
69
-      break;
70
-    case OUTPUT:
71
-      LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR |=  LPC_PIN(LPC1768_PIN_PIN(pin));
72
-      break;
73
-    case INPUT_PULLUP:
74
-      LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
75
-      config.Pinmode = PINSEL_PINMODE_PULLUP;
76
-      break;
77
-    case INPUT_PULLDOWN:
78
-      LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
79
-      config.Pinmode = PINSEL_PINMODE_PULLDOWN;
80
-      break;
81
-    default: return;
82
-  }
83
-  PINSEL_ConfigPin(&config);
84
-}
85
-
86
-void digitalWrite(pin_t pin, uint8_t pin_status) {
87
-  if (!VALID_PIN(pin)) return;
88
-
89
-  if (pin_status)
90
-    LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOSET = LPC_PIN(LPC1768_PIN_PIN(pin));
91
-  else
92
-    LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOCLR = LPC_PIN(LPC1768_PIN_PIN(pin));
93
-
94
-  pinMode(pin, OUTPUT);  // Set pin mode on every write (Arduino version does this)
95
-
96
-  /**
97
-   * Must be done AFTER the output state is set. Doing this before will cause a
98
-   * 2uS glitch if writing a "1".
99
-   *
100
-   * When the Port Direction bit is written to a "1" the output is immediately set
101
-   * to the value of the FIOPIN bit which is "0" because of power up defaults.
102
-   */
103
-}
104
-
105
-bool digitalRead(pin_t pin) {
106
-  if (!VALID_PIN(pin)) return false;
107
-
108
-  return LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOPIN & LPC_PIN(LPC1768_PIN_PIN(pin)) ? 1 : 0;
109
-}
110
-
111
-void analogWrite(pin_t pin, int pwm_value) {  // 1 - 254: pwm_value, 0: LOW, 255: HIGH
112
-  if (!VALID_PIN(pin)) return;
113
-
114
-  #define MR0_MARGIN 200       // if channel value too close to MR0 the system locks up
115
-
116
-  static bool out_of_PWM_slots = false;
117
-
118
-  uint value = MAX(MIN(pwm_value, 255), 0);
119
-  if (value == 0 || value == 255) {  // treat as digital pin
120
-    LPC1768_PWM_detach_pin(pin);    // turn off PWM
121
-    digitalWrite(pin, value);
122
-  }
123
-  else {
124
-    if (LPC1768_PWM_attach_pin(pin, 1, LPC_PWM1->MR0, 0xFF))
125
-      LPC1768_PWM_write(pin, map(value, 0, 255, 1, LPC_PWM1->MR0));  // map 1-254 onto PWM range
126
-    else {                                                                 // out of PWM channels
127
-      if (!out_of_PWM_slots) SERIAL_ECHOPGM(".\nWARNING - OUT OF PWM CHANNELS\n.\n");  //only warn once
128
-      out_of_PWM_slots = true;
129
-      digitalWrite(pin, value);  // treat as a digital pin if out of channels
130
-    }
131
-  }
132
-}
133
-
134
-extern bool HAL_adc_finished();
135
-
136
-uint16_t analogRead(pin_t adc_pin) {
137
-  HAL_adc_start_conversion(adc_pin);
138
-  while (!HAL_adc_finished());  // Wait for conversion to finish
139
-  return HAL_adc_get_result();
140
-}
141
-
142
-// **************************
143
-// Persistent Config Storage
144
-// **************************
145
-
146
-void eeprom_write_byte(uint8_t *pos, unsigned char value) {
147
-
148
-}
149
-
150
-uint8_t eeprom_read_byte(uint8_t * pos) { return '\0'; }
151
-
152
-void eeprom_read_block(void *__dst, const void *__src, size_t __n) { }
153
-
154
-void eeprom_update_block(const void *__src, void *__dst, size_t __n) { }
155
-
156
-char *dtostrf (double __val, signed char __width, unsigned char __prec, char *__s) {
157
-  char format_string[20];
158
-  snprintf(format_string, 20, "%%%d.%df", __width, __prec);
159
-  sprintf(__s, format_string, __val);
160
-  return __s;
161
-}
162
-
163
-int32_t random(int32_t max) {
164
-  return rand() % max;
165
-}
166
-
167
-int32_t random(int32_t min, int32_t max) {
168
-  return min + rand() % (max - min);
169
-}
170
-
171
-void randomSeed(uint32_t value) {
172
-  srand(value);
173
-}
174
-
175
-int map(uint16_t x, uint16_t in_min, uint16_t in_max, uint16_t out_min, uint16_t out_max) {
176
-  return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
177
-}
178
-
179
-#endif // TARGET_LPC1768

+ 0
- 21
Marlin/src/HAL/HAL_LPC1768/debug_extra_script.py Просмотреть файл

@@ -1,21 +0,0 @@
1
-Import("env")
2
-
3
-env.AddPostAction(
4
-    "$BUILD_DIR/firmware.hex",
5
-    env.VerboseAction(" ".join([
6
-        "sed", "-i.bak",
7
-        "s/:10040000FFFFFFFFFFFFFFFFFFFFFFFFDEF9FFFF23/:10040000FFFFFFFFFFFFFFFFFFFFFFFFFEFFFFFFFD/",
8
-        "$BUILD_DIR/firmware.hex"
9
-    ]), "Fixing $BUILD_DIR/firmware.hex secure flash flags"))
10
-env.AddPreAction(
11
-    "upload",
12
-     env.VerboseAction(" ".join([
13
-         "echo",
14
-         "'h\\nloadfile $BUILD_DIR/firmware.hex\\nr\\nq\\n'",
15
-         ">$BUILD_DIR/aux.jlink"
16
-     ]), "Creating auxiliary files"))
17
-
18
-env.Replace(
19
-    UPLOADHEXCMD=
20
-    'JLinkExe -device MK20DX256xxx7 -speed 4000 -if swd -autoconnect 1 -CommanderScript $BUILD_DIR/aux.jlink -SkipProgOnCRCMatch = 1 -VerifyDownload = 1'
21
-)

+ 11
- 15
Marlin/src/HAL/HAL_LPC1768/fastio.h Просмотреть файл

@@ -35,27 +35,23 @@
35 35
 #ifndef _FASTIO_LPC1768_H
36 36
 #define _FASTIO_LPC1768_H
37 37
 
38
-#include <LPC17xx.h>
39 38
 #include <Arduino.h>
40
-#include <pinmapping.h>
41 39
 
42
-bool useable_hardware_PWM(pin_t pin);
43 40
 #define USEABLE_HARDWARE_PWM(pin) useable_hardware_PWM(pin)
44 41
 
45
-#define LPC_PORT_OFFSET         (0x0020)
46
-#define LPC_PIN(pin)            (1UL << pin)
47
-#define LPC_GPIO(port)          ((volatile LPC_GPIO_TypeDef *)(LPC_GPIO0_BASE + LPC_PORT_OFFSET * port))
42
+#define LPC_PIN(pin)            (gpio_pin(pin))
43
+#define LPC_GPIO(port)          (gpio_port(port))
48 44
 
49
-#define SET_DIR_INPUT(IO)       (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(IO)))
50
-#define SET_DIR_OUTPUT(IO)      (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIODIR |=  LPC_PIN(LPC1768_PIN_PIN(IO)))
45
+#define SET_DIR_INPUT(IO)       (gpio_set_input(IO))
46
+#define SET_DIR_OUTPUT(IO)      (gpio_set_output(IO))
51 47
 
52
-#define SET_MODE(IO, mode)      (pin_mode((LPC1768_PIN_PORT(IO), LPC1768_PIN_PIN(IO)), mode))
48
+#define SET_MODE(IO, mode)      (pinMode(IO, mode))
53 49
 
54
-#define WRITE_PIN_SET(IO)       (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIOSET = LPC_PIN(LPC1768_PIN_PIN(IO)))
55
-#define WRITE_PIN_CLR(IO)       (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIOCLR = LPC_PIN(LPC1768_PIN_PIN(IO)))
50
+#define WRITE_PIN_SET(IO)       (gpio_set(IO))
51
+#define WRITE_PIN_CLR(IO)       (gpio_clear(IO))
56 52
 
57
-#define READ_PIN(IO)            ((LPC_GPIO(LPC1768_PIN_PORT(IO))->FIOPIN & LPC_PIN(LPC1768_PIN_PIN(IO))) ? 1 : 0)
58
-#define WRITE_PIN(IO,V)         ((V) ? WRITE_PIN_SET(IO) : WRITE_PIN_CLR(IO))
53
+#define READ_PIN(IO)            (gpio_get(IO))
54
+#define WRITE_PIN(IO,V)         (gpio_set(IO, V))
59 55
 
60 56
 /**
61 57
  * Magic I/O routines
@@ -89,10 +85,10 @@ bool useable_hardware_PWM(pin_t pin);
89 85
 #define _PULLDOWN(IO,V)   pinMode(IO, (V) ? INPUT_PULLDOWN : INPUT)
90 86
 
91 87
 /// check if pin is an input
92
-#define _GET_INPUT(IO)    (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIODIR & LPC_PIN(LPC1768_PIN_PIN(IO)) != 0)
88
+#define _GET_INPUT(IO)    (!gpio_get_dir(IO))
93 89
 
94 90
 /// check if pin is an output
95
-#define _GET_OUTPUT(IO)   (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIODIR & LPC_PIN(LPC1768_PIN_PIN(IO)) == 0)
91
+#define _GET_OUTPUT(IO)   (gpio_get_dir(IO))
96 92
 
97 93
 /// check if pin is a timer
98 94
 /// all gpio pins are pwm capable, either interrupt or hardware pwm controlled

+ 0
- 125
Marlin/src/HAL/HAL_LPC1768/include/Arduino.h Просмотреть файл

@@ -1,125 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
- *
21
- */
22
-
23
-#ifndef __ARDUINO_H__
24
-#define __ARDUINO_H__
25
-#include <stddef.h>
26
-#include <stdint.h>
27
-#include <math.h>
28
-
29
-#include <pinmapping.h>
30
-
31
-#define HIGH         0x01
32
-#define LOW          0x00
33
-
34
-#define INPUT          0x00
35
-#define OUTPUT         0x01
36
-#define INPUT_PULLUP   0x02
37
-#define INPUT_PULLDOWN 0x03
38
-
39
-#define LSBFIRST     0
40
-#define MSBFIRST     1
41
-
42
-#define CHANGE       0x02
43
-#define FALLING      0x03
44
-#define RISING       0x04
45
-
46
-typedef uint8_t byte;
47
-#define PROGMEM
48
-#define PSTR(v) (v)
49
-#define PGM_P const char *
50
-
51
-// Used for libraries, preprocessor, and constants
52
-#define min(a,b) ((a)<(b)?(a):(b))
53
-#define max(a,b) ((a)>(b)?(a):(b))
54
-#define abs(x) ((x)>0?(x):-(x))
55
-
56
-#ifndef isnan
57
-  #define isnan std::isnan
58
-#endif
59
-#ifndef isinf
60
-  #define isinf std::isinf
61
-#endif
62
-
63
-#define sq(v) ((v) * (v))
64
-#define square(v) sq(v)
65
-#define constrain(value, arg_min, arg_max) ((value) < (arg_min) ? (arg_min) :((value) > (arg_max) ? (arg_max) : (value)))
66
-
67
-//Interrupts
68
-void cli(void); // Disable
69
-void sei(void); // Enable
70
-void attachInterrupt(const pin_t pin, void (*callback)(void), uint32_t mode);
71
-void detachInterrupt(const pin_t pin);
72
-extern "C" void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode);
73
-extern "C" void GpioDisableInt(uint32_t port, uint32_t pin);
74
-
75
-// Program Memory
76
-#define pgm_read_ptr(addr)        (*((void**)(addr)))
77
-#define pgm_read_byte_near(addr)  (*((uint8_t*)(addr)))
78
-#define pgm_read_float_near(addr) (*((float*)(addr)))
79
-#define pgm_read_word_near(addr)  (*((uint16_t*)(addr)))
80
-#define pgm_read_dword_near(addr) (*((uint32_t*)(addr)))
81
-#define pgm_read_byte(addr)       pgm_read_byte_near(addr)
82
-#define pgm_read_float(addr)      pgm_read_float_near(addr)
83
-#define pgm_read_word(addr)       pgm_read_word_near(addr)
84
-#define pgm_read_dword(addr)      pgm_read_dword_near(addr)
85
-
86
-#define memcpy_P memcpy
87
-#define sprintf_P sprintf
88
-#define strstr_P strstr
89
-#define strncpy_P strncpy
90
-#define vsnprintf_P vsnprintf
91
-#define strcpy_P strcpy
92
-#define snprintf_P snprintf
93
-#define strlen_P strlen
94
-#define strchr_P strchr
95
-
96
-// Time functions
97
-extern "C" {
98
-  void delay(const int milis);
99
-}
100
-void _delay_ms(const int delay);
101
-void delayMicroseconds(unsigned long);
102
-uint32_t millis();
103
-
104
-//IO functions
105
-void pinMode(const pin_t, const uint8_t);
106
-void digitalWrite(pin_t, uint8_t);
107
-bool digitalRead(pin_t);
108
-void analogWrite(pin_t, int);
109
-uint16_t analogRead(pin_t);
110
-
111
-// EEPROM
112
-void eeprom_write_byte(uint8_t *pos, unsigned char value);
113
-uint8_t eeprom_read_byte(uint8_t *pos);
114
-void eeprom_read_block (void *__dst, const void *__src, size_t __n);
115
-void eeprom_update_block (const void *__src, void *__dst, size_t __n);
116
-
117
-int32_t random(int32_t);
118
-int32_t random(int32_t, int32_t);
119
-void randomSeed(uint32_t);
120
-
121
-char *dtostrf (double __val, signed char __width, unsigned char __prec, char *__s);
122
-
123
-int map(uint16_t x, uint16_t in_min, uint16_t in_max, uint16_t out_min, uint16_t out_max);
124
-
125
-#endif // __ARDUINO_DEF_H__

+ 0
- 335
Marlin/src/HAL/HAL_LPC1768/include/HardwareSerial.cpp Просмотреть файл

@@ -1,335 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
- *
21
- */
22
-
23
-#ifdef TARGET_LPC1768
24
-
25
-#include "HardwareSerial.h"
26
-
27
-#if SERIAL_PORT == 0 || SERIAL_PORT_2 == 0
28
-  HardwareSerial Serial = HardwareSerial(LPC_UART0);
29
-#elif SERIAL_PORT == 1 || SERIAL_PORT_2 == 1
30
-  HardwareSerial Serial1 = HardwareSerial((LPC_UART_TypeDef *) LPC_UART1);
31
-#elif SERIAL_PORT == 2 || SERIAL_PORT_2 == 2
32
-  HardwareSerial Serial2 = HardwareSerial(LPC_UART2);
33
-#elif SERIAL_PORT == 3 || SERIAL_PORT_2 == 3
34
-  HardwareSerial Serial3 = HardwareSerial(LPC_UART3);
35
-#endif
36
-
37
-void HardwareSerial::begin(uint32_t baudrate) {
38
-
39
-  UART_CFG_Type UARTConfigStruct;
40
-  PINSEL_CFG_Type PinCfg;
41
-  UART_FIFO_CFG_Type FIFOConfig;
42
-
43
-  if (Baudrate == baudrate) return; // No need to re-initialize
44
-
45
-  if (UARTx == LPC_UART0) {
46
-    // Initialize UART0 pin connect
47
-    PinCfg.Funcnum = 1;
48
-    PinCfg.OpenDrain = 0;
49
-    PinCfg.Pinmode = 0;
50
-    PinCfg.Pinnum = 2;
51
-    PinCfg.Portnum = 0;
52
-    PINSEL_ConfigPin(&PinCfg);
53
-    PinCfg.Pinnum = 3;
54
-    PINSEL_ConfigPin(&PinCfg);
55
-  } else if ((LPC_UART1_TypeDef *) UARTx == LPC_UART1) {
56
-    // Initialize UART1 pin connect
57
-    PinCfg.Funcnum = 1;
58
-    PinCfg.OpenDrain = 0;
59
-    PinCfg.Pinmode = 0;
60
-    PinCfg.Pinnum = 15;
61
-    PinCfg.Portnum = 0;
62
-    PINSEL_ConfigPin(&PinCfg);
63
-    PinCfg.Pinnum = 16;
64
-    PINSEL_ConfigPin(&PinCfg);
65
-  } else if (UARTx == LPC_UART2) {
66
-    // Initialize UART2 pin connect
67
-    PinCfg.Funcnum = 1;
68
-    PinCfg.OpenDrain = 0;
69
-    PinCfg.Pinmode = 0;
70
-    PinCfg.Pinnum = 10;
71
-    PinCfg.Portnum = 0;
72
-    PINSEL_ConfigPin(&PinCfg);
73
-    PinCfg.Pinnum = 11;
74
-    PINSEL_ConfigPin(&PinCfg);
75
-  } else if (UARTx == LPC_UART3) {
76
-    // Initialize UART2 pin connect
77
-    PinCfg.Funcnum = 1;
78
-    PinCfg.OpenDrain = 0;
79
-    PinCfg.Pinmode = 0;
80
-    PinCfg.Pinnum = 0;
81
-    PinCfg.Portnum = 0;
82
-    PINSEL_ConfigPin(&PinCfg);
83
-    PinCfg.Pinnum = 1;
84
-    PINSEL_ConfigPin(&PinCfg);
85
-  }
86
-
87
-  /* Initialize UART Configuration parameter structure to default state:
88
-   * Baudrate = 9600bps
89
-   * 8 data bit
90
-   * 1 Stop bit
91
-   * None parity
92
-   */
93
-  UART_ConfigStructInit(&UARTConfigStruct);
94
-
95
-  // Re-configure baudrate
96
-  UARTConfigStruct.Baud_rate = baudrate;
97
-
98
-  // Initialize eripheral with given to corresponding parameter
99
-  UART_Init(UARTx, &UARTConfigStruct);
100
-
101
-  // Enable and reset the TX and RX FIFOs
102
-  UART_FIFOConfigStructInit(&FIFOConfig);
103
-  UART_FIFOConfig(UARTx, &FIFOConfig);
104
-
105
-  // Enable UART Transmit
106
-  UART_TxCmd(UARTx, ENABLE);
107
-
108
-  // Configure Interrupts
109
-  UART_IntConfig(UARTx, UART_INTCFG_RBR, ENABLE);
110
-  UART_IntConfig(UARTx, UART_INTCFG_RLS, ENABLE);
111
-
112
-  // Set proper priority and enable interrupts
113
-  if (UARTx == LPC_UART0) {
114
-    NVIC_SetPriority(UART0_IRQn, NVIC_EncodePriority(0, 3, 0));
115
-    NVIC_EnableIRQ(UART0_IRQn);
116
-  }
117
-  else if ((LPC_UART1_TypeDef *) UARTx == LPC_UART1) {
118
-    NVIC_SetPriority(UART1_IRQn, NVIC_EncodePriority(0, 3, 0));
119
-   NVIC_EnableIRQ(UART1_IRQn);
120
-  }
121
-  else if (UARTx == LPC_UART2) {
122
-    NVIC_SetPriority(UART2_IRQn, NVIC_EncodePriority(0, 3, 0));
123
-    NVIC_EnableIRQ(UART2_IRQn);
124
-  }
125
-  else if (UARTx == LPC_UART3) {
126
-    NVIC_SetPriority(UART3_IRQn, NVIC_EncodePriority(0, 3, 0));
127
-    NVIC_EnableIRQ(UART3_IRQn);
128
-  }
129
-
130
-  RxQueueWritePos = RxQueueReadPos = 0;
131
-  #if TX_BUFFER_SIZE > 0
132
-    TxQueueWritePos = TxQueueReadPos = 0;
133
-  #endif
134
-
135
-  // Save the configured baudrate
136
-  Baudrate = baudrate;
137
-}
138
-
139
-int16_t HardwareSerial::peek() {
140
-  int16_t byte = -1;
141
-
142
-  // Temporarily lock out UART receive interrupts during this read so the UART receive
143
-  // interrupt won't cause problems with the index values
144
-  UART_IntConfig(UARTx, UART_INTCFG_RBR, DISABLE);
145
-
146
-  if (RxQueueReadPos != RxQueueWritePos)
147
-    byte = RxBuffer[RxQueueReadPos];
148
-
149
-  // Re-enable UART interrupts
150
-  UART_IntConfig(UARTx, UART_INTCFG_RBR, ENABLE);
151
-
152
-  return byte;
153
-}
154
-
155
-int16_t HardwareSerial::read() {
156
-  int16_t byte = -1;
157
-
158
-  // Temporarily lock out UART receive interrupts during this read so the UART receive
159
-  // interrupt won't cause problems with the index values
160
-  UART_IntConfig(UARTx, UART_INTCFG_RBR, DISABLE);
161
-
162
-  if (RxQueueReadPos != RxQueueWritePos) {
163
-    byte = RxBuffer[RxQueueReadPos];
164
-    RxQueueReadPos = (RxQueueReadPos + 1) % RX_BUFFER_SIZE;
165
-  }
166
-
167
-  // Re-enable UART interrupts
168
-  UART_IntConfig(UARTx, UART_INTCFG_RBR, ENABLE);
169
-
170
-  return byte;
171
-}
172
-
173
-size_t HardwareSerial::write(uint8_t send) {
174
-#if TX_BUFFER_SIZE > 0
175
-  size_t bytes = 0;
176
-  uint32_t fifolvl = 0;
177
-
178
-  // If the Tx Buffer is full, wait for space to clear
179
-  if ((TxQueueWritePos+1) % TX_BUFFER_SIZE == TxQueueReadPos) flushTX();
180
-
181
-  // Temporarily lock out UART transmit interrupts during this read so the UART transmit interrupt won't
182
-  // cause problems with the index values
183
-  UART_IntConfig(UARTx, UART_INTCFG_THRE, DISABLE);
184
-
185
-  // LPC17xx.h incorrectly defines FIFOLVL as a uint8_t, when it's actually a 32-bit register
186
-  if ((LPC_UART1_TypeDef *) UARTx == LPC_UART1) {
187
-    fifolvl = *(reinterpret_cast<volatile uint32_t *>(&((LPC_UART1_TypeDef *) UARTx)->FIFOLVL));
188
-  } else fifolvl = *(reinterpret_cast<volatile uint32_t *>(&UARTx->FIFOLVL));
189
-
190
-  // If the queue is empty and there's space in the FIFO, immediately send the byte
191
-  if (TxQueueWritePos == TxQueueReadPos && fifolvl < UART_TX_FIFO_SIZE) {
192
-    bytes = UART_Send(UARTx, &send, 1, BLOCKING);
193
-  }
194
-  // Otherwiise, write the byte to the transmit buffer
195
-  else if ((TxQueueWritePos+1) % TX_BUFFER_SIZE != TxQueueReadPos) {
196
-    TxBuffer[TxQueueWritePos] = send;
197
-    TxQueueWritePos = (TxQueueWritePos+1) % TX_BUFFER_SIZE;
198
-    bytes++;
199
-  }
200
-
201
-  // Re-enable the TX Interrupt
202
-  UART_IntConfig(UARTx, UART_INTCFG_THRE, ENABLE);
203
-
204
-  return bytes;
205
-#else
206
-  return UART_Send(UARTx, &send, 1, BLOCKING);
207
-#endif
208
-}
209
-
210
-#if TX_BUFFER_SIZE > 0
211
-  void HardwareSerial::flushTX() {
212
-    // Wait for the tx buffer and FIFO to drain
213
-    while (TxQueueWritePos != TxQueueReadPos && UART_CheckBusy(UARTx) == SET);
214
-  }
215
-#endif
216
-
217
-size_t HardwareSerial::available() {
218
-  return (RxQueueWritePos + RX_BUFFER_SIZE - RxQueueReadPos) % RX_BUFFER_SIZE;
219
-}
220
-
221
-void HardwareSerial::flush() {
222
-  RxQueueWritePos = 0;
223
-  RxQueueReadPos = 0;
224
-}
225
-
226
-size_t HardwareSerial::printf(const char *format, ...) {
227
-  char RxBuffer[256];
228
-  va_list vArgs;
229
-  va_start(vArgs, format);
230
-  int length = vsnprintf(RxBuffer, 256, format, vArgs);
231
-  va_end(vArgs);
232
-  if (length > 0 && length < 256) {
233
-    for (size_t i = 0; i < (size_t)length; ++i)
234
-      write(RxBuffer[i]);
235
-  }
236
-  return length;
237
-}
238
-
239
-void HardwareSerial::IRQHandler() {
240
-  uint32_t IIRValue;
241
-  uint8_t LSRValue, byte;
242
-
243
-  IIRValue = UART_GetIntId(UARTx);
244
-  IIRValue &= UART_IIR_INTID_MASK; // check bit 1~3, interrupt identification
245
-
246
-  // Receive Line Status
247
-  if (IIRValue == UART_IIR_INTID_RLS) {
248
-    LSRValue = UART_GetLineStatus(UARTx);
249
-
250
-    // Receive Line Status
251
-    if (LSRValue & (UART_LSR_OE | UART_LSR_PE | UART_LSR_FE | UART_LSR_RXFE | UART_LSR_BI)) {
252
-      // There are errors or break interrupt
253
-      // Read LSR will clear the interrupt
254
-      Status = LSRValue;
255
-      byte = UART_ReceiveByte(UARTx); // Dummy read on RX to clear interrupt, then bail out
256
-      return;
257
-    }
258
-  }
259
-
260
-  // Receive Data Available
261
-  if (IIRValue == UART_IIR_INTID_RDA) {
262
-    // Clear the FIFO
263
-    while (UART_Receive(UARTx, &byte, 1, NONE_BLOCKING)) {
264
-      #if ENABLED(EMERGENCY_PARSER)
265
-        emergency_parser.update(emergency_state, byte);
266
-      #endif
267
-      if ((RxQueueWritePos + 1) % RX_BUFFER_SIZE != RxQueueReadPos) {
268
-        RxBuffer[RxQueueWritePos] = byte;
269
-        RxQueueWritePos = (RxQueueWritePos + 1) % RX_BUFFER_SIZE;
270
-      } else
271
-        break;
272
-    }
273
-    // Character timeout indicator
274
-  } else if (IIRValue == UART_IIR_INTID_CTI) {
275
-    // Character Time-out indicator
276
-    Status |= 0x100; // Bit 9 as the CTI error
277
-  }
278
-
279
-  #if TX_BUFFER_SIZE > 0
280
-    if (IIRValue == UART_IIR_INTID_THRE) {
281
-      // Disable THRE interrupt
282
-      UART_IntConfig(UARTx, UART_INTCFG_THRE, DISABLE);
283
-
284
-      // Wait for FIFO buffer empty
285
-      while (UART_CheckBusy(UARTx) == SET);
286
-
287
-      // Transfer up to UART_TX_FIFO_SIZE bytes of data
288
-      for (int i = 0; i < UART_TX_FIFO_SIZE && TxQueueWritePos != TxQueueReadPos; i++) {
289
-        // Move a piece of data into the transmit FIFO
290
-        if (UART_Send(UARTx, &TxBuffer[TxQueueReadPos], 1, NONE_BLOCKING)) {
291
-          TxQueueReadPos = (TxQueueReadPos+1) % TX_BUFFER_SIZE;
292
-        } else break;
293
-      }
294
-
295
-      // If there is no more data to send, disable the transmit interrupt - else enable it or keep it enabled
296
-      if (TxQueueWritePos == TxQueueReadPos) {
297
-        UART_IntConfig(UARTx, UART_INTCFG_THRE, DISABLE);
298
-      } else UART_IntConfig(UARTx, UART_INTCFG_THRE, ENABLE);
299
-    }
300
-  #endif
301
-}
302
-
303
-#ifdef __cplusplus
304
-extern "C" {
305
-#endif
306
-
307
-void UART0_IRQHandler(void) {
308
-  #if SERIAL_PORT == 0 || SERIAL_PORT_2 == 0
309
-    Serial.IRQHandler();
310
-  #endif
311
-}
312
-
313
-void UART1_IRQHandler(void) {
314
-  #if SERIAL_PORT == 1 || SERIAL_PORT_2 == 1
315
-    Serial1.IRQHandler();
316
-  #endif
317
-}
318
-
319
-void UART2_IRQHandler(void) {
320
-  #if SERIAL_PORT == 2 || SERIAL_PORT_2 == 2
321
-    Serial2.IRQHandler();
322
-  #endif
323
-}
324
-
325
-void UART3_IRQHandler(void) {
326
-  #if SERIAL_PORT == 3 || SERIAL_PORT_2 == 3
327
-    Serial3.IRQHandler();
328
-  #endif
329
-}
330
-
331
-#ifdef __cplusplus
332
-}
333
-#endif
334
-
335
-#endif // TARGET_LPC1768

+ 0
- 91
Marlin/src/HAL/HAL_LPC1768/include/HardwareSerial.h Просмотреть файл

@@ -1,91 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
- *
21
- */
22
-
23
-#ifndef HARDWARE_SERIAL_H_
24
-#define HARDWARE_SERIAL_H_
25
-
26
-#include "../../../inc/MarlinConfigPre.h"
27
-#if ENABLED(EMERGENCY_PARSER)
28
-  #include "../../../feature/emergency_parser.h"
29
-#endif
30
-
31
-#include <stdarg.h>
32
-#include <stdio.h>
33
-#include <Stream.h>
34
-
35
-extern "C" {
36
-  #include <lpc17xx_uart.h>
37
-  #include "lpc17xx_pinsel.h"
38
-}
39
-
40
-class HardwareSerial : public Stream {
41
-private:
42
-  LPC_UART_TypeDef *UARTx;
43
-
44
-  uint32_t Baudrate;
45
-  uint32_t Status;
46
-  uint8_t RxBuffer[RX_BUFFER_SIZE];
47
-  uint32_t RxQueueWritePos;
48
-  uint32_t RxQueueReadPos;
49
-  #if TX_BUFFER_SIZE > 0
50
-    uint8_t TxBuffer[TX_BUFFER_SIZE];
51
-    uint32_t TxQueueWritePos;
52
-    uint32_t TxQueueReadPos;
53
-  #endif
54
-  #if ENABLED(EMERGENCY_PARSER)
55
-    EmergencyParser::State emergency_state;
56
-  #endif
57
-
58
-public:
59
-  HardwareSerial(LPC_UART_TypeDef *UARTx)
60
-    : UARTx(UARTx)
61
-    , Baudrate(0)
62
-    , RxQueueWritePos(0)
63
-    , RxQueueReadPos(0)
64
-    #if TX_BUFFER_SIZE > 0
65
-      , TxQueueWritePos(0)
66
-      , TxQueueReadPos(0)
67
-    #endif
68
-    #if ENABLED(EMERGENCY_PARSER)
69
-      , emergency_state(EmergencyParser::State::EP_RESET)
70
-    #endif
71
-  {
72
-  }
73
-
74
-  void begin(uint32_t baudrate);
75
-  int16_t peek();
76
-  int16_t read();
77
-  size_t write(uint8_t send);
78
-  #if TX_BUFFER_SIZE > 0
79
-    void flushTX();
80
-  #endif
81
-  size_t available();
82
-  void flush();
83
-  size_t printf(const char *format, ...);
84
-
85
-  operator bool() { return true; }
86
-
87
-  void IRQHandler();
88
-
89
-};
90
-
91
-#endif // MARLIN_SRC_HAL_HAL_SERIAL_H_

+ 0
- 329
Marlin/src/HAL/HAL_LPC1768/include/SoftwareSerial.cpp Просмотреть файл

@@ -1,329 +0,0 @@
1
-/*
2
- * SoftwareSerial.cpp (formerly NewSoftSerial.cpp)
3
- *
4
- * Multi-instance software serial library for Arduino/Wiring
5
- * -- Interrupt-driven receive and other improvements by ladyada
6
- *    (http://ladyada.net)
7
- * -- Tuning, circular buffer, derivation from class Print/Stream,
8
- *    multi-instance support, porting to 8MHz processors,
9
- *    various optimizations, PROGMEM delay tables, inverse logic and
10
- *    direct port writing by Mikal Hart (http://www.arduiniana.org)
11
- * -- Pin change interrupt macros by Paul Stoffregen (http://www.pjrc.com)
12
- * -- 20MHz processor support by Garrett Mace (http://www.macetech.com)
13
- * -- ATmega1280/2560 support by Brett Hagman (http://www.roguerobotics.com/)
14
- *
15
- * This library is free software; you can redistribute it and/or
16
- * modify it under the terms of the GNU Lesser General Public
17
- * License as published by the Free Software Foundation; either
18
- * version 2.1 of the License, or (at your option) any later version.
19
- *
20
- * This library is distributed in the hope that it will be useful,
21
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
22
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
23
- * Lesser General Public License for more details.
24
- *
25
- * You should have received a copy of the GNU Lesser General Public
26
- * License along with this library; if not, write to the Free Software
27
- * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
28
- *
29
- * The latest version of this library can always be found at
30
- * http://arduiniana.org.
31
- */
32
-
33
-#ifdef TARGET_LPC1768
34
-
35
-//
36
-// Includes
37
-//
38
-//#include <WInterrupts.h>
39
-#include "../../../inc/MarlinConfig.h"
40
-#include "../../shared/Delay.h"
41
-#include <stdint.h>
42
-#include <stdarg.h>
43
-#include <Arduino.h>
44
-#include <pinmapping.h>
45
-#include "../fastio.h"
46
-#include "SoftwareSerial.h"
47
-
48
-void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode);
49
-void GpioDisableInt(uint32_t port, uint32_t pin);
50
-//
51
-// Statics
52
-//
53
-SoftwareSerial *SoftwareSerial::active_object = 0;
54
-unsigned char SoftwareSerial::_receive_buffer[_SS_MAX_RX_BUFF];
55
-volatile uint8_t SoftwareSerial::_receive_buffer_tail = 0;
56
-volatile uint8_t SoftwareSerial::_receive_buffer_head = 0;
57
-
58
-typedef struct _DELAY_TABLE {
59
-  long baud;
60
-  uint16_t rx_delay_centering;
61
-  uint16_t rx_delay_intrabit;
62
-  uint16_t rx_delay_stopbit;
63
-  uint16_t tx_delay;
64
-} DELAY_TABLE;
65
-
66
-// rough delay estimation
67
-static const DELAY_TABLE table[] = {
68
-  //baud    |rxcenter|rxintra |rxstop  |tx { 250000,   2,      4,       4,       4,   }, //Done but not good due to instruction cycle error { 115200,   4,      8,       8,       8,   }, //Done but not good due to instruction cycle error
69
-  //{ 74880,   69,       139,       62,      162,  }, // estimation
70
-  //{ 57600,   100,       185,      1,       208,  }, // Done but not good due to instruction cycle error
71
-  //{ 38400,   13,      26,      26,      26,  }, // Done
72
-  //{ 19200,   26,      52,      52,      52,  }, // Done { 9600,    52,      104,     104,     104, }, // Done
73
-  //{ 4800,    104,     208,     208,     208, },
74
-  //{ 2400,    208,     417,     417,     417, },
75
-  //{ 1200,    416,    833,      833,     833,},
76
-};
77
-
78
-//
79
-// Private methods
80
-//
81
-
82
-inline void SoftwareSerial::tunedDelay(const uint32_t count) {
83
-  DELAY_US(count);
84
-}
85
-
86
-// This function sets the current object as the "listening"
87
-// one and returns true if it replaces another
88
-bool SoftwareSerial::listen() {
89
-  if (!_rx_delay_stopbit)
90
-    return false;
91
-
92
-  if (active_object != this) {
93
-    if (active_object)
94
-      active_object->stopListening();
95
-
96
-    _buffer_overflow = false;
97
-    _receive_buffer_head = _receive_buffer_tail = 0;
98
-    active_object = this;
99
-
100
-    setRxIntMsk(true);
101
-    return true;
102
-  }
103
-
104
-  return false;
105
-}
106
-
107
-// Stop listening. Returns true if we were actually listening.
108
-bool SoftwareSerial::stopListening() {
109
-  if (active_object == this) {
110
-    setRxIntMsk(false);
111
-    active_object = NULL;
112
-    return true;
113
-  }
114
-  return false;
115
-}
116
-
117
-//
118
-// The receive routine called by the interrupt handler
119
-//
120
-void SoftwareSerial::recv() {
121
-  uint8_t d = 0;
122
-
123
-  // If RX line is high, then we don't see any start bit
124
-  // so interrupt is probably not for us
125
-  if (_inverse_logic ? rx_pin_read() : !rx_pin_read()) {
126
-    // Disable further interrupts during reception, this prevents
127
-    // triggering another interrupt directly after we return, which can
128
-    // cause problems at higher baudrates.
129
-    setRxIntMsk(false);//__disable_irq();//
130
-
131
-    // Wait approximately 1/2 of a bit width to "center" the sample
132
-    tunedDelay(_rx_delay_centering);
133
-    // Read each of the 8 bits
134
-    for (uint8_t i=8; i > 0; --i) {
135
-      tunedDelay(_rx_delay_intrabit);
136
-      d >>= 1;
137
-      if (rx_pin_read()) d |= 0x80;
138
-    }
139
-
140
-    if (_inverse_logic) d = ~d;
141
-
142
-    // if buffer full, set the overflow flag and return
143
-    uint8_t next = (_receive_buffer_tail + 1) % _SS_MAX_RX_BUFF;
144
-    if (next != _receive_buffer_head) {
145
-      // save new data in buffer: tail points to where byte goes
146
-      _receive_buffer[_receive_buffer_tail] = d; // save new byte
147
-      _receive_buffer_tail = next;
148
-    }
149
-    else {
150
-      _buffer_overflow = true;
151
-    }
152
-    tunedDelay(_rx_delay_stopbit);
153
-    // Re-enable interrupts when we're sure to be inside the stop bit
154
-    setRxIntMsk(true);  //__enable_irq();//
155
-  }
156
-}
157
-
158
-uint32_t SoftwareSerial::rx_pin_read() {
159
-  return digitalRead(_receivePin);
160
-}
161
-
162
-//
163
-// Interrupt handling
164
-//
165
-
166
-/* static */
167
-inline void SoftwareSerial::handle_interrupt() {
168
-  if (active_object)
169
-    active_object->recv();
170
-}
171
-extern "C" void intWrapper() {
172
-  SoftwareSerial::handle_interrupt();
173
-}
174
-//
175
-// Constructor
176
-//
177
-SoftwareSerial::SoftwareSerial(pin_t receivePin, pin_t transmitPin, bool inverse_logic /* = false */) :
178
-  _rx_delay_centering(0),
179
-  _rx_delay_intrabit(0),
180
-  _rx_delay_stopbit(0),
181
-  _tx_delay(0),
182
-  _buffer_overflow(false),
183
-  _inverse_logic(inverse_logic) {
184
-  setTX(transmitPin);
185
-  setRX(receivePin);
186
-}
187
-
188
-//
189
-// Destructor
190
-//
191
-SoftwareSerial::~SoftwareSerial() {
192
-  end();
193
-}
194
-
195
-void SoftwareSerial::setTX(pin_t tx) {
196
-  // First write, then set output. If we do this the other way around,
197
-  // the pin would be output low for a short while before switching to
198
-  // output hihg. Now, it is input with pullup for a short while, which
199
-  // is fine. With inverse logic, either order is fine.
200
-
201
-  digitalWrite(tx, _inverse_logic ? LOW : HIGH);
202
-  pinMode(tx,OUTPUT);
203
-  _transmitPin = tx;
204
-}
205
-
206
-void SoftwareSerial::setRX(pin_t rx) {
207
-  pinMode(rx, INPUT_PULLUP); // pullup for normal logic!
208
-  //if (!_inverse_logic)
209
-  // digitalWrite(rx, HIGH);
210
-  _receivePin = rx;
211
-  _receivePort = LPC1768_PIN_PORT(rx);
212
-  _receivePortPin = LPC1768_PIN_PIN(rx);
213
-  /* GPIO_T * rxPort = digitalPinToPort(rx);
214
-  _receivePortRegister = portInputRegister(rxPort);
215
-  _receiveBitMask = digitalPinToBitMask(rx);*/
216
-}
217
-
218
-//
219
-// Public methods
220
-//
221
-
222
-void SoftwareSerial::begin(long speed) {
223
-  _rx_delay_centering = _rx_delay_intrabit = _rx_delay_stopbit = _tx_delay = 0;
224
-
225
-  for(uint8_t i = 0; i < sizeof(table)/sizeof(table[0]); ++i) {
226
-    long baud = table[i].baud;
227
-    if (baud == speed) {
228
-      _rx_delay_centering = table[i].rx_delay_centering;
229
-      _rx_delay_intrabit = table[i].rx_delay_intrabit;
230
-      _rx_delay_stopbit = table[i].rx_delay_stopbit;
231
-      _tx_delay = table[i].tx_delay;
232
-      break;
233
-    }
234
-  }
235
-
236
-  attachInterrupt(_receivePin, intWrapper, CHANGE); //this->handle_interrupt, CHANGE);
237
-
238
-  listen();
239
-  tunedDelay(_tx_delay);
240
-
241
-}
242
-
243
-void SoftwareSerial::setRxIntMsk(bool enable) {
244
-  if (enable)
245
-    GpioEnableInt(_receivePort,_receivePin,CHANGE);
246
-  else
247
-    GpioDisableInt(_receivePort,_receivePin);
248
-}
249
-
250
-void SoftwareSerial::end() {
251
-  stopListening();
252
-}
253
-
254
-
255
-// Read data from buffer
256
-int16_t SoftwareSerial::read() {
257
-  if (!isListening()) return -1;
258
-
259
-  // Empty buffer?
260
-  if (_receive_buffer_head == _receive_buffer_tail) return -1;
261
-
262
-  // Read from "head"
263
-  uint8_t d = _receive_buffer[_receive_buffer_head]; // grab next byte
264
-  _receive_buffer_head = (_receive_buffer_head + 1) % _SS_MAX_RX_BUFF;
265
-  return d;
266
-}
267
-
268
-size_t SoftwareSerial::available() {
269
-  if (!isListening()) return 0;
270
-
271
-  return (_receive_buffer_tail + _SS_MAX_RX_BUFF - _receive_buffer_head) % _SS_MAX_RX_BUFF;
272
-}
273
-
274
-size_t SoftwareSerial::write(uint8_t b) {
275
-  // By declaring these as local variables, the compiler will put them
276
-  // in registers _before_ disabling interrupts and entering the
277
-  // critical timing sections below, which makes it a lot easier to
278
-  // verify the cycle timings
279
-
280
-  bool inv = _inverse_logic;
281
-  uint16_t delay = _tx_delay;
282
-
283
-  if (inv) b = ~b;
284
-
285
-  cli();  // turn off interrupts for a clean txmit
286
-
287
-  // Write the start bit
288
-  digitalWrite(_transmitPin, !!inv);
289
-
290
-  tunedDelay(delay);
291
-
292
-  // Write each of the 8 bits
293
-  for (uint8_t i = 8; i > 0; --i) {
294
-    digitalWrite(_transmitPin, b & 1); // send 1 //(GPIO_Desc[_transmitPin].P)->DOUT |= GPIO_Desc[_transmitPin].bit;
295
-                                       // send 0 //(GPIO_Desc[_transmitPin].P)->DOUT &= ~GPIO_Desc[_transmitPin].bit;
296
-    tunedDelay(delay);
297
-    b >>= 1;
298
-  }
299
-
300
-  // restore pin to natural state
301
-  digitalWrite(_transmitPin, !inv);
302
-
303
-  sei(); // turn interrupts back on
304
-  tunedDelay(delay);
305
-
306
-  return 1;
307
-}
308
-
309
-void SoftwareSerial::flush() {
310
-  if (!isListening()) return;
311
-
312
-  cli();
313
-  _receive_buffer_head = _receive_buffer_tail = 0;
314
-  sei();
315
-}
316
-
317
-int16_t SoftwareSerial::peek() {
318
-  if (!isListening())
319
-    return -1;
320
-
321
-  // Empty buffer?
322
-  if (_receive_buffer_head == _receive_buffer_tail)
323
-    return -1;
324
-
325
-  // Read from "head"
326
-  return _receive_buffer[_receive_buffer_head];
327
-}
328
-
329
-#endif // TARGET_LPC1768

+ 0
- 120
Marlin/src/HAL/HAL_LPC1768/include/SoftwareSerial.h Просмотреть файл

@@ -1,120 +0,0 @@
1
-/*
2
- * SoftwareSerial.h (formerly NewSoftSerial.h)
3
- *
4
- * Multi-instance software serial library for Arduino/Wiring
5
- * -- Interrupt-driven receive and other improvements by ladyada
6
- *    (http://ladyada.net)
7
- * -- Tuning, circular buffer, derivation from class Print/Stream,
8
- *    multi-instance support, porting to 8MHz processors,
9
- *    various optimizations, PROGMEM delay tables, inverse logic and
10
- *    direct port writing by Mikal Hart (http://www.arduiniana.org)
11
- * -- Pin change interrupt macros by Paul Stoffregen (http://www.pjrc.com)
12
- * -- 20MHz processor support by Garrett Mace (http://www.macetech.com)
13
- * -- ATmega1280/2560 support by Brett Hagman (http://www.roguerobotics.com/)
14
- *
15
- * This library is free software; you can redistribute it and/or
16
- * modify it under the terms of the GNU Lesser General Public
17
- * License as published by the Free Software Foundation; either
18
- * version 2.1 of the License, or (at your option) any later version.
19
- *
20
- * This library is distributed in the hope that it will be useful,
21
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
22
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
23
- * Lesser General Public License for more details.
24
- *
25
- * You should have received a copy of the GNU Lesser General Public
26
- * License along with this library; if not, write to the Free Software
27
- * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
28
- *
29
- * The latest version of this library can always be found at
30
- * http://arduiniana.org.
31
- */
32
-
33
-#ifndef SOFTWARESERIAL_H
34
-#define SOFTWARESERIAL_H
35
-
36
-#include <Arduino.h>
37
-#include <stdint.h>
38
-//#include "serial.h"
39
-#include <Stream.h>
40
-#include <Print.h>
41
-
42
-/******************************************************************************
43
-* Definitions
44
-******************************************************************************/
45
-
46
-#define _SS_MAX_RX_BUFF 64 // RX buffer size
47
-
48
-class SoftwareSerial : public Stream
49
-{
50
-private:
51
-  // per object data
52
-  pin_t _receivePin;
53
-  pin_t _transmitPin;
54
-//  uint32_t _receiveBitMask; // for rx interrupts
55
-  uint32_t _receivePort;
56
-  uint32_t _receivePortPin;
57
-
58
-
59
-  // Expressed as 4-cycle delays (must never be 0!)
60
-  uint16_t _rx_delay_centering;
61
-  uint16_t _rx_delay_intrabit;
62
-  uint16_t _rx_delay_stopbit;
63
-  uint16_t _tx_delay;
64
-
65
-  uint16_t _buffer_overflow:1;
66
-  uint16_t _inverse_logic:1;
67
-
68
-  // static data
69
-  static unsigned char _receive_buffer[_SS_MAX_RX_BUFF];
70
-  static volatile uint8_t _receive_buffer_tail;
71
-  static volatile uint8_t _receive_buffer_head;
72
-  static SoftwareSerial *active_object;
73
-
74
-  // private methods
75
-  void recv();
76
-  uint32_t rx_pin_read();
77
-  void tx_pin_write(uint8_t pin_state);
78
-  void setTX(pin_t transmitPin);
79
-  void setRX(pin_t receivePin);
80
-  void setRxIntMsk(bool enable);
81
-
82
-  // private static method for timing
83
-  static inline void tunedDelay(uint32_t delay);
84
-
85
-public:
86
-  // public methods
87
-
88
-  SoftwareSerial(pin_t receivePin, pin_t transmitPin, bool inverse_logic = false);
89
-  ~SoftwareSerial();
90
-  void begin(long speed);
91
-  bool listen();
92
-  void end();
93
-  bool isListening() { return this == active_object; }
94
-  bool stopListening();
95
-  bool overflow() { bool ret = _buffer_overflow; if (ret) _buffer_overflow = false; return ret; }
96
-  int16_t peek();
97
-
98
-  virtual size_t write(uint8_t byte);
99
-  virtual int16_t read();
100
-  virtual size_t available();
101
-  virtual void flush();
102
-  operator bool() { return true; }
103
-
104
-  using Print::write;
105
-  //using HalSerial::write;
106
-
107
-  // public only for easy access by interrupt handlers
108
-  static inline void handle_interrupt() __attribute__((__always_inline__));
109
-};
110
-
111
-// Arduino 0012 workaround
112
-#undef int
113
-#undef char
114
-#undef long
115
-#undef byte
116
-#undef float
117
-#undef abs
118
-#undef round
119
-
120
-#endif // SOFTWARESERIAL_H

+ 0
- 219
Marlin/src/HAL/HAL_LPC1768/include/Wire.cpp Просмотреть файл

@@ -1,219 +0,0 @@
1
-/*
2
-  TwoWire.cpp - TWI/I2C library for Wiring & Arduino
3
-  Copyright (c) 2006 Nicholas Zambetti.  All right reserved.
4
-
5
-  This library is free software; you can redistribute it and/or
6
-  modify it under the terms of the GNU Lesser General Public
7
-  License as published by the Free Software Foundation; either
8
-  version 2.1 of the License, or (at your option) any later version.
9
-
10
-  This library is distributed in the hope that it will be useful,
11
-  but WITHOUT ANY WARRANTY; without even the implied warranty of
12
-  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
13
-  Lesser General Public License for more details.
14
-
15
-  You should have received a copy of the GNU Lesser General Public
16
-  License along with this library; if not, write to the Free Software
17
-  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
18
-*/
19
-
20
-#ifdef TARGET_LPC1768
21
-
22
-extern "C" {
23
-  #include <stdlib.h>
24
-  #include <string.h>
25
-  #include <inttypes.h>
26
-  #include <lpc17xx_i2c.h>
27
-  #include <lpc17xx_pinsel.h>
28
-  #include <lpc17xx_libcfg_default.h>
29
-}
30
-
31
-#include <Wire.h>
32
-
33
-#define USEDI2CDEV_M 1
34
-
35
-#if (USEDI2CDEV_M == 0)
36
-  #define I2CDEV_M LPC_I2C0
37
-#elif (USEDI2CDEV_M == 1)
38
-  #define I2CDEV_M LPC_I2C1
39
-#elif (USEDI2CDEV_M == 2)
40
-  #define I2CDEV_M LPC_I2C2
41
-#else
42
-  #error "Master I2C device not defined!"
43
-#endif
44
-
45
-// Initialize Class Variables //////////////////////////////////////////////////
46
-
47
-uint8_t TwoWire::rxBuffer[BUFFER_LENGTH];
48
-uint8_t TwoWire::rxBufferIndex = 0;
49
-uint8_t TwoWire::rxBufferLength = 0;
50
-
51
-uint8_t TwoWire::txAddress = 0;
52
-uint8_t TwoWire::txBuffer[BUFFER_LENGTH];
53
-uint8_t TwoWire::txBufferIndex = 0;
54
-uint8_t TwoWire::txBufferLength = 0;
55
-
56
-uint8_t TwoWire::transmitting = 0;
57
-
58
-// Constructors ////////////////////////////////////////////////////////////////
59
-
60
-TwoWire::TwoWire() {
61
-}
62
-
63
-// Public Methods //////////////////////////////////////////////////////////////
64
-
65
-void TwoWire::begin(void) {
66
-  rxBufferIndex = 0;
67
-  rxBufferLength = 0;
68
-
69
-  txBufferIndex = 0;
70
-  txBufferLength = 0;
71
-
72
-  /*
73
-   * Init I2C pin connect
74
-   */
75
-  PINSEL_CFG_Type PinCfg;
76
-  PinCfg.OpenDrain = 0;
77
-  PinCfg.Pinmode = 0;
78
-
79
-  #if USEDI2CDEV_M == 0
80
-    PinCfg.Funcnum = 1;
81
-    PinCfg.Pinnum = 27;
82
-    PinCfg.Portnum = 0;
83
-    PINSEL_ConfigPin(&PinCfg); // SDA0 / D57  AUX-1
84
-    PinCfg.Pinnum = 28;
85
-    PINSEL_ConfigPin(&PinCfg); // SCL0 / D58  AUX-1
86
-  #endif
87
-
88
-  #if USEDI2CDEV_M == 1
89
-    PinCfg.Funcnum = 3;
90
-    PinCfg.Pinnum = 0;
91
-    PinCfg.Portnum = 0;
92
-    PINSEL_ConfigPin(&PinCfg);  // SDA1 / D20 SCA
93
-    PinCfg.Pinnum = 1;
94
-    PINSEL_ConfigPin(&PinCfg);  // SCL1 / D21 SCL
95
-  #endif
96
-
97
-  #if USEDI2CDEV_M == 2
98
-    PinCfg.Funcnum = 2;
99
-    PinCfg.Pinnum = 10;
100
-    PinCfg.Portnum = 0;
101
-    PINSEL_ConfigPin(&PinCfg); // SDA2 / D38  X_ENABLE_PIN
102
-    PinCfg.Pinnum = 11;
103
-    PINSEL_ConfigPin(&PinCfg); // SCL2 / D55  X_DIR_PIN
104
-  #endif
105
-
106
-  // Initialize I2C peripheral
107
-  I2C_Init(I2CDEV_M, 100000);
108
-
109
-  // Enable Master I2C operation
110
-  I2C_Cmd(I2CDEV_M, I2C_MASTER_MODE, ENABLE);
111
-}
112
-
113
-uint8_t TwoWire::requestFrom(uint8_t address, uint8_t quantity) {
114
-  // clamp to buffer length
115
-  if (quantity > BUFFER_LENGTH)
116
-    quantity = BUFFER_LENGTH;
117
-
118
-  // perform blocking read into buffer
119
-  I2C_M_SETUP_Type transferMCfg;
120
-  transferMCfg.sl_addr7bit = address >> 1; // not sure about the right shift
121
-  transferMCfg.tx_data = NULL;
122
-  transferMCfg.tx_length = 0;
123
-  transferMCfg.rx_data = rxBuffer;
124
-  transferMCfg.rx_length = quantity;
125
-  transferMCfg.retransmissions_max = 3;
126
-  I2C_MasterTransferData(I2CDEV_M, &transferMCfg, I2C_TRANSFER_POLLING);
127
-
128
-  // set rx buffer iterator vars
129
-  rxBufferIndex = 0;
130
-  rxBufferLength = transferMCfg.rx_count;
131
-
132
-  return transferMCfg.rx_count;
133
-}
134
-
135
-uint8_t TwoWire::requestFrom(int address, int quantity) {
136
-  return requestFrom((uint8_t)address, (uint8_t)quantity);
137
-}
138
-
139
-void TwoWire::beginTransmission(uint8_t address) {
140
-  // indicate that we are transmitting
141
-  transmitting = 1;
142
-  // set address of targeted slave
143
-  txAddress = address;
144
-  // reset tx buffer iterator vars
145
-  txBufferIndex = 0;
146
-  txBufferLength = 0;
147
-}
148
-
149
-void TwoWire::beginTransmission(int address) {
150
-  beginTransmission((uint8_t)address);
151
-}
152
-
153
-uint8_t TwoWire::endTransmission(void) {
154
-  // transmit buffer (blocking)
155
-  I2C_M_SETUP_Type transferMCfg;
156
-  transferMCfg.sl_addr7bit = txAddress >> 1; // not sure about the right shift
157
-  transferMCfg.tx_data = txBuffer;
158
-  transferMCfg.tx_length = txBufferLength;
159
-  transferMCfg.rx_data = NULL;
160
-  transferMCfg.rx_length = 0;
161
-  transferMCfg.retransmissions_max = 3;
162
-  Status status = I2C_MasterTransferData(I2CDEV_M, &transferMCfg, I2C_TRANSFER_POLLING);
163
-
164
-  // reset tx buffer iterator vars
165
-  txBufferIndex = 0;
166
-  txBufferLength = 0;
167
-
168
-  // indicate that we are done transmitting
169
-  transmitting = 0;
170
-
171
-  return status == SUCCESS ? 0 : 4;
172
-}
173
-
174
-// must be called after beginTransmission(address)
175
-size_t TwoWire::write(uint8_t data) {
176
-  if (transmitting) {
177
-    // don't bother if buffer is full
178
-    if (txBufferLength >= BUFFER_LENGTH) return 0;
179
-
180
-    // put byte in tx buffer
181
-    txBuffer[txBufferIndex++] = data;
182
-
183
-    // update amount in buffer
184
-    txBufferLength = txBufferIndex;
185
-  }
186
-
187
-  return 1;
188
-}
189
-
190
-// must be called after beginTransmission(address)
191
-size_t TwoWire::write(const uint8_t *data, size_t quantity) {
192
-  size_t sent = 0;
193
-  if (transmitting)
194
-    for (sent = 0; sent < quantity; ++sent)
195
-      if (!write(data[sent])) break;
196
-
197
-  return sent;
198
-}
199
-
200
-// Must be called after requestFrom(address, numBytes)
201
-int TwoWire::available(void) {
202
-  return rxBufferLength - rxBufferIndex;
203
-}
204
-
205
-// Must be called after requestFrom(address, numBytes)
206
-int TwoWire::read(void) {
207
-  return rxBufferIndex < rxBufferLength ? rxBuffer[rxBufferIndex++] : -1;
208
-}
209
-
210
-// Must be called after requestFrom(address, numBytes)
211
-int TwoWire::peek(void) {
212
-  return rxBufferIndex < rxBufferLength ? rxBuffer[rxBufferIndex] : -1;
213
-}
214
-
215
-// Preinstantiate Objects //////////////////////////////////////////////////////
216
-
217
-TwoWire Wire = TwoWire();
218
-
219
-#endif // TARGET_LPC1768

+ 0
- 67
Marlin/src/HAL/HAL_LPC1768/include/Wire.h Просмотреть файл

@@ -1,67 +0,0 @@
1
-/**
2
- * TwoWire.h - TWI/I2C library for Arduino & Wiring
3
- * Copyright (c) 2006 Nicholas Zambetti.  All right reserved.
4
- *
5
- * This library is free software; you can redistribute it and/or
6
- * modify it under the terms of the GNU Lesser General Public
7
- * License as published by the Free Software Foundation; either
8
- * version 2.1 of the License, or (at your option) any later version.
9
- *
10
- * This library is distributed in the hope that it will be useful,
11
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
12
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
13
- * Lesser General Public License for more details.
14
- *
15
- * You should have received a copy of the GNU Lesser General Public
16
- * License along with this library; if not, write to the Free Software
17
- * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
18
- *
19
- * Modified 2012 by Todd Krein (todd@krein.org) to implement repeated starts
20
- */
21
-
22
-#ifndef _TWOWIRE_H_
23
-#define _TWOWIRE_H_
24
-
25
-#include <inttypes.h>
26
-
27
-#define BUFFER_LENGTH 32
28
-
29
-class TwoWire {
30
-  private:
31
-    static uint8_t rxBuffer[];
32
-    static uint8_t rxBufferIndex;
33
-    static uint8_t rxBufferLength;
34
-
35
-    static uint8_t txAddress;
36
-    static uint8_t txBuffer[];
37
-    static uint8_t txBufferIndex;
38
-    static uint8_t txBufferLength;
39
-
40
-    static uint8_t transmitting;
41
-
42
-  public:
43
-    TwoWire();
44
-    void begin();
45
-    void beginTransmission(uint8_t);
46
-    void beginTransmission(int);
47
-    uint8_t endTransmission(void);
48
-    uint8_t endTransmission(uint8_t);
49
-
50
-    uint8_t requestFrom(uint8_t, uint8_t);
51
-    uint8_t requestFrom(int, int);
52
-
53
-    virtual size_t write(uint8_t);
54
-    virtual size_t write(const uint8_t *, size_t);
55
-    virtual int available(void);
56
-    virtual int read(void);
57
-    virtual int peek(void);
58
-
59
-    inline size_t write(unsigned long n) { return write((uint8_t)n); }
60
-    inline size_t write(long n) { return write((uint8_t)n); }
61
-    inline size_t write(unsigned int n) { return write((uint8_t)n); }
62
-    inline size_t write(int n) { return write((uint8_t)n); }
63
-};
64
-
65
-extern TwoWire Wire;
66
-
67
-#endif // _TWOWIRE_H_

+ 0
- 74
Marlin/src/HAL/HAL_LPC1768/include/pinmapping.cpp Просмотреть файл

@@ -1,74 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
- *
21
- */
22
-
23
-#ifdef TARGET_LPC1768
24
-
25
-#include <pinmapping.h>
26
-
27
-#include "../../../gcode/parser.h"
28
-
29
-// Get the digital pin for an analog index
30
-pin_t analogInputToDigitalPin(const int8_t p) {
31
-  return (WITHIN(p, 0, NUM_ANALOG_INPUTS) ? adc_pin_table[p] : P_NC);
32
-}
33
-
34
-// Return the index of a pin number
35
-// The pin number given here is in the form ppp:nnnnn
36
-int16_t GET_PIN_MAP_INDEX(const pin_t pin) {
37
-  const uint16_t index = (LPC1768_PIN_PORT(pin) << 5) | LPC1768_PIN_PIN(pin);
38
-  return (index < NUM_DIGITAL_PINS && pin_map[index] != P_NC) ? index : -1;
39
-}
40
-
41
-// Test whether the pin is valid
42
-bool VALID_PIN(const pin_t p) {
43
-  const int16_t ind = GET_PIN_MAP_INDEX(p);
44
-  return ind >= 0 && pin_map[ind] >= 0;
45
-}
46
-
47
-// Get the analog index for a digital pin
48
-int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p) {
49
-  return (VALID_PIN(p) ? LPC1768_PIN_ADC(p) : -1);
50
-}
51
-
52
-// Test whether the pin is PWM
53
-bool PWM_PIN(const pin_t p) {
54
-  return VALID_PIN(p) && LPC1768_PIN_PWM(p);
55
-}
56
-
57
-// Test whether the pin is interruptable
58
-bool INTERRUPT_PIN(const pin_t p) {
59
-  return VALID_PIN(p) && LPC1768_PIN_INTERRUPT(p);
60
-}
61
-
62
-// Get the pin number at the given index
63
-pin_t GET_PIN_MAP_PIN(const int16_t ind) {
64
-  return WITHIN(ind, 0, NUM_DIGITAL_PINS - 1) ? pin_map[ind] : P_NC;
65
-}
66
-
67
-int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) {
68
-  const uint16_t val = (uint16_t)parser.intval(code), port = val / 100, pin = val % 100;
69
-  const  int16_t ind = (port < (NUM_DIGITAL_PINS >> 5) && (pin < 32))
70
-                      ? GET_PIN_MAP_INDEX(port << 5 | pin) : -2;
71
-  return ind > -2 ? ind : dval;
72
-}
73
-
74
-#endif // TARGET_LPC1768

+ 0
- 294
Marlin/src/HAL/HAL_LPC1768/include/pinmapping.h Просмотреть файл

@@ -1,294 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
- *
21
- */
22
-
23
-#ifndef _PINMAPPING_H_
24
-#define _PINMAPPING_H_
25
-
26
-#include "../../../inc/MarlinConfigPre.h"
27
-
28
-#include <stdint.h>
29
-
30
-typedef int16_t pin_t;
31
-
32
-#define PORT_0  000
33
-#define PORT_1  001
34
-#define PORT_2  010
35
-#define PORT_3  011
36
-#define PORT_4  100
37
-
38
-#define PORT_(p)  PORT_##p
39
-#define PORT(p)   PORT_(p)
40
-
41
-#define PIN_0  00000
42
-#define PIN_1  00001
43
-#define PIN_2  00010
44
-#define PIN_3  00011
45
-#define PIN_4  00100
46
-#define PIN_5  00101
47
-#define PIN_6  00110
48
-#define PIN_7  00111
49
-#define PIN_8  01000
50
-#define PIN_9  01001
51
-#define PIN_10 01010
52
-#define PIN_11 01011
53
-#define PIN_12 01100
54
-#define PIN_13 01101
55
-#define PIN_14 01110
56
-#define PIN_15 01111
57
-#define PIN_16 10000
58
-#define PIN_17 10001
59
-#define PIN_18 10010
60
-#define PIN_19 10011
61
-#define PIN_20 10100
62
-#define PIN_21 10101
63
-#define PIN_22 10110
64
-#define PIN_23 10111
65
-#define PIN_24 11000
66
-#define PIN_25 11001
67
-#define PIN_26 11010
68
-#define PIN_27 11011
69
-#define PIN_28 11100
70
-#define PIN_29 11101
71
-#define PIN_30 11110
72
-#define PIN_31 11111
73
-
74
-#define PIN_(p) PIN_##p
75
-#define PIN(p)  PIN_(p)
76
-
77
-#define ADC_NONE    0000
78
-#define ADC_CHAN_0  0001
79
-#define ADC_CHAN_1  0010
80
-#define ADC_CHAN_2  0011
81
-#define ADC_CHAN_3  0100
82
-#define ADC_CHAN_4  0101
83
-#define ADC_CHAN_5  0110
84
-#define ADC_CHAN_6  0111
85
-#define ADC_CHAN_7  1000
86
-
87
-#define ADC_CHAN_(c)  ADC_CHAN_##c
88
-#define ADC_CHAN(p)   ADC_CHAN_(p)
89
-
90
-#define BOOL_0 0
91
-#define BOOL_1 1
92
-#define BOOL_(b)      BOOL_##b
93
-
94
-#define INTERRUPT(b)  BOOL_(b)
95
-#define PWM(b)        BOOL_(b)
96
-
97
-// Combine elements into pin bits: 0b00AAAAWIPPPNNNNN
98
-#define LPC1768_PIN_(port, pin, int, pwm, adc)  0b00##adc##pwm##int##port##pin
99
-#define LPC1768_PIN(port, pin, int, pwm, adc)   LPC1768_PIN_(port, pin, int, pwm, adc)
100
-
101
-constexpr uint8_t LPC1768_PIN_PORT(const pin_t pin) { return ((uint8_t)((pin >> 5) & 0b111)); }
102
-constexpr uint8_t LPC1768_PIN_PIN(const pin_t pin) { return ((uint8_t)(pin & 0b11111)); }
103
-constexpr bool LPC1768_PIN_INTERRUPT(const pin_t pin) { return (((pin >> 8) & 0b1) != 0); }
104
-constexpr bool LPC1768_PIN_PWM(const pin_t pin) { return (((pin >> 9) & 0b1) != 0); }
105
-constexpr int8_t LPC1768_PIN_ADC(const pin_t pin) { return (int8_t)((pin >> 10) & 0b1111) - 1; }
106
-
107
-// ******************
108
-// Runtime pinmapping
109
-// ******************
110
-#define P_NC -1
111
-
112
-#if SERIAL_PORT != 3 && SERIAL_PORT_2 != 3
113
-  #define P0_00 LPC1768_PIN(PORT(0), PIN( 0), INTERRUPT(1), PWM(0), ADC_NONE)
114
-  #define P0_01 LPC1768_PIN(PORT(0), PIN( 1), INTERRUPT(1), PWM(0), ADC_NONE)
115
-#endif
116
-#if SERIAL_PORT != 0 && SERIAL_PORT_2 != 0
117
-  #define P0_02 LPC1768_PIN(PORT(0), PIN( 2), INTERRUPT(1), PWM(0), ADC_CHAN(7))
118
-  #define P0_03 LPC1768_PIN(PORT(0), PIN( 3), INTERRUPT(1), PWM(0), ADC_CHAN(6))
119
-#endif
120
-#define P0_04   LPC1768_PIN(PORT(0), PIN( 4), INTERRUPT(1), PWM(0), ADC_NONE)
121
-#define P0_05   LPC1768_PIN(PORT(0), PIN( 5), INTERRUPT(1), PWM(0), ADC_NONE)
122
-#define P0_06   LPC1768_PIN(PORT(0), PIN( 6), INTERRUPT(1), PWM(0), ADC_NONE)
123
-#define P0_07   LPC1768_PIN(PORT(0), PIN( 7), INTERRUPT(1), PWM(0), ADC_NONE)
124
-#define P0_08   LPC1768_PIN(PORT(0), PIN( 8), INTERRUPT(1), PWM(0), ADC_NONE)
125
-#define P0_09   LPC1768_PIN(PORT(0), PIN( 9), INTERRUPT(1), PWM(0), ADC_NONE)
126
-#if SERIAL_PORT != 2 && SERIAL_PORT_2 != 2
127
-  #define P0_10 LPC1768_PIN(PORT(0), PIN(10), INTERRUPT(1), PWM(0), ADC_NONE)
128
-  #define P0_11 LPC1768_PIN(PORT(0), PIN(11), INTERRUPT(1), PWM(0), ADC_NONE)
129
-#endif
130
-#if SERIAL_PORT != 1 && SERIAL_PORT_2 != 1
131
-  #define P0_15 LPC1768_PIN(PORT(0), PIN(15), INTERRUPT(1), PWM(0), ADC_NONE)
132
-  #define P0_16 LPC1768_PIN(PORT(0), PIN(16), INTERRUPT(1), PWM(0), ADC_NONE)
133
-#endif
134
-#define P0_17   LPC1768_PIN(PORT(0), PIN(17), INTERRUPT(1), PWM(0), ADC_NONE)
135
-#define P0_18   LPC1768_PIN(PORT(0), PIN(18), INTERRUPT(1), PWM(0), ADC_NONE)
136
-#define P0_19   LPC1768_PIN(PORT(0), PIN(19), INTERRUPT(1), PWM(0), ADC_NONE)
137
-#define P0_20   LPC1768_PIN(PORT(0), PIN(20), INTERRUPT(1), PWM(0), ADC_NONE)
138
-#define P0_21   LPC1768_PIN(PORT(0), PIN(21), INTERRUPT(1), PWM(0), ADC_NONE)
139
-#define P0_22   LPC1768_PIN(PORT(0), PIN(22), INTERRUPT(1), PWM(0), ADC_NONE)
140
-#define P0_23   LPC1768_PIN(PORT(0), PIN(23), INTERRUPT(1), PWM(0), ADC_CHAN(0))
141
-#define P0_24   LPC1768_PIN(PORT(0), PIN(24), INTERRUPT(1), PWM(0), ADC_CHAN(1))
142
-#define P0_25   LPC1768_PIN(PORT(0), PIN(25), INTERRUPT(1), PWM(0), ADC_CHAN(2))
143
-#define P0_26   LPC1768_PIN(PORT(0), PIN(26), INTERRUPT(1), PWM(0), ADC_CHAN(3))
144
-#define P0_27   LPC1768_PIN(PORT(0), PIN(27), INTERRUPT(1), PWM(0), ADC_NONE)
145
-#define P0_28   LPC1768_PIN(PORT(0), PIN(28), INTERRUPT(1), PWM(0), ADC_NONE)
146
-#if SERIAL_PORT != -1 && SERIAL_PORT_2 != -1
147
-  #define P0_29 LPC1768_PIN(PORT(0), PIN(29), INTERRUPT(1), PWM(0), ADC_NONE)
148
-  #define P0_30 LPC1768_PIN(PORT(0), PIN(30), INTERRUPT(1), PWM(0), ADC_NONE)
149
-#endif
150
-#define P1_00   LPC1768_PIN(PORT(1), PIN( 0), INTERRUPT(0), PWM(0), ADC_NONE)
151
-#define P1_01   LPC1768_PIN(PORT(1), PIN( 1), INTERRUPT(0), PWM(0), ADC_NONE)
152
-#define P1_04   LPC1768_PIN(PORT(1), PIN( 4), INTERRUPT(0), PWM(0), ADC_NONE)
153
-#define P1_08   LPC1768_PIN(PORT(1), PIN( 8), INTERRUPT(0), PWM(0), ADC_NONE)
154
-#define P1_09   LPC1768_PIN(PORT(1), PIN( 9), INTERRUPT(0), PWM(0), ADC_NONE)
155
-#define P1_10   LPC1768_PIN(PORT(1), PIN(10), INTERRUPT(0), PWM(0), ADC_NONE)
156
-#define P1_14   LPC1768_PIN(PORT(1), PIN(14), INTERRUPT(0), PWM(0), ADC_NONE)
157
-#define P1_15   LPC1768_PIN(PORT(1), PIN(15), INTERRUPT(0), PWM(0), ADC_NONE)
158
-#define P1_16   LPC1768_PIN(PORT(1), PIN(16), INTERRUPT(0), PWM(0), ADC_NONE)
159
-#define P1_17   LPC1768_PIN(PORT(1), PIN(17), INTERRUPT(0), PWM(0), ADC_NONE)
160
-#define P1_18   LPC1768_PIN(PORT(1), PIN(18), INTERRUPT(0), PWM(1), ADC_NONE)
161
-#define P1_19   LPC1768_PIN(PORT(1), PIN(19), INTERRUPT(0), PWM(0), ADC_NONE)
162
-#define P1_20   LPC1768_PIN(PORT(1), PIN(20), INTERRUPT(0), PWM(1), ADC_NONE)
163
-#define P1_21   LPC1768_PIN(PORT(1), PIN(21), INTERRUPT(0), PWM(1), ADC_NONE)
164
-#define P1_22   LPC1768_PIN(PORT(1), PIN(22), INTERRUPT(0), PWM(0), ADC_NONE)
165
-#define P1_23   LPC1768_PIN(PORT(1), PIN(23), INTERRUPT(0), PWM(1), ADC_NONE)
166
-#define P1_24   LPC1768_PIN(PORT(1), PIN(24), INTERRUPT(0), PWM(1), ADC_NONE)
167
-#define P1_25   LPC1768_PIN(PORT(1), PIN(25), INTERRUPT(0), PWM(0), ADC_NONE)
168
-#define P1_26   LPC1768_PIN(PORT(1), PIN(26), INTERRUPT(0), PWM(1), ADC_NONE)
169
-#define P1_27   LPC1768_PIN(PORT(1), PIN(27), INTERRUPT(0), PWM(0), ADC_NONE)
170
-#define P1_28   LPC1768_PIN(PORT(1), PIN(28), INTERRUPT(0), PWM(0), ADC_NONE)
171
-#define P1_29   LPC1768_PIN(PORT(1), PIN(29), INTERRUPT(0), PWM(0), ADC_NONE)
172
-#define P1_30   LPC1768_PIN(PORT(1), PIN(30), INTERRUPT(0), PWM(0), ADC_CHAN(4))
173
-#define P1_31   LPC1768_PIN(PORT(1), PIN(31), INTERRUPT(0), PWM(0), ADC_CHAN(5))
174
-#define P2_00   LPC1768_PIN(PORT(2), PIN( 0), INTERRUPT(1), PWM(1), ADC_NONE)
175
-#define P2_01   LPC1768_PIN(PORT(2), PIN( 1), INTERRUPT(1), PWM(1), ADC_NONE)
176
-#define P2_02   LPC1768_PIN(PORT(2), PIN( 2), INTERRUPT(1), PWM(1), ADC_NONE)
177
-#define P2_03   LPC1768_PIN(PORT(2), PIN( 3), INTERRUPT(1), PWM(1), ADC_NONE)
178
-#define P2_04   LPC1768_PIN(PORT(2), PIN( 4), INTERRUPT(1), PWM(1), ADC_NONE)
179
-#define P2_05   LPC1768_PIN(PORT(2), PIN( 5), INTERRUPT(1), PWM(1), ADC_NONE)
180
-#define P2_06   LPC1768_PIN(PORT(2), PIN( 6), INTERRUPT(1), PWM(0), ADC_NONE)
181
-#define P2_07   LPC1768_PIN(PORT(2), PIN( 7), INTERRUPT(1), PWM(0), ADC_NONE)
182
-#define P2_08   LPC1768_PIN(PORT(2), PIN( 8), INTERRUPT(1), PWM(0), ADC_NONE)
183
-#define P2_09   LPC1768_PIN(PORT(2), PIN( 9), INTERRUPT(1), PWM(0), ADC_NONE)
184
-#define P2_10   LPC1768_PIN(PORT(2), PIN(10), INTERRUPT(1), PWM(0), ADC_NONE)
185
-#define P2_11   LPC1768_PIN(PORT(2), PIN(11), INTERRUPT(1), PWM(0), ADC_NONE)
186
-#define P2_12   LPC1768_PIN(PORT(2), PIN(12), INTERRUPT(1), PWM(0), ADC_NONE)
187
-#define P2_13   LPC1768_PIN(PORT(2), PIN(13), INTERRUPT(1), PWM(0), ADC_NONE)
188
-#define P3_25   LPC1768_PIN(PORT(3), PIN(25), INTERRUPT(0), PWM(1), ADC_NONE)
189
-#define P3_26   LPC1768_PIN(PORT(3), PIN(26), INTERRUPT(0), PWM(1), ADC_NONE)
190
-#define P4_28   LPC1768_PIN(PORT(4), PIN(28), INTERRUPT(0), PWM(0), ADC_NONE)
191
-#define P4_29   LPC1768_PIN(PORT(4), PIN(29), INTERRUPT(0), PWM(0), ADC_NONE)
192
-
193
-// Pin index for M43 and M226
194
-constexpr pin_t pin_map[] = {
195
-  #if SERIAL_PORT != 3 && SERIAL_PORT_2 != 3
196
-    P0_00, P0_01,
197
-  #else
198
-    P_NC,  P_NC,
199
-  #endif
200
-  #if SERIAL_PORT != 0 && SERIAL_PORT_2 != 0
201
-                  P0_02, P0_03,
202
-  #else
203
-                  P_NC,  P_NC,
204
-  #endif
205
-                                P0_04, P0_05, P0_06, P0_07,
206
-    P0_08, P0_09,
207
-  #if SERIAL_PORT != 2 && SERIAL_PORT_2 != 2
208
-                  P0_10, P0_11,
209
-  #else
210
-                  P_NC,  P_NC,
211
-  #endif
212
-                                P_NC,  P_NC,  P_NC,
213
-  #if SERIAL_PORT != 1 && SERIAL_PORT_2 != 1
214
-                                                     P0_15,
215
-    P0_16,
216
-  #else
217
-                                                     P_NC,
218
-    P_NC,
219
-  #endif
220
-           P0_17, P0_18, P0_19, P0_20, P0_21, P0_22, P0_23,
221
-    P0_24, P0_25, P0_26, P0_27, P0_28,
222
-  #if SERIAL_PORT != -1 && SERIAL_PORT_2 != -1
223
-                                       P0_29, P0_30,
224
-  #else
225
-                                       P_NC,  P_NC,
226
-  #endif
227
-                                                   P_NC,
228
-
229
-  P1_00, P1_01, P_NC,  P_NC,  P1_04, P_NC,  P_NC,  P_NC,
230
-  P1_08, P1_09, P1_10, P_NC,  P_NC,  P_NC,  P1_14, P1_15,
231
-  P1_16, P1_17, P1_18, P1_19, P1_20, P1_21, P1_22, P1_23,
232
-  P1_24, P1_25, P1_26, P1_27, P1_28, P1_29, P1_30, P1_31,
233
-
234
-  P2_00, P2_01, P2_02, P2_03, P2_04, P2_05, P2_06, P2_07,
235
-  P2_08, P2_09, P2_10, P2_11, P2_12, P2_13, P_NC,  P_NC,
236
-  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,
237
-  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,
238
-
239
-  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,
240
-  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,
241
-  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,
242
-  P_NC,  P3_25, P3_26, P_NC,  P_NC,  P_NC,  P_NC,  P_NC,
243
-
244
-  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,
245
-  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,
246
-  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,  P_NC,
247
-  P_NC,  P_NC,  P_NC,  P_NC,  P4_28, P4_29, P_NC,  P_NC
248
-};
249
-
250
-constexpr uint8_t NUM_DIGITAL_PINS = COUNT(pin_map);
251
-
252
-constexpr pin_t adc_pin_table[] = {
253
-  P0_23, P0_24, P0_25, P0_26, P1_30, P1_31,
254
-  #if SERIAL_PORT != 0 && SERIAL_PORT_2 != 0
255
-    P0_03, P0_02
256
-  #endif
257
-};
258
-
259
-#if SERIAL_PORT != 0 && SERIAL_PORT_2 != 0
260
-  #define NUM_ANALOG_INPUTS 8
261
-#else
262
-  #define NUM_ANALOG_INPUTS 6
263
-#endif
264
-
265
-// P0.6 thru P0.9 are for the onboard SD card
266
-#define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09
267
-
268
-// Get the digital pin for an analog index
269
-pin_t analogInputToDigitalPin(const int8_t p);
270
-#define digitalPinToInterrupt(pin) (pin)
271
-// Return the index of a pin number
272
-// The pin number given here is in the form ppp:nnnnn
273
-int16_t GET_PIN_MAP_INDEX(const pin_t pin);
274
-
275
-// Test whether the pin is valid
276
-bool VALID_PIN(const pin_t p);
277
-
278
-// Get the analog index for a digital pin
279
-int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p);
280
-
281
-// Test whether the pin is PWM
282
-bool PWM_PIN(const pin_t p);
283
-
284
-// Test whether the pin is interruptable
285
-bool INTERRUPT_PIN(const pin_t p);
286
-#define LPC1768_PIN_INTERRUPT_M(pin) (((pin >> 8) & 0b1) != 0)
287
-
288
-// Get the pin number at the given index
289
-pin_t GET_PIN_MAP_PIN(const int16_t ind);
290
-
291
-// Parse a G-code word into a pin index
292
-int16_t PARSED_PIN_INDEX(const char code, const int16_t dval);
293
-
294
-#endif // _PINMAPPING_H_

+ 0
- 161
Marlin/src/HAL/HAL_LPC1768/include/serial.h Просмотреть файл

@@ -1,161 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
- *
21
- */
22
-
23
-#ifndef _HAL_SERIAL_H_
24
-#define _HAL_SERIAL_H_
25
-
26
-#include "../../../inc/MarlinConfigPre.h"
27
-#if ENABLED(EMERGENCY_PARSER)
28
-  #include "../../../feature/emergency_parser.h"
29
-#endif
30
-
31
-#include <stdarg.h>
32
-#include <stdio.h>
33
-#include <Print.h>
34
-
35
-/**
36
- * Generic RingBuffer
37
- * T type of the buffer array
38
- * S size of the buffer (must be power of 2)
39
- */
40
-
41
-template <typename T, uint32_t S> class RingBuffer {
42
-public:
43
-  RingBuffer() {index_read = index_write = 0;}
44
-
45
-  uint32_t available() {return mask(index_write - index_read);}
46
-  uint32_t free() {return buffer_size - available();}
47
-  bool empty() {return index_read == index_write;}
48
-  bool full() {return next(index_write) == index_read;}
49
-  void clear() {index_read = index_write = 0;}
50
-
51
-  bool peek(T *const value) {
52
-    if (value == nullptr || empty()) return false;
53
-    *value = buffer[index_read];
54
-    return true;
55
-  }
56
-
57
-  uint32_t read(T *const value) {
58
-    if (value == nullptr || empty()) return 0;
59
-    *value = buffer[index_read];
60
-    index_read = next(index_read);
61
-    return 1;
62
-  }
63
-
64
-  uint32_t write(T value) {
65
-    uint32_t next_head = next(index_write);
66
-    if (next_head == index_read) return 0;     // buffer full
67
-    buffer[index_write] = value;
68
-    index_write = next_head;
69
-    return 1;
70
-  }
71
-
72
-private:
73
-  inline uint32_t mask(uint32_t val) {
74
-    return val & buffer_mask;
75
-  }
76
-
77
-  inline uint32_t next(uint32_t val) {
78
-    return mask(val + 1);
79
-  }
80
-
81
-  static const uint32_t buffer_size = S;
82
-  static const uint32_t buffer_mask = buffer_size - 1;
83
-  T buffer[buffer_size];
84
-  volatile uint32_t index_write;
85
-  volatile uint32_t index_read;
86
-};
87
-
88
-/**
89
- *  Serial Interface Class
90
- *  Data is injected directly into, and consumed from, the fifo buffers
91
- */
92
-
93
-class HalSerial: public Print {
94
-public:
95
-
96
-  #if ENABLED(EMERGENCY_PARSER)
97
-    EmergencyParser::State emergency_state;
98
-  #endif
99
-
100
-  HalSerial() : host_connected(false) { }
101
-  virtual ~HalSerial() { }
102
-
103
-  operator bool() { return host_connected; }
104
-
105
-  void begin(int32_t baud) { }
106
-
107
-  int16_t peek() {
108
-    uint8_t value;
109
-    return receive_buffer.peek(&value) ? value : -1;
110
-  }
111
-
112
-  int16_t read() {
113
-    uint8_t value;
114
-    return receive_buffer.read(&value) ? value : -1;
115
-  }
116
-
117
-  size_t write(const uint8_t c) {
118
-    if (!host_connected) return 0;          // Do not fill buffer when host disconnected
119
-    while (transmit_buffer.write(c) == 0) { // Block until there is free room in buffer
120
-      if (!host_connected) return 0;        // Break infinite loop on host disconect
121
-    }
122
-    return 1;
123
-  }
124
-
125
-  size_t available() {
126
-    return (size_t)receive_buffer.available();
127
-  }
128
-
129
-  void flush() {
130
-    receive_buffer.clear();
131
-  }
132
-
133
-  uint8_t availableForWrite(void) {
134
-    return transmit_buffer.free() > 255 ? 255 : (uint8_t)transmit_buffer.free();
135
-  }
136
-
137
-  void flushTX(void) {
138
-    while (transmit_buffer.available() && host_connected) { /* nada */}
139
-  }
140
-
141
-  size_t printf(const char *format, ...) {
142
-    static char buffer[256];
143
-    va_list vArgs;
144
-    va_start(vArgs, format);
145
-    int length = vsnprintf((char *) buffer, 256, (char const *) format, vArgs);
146
-    va_end(vArgs);
147
-    size_t i = 0;
148
-    if (length > 0 && length < 256) {
149
-      while (i < (size_t)length && host_connected) {
150
-        i += transmit_buffer.write(buffer[i]);
151
-      }
152
-    }
153
-    return i;
154
-  }
155
-
156
-  RingBuffer<uint8_t, 128> receive_buffer;
157
-  RingBuffer<uint8_t, 128> transmit_buffer;
158
-  volatile bool host_connected;
159
-};
160
-
161
-#endif // _HAL_SERIAL_H_

+ 0
- 60
Marlin/src/HAL/HAL_LPC1768/lpc1768_flag_script.py Просмотреть файл

@@ -1,60 +0,0 @@
1
-from __future__ import print_function
2
-import sys
3
-
4
-#dynamic build flags for generic compile options
5
-if __name__ == "__main__":
6
-  args = " ".join([ "-std=gnu11",
7
-                    "-std=gnu++11",
8
-                    "-Os",
9
-                    "-mcpu=cortex-m3",
10
-                    "-mthumb",
11
-
12
-                    "-fsigned-char",
13
-                    "-fno-move-loop-invariants",
14
-                    "-fno-strict-aliasing",
15
-                    "-fsingle-precision-constant",
16
-
17
-                    "--specs=nano.specs",
18
-                    "--specs=nosys.specs",
19
-
20
-                    # For external libraries
21
-                    "-IMarlin/src/HAL/HAL_LPC1768/include",
22
-
23
-                    # For MarlinFirmware/U8glib-HAL
24
-                    "-IMarlin/src/HAL/HAL_LPC1768/u8g",
25
-                    "-DU8G_HAL_LINKS",
26
-
27
-                    "-MMD",
28
-                    "-MP",
29
-                    "-DTARGET_LPC1768"
30
-                  ])
31
-
32
-  for i in range(1, len(sys.argv)):
33
-    args += " " + sys.argv[i]
34
-
35
-  print(args)
36
-
37
-# extra script for linker options
38
-else:
39
-  from SCons.Script import DefaultEnvironment
40
-  env = DefaultEnvironment()
41
-  env.Append(
42
-      ARFLAGS=["rcs"],
43
-
44
-      ASFLAGS=["-x", "assembler-with-cpp"],
45
-
46
-      CXXFLAGS=[
47
-          "-fabi-version=0",
48
-          "-fno-use-cxa-atexit",
49
-          "-fno-threadsafe-statics"
50
-      ],
51
-      LINKFLAGS=[
52
-          "-Wl,-Tframeworks/CMSIS/LPC1768/system/LPC1768.ld,--gc-sections",
53
-          "-Os",
54
-          "-mcpu=cortex-m3",
55
-          "-mthumb",
56
-          "--specs=nano.specs",
57
-          "--specs=nosys.specs",
58
-          "-u_printf_float"
59
-      ],
60
-  )

+ 28
- 77
Marlin/src/HAL/HAL_LPC1768/main.cpp Просмотреть файл

@@ -1,15 +1,6 @@
1 1
 #ifdef TARGET_LPC1768
2 2
 
3
-// ---------------------
4
-// Userspace entry point
5
-// ---------------------
6
-extern void setup();
7
-extern void loop();
8
-
9
-extern "C" {
10
-  #include <lpc17xx_gpio.h>
11
-}
12
-
3
+#include <LPC1768_PWM.h>
13 4
 #include <usb/usb.h>
14 5
 #include <usb/usbcfg.h>
15 6
 #include <usb/usbhw.h>
@@ -17,80 +8,44 @@ extern "C" {
17 8
 #include <usb/cdc.h>
18 9
 #include <usb/cdcuser.h>
19 10
 #include <usb/mscuser.h>
20
-
21
-extern "C" {
22
-  #include <debug_frmwrk.h>
23
-  #include <chanfs/diskio.h>
24
-  #include <chanfs/ff.h>
25
-}
11
+#include <CDCSerial.h>
26 12
 
27 13
 #include "../../inc/MarlinConfig.h"
28 14
 #include "HAL.h"
29
-#include "fastio.h"
30 15
 #include "HAL_timers.h"
31
-#include <stdio.h>
32
-#include <stdarg.h>
33
-#include <Arduino.h>
34
-#include "serial.h"
35
-#include "LPC1768_PWM.h"
36
-
37
-static __INLINE uint32_t SysTick_Config(uint32_t ticks) {
38
-  if (ticks > SysTick_LOAD_RELOAD_Msk) return 1;
39
-
40
-  SysTick->LOAD = (ticks & SysTick_LOAD_RELOAD_Msk) - 1;        // Set reload register
41
-  SysTick->VAL  = 0;                                            // Load the SysTick Counter Value
42
-  SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk |
43
-                  SysTick_CTRL_TICKINT_Msk   |
44
-                  SysTick_CTRL_ENABLE_Msk;                      // Enable SysTick IRQ and SysTick Timer
45
-
46
-  NVIC_SetPriority(SysTick_IRQn, NVIC_EncodePriority(0, 0, 0)); // Set Priority for Cortex-M3 System Interrupts
47
-  return 0;
48
-}
49
-
50
-extern "C" {
51
-  extern int isLPC1769();
52
-  extern void disk_timerproc(void);
53
-  volatile uint32_t _millis;
54
-
55
-  void SysTick_Handler(void) {
56
-    ++_millis;
57
-    disk_timerproc();
58
-  }
59 16
 
60
-  // Runs after clock init and before global static constructors
61
-  void SystemPostInit() {
62
-    _millis = 0;                            // Initialize the millisecond counter value
63
-    SysTick_Config(SystemCoreClock / 1000); // Start millisecond global counter
64
-
65
-    // Runs before setup() to configure LED_PIN and used to indicate successful bootloader execution
66
-    #if PIN_EXISTS(LED)
67
-      SET_DIR_OUTPUT(LED_PIN);
68
-      WRITE_PIN_CLR(LED_PIN);
69
-
70
-      // MKS_SBASE has 3 other LEDs the bootloader uses during flashing. Clear them.
71
-      SET_DIR_OUTPUT(P1_19);
72
-      WRITE_PIN_CLR(P1_19);
73
-      SET_DIR_OUTPUT(P1_20);
74
-      WRITE_PIN_CLR(P1_20);
75
-      SET_DIR_OUTPUT(P1_21);
76
-      WRITE_PIN_CLR(P1_21);
17
+extern uint32_t MSC_SD_Init(uint8_t pdrv);
18
+extern "C" int isLPC1769();
19
+extern "C" void disk_timerproc(void);
77 20
 
78
-      for (uint8_t i = 6; i--;) {
79
-        TOGGLE(LED_PIN);
80
-        delay(100);
81
-      }
82
-    #endif
83
-  }
21
+void SysTick_Callback() {
22
+  disk_timerproc();
84 23
 }
85 24
 
86
-extern uint32_t MSC_SD_Init(uint8_t pdrv);
87
-
88
-int main(void) {
25
+void HAL_init() {
26
+  #if PIN_EXISTS(LED)
27
+    SET_DIR_OUTPUT(LED_PIN);
28
+    WRITE_PIN_CLR(LED_PIN);
29
+
30
+    // MKS_SBASE has 3 other LEDs the bootloader uses during flashing. Clear them.
31
+    SET_DIR_OUTPUT(P1_19);
32
+    WRITE_PIN_CLR(P1_19);
33
+    SET_DIR_OUTPUT(P1_20);
34
+    WRITE_PIN_CLR(P1_20);
35
+    SET_DIR_OUTPUT(P1_21);
36
+    WRITE_PIN_CLR(P1_21);
37
+
38
+    // Flash status LED 3 times to indicate Marlin has started booting
39
+    for (uint8_t i = 0; i < 6; ++i) {
40
+      TOGGLE(LED_PIN);
41
+      delay(100);
42
+    }
43
+  #endif
89 44
 
90 45
   (void)MSC_SD_Init(0);
91 46
 
92
-  USB_Init();                               // USB Initialization
93
-  USB_Connect(TRUE);                        // USB Connect
47
+  USB_Init();
48
+  USB_Connect(TRUE);
94 49
 
95 50
   const uint32_t usb_timeout = millis() + 2000;
96 51
   while (!USB_Configuration && PENDING(millis(), usb_timeout)) {
@@ -110,11 +65,7 @@ int main(void) {
110 65
   #endif
111 66
 
112 67
   HAL_timer_init();
113
-
114 68
   LPC1768_PWM_init();
115
-
116
-  setup();
117
-  for (;;) loop();
118 69
 }
119 70
 
120 71
 #endif // TARGET_LPC1768

+ 17
- 26
Marlin/src/HAL/HAL_LPC1768/servo_private.h Просмотреть файл

@@ -50,35 +50,26 @@
50 50
 #ifndef SERVO_PRIVATE_H
51 51
 #define SERVO_PRIVATE_H
52 52
 
53
-#include <stdint.h>
53
+#include <LPC1768_Servo.h>
54 54
 
55
-// Macros
56
-//values in microseconds
57
-#define MIN_PULSE_WIDTH       544     // the shortest pulse sent to a servo
58
-#define MAX_PULSE_WIDTH      2400     // the longest pulse sent to a servo
59
-#define DEFAULT_PULSE_WIDTH  1500     // default pulse width when servo is attached
60
-#define REFRESH_INTERVAL    20000     // minimum time to refresh servos in microseconds
55
+class MarlinServo: public Servo  {
56
+  void move(const int value) {
57
+    constexpr uint16_t servo_delay[] = SERVO_DELAY;
58
+    static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
59
+    if (this->attach(0) >= 0) {    // notice the pin number is zero here
60
+      this->write(value);
61 61
 
62
-#define MAX_SERVOS             4
62
+      safe_delay(servo_delay[this->servoIndex]);
63 63
 
64
-#define INVALID_SERVO         255     // flag indicating an invalid servo index
64
+      #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
65
+        this->detach();
66
+        LPC1768_PWM_detach_pin(servo_info[this->servoIndex].Pin.nbr);  // shut down the PWM signal
67
+        LPC1768_PWM_attach_pin(servo_info[this->servoIndex].Pin.nbr, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH, this->servoIndex);  // make sure no one else steals the slot
68
+      #endif
69
+    }
70
+  }
71
+}
65 72
 
66
-
67
-// Types
68
-
69
-typedef struct {
70
-  uint8_t nbr        : 8 ;            // a pin number from 0 to 254 (255 signals invalid pin)
71
-  uint8_t isActive   : 1 ;            // true if this channel is enabled, pin not pulsed if false
72
-} ServoPin_t;
73
-
74
-typedef struct {
75
-  ServoPin_t Pin;
76
-  unsigned int pulse_width;           // pulse width in microseconds
77
-} ServoInfo_t;
78
-
79
-// Global variables
80
-
81
-extern uint8_t ServoCount;
82
-extern ServoInfo_t servo_info[MAX_SERVOS];
73
+#define HAL_SERVO_LIB MarlinServo
83 74
 
84 75
 #endif // SERVO_PRIVATE_H

Marlin/src/HAL/HAL_LPC1768/u8g_com_HAL_LPC1768_hw_spi.cpp → Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp Просмотреть файл

@@ -55,7 +55,7 @@
55 55
 
56 56
 #ifdef TARGET_LPC1768
57 57
 
58
-#include "../../inc/MarlinConfigPre.h"
58
+#include "../../../inc/MarlinConfigPre.h"
59 59
 
60 60
 #if ENABLED(DOGLCD)
61 61
 

Marlin/src/HAL/HAL_LPC1768/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp → Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp Просмотреть файл

@@ -77,7 +77,7 @@
77 77
 
78 78
 #ifdef TARGET_LPC1768
79 79
 
80
-#include "../../inc/MarlinConfigPre.h"
80
+#include "../../../inc/MarlinConfigPre.h"
81 81
 
82 82
 #if ENABLED(DOGLCD)
83 83
 

Marlin/src/HAL/HAL_LPC1768/u8g_com_HAL_LPC1768_ssd_sw_i2c.cpp under construction → Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_sw_i2c.cpp under construction Просмотреть файл


Marlin/src/HAL/HAL_LPC1768/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp → Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp Просмотреть файл

@@ -55,13 +55,13 @@
55 55
 
56 56
 #ifdef TARGET_LPC1768
57 57
 
58
-#include "../../inc/MarlinConfigPre.h"
58
+#include "../../../inc/MarlinConfigPre.h"
59 59
 
60 60
 #if ENABLED(DOGLCD)
61 61
 
62 62
 //#include <inttypes.h>
63 63
 #include <U8glib.h>
64
-#include "../shared/Delay.h"
64
+#include "../../shared/Delay.h"
65 65
 
66 66
 #define SPI_FULL_SPEED 0
67 67
 #define SPI_HALF_SPEED 1

Marlin/src/HAL/HAL_LPC1768/u8g_com_HAL_LPC1768_st7920_sw_spi.cpp → Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_sw_spi.cpp Просмотреть файл

@@ -55,13 +55,13 @@
55 55
 
56 56
 #ifdef TARGET_LPC1768
57 57
 
58
-#include "../../inc/MarlinConfigPre.h"
58
+#include "../../../inc/MarlinConfigPre.h"
59 59
 
60 60
 #if ENABLED(DOGLCD)
61 61
 
62 62
 #include <U8glib.h>
63 63
 #include "SoftwareSPI.h"
64
-#include "../shared/Delay.h"
64
+#include "../../shared/Delay.h"
65 65
 
66 66
 #define SPI_SPEED 3  // About 1 MHz
67 67
 

Marlin/src/HAL/HAL_LPC1768/u8g_com_HAL_LPC1768_sw_spi.cpp → Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp Просмотреть файл

@@ -55,7 +55,7 @@
55 55
 
56 56
 #ifdef TARGET_LPC1768
57 57
 
58
-#include "../../inc/MarlinConfigPre.h"
58
+#include "../../../inc/MarlinConfigPre.h"
59 59
 
60 60
 #if ENABLED(DOGLCD)
61 61
 

+ 13
- 0
Marlin/src/HAL/HAL_LPC1768/usb_serial.cpp Просмотреть файл

@@ -0,0 +1,13 @@
1
+#ifdef TARGET_LPC1768
2
+#include "../../inc/MarlinConfigPre.h"
3
+
4
+#if ENABLED(EMERGENCY_PARSER)
5
+  #include "../../feature/emergency_parser.h"
6
+  EmergencyParser::State emergency_state;
7
+  bool CDC_RecvCallback(const char buffer) {
8
+    emergency_parser.update(emergency_state, buffer);
9
+    return true;
10
+  }
11
+#endif // ENABLED(EMERGENCY_PARSER)
12
+
13
+#endif // TARGET_LPC1768

frameworks/CMSIS/LPC1768/lib/usb/Re-ARM_usb_driver.inf → Marlin/src/HAL/HAL_LPC1768/win_usb_driver/lpc176x_usb_driver.inf Просмотреть файл


+ 1
- 1
Marlin/src/HAL/shared/servo.h Просмотреть файл

@@ -73,7 +73,7 @@
73 73
 #elif IS_TEENSY35 || IS_TEENSY36
74 74
   #include "../HAL_TEENSY35_36/HAL_Servo_Teensy.h"
75 75
 #elif defined(TARGET_LPC1768)
76
-  #include "../HAL_LPC1768/LPC1768_Servo.h"
76
+  #include "../HAL_LPC1768/servo_private.h"
77 77
 #elif defined(__STM32F1__) || defined(TARGET_STM32F1)
78 78
   #include "../HAL_STM32F1/HAL_Servo_STM32F1.h"
79 79
 #elif defined(STM32GENERIC) && defined(STM32F4)

+ 0
- 306
frameworks/CMSIS/LPC1768/driver/debug_frmwrk.c Просмотреть файл

@@ -1,306 +0,0 @@
1
-/**********************************************************************
2
-* $Id$    debug_frmwrk.c        2010-05-21
3
-*
4
-* @file   debug_frmwrk.c
5
-* @brief  Contains some utilities that used for debugging through UART
6
-* @version  2.0
7
-* @date   21. May. 2010
8
-* @author NXP MCU SW Application Team
9
-*
10
-* Copyright(C) 2010, NXP Semiconductor
11
-* All rights reserved.
12
-*
13
-***********************************************************************
14
-* Software that is described herein is for illustrative purposes only
15
-* which provides customers with programming information regarding the
16
-* products. This software is supplied "AS IS" without any warranties.
17
-* NXP Semiconductors assumes no responsibility or liability for the
18
-* use of the software, conveys no license or title under any patent,
19
-* copyright, or mask work right to the product. NXP Semiconductors
20
-* reserves the right to make changes in the software without
21
-* notification. NXP Semiconductors also make no representation or
22
-* warranty that such application will be suitable for the specified
23
-* use without further testing or modification.
24
-* Permission to use, copy, modify, and distribute this software and its
25
-* documentation is hereby granted, under NXP Semiconductors'
26
-* relevant copyright in the software, without fee, provided that it
27
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
28
-* copyright, permission, and disclaimer notice must appear in all copies of
29
-* this code.
30
-**********************************************************************/
31
-
32
-#include "debug_frmwrk.h"
33
-#include "lpc17xx_pinsel.h"
34
-
35
-/* If this source file built with example, the LPC17xx FW library configuration
36
- * file in each example directory ("lpc17xx_libcfg.h") must be included,
37
- * otherwise the default FW library configuration file must be included instead
38
- */
39
-#ifdef __BUILD_WITH_EXAMPLE__
40
-  #include "lpc17xx_libcfg.h"
41
-#else
42
-  #include "lpc17xx_libcfg_default.h"
43
-#endif
44
-
45
-#ifdef _DBGFWK
46
-
47
-/* Debug framework */
48
-static Bool debug_frmwrk_initialized = FALSE;
49
-
50
-void (*_db_msg)(LPC_UART_TypeDef *UARTx, const void *s) = UARTPuts;
51
-void (*_db_msg_)(LPC_UART_TypeDef *UARTx, const void *s) = UARTPuts_;
52
-void (*_db_char)(LPC_UART_TypeDef *UARTx, uint8_t ch) = UARTPutChar;
53
-void (*_db_dec)(LPC_UART_TypeDef *UARTx, uint8_t decn) = UARTPutHex;
54
-void (*_db_dec_16)(LPC_UART_TypeDef *UARTx, uint16_t decn) = UARTPutHex16;
55
-void (*_db_dec_32)(LPC_UART_TypeDef *UARTx, uint32_t decn) = UARTPutHex32;
56
-void (*_db_hex)(LPC_UART_TypeDef *UARTx, uint8_t hexn) = UARTPutDec;
57
-void (*_db_hex_16)(LPC_UART_TypeDef *UARTx, uint16_t hexn) = UARTPutDec16;
58
-void (*_db_hex_32)(LPC_UART_TypeDef *UARTx, uint32_t hexn) = UARTPutDec32;
59
-uint8_t (*_db_get_char)(LPC_UART_TypeDef *UARTx) = UARTGetChar;
60
-
61
-
62
-/*********************************************************************//**
63
- * @brief   Puts a character to UART port
64
- * @param[in] UARTx Pointer to UART peripheral
65
- * @param[in] ch    Character to put
66
- * @return    None
67
- **********************************************************************/
68
-void UARTPutChar(LPC_UART_TypeDef *UARTx, uint8_t ch) {
69
-  if (debug_frmwrk_initialized)
70
-    UART_Send(UARTx, &ch, 1, BLOCKING);
71
-}
72
-
73
-/*********************************************************************//**
74
- * @brief   Get a character to UART port
75
- * @param[in] UARTx Pointer to UART peripheral
76
- * @return    character value that returned
77
- **********************************************************************/
78
-uint8_t UARTGetChar(LPC_UART_TypeDef *UARTx) {
79
-  uint8_t tmp = 0;
80
-
81
-  if (debug_frmwrk_initialized)
82
-    UART_Receive(UARTx, &tmp, 1, BLOCKING);
83
-
84
-  return(tmp);
85
-}
86
-
87
-/*********************************************************************//**
88
- * @brief   Puts a string to UART port
89
- * @param[in] UARTx   Pointer to UART peripheral
90
- * @param[in] str   string to put
91
- * @return    None
92
- **********************************************************************/
93
-void UARTPuts(LPC_UART_TypeDef *UARTx, const void *str) {
94
-  if (!debug_frmwrk_initialized) return;
95
-
96
-  uint8_t *s = (uint8_t*)str;
97
-  while (*s) UARTPutChar(UARTx, *s++);
98
-}
99
-
100
-/*********************************************************************//**
101
- * @brief   Puts a string to UART port and print new line
102
- * @param[in] UARTx Pointer to UART peripheral
103
- * @param[in] str   String to put
104
- * @return    None
105
- **********************************************************************/
106
-void UARTPuts_(LPC_UART_TypeDef *UARTx, const void *str) {
107
-  if (!debug_frmwrk_initialized) return;
108
-
109
-  UARTPuts (UARTx, str);
110
-  UARTPuts (UARTx, "\n\r");
111
-}
112
-
113
-/*********************************************************************//**
114
- * @brief   Puts a decimal number to UART port
115
- * @param[in] UARTx Pointer to UART peripheral
116
- * @param[in] decnum  Decimal number (8-bit long)
117
- * @return    None
118
- **********************************************************************/
119
-void UARTPutDec(LPC_UART_TypeDef *UARTx, uint8_t decnum) {
120
-  if (!debug_frmwrk_initialized) return;
121
-
122
-  uint8_t c1 = decnum%10;
123
-  uint8_t c2 = (decnum /             10) % 10;
124
-  uint8_t c3 = (decnum /            100) % 10;
125
-  UARTPutChar(UARTx, '0'+c3);
126
-  UARTPutChar(UARTx, '0'+c2);
127
-  UARTPutChar(UARTx, '0'+c1);
128
-}
129
-
130
-/*********************************************************************//**
131
- * @brief   Puts a decimal number to UART port
132
- * @param[in] UARTx Pointer to UART peripheral
133
- * @param[in] decnum  Decimal number (8-bit long)
134
- * @return    None
135
- **********************************************************************/
136
-void UARTPutDec16(LPC_UART_TypeDef *UARTx, uint16_t decnum) {
137
-  if (!debug_frmwrk_initialized) return;
138
-
139
-  uint8_t c1 = decnum%10;
140
-  uint8_t c2 = (decnum /             10) % 10;
141
-  uint8_t c3 = (decnum /            100) % 10;
142
-  uint8_t c4 = (decnum /           1000) % 10;
143
-  uint8_t c5 = (decnum /          10000) % 10;
144
-  UARTPutChar(UARTx, '0'+c5);
145
-  UARTPutChar(UARTx, '0'+c4);
146
-  UARTPutChar(UARTx, '0'+c3);
147
-  UARTPutChar(UARTx, '0'+c2);
148
-  UARTPutChar(UARTx, '0'+c1);
149
-}
150
-
151
-/*********************************************************************//**
152
- * @brief   Puts a decimal number to UART port
153
- * @param[in] UARTx Pointer to UART peripheral
154
- * @param[in] decnum  Decimal number (8-bit long)
155
- * @return    None
156
- **********************************************************************/
157
-void UARTPutDec32(LPC_UART_TypeDef *UARTx, uint32_t decnum) {
158
-  if (!debug_frmwrk_initialized) return;
159
-
160
-  const uint8_t  c1 =  decnum               % 10,
161
-                 c2 = (decnum /         10) % 10,
162
-                 c3 = (decnum /        100) % 10,
163
-                 c4 = (decnum /       1000) % 10,
164
-                 c5 = (decnum /      10000) % 10,
165
-                 c6 = (decnum /     100000) % 10,
166
-                 c7 = (decnum /    1000000) % 10,
167
-                 c8 = (decnum /   10000000) % 10,
168
-                 c9 = (decnum /  100000000) % 10,
169
-                c10 = (decnum / 1000000000) % 10;
170
-  UARTPutChar(UARTx, '0' + c10);
171
-  UARTPutChar(UARTx, '0' +  c9);
172
-  UARTPutChar(UARTx, '0' +  c8);
173
-  UARTPutChar(UARTx, '0' +  c7);
174
-  UARTPutChar(UARTx, '0' +  c6);
175
-  UARTPutChar(UARTx, '0' +  c5);
176
-  UARTPutChar(UARTx, '0' +  c4);
177
-  UARTPutChar(UARTx, '0' +  c3);
178
-  UARTPutChar(UARTx, '0' +  c2);
179
-  UARTPutChar(UARTx, '0' +  c1);
180
-}
181
-
182
-/*********************************************************************//**
183
- * @brief   Puts a hex number to UART port
184
- * @param[in] UARTx Pointer to UART peripheral
185
- * @param[in] hexnum  Hex number (8-bit long)
186
- * @return    None
187
- **********************************************************************/
188
-void UARTPutHex(LPC_UART_TypeDef *UARTx, uint8_t hexnum) {
189
-  if (!debug_frmwrk_initialized) return;
190
-
191
-  UARTPuts(UARTx, "0x");
192
-  uint8_t nibble, i = 1;
193
-  do {
194
-    nibble = (hexnum >> (4 * i)) & 0x0F;
195
-    UARTPutChar(UARTx, (nibble > 9) ? ('A' + nibble - 10) : ('0' + nibble));
196
-  } while (i--);
197
-}
198
-
199
-/*********************************************************************//**
200
- * @brief   Puts a hex number to UART port
201
- * @param[in] UARTx Pointer to UART peripheral
202
- * @param[in] hexnum  Hex number (16-bit long)
203
- * @return    None
204
- **********************************************************************/
205
-void UARTPutHex16(LPC_UART_TypeDef *UARTx, uint16_t hexnum) {
206
-  if (!debug_frmwrk_initialized) return;
207
-
208
-  UARTPuts(UARTx, "0x");
209
-  uint8_t nibble, i = 3;
210
-  do {
211
-    nibble = (hexnum >> (4 * i)) & 0x0F;
212
-    UARTPutChar(UARTx, (nibble > 9) ? ('A' + nibble - 10) : ('0' + nibble));
213
-  } while (i--);
214
-}
215
-
216
-/*********************************************************************//**
217
- * @brief   Puts a hex number to UART port
218
- * @param[in] UARTx Pointer to UART peripheral
219
- * @param[in] hexnum  Hex number (32-bit long)
220
- * @return    None
221
- **********************************************************************/
222
-void UARTPutHex32(LPC_UART_TypeDef *UARTx, uint32_t hexnum) {
223
-  if (!debug_frmwrk_initialized) return;
224
-
225
-  UARTPuts(UARTx, "0x");
226
-  uint8_t nibble, i = 7;
227
-  do {
228
-    nibble = (hexnum >> (4 * i)) & 0x0F;
229
-    UARTPutChar(UARTx, (nibble > 9) ? ('A' + nibble - 10) : ('0' + nibble));
230
-  } while (i--);
231
-}
232
-
233
-/*********************************************************************//**
234
- * @brief   print function that supports format as same as printf()
235
- *        function of <stdio.h> library
236
- * @param[in] None
237
- * @return    None
238
- **********************************************************************/
239
-//void  _printf (const  char *format, ...) {
240
-//  static  char  buffer[512 + 1];
241
-//          va_list     vArgs;
242
-//          char  *tmp;
243
-//  va_start(vArgs, format);
244
-//  vsprintf((char *)buffer, (char const *)format, vArgs);
245
-//  va_end(vArgs);
246
-//
247
-//  _DBG(buffer);
248
-//}
249
-
250
-/*********************************************************************//**
251
- * @brief   Initialize Debug frame work through initializing UART port
252
- * @param[in] None
253
- * @return    None
254
- **********************************************************************/
255
-void debug_frmwrk_init(void) {
256
-  UART_CFG_Type UARTConfigStruct;
257
-  PINSEL_CFG_Type PinCfg;
258
-
259
-  #if (USED_UART_DEBUG_PORT==0)
260
-    /*
261
-     * Initialize UART0 pin connect
262
-     */
263
-    PinCfg.Funcnum = 1;
264
-    PinCfg.OpenDrain = 0;
265
-    PinCfg.Pinmode = 0;
266
-    PinCfg.Pinnum = 2;
267
-    PinCfg.Portnum = 0;
268
-    PINSEL_ConfigPin(&PinCfg);
269
-    PinCfg.Pinnum = 3;
270
-    PINSEL_ConfigPin(&PinCfg);
271
-
272
-  #elif (USED_UART_DEBUG_PORT==1)
273
-    /*
274
-     * Initialize UART1 pin connect
275
-     */
276
-    PinCfg.Funcnum = 1;
277
-    PinCfg.OpenDrain = 0;
278
-    PinCfg.Pinmode = 0;
279
-    PinCfg.Pinnum = 15;
280
-    PinCfg.Portnum = 0;
281
-    PINSEL_ConfigPin(&PinCfg);
282
-    PinCfg.Pinnum = 16;
283
-    PINSEL_ConfigPin(&PinCfg);
284
-  #endif
285
-
286
-  /* Initialize UART Configuration parameter structure to default state:
287
-   * Baudrate = 9600bps
288
-   * 8 data bit
289
-   * 1 Stop bit
290
-   * None parity
291
-   */
292
-  UART_ConfigStructInit(&UARTConfigStruct);
293
-
294
-  // Re-configure baudrate to 115200bps
295
-  UARTConfigStruct.Baud_rate = 115200;
296
-
297
-  // Initialize DEBUG_UART_PORT peripheral with given to corresponding parameter
298
-  UART_Init((LPC_UART_TypeDef *)DEBUG_UART_PORT, &UARTConfigStruct);
299
-
300
-  // Enable UART Transmit
301
-  UART_TxCmd((LPC_UART_TypeDef *)DEBUG_UART_PORT, ENABLE);
302
-
303
-  debug_frmwrk_initialized = TRUE;
304
-}
305
-
306
-#endif // _DBGFWK

+ 0
- 358
frameworks/CMSIS/LPC1768/driver/lpc17xx_adc.c Просмотреть файл

@@ -1,358 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_adc.c				2010-06-18
3
-*//**
4
-* @file		lpc17xx_adc.c
5
-* @brief	Contains all functions support for ADC firmware library on LPC17xx
6
-* @version	3.1
7
-* @date		26. July. 2011
8
-* @author	NXP MCU SW Application Team
9
-*
10
-* Copyright(C) 2011, NXP Semiconductor
11
-* All rights reserved.
12
-*
13
-***********************************************************************
14
-* Software that is described herein is for illustrative purposes only
15
-* which provides customers with programming information regarding the
16
-* products. This software is supplied "AS IS" without any warranties.
17
-* NXP Semiconductors assumes no responsibility or liability for the
18
-* use of the software, conveys no license or title under any patent,
19
-* copyright, or mask work right to the product. NXP Semiconductors
20
-* reserves the right to make changes in the software without
21
-* notification. NXP Semiconductors also make no representation or
22
-* warranty that such application will be suitable for the specified
23
-* use without further testing or modification.
24
-* Permission to use, copy, modify, and distribute this software and its
25
-* documentation is hereby granted, under NXP Semiconductors'
26
-* relevant copyright in the software, without fee, provided that it
27
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
28
-* copyright, permission, and disclaimer notice must appear in all copies of
29
-* this code.
30
-**********************************************************************/
31
-
32
-/* Peripheral group ----------------------------------------------------------- */
33
-/** @addtogroup ADC
34
- * @{
35
- */
36
-
37
-/* Includes ------------------------------------------------------------------- */
38
-#include "lpc17xx_adc.h"
39
-#include "lpc17xx_clkpwr.h"
40
-
41
-/* If this source file built with example, the LPC17xx FW library configuration
42
- * file in each example directory ("lpc17xx_libcfg.h") must be included,
43
- * otherwise the default FW library configuration file must be included instead
44
- */
45
-#ifdef __BUILD_WITH_EXAMPLE__
46
-#include "lpc17xx_libcfg.h"
47
-#else
48
-#include "lpc17xx_libcfg_default.h"
49
-#endif /* __BUILD_WITH_EXAMPLE__ */
50
-
51
-
52
-#ifdef _ADC
53
-
54
-/* Public Functions ----------------------------------------------------------- */
55
-/** @addtogroup ADC_Public_Functions
56
- * @{
57
- */
58
-
59
-/*********************************************************************//**
60
- * @brief 		Initial for ADC
61
- * 					+ Set bit PCADC
62
- * 					+ Set clock for ADC
63
- * 					+ Set Clock Frequency
64
- * @param[in]	ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
65
- * @param[in]	rate ADC conversion rate, should be <=200KHz
66
- * @return 		None
67
- **********************************************************************/
68
-void ADC_Init(LPC_ADC_TypeDef *ADCx, uint32_t rate)
69
-{
70
-	uint32_t ADCPClk, temp, tmp;
71
-
72
-	CHECK_PARAM(PARAM_ADCx(ADCx));
73
-	CHECK_PARAM(PARAM_ADC_RATE(rate));
74
-
75
-	// Turn on power and clock
76
-	CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCAD, ENABLE);
77
-
78
-	ADCx->ADCR = 0;
79
-
80
-	//Enable PDN bit
81
-	tmp = ADC_CR_PDN;
82
-	// Set clock frequency
83
-	ADCPClk = CLKPWR_GetPCLK(CLKPWR_PCLKSEL_ADC);
84
-	/* The APB clock (PCLK_ADC0) is divided by (CLKDIV+1) to produce the clock for
85
-	 * A/D converter, which should be less than or equal to 13MHz.
86
-	 * A fully conversion requires 65 of these clocks.
87
-	 * ADC clock = PCLK_ADC0 / (CLKDIV + 1);
88
-	 * ADC rate = ADC clock / 65;
89
-	 */
90
-	temp = rate * 65;
91
-	temp = (ADCPClk * 2 + temp)/(2 * temp) - 1; //get the round value by fomular: (2*A + B)/(2*B)
92
-	tmp |=  ADC_CR_CLKDIV(temp);
93
-
94
-	ADCx->ADCR = tmp;
95
-}
96
-
97
-
98
-/*********************************************************************//**
99
-* @brief 		Close ADC
100
-* @param[in]	ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
101
-* @return 		None
102
-**********************************************************************/
103
-void ADC_DeInit(LPC_ADC_TypeDef *ADCx)
104
-{
105
-	CHECK_PARAM(PARAM_ADCx(ADCx));
106
-    if (ADCx->ADCR & ADC_CR_START_MASK) //need to stop START bits before DeInit
107
-        ADCx->ADCR &= ~ADC_CR_START_MASK;
108
-     // Clear SEL bits
109
-    ADCx->ADCR &= ~0xFF;
110
-	// Clear PDN bit
111
-	ADCx->ADCR &= ~ADC_CR_PDN;
112
-	// Turn on power and clock
113
-	CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCAD, DISABLE);
114
-}
115
-
116
-
117
-/*********************************************************************//**
118
-* @brief 		Get Result conversion from A/D data register
119
-* @param[in]	channel number which want to read back the result
120
-* @return 		Result of conversion
121
-*********************************************************************/
122
-uint32_t ADC_GetData(uint32_t channel)
123
-{
124
-	uint32_t adc_value;
125
-
126
-	CHECK_PARAM(PARAM_ADC_CHANNEL_SELECTION(channel));
127
-
128
-	adc_value = *(uint32_t *)((&LPC_ADC->ADDR0) + channel);
129
-	return ADC_GDR_RESULT(adc_value);
130
-}
131
-
132
-/*********************************************************************//**
133
-* @brief 		Set start mode for ADC
134
-* @param[in]	ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
135
-* @param[in]	start_mode Start mode choose one of modes in
136
-* 				'ADC_START_OPT' enumeration type definition, should be:
137
-* 				- ADC_START_CONTINUOUS
138
-* 				- ADC_START_NOW
139
-* 				- ADC_START_ON_EINT0
140
-* 				- ADC_START_ON_CAP01
141
-*				- ADC_START_ON_MAT01
142
-*				- ADC_START_ON_MAT03
143
-*				- ADC_START_ON_MAT10
144
-*				- ADC_START_ON_MAT11
145
-* @return 		None
146
-*********************************************************************/
147
-void ADC_StartCmd(LPC_ADC_TypeDef *ADCx, uint8_t start_mode)
148
-{
149
-	CHECK_PARAM(PARAM_ADCx(ADCx));
150
-	CHECK_PARAM(PARAM_ADC_START_OPT(start_mode));
151
-
152
-	ADCx->ADCR &= ~ADC_CR_START_MASK;
153
-	ADCx->ADCR |=ADC_CR_START_MODE_SEL((uint32_t)start_mode);
154
-}
155
-
156
-
157
-/*********************************************************************//**
158
-* @brief 		ADC Burst mode setting
159
-* @param[in]	ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
160
-* @param[in]	NewState
161
-* 				-	1: Set Burst mode
162
-* 				-	0: reset Burst mode
163
-* @return 		None
164
-**********************************************************************/
165
-void ADC_BurstCmd(LPC_ADC_TypeDef *ADCx, FunctionalState NewState)
166
-{
167
-	CHECK_PARAM(PARAM_ADCx(ADCx));
168
-
169
-	ADCx->ADCR &= ~ADC_CR_BURST;
170
-	if (NewState){
171
-		ADCx->ADCR |= ADC_CR_BURST;
172
-	}
173
-}
174
-
175
-/*********************************************************************//**
176
-* @brief 		Set AD conversion in power mode
177
-* @param[in]	ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
178
-* @param[in]	NewState
179
-* 				-	1: AD converter is optional
180
-* 				-	0: AD Converter is in power down mode
181
-* @return 		None
182
-**********************************************************************/
183
-void ADC_PowerdownCmd(LPC_ADC_TypeDef *ADCx, FunctionalState NewState)
184
-{
185
-	CHECK_PARAM(PARAM_ADCx(ADCx));
186
-
187
-	ADCx->ADCR &= ~ADC_CR_PDN;
188
-	if (NewState){
189
-		ADCx->ADCR |= ADC_CR_PDN;
190
-	}
191
-}
192
-
193
-/*********************************************************************//**
194
-* @brief 		Set Edge start configuration
195
-* @param[in]	ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
196
-* @param[in]	EdgeOption is ADC_START_ON_RISING and ADC_START_ON_FALLING
197
-* 					0:ADC_START_ON_RISING
198
-* 					1:ADC_START_ON_FALLING
199
-* @return 		None
200
-**********************************************************************/
201
-void ADC_EdgeStartConfig(LPC_ADC_TypeDef *ADCx, uint8_t EdgeOption)
202
-{
203
-	CHECK_PARAM(PARAM_ADCx(ADCx));
204
-	CHECK_PARAM(PARAM_ADC_START_ON_EDGE_OPT(EdgeOption));
205
-
206
-	ADCx->ADCR &= ~ADC_CR_EDGE;
207
-	if (EdgeOption){
208
-		ADCx->ADCR |= ADC_CR_EDGE;
209
-	}
210
-}
211
-
212
-/*********************************************************************//**
213
-* @brief 		ADC interrupt configuration
214
-* @param[in]	ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
215
-* @param[in]	IntType: type of interrupt, should be:
216
-* 				- ADC_ADINTEN0: Interrupt channel 0
217
-* 				- ADC_ADINTEN1: Interrupt channel 1
218
-* 				...
219
-* 				- ADC_ADINTEN7: Interrupt channel 7
220
-* 				- ADC_ADGINTEN: Individual channel/global flag done generate an interrupt
221
-* @param[in]	NewState:
222
-* 					- SET : enable ADC interrupt
223
-* 					- RESET: disable ADC interrupt
224
-* @return 		None
225
-**********************************************************************/
226
-void ADC_IntConfig (LPC_ADC_TypeDef *ADCx, ADC_TYPE_INT_OPT IntType, FunctionalState NewState)
227
-{
228
-	CHECK_PARAM(PARAM_ADCx(ADCx));
229
-	CHECK_PARAM(PARAM_ADC_TYPE_INT_OPT(IntType));
230
-
231
-	ADCx->ADINTEN &= ~ADC_INTEN_CH(IntType);
232
-	if (NewState){
233
-		ADCx->ADINTEN |= ADC_INTEN_CH(IntType);
234
-	}
235
-}
236
-
237
-/*********************************************************************//**
238
-* @brief 		Enable/Disable ADC channel number
239
-* @param[in]	ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
240
-* @param[in]	Channel channel number
241
-* @param[in]	NewState Enable or Disable
242
-*
243
-* @return 		None
244
-**********************************************************************/
245
-void ADC_ChannelCmd (LPC_ADC_TypeDef *ADCx, uint8_t Channel, FunctionalState NewState)
246
-{
247
-	CHECK_PARAM(PARAM_ADCx(ADCx));
248
-	CHECK_PARAM(PARAM_ADC_CHANNEL_SELECTION(Channel));
249
-
250
-	if (NewState == ENABLE) {
251
-		ADCx->ADCR |= ADC_CR_CH_SEL(Channel);
252
-	} else {
253
-        if (ADCx->ADCR & ADC_CR_START_MASK) //need to stop START bits before disable channel
254
-		   ADCx->ADCR &= ~ADC_CR_START_MASK;
255
-		ADCx->ADCR &= ~ADC_CR_CH_SEL(Channel);
256
-	}
257
-}
258
-
259
-/*********************************************************************//**
260
-* @brief 		Get ADC result
261
-* @param[in]	ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
262
-* @param[in]	channel: channel number, should be 0...7
263
-* @return 		Data conversion
264
-**********************************************************************/
265
-uint16_t ADC_ChannelGetData(LPC_ADC_TypeDef *ADCx, uint8_t channel)
266
-{
267
-	uint32_t adc_value;
268
-
269
-	CHECK_PARAM(PARAM_ADCx(ADCx));
270
-	CHECK_PARAM(PARAM_ADC_CHANNEL_SELECTION(channel));
271
-
272
-	adc_value = *(uint32_t *) ((&ADCx->ADDR0) + channel);
273
-	return ADC_DR_RESULT(adc_value);
274
-}
275
-
276
-/*********************************************************************//**
277
-* @brief 		Get ADC Chanel status from ADC data register
278
-* @param[in]	ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
279
-* @param[in]	channel: channel number, should be 0..7
280
-* @param[in]  	StatusType
281
-*              		 	0:Burst status
282
-*               		1:Done 	status
283
-* @return 		SET / RESET
284
-**********************************************************************/
285
-FlagStatus ADC_ChannelGetStatus(LPC_ADC_TypeDef *ADCx, uint8_t channel, uint32_t StatusType)
286
-{
287
-	uint32_t temp;
288
-
289
-	CHECK_PARAM(PARAM_ADCx(ADCx));
290
-	CHECK_PARAM(PARAM_ADC_CHANNEL_SELECTION(channel));
291
-	CHECK_PARAM(PARAM_ADC_DATA_STATUS(StatusType));
292
-
293
-	temp =  *(uint32_t *) ((&ADCx->ADDR0) + channel);
294
-	if (StatusType) {
295
-		temp &= ADC_DR_DONE_FLAG;
296
-	}else{
297
-		temp &= ADC_DR_OVERRUN_FLAG;
298
-	}
299
-	if (temp) {
300
-		return SET;
301
-	} else {
302
-		return RESET;
303
-	}
304
-
305
-}
306
-
307
-/*********************************************************************//**
308
-* @brief 		Get ADC Data from AD Global register
309
-* @param[in]	ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
310
-* @return 		Result of conversion
311
-**********************************************************************/
312
-uint32_t ADC_GlobalGetData(LPC_ADC_TypeDef *ADCx)
313
-{
314
-	CHECK_PARAM(PARAM_ADCx(ADCx));
315
-
316
-	return ((uint32_t)(ADCx->ADGDR));
317
-}
318
-
319
-/*********************************************************************//**
320
-* @brief 		Get ADC Chanel status from AD global data register
321
-* @param[in]	ADCx pointer to LPC_ADC_TypeDef, should be: LPC_ADC
322
-* @param[in]  	StatusType
323
-*              		 	0:Burst status
324
-*               		1:Done 	status
325
-* @return 		SET / RESET
326
-**********************************************************************/
327
-FlagStatus	ADC_GlobalGetStatus(LPC_ADC_TypeDef *ADCx, uint32_t StatusType)
328
-{
329
-	uint32_t temp;
330
-
331
-	CHECK_PARAM(PARAM_ADCx(ADCx));
332
-	CHECK_PARAM(PARAM_ADC_DATA_STATUS(StatusType));
333
-
334
-	temp =  ADCx->ADGDR;
335
-	if (StatusType){
336
-		temp &= ADC_DR_DONE_FLAG;
337
-	}else{
338
-		temp &= ADC_DR_OVERRUN_FLAG;
339
-	}
340
-	if (temp){
341
-		return SET;
342
-	}else{
343
-		return RESET;
344
-	}
345
-}
346
-
347
-/**
348
- * @}
349
- */
350
-
351
-#endif /* _ADC */
352
-
353
-/**
354
- * @}
355
- */
356
-
357
-/* --------------------------------- End Of File ------------------------------ */
358
-

+ 0
- 1936
frameworks/CMSIS/LPC1768/driver/lpc17xx_can.c
Разница между файлами не показана из-за своего большого размера
Просмотреть файл


+ 0
- 350
frameworks/CMSIS/LPC1768/driver/lpc17xx_clkpwr.c Просмотреть файл

@@ -1,350 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_clkpwr.c				2010-06-18
3
-*//**
4
-* @file		lpc17xx_clkpwr.c
5
-* @brief	Contains all functions support for Clock and Power Control
6
-* 			firmware library on LPC17xx
7
-* @version	3.0
8
-* @date		18. June. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @addtogroup CLKPWR
35
- * @{
36
- */
37
-
38
-/* Includes ------------------------------------------------------------------- */
39
-#include "lpc17xx_clkpwr.h"
40
-
41
-
42
-/* Public Functions ----------------------------------------------------------- */
43
-/** @addtogroup CLKPWR_Public_Functions
44
- * @{
45
- */
46
-
47
-/*********************************************************************//**
48
- * @brief 		Set value of each Peripheral Clock Selection
49
- * @param[in]	ClkType	Peripheral Clock Selection of each type,
50
- * 				should be one of the following:
51
- *				- CLKPWR_PCLKSEL_WDT   		: WDT
52
-				- CLKPWR_PCLKSEL_TIMER0   	: Timer 0
53
-				- CLKPWR_PCLKSEL_TIMER1   	: Timer 1
54
-				- CLKPWR_PCLKSEL_UART0   	: UART 0
55
-				- CLKPWR_PCLKSEL_UART1  	: UART 1
56
-				- CLKPWR_PCLKSEL_PWM1   	: PWM 1
57
-				- CLKPWR_PCLKSEL_I2C0   	: I2C 0
58
-				- CLKPWR_PCLKSEL_SPI   		: SPI
59
-				- CLKPWR_PCLKSEL_SSP1   	: SSP 1
60
-				- CLKPWR_PCLKSEL_DAC   		: DAC
61
-				- CLKPWR_PCLKSEL_ADC   		: ADC
62
-				- CLKPWR_PCLKSEL_CAN1  		: CAN 1
63
-				- CLKPWR_PCLKSEL_CAN2  		: CAN 2
64
-				- CLKPWR_PCLKSEL_ACF   		: ACF
65
-				- CLKPWR_PCLKSEL_QEI 		: QEI
66
-				- CLKPWR_PCLKSEL_PCB   		: PCB
67
-				- CLKPWR_PCLKSEL_I2C1   	: I2C 1
68
-				- CLKPWR_PCLKSEL_SSP0   	: SSP 0
69
-				- CLKPWR_PCLKSEL_TIMER2   	: Timer 2
70
-				- CLKPWR_PCLKSEL_TIMER3   	: Timer 3
71
-				- CLKPWR_PCLKSEL_UART2   	: UART 2
72
-				- CLKPWR_PCLKSEL_UART3   	: UART 3
73
-				- CLKPWR_PCLKSEL_I2C2   	: I2C 2
74
-				- CLKPWR_PCLKSEL_I2S   		: I2S
75
-				- CLKPWR_PCLKSEL_RIT   		: RIT
76
-				- CLKPWR_PCLKSEL_SYSCON   	: SYSCON
77
-				- CLKPWR_PCLKSEL_MC 		: MC
78
-
79
- * @param[in]	DivVal	Value of divider, should be:
80
- * 				- CLKPWR_PCLKSEL_CCLK_DIV_4 : PCLK_peripheral = CCLK/4
81
- * 				- CLKPWR_PCLKSEL_CCLK_DIV_1 : PCLK_peripheral = CCLK/1
82
- *				- CLKPWR_PCLKSEL_CCLK_DIV_2 : PCLK_peripheral = CCLK/2
83
- *
84
- * @return none
85
- **********************************************************************/
86
-void CLKPWR_SetPCLKDiv (uint32_t ClkType, uint32_t DivVal)
87
-{
88
-	uint32_t bitpos;
89
-
90
-	bitpos = (ClkType < 32) ? (ClkType) : (ClkType - 32);
91
-
92
-	/* PCLKSEL0 selected */
93
-	if (ClkType < 32)
94
-	{
95
-		/* Clear two bit at bit position */
96
-		LPC_SC->PCLKSEL0 &= (~(CLKPWR_PCLKSEL_BITMASK(bitpos)));
97
-
98
-		/* Set two selected bit */
99
-		LPC_SC->PCLKSEL0 |= (CLKPWR_PCLKSEL_SET(bitpos, DivVal));
100
-	}
101
-	/* PCLKSEL1 selected */
102
-	else
103
-	{
104
-		/* Clear two bit at bit position */
105
-		LPC_SC->PCLKSEL1 &= ~(CLKPWR_PCLKSEL_BITMASK(bitpos));
106
-
107
-		/* Set two selected bit */
108
-		LPC_SC->PCLKSEL1 |= (CLKPWR_PCLKSEL_SET(bitpos, DivVal));
109
-	}
110
-}
111
-
112
-
113
-/*********************************************************************//**
114
- * @brief		Get current value of each Peripheral Clock Selection
115
- * @param[in]	ClkType	Peripheral Clock Selection of each type,
116
- * 				should be one of the following:
117
- *				- CLKPWR_PCLKSEL_WDT   		: WDT
118
-				- CLKPWR_PCLKSEL_TIMER0   	: Timer 0
119
-				- CLKPWR_PCLKSEL_TIMER1   	: Timer 1
120
-				- CLKPWR_PCLKSEL_UART0   	: UART 0
121
-				- CLKPWR_PCLKSEL_UART1  	: UART 1
122
-				- CLKPWR_PCLKSEL_PWM1   	: PWM 1
123
-				- CLKPWR_PCLKSEL_I2C0   	: I2C 0
124
-				- CLKPWR_PCLKSEL_SPI   		: SPI
125
-				- CLKPWR_PCLKSEL_SSP1   	: SSP 1
126
-				- CLKPWR_PCLKSEL_DAC   		: DAC
127
-				- CLKPWR_PCLKSEL_ADC   		: ADC
128
-				- CLKPWR_PCLKSEL_CAN1  		: CAN 1
129
-				- CLKPWR_PCLKSEL_CAN2  		: CAN 2
130
-				- CLKPWR_PCLKSEL_ACF   		: ACF
131
-				- CLKPWR_PCLKSEL_QEI 		: QEI
132
-				- CLKPWR_PCLKSEL_PCB   		: PCB
133
-				- CLKPWR_PCLKSEL_I2C1   	: I2C 1
134
-				- CLKPWR_PCLKSEL_SSP0   	: SSP 0
135
-				- CLKPWR_PCLKSEL_TIMER2   	: Timer 2
136
-				- CLKPWR_PCLKSEL_TIMER3   	: Timer 3
137
-				- CLKPWR_PCLKSEL_UART2   	: UART 2
138
-				- CLKPWR_PCLKSEL_UART3   	: UART 3
139
-				- CLKPWR_PCLKSEL_I2C2   	: I2C 2
140
-				- CLKPWR_PCLKSEL_I2S   		: I2S
141
-				- CLKPWR_PCLKSEL_RIT   		: RIT
142
-				- CLKPWR_PCLKSEL_SYSCON   	: SYSCON
143
-				- CLKPWR_PCLKSEL_MC 		: MC
144
-
145
- * @return		Value of Selected Peripheral Clock Selection
146
- **********************************************************************/
147
-uint32_t CLKPWR_GetPCLKSEL (uint32_t ClkType)
148
-{
149
-	uint32_t bitpos, retval;
150
-
151
-	if (ClkType < 32)
152
-	{
153
-		bitpos = ClkType;
154
-		retval = LPC_SC->PCLKSEL0;
155
-	}
156
-	else
157
-	{
158
-		bitpos = ClkType - 32;
159
-		retval = LPC_SC->PCLKSEL1;
160
-	}
161
-
162
-	retval = CLKPWR_PCLKSEL_GET(bitpos, retval);
163
-	return retval;
164
-}
165
-
166
-
167
-
168
-/*********************************************************************//**
169
- * @brief 		Get current value of each Peripheral Clock
170
- * @param[in]	ClkType	Peripheral Clock Selection of each type,
171
- * 				should be one of the following:
172
- *				- CLKPWR_PCLKSEL_WDT   		: WDT
173
-				- CLKPWR_PCLKSEL_TIMER0   	: Timer 0
174
-				- CLKPWR_PCLKSEL_TIMER1   	: Timer 1
175
-				- CLKPWR_PCLKSEL_UART0   	: UART 0
176
-				- CLKPWR_PCLKSEL_UART1  	: UART 1
177
-				- CLKPWR_PCLKSEL_PWM1   	: PWM 1
178
-				- CLKPWR_PCLKSEL_I2C0   	: I2C 0
179
-				- CLKPWR_PCLKSEL_SPI   		: SPI
180
-				- CLKPWR_PCLKSEL_SSP1   	: SSP 1
181
-				- CLKPWR_PCLKSEL_DAC   		: DAC
182
-				- CLKPWR_PCLKSEL_ADC   		: ADC
183
-				- CLKPWR_PCLKSEL_CAN1  		: CAN 1
184
-				- CLKPWR_PCLKSEL_CAN2  		: CAN 2
185
-				- CLKPWR_PCLKSEL_ACF   		: ACF
186
-				- CLKPWR_PCLKSEL_QEI 		: QEI
187
-				- CLKPWR_PCLKSEL_PCB   		: PCB
188
-				- CLKPWR_PCLKSEL_I2C1   	: I2C 1
189
-				- CLKPWR_PCLKSEL_SSP0   	: SSP 0
190
-				- CLKPWR_PCLKSEL_TIMER2   	: Timer 2
191
-				- CLKPWR_PCLKSEL_TIMER3   	: Timer 3
192
-				- CLKPWR_PCLKSEL_UART2   	: UART 2
193
-				- CLKPWR_PCLKSEL_UART3   	: UART 3
194
-				- CLKPWR_PCLKSEL_I2C2   	: I2C 2
195
-				- CLKPWR_PCLKSEL_I2S   		: I2S
196
-				- CLKPWR_PCLKSEL_RIT   		: RIT
197
-				- CLKPWR_PCLKSEL_SYSCON   	: SYSCON
198
-				- CLKPWR_PCLKSEL_MC 		: MC
199
-
200
- * @return		Value of Selected Peripheral Clock
201
- **********************************************************************/
202
-uint32_t CLKPWR_GetPCLK (uint32_t ClkType)
203
-{
204
-	uint32_t retval, div;
205
-
206
-	retval = SystemCoreClock;
207
-	div = CLKPWR_GetPCLKSEL(ClkType);
208
-
209
-	switch (div)
210
-	{
211
-	case 0:
212
-		div = 4;
213
-		break;
214
-
215
-	case 1:
216
-		div = 1;
217
-		break;
218
-
219
-	case 2:
220
-		div = 2;
221
-		break;
222
-
223
-	case 3:
224
-		div = 8;
225
-		break;
226
-	}
227
-	retval /= div;
228
-
229
-	return retval;
230
-}
231
-
232
-
233
-
234
-/*********************************************************************//**
235
- * @brief 		Configure power supply for each peripheral according to NewState
236
- * @param[in]	PPType	Type of peripheral used to enable power,
237
- *     					should be one of the following:
238
- *     			-  CLKPWR_PCONP_PCTIM0 		: Timer 0
239
-				-  CLKPWR_PCONP_PCTIM1 		: Timer 1
240
-				-  CLKPWR_PCONP_PCUART0  	: UART 0
241
-				-  CLKPWR_PCONP_PCUART1   	: UART 1
242
-				-  CLKPWR_PCONP_PCPWM1 		: PWM 1
243
-				-  CLKPWR_PCONP_PCI2C0 		: I2C 0
244
-				-  CLKPWR_PCONP_PCSPI   	: SPI
245
-				-  CLKPWR_PCONP_PCRTC   	: RTC
246
-				-  CLKPWR_PCONP_PCSSP1 		: SSP 1
247
-				-  CLKPWR_PCONP_PCAD   		: ADC
248
-				-  CLKPWR_PCONP_PCAN1   	: CAN 1
249
-				-  CLKPWR_PCONP_PCAN2   	: CAN 2
250
-				-  CLKPWR_PCONP_PCGPIO 		: GPIO
251
-				-  CLKPWR_PCONP_PCRIT 		: RIT
252
-				-  CLKPWR_PCONP_PCMC 		: MC
253
-				-  CLKPWR_PCONP_PCQEI 		: QEI
254
-				-  CLKPWR_PCONP_PCI2C1   	: I2C 1
255
-				-  CLKPWR_PCONP_PCSSP0 		: SSP 0
256
-				-  CLKPWR_PCONP_PCTIM2 		: Timer 2
257
-				-  CLKPWR_PCONP_PCTIM3 		: Timer 3
258
-				-  CLKPWR_PCONP_PCUART2  	: UART 2
259
-				-  CLKPWR_PCONP_PCUART3   	: UART 3
260
-				-  CLKPWR_PCONP_PCI2C2 		: I2C 2
261
-				-  CLKPWR_PCONP_PCI2S   	: I2S
262
-				-  CLKPWR_PCONP_PCGPDMA   	: GPDMA
263
-				-  CLKPWR_PCONP_PCENET 		: Ethernet
264
-				-  CLKPWR_PCONP_PCUSB   	: USB
265
- *
266
- * @param[in]	NewState	New state of Peripheral Power, should be:
267
- * 				- ENABLE	: Enable power for this peripheral
268
- * 				- DISABLE	: Disable power for this peripheral
269
- *
270
- * @return none
271
- **********************************************************************/
272
-void CLKPWR_ConfigPPWR (uint32_t PPType, FunctionalState NewState)
273
-{
274
-	if (NewState == ENABLE)
275
-	{
276
-		LPC_SC->PCONP |= PPType & CLKPWR_PCONP_BITMASK;
277
-	}
278
-	else if (NewState == DISABLE)
279
-	{
280
-		LPC_SC->PCONP &= (~PPType) & CLKPWR_PCONP_BITMASK;
281
-	}
282
-}
283
-
284
-
285
-/*********************************************************************//**
286
- * @brief 		Enter Sleep mode with co-operated instruction by the Cortex-M3.
287
- * @param[in]	None
288
- * @return		None
289
- **********************************************************************/
290
-void CLKPWR_Sleep(void)
291
-{
292
-	LPC_SC->PCON = 0x00;
293
-	/* Sleep Mode*/
294
-	__WFI();
295
-}
296
-
297
-
298
-/*********************************************************************//**
299
- * @brief 		Enter Deep Sleep mode with co-operated instruction by the Cortex-M3.
300
- * @param[in]	None
301
- * @return		None
302
- **********************************************************************/
303
-void CLKPWR_DeepSleep(void)
304
-{
305
-    /* Deep-Sleep Mode, set SLEEPDEEP bit */
306
-	SCB->SCR = 0x4;
307
-	LPC_SC->PCON = 0x00;
308
-	/* Deep Sleep Mode*/
309
-	__WFI();
310
-}
311
-
312
-
313
-/*********************************************************************//**
314
- * @brief 		Enter Power Down mode with co-operated instruction by the Cortex-M3.
315
- * @param[in]	None
316
- * @return		None
317
- **********************************************************************/
318
-void CLKPWR_PowerDown(void)
319
-{
320
-    /* Deep-Sleep Mode, set SLEEPDEEP bit */
321
-	SCB->SCR = 0x4;
322
-	LPC_SC->PCON = 0x01;
323
-	/* Power Down Mode*/
324
-	__WFI();
325
-}
326
-
327
-
328
-/*********************************************************************//**
329
- * @brief 		Enter Deep Power Down mode with co-operated instruction by the Cortex-M3.
330
- * @param[in]	None
331
- * @return		None
332
- **********************************************************************/
333
-void CLKPWR_DeepPowerDown(void)
334
-{
335
-    /* Deep-Sleep Mode, set SLEEPDEEP bit */
336
-	SCB->SCR = 0x4;
337
-	LPC_SC->PCON = 0x03;
338
-	/* Deep Power Down Mode*/
339
-	__WFI();
340
-}
341
-
342
-/**
343
- * @}
344
- */
345
-
346
-/**
347
- * @}
348
- */
349
-
350
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 151
frameworks/CMSIS/LPC1768/driver/lpc17xx_dac.c Просмотреть файл

@@ -1,151 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_dac.c				2010-05-21
3
-*//**
4
-* @file		lpc17xx_dac.c
5
-* @brief	Contains all functions support for DAC firmware library on LPC17xx
6
-* @version	2.0
7
-* @date		21. May. 2010
8
-* @author	NXP MCU SW Application Team
9
-*
10
-* Copyright(C) 2010, NXP Semiconductor
11
-* All rights reserved.
12
-*
13
-***********************************************************************
14
-* Software that is described herein is for illustrative purposes only
15
-* which provides customers with programming information regarding the
16
-* products. This software is supplied "AS IS" without any warranties.
17
-* NXP Semiconductors assumes no responsibility or liability for the
18
-* use of the software, conveys no license or title under any patent,
19
-* copyright, or mask work right to the product. NXP Semiconductors
20
-* reserves the right to make changes in the software without
21
-* notification. NXP Semiconductors also make no representation or
22
-* warranty that such application will be suitable for the specified
23
-* use without further testing or modification.
24
-* Permission to use, copy, modify, and distribute this software and its
25
-* documentation is hereby granted, under NXP Semiconductors'
26
-* relevant copyright in the software, without fee, provided that it
27
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
28
-* copyright, permission, and disclaimer notice must appear in all copies of
29
-* this code.
30
-**********************************************************************/
31
-
32
-/* Peripheral group ----------------------------------------------------------- */
33
-/** @addtogroup DAC
34
- * @{
35
- */
36
-
37
-/* Includes ------------------------------------------------------------------- */
38
-#include "lpc17xx_dac.h"
39
-#include "lpc17xx_clkpwr.h"
40
-
41
-/* If this source file built with example, the LPC17xx FW library configuration
42
- * file in each example directory ("lpc17xx_libcfg.h") must be included,
43
- * otherwise the default FW library configuration file must be included instead
44
- */
45
-#ifdef __BUILD_WITH_EXAMPLE__
46
-#include "lpc17xx_libcfg.h"
47
-#else
48
-#include "lpc17xx_libcfg_default.h"
49
-#endif /* __BUILD_WITH_EXAMPLE__ */
50
-
51
-
52
-#ifdef _DAC
53
-
54
-/* Public Functions ----------------------------------------------------------- */
55
-/** @addtogroup DAC_Public_Functions
56
- * @{
57
- */
58
-
59
-/*********************************************************************//**
60
- * @brief 		Initial ADC configuration
61
- * 					- Maximum	current is 700 uA
62
- * 					- Value to AOUT is 0
63
- * @param[in] 	DACx pointer to LPC_DAC_TypeDef, should be: LPC_DAC
64
- * @return 		None
65
- ***********************************************************************/
66
-void DAC_Init(LPC_DAC_TypeDef *DACx)
67
-{
68
-	CHECK_PARAM(PARAM_DACx(DACx));
69
-	/* Set default clock divider for DAC */
70
-	// CLKPWR_SetPCLKDiv (CLKPWR_PCLKSEL_DAC, CLKPWR_PCLKSEL_CCLK_DIV_4);
71
-	//Set maximum current output
72
-	DAC_SetBias(LPC_DAC,DAC_MAX_CURRENT_700uA);
73
-}
74
-
75
-/*********************************************************************//**
76
- * @brief 		Update value to DAC
77
- * @param[in] 	DACx pointer to LPC_DAC_TypeDef, should be: LPC_DAC
78
- * @param[in] 	dac_value : value 10 bit to be converted to output
79
- * @return 		None
80
- ***********************************************************************/
81
-void DAC_UpdateValue (LPC_DAC_TypeDef *DACx,uint32_t dac_value)
82
-{
83
-	uint32_t tmp;
84
-	CHECK_PARAM(PARAM_DACx(DACx));
85
-	tmp = DACx->DACR & DAC_BIAS_EN;
86
-	tmp |= DAC_VALUE(dac_value);
87
-	// Update value
88
-	DACx->DACR = tmp;
89
-}
90
-
91
-/*********************************************************************//**
92
- * @brief 		Set Maximum current for DAC
93
- * @param[in] 	DACx pointer to LPC_DAC_TypeDef, should be: LPC_DAC
94
- * @param[in] 	bias : 0 is 700 uA
95
- * 					   1    350 uA
96
- * @return 		None
97
- ***********************************************************************/
98
-void DAC_SetBias (LPC_DAC_TypeDef *DACx,uint32_t bias)
99
-{
100
-	CHECK_PARAM(PARAM_DAC_CURRENT_OPT(bias));
101
-	DACx->DACR &=~DAC_BIAS_EN;
102
-	if (bias  == DAC_MAX_CURRENT_350uA)
103
-	{
104
-		DACx->DACR |= DAC_BIAS_EN;
105
-	}
106
-}
107
-
108
-/*********************************************************************//**
109
- * @brief 		To enable the DMA operation and control DMA timer
110
- * @param[in]	DACx pointer to LPC_DAC_TypeDef, should be: LPC_DAC
111
- * @param[in] 	DAC_ConverterConfigStruct pointer to DAC_CONVERTER_CFG_Type
112
- * 					- DBLBUF_ENA :  enable/disable DACR double buffering feature
113
- * 					- CNT_ENA    :  enable/disable timer out counter
114
- * 					- DMA_ENA    :	enable/disable DMA access
115
- * @return 		None
116
- ***********************************************************************/
117
-void DAC_ConfigDAConverterControl (LPC_DAC_TypeDef *DACx,DAC_CONVERTER_CFG_Type *DAC_ConverterConfigStruct)
118
-{
119
-	CHECK_PARAM(PARAM_DACx(DACx));
120
-	DACx->DACCTRL &= ~DAC_DACCTRL_MASK;
121
-	if (DAC_ConverterConfigStruct->DBLBUF_ENA)
122
-		DACx->DACCTRL	|= DAC_DBLBUF_ENA;
123
-	if (DAC_ConverterConfigStruct->CNT_ENA)
124
-		DACx->DACCTRL	|= DAC_CNT_ENA;
125
-	if (DAC_ConverterConfigStruct->DMA_ENA)
126
-		DACx->DACCTRL	|= DAC_DMA_ENA;
127
-}
128
-
129
-/*********************************************************************//**
130
- * @brief 		Set reload value for interrupt/DMA counter
131
- * @param[in] 	DACx pointer to LPC_DAC_TypeDef, should be: LPC_DAC
132
- * @param[in] 	time_out time out to reload for interrupt/DMA counter
133
- * @return 		None
134
- ***********************************************************************/
135
-void DAC_SetDMATimeOut(LPC_DAC_TypeDef *DACx, uint32_t time_out)
136
-{
137
-	CHECK_PARAM(PARAM_DACx(DACx));
138
-	DACx->DACCNTVAL = DAC_CCNT_VALUE(time_out);
139
-}
140
-
141
-/**
142
- * @}
143
- */
144
-
145
-#endif /* _DAC */
146
-
147
-/**
148
- * @}
149
- */
150
-
151
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 963
frameworks/CMSIS/LPC1768/driver/lpc17xx_emac.c Просмотреть файл

@@ -1,963 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_emac.c				2010-05-21
3
-*//**
4
-* @file		lpc17xx_emac.c
5
-* @brief	Contains all functions support for Ethernet MAC firmware
6
-* 			library on LPC17xx
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @addtogroup EMAC
35
- * @{
36
- */
37
-
38
-/* Includes ------------------------------------------------------------------- */
39
-#include "lpc17xx_emac.h"
40
-#include "lpc17xx_clkpwr.h"
41
-
42
-/* If this source file built with example, the LPC17xx FW library configuration
43
- * file in each example directory ("lpc17xx_libcfg.h") must be included,
44
- * otherwise the default FW library configuration file must be included instead
45
- */
46
-#ifdef __BUILD_WITH_EXAMPLE__
47
-#include "lpc17xx_libcfg.h"
48
-#else
49
-#include "lpc17xx_libcfg_default.h"
50
-#endif /* __BUILD_WITH_EXAMPLE__ */
51
-
52
-
53
-#ifdef _EMAC
54
-
55
-/* Private Variables ---------------------------------------------------------- */
56
-/** @defgroup EMAC_Private_Variables EMAC Private Variables
57
- * @{
58
- */
59
-
60
-/* MII Mgmt Configuration register - Clock divider setting */
61
-const uint8_t EMAC_clkdiv[] = { 4, 6, 8, 10, 14, 20, 28, 36, 40, 44, 48, 52, 56, 60, 64};
62
-
63
-/* EMAC local DMA Descriptors */
64
-
65
-/** Rx Descriptor data array */
66
-static RX_Desc Rx_Desc[EMAC_NUM_RX_FRAG];
67
-
68
-/** Rx Status data array - Must be 8-Byte aligned */
69
-#if defined ( __CC_ARM   )
70
-static __align(8) RX_Stat Rx_Stat[EMAC_NUM_RX_FRAG];
71
-#elif defined ( __ICCARM__ )
72
-#pragma data_alignment=8
73
-static RX_Stat Rx_Stat[EMAC_NUM_RX_FRAG];
74
-#elif defined   (  __GNUC__  )
75
-static __attribute__ ((aligned (8))) RX_Stat Rx_Stat[EMAC_NUM_RX_FRAG];
76
-#endif
77
-
78
-/** Tx Descriptor data array */
79
-static TX_Desc Tx_Desc[EMAC_NUM_TX_FRAG];
80
-/** Tx Status data array */
81
-static TX_Stat Tx_Stat[EMAC_NUM_TX_FRAG];
82
-
83
-/* EMAC local DMA buffers */
84
-/** Rx buffer data */
85
-static uint32_t rx_buf[EMAC_NUM_RX_FRAG][EMAC_ETH_MAX_FLEN>>2];
86
-/** Tx buffer data */
87
-static uint32_t tx_buf[EMAC_NUM_TX_FRAG][EMAC_ETH_MAX_FLEN>>2];
88
-
89
-/**
90
- * @}
91
- */
92
-
93
-/* Private Functions ---------------------------------------------------------- */
94
-static void rx_descr_init (void);
95
-static void tx_descr_init (void);
96
-static int32_t write_PHY (uint32_t PhyReg, uint16_t Value);
97
-static int32_t  read_PHY (uint32_t PhyReg);
98
-
99
-static void setEmacAddr(uint8_t abStationAddr[]);
100
-static int32_t emac_CRCCalc(uint8_t frame_no_fcs[], int32_t frame_len);
101
-
102
-
103
-/*--------------------------- rx_descr_init ---------------------------------*/
104
-/*********************************************************************//**
105
- * @brief 		Initializes RX Descriptor
106
- * @param[in] 	None
107
- * @return 		None
108
- ***********************************************************************/
109
-static void rx_descr_init (void)
110
-{
111
-	/* Initialize Receive Descriptor and Status array. */
112
-	uint32_t i;
113
-
114
-	for (i = 0; i < EMAC_NUM_RX_FRAG; i++) {
115
-		Rx_Desc[i].Packet  = (uint32_t)&rx_buf[i];
116
-		Rx_Desc[i].Ctrl    = EMAC_RCTRL_INT | (EMAC_ETH_MAX_FLEN - 1);
117
-		Rx_Stat[i].Info    = 0;
118
-		Rx_Stat[i].HashCRC = 0;
119
-	}
120
-
121
-	/* Set EMAC Receive Descriptor Registers. */
122
-	LPC_EMAC->RxDescriptor       = (uint32_t)&Rx_Desc[0];
123
-	LPC_EMAC->RxStatus           = (uint32_t)&Rx_Stat[0];
124
-	LPC_EMAC->RxDescriptorNumber = EMAC_NUM_RX_FRAG - 1;
125
-
126
-	/* Rx Descriptors Point to 0 */
127
-	LPC_EMAC->RxConsumeIndex  = 0;
128
-}
129
-
130
-
131
-/*--------------------------- tx_descr_init ---- ----------------------------*/
132
-/*********************************************************************//**
133
- * @brief 		Initializes TX Descriptor
134
- * @param[in] 	None
135
- * @return 		None
136
- ***********************************************************************/
137
-static void tx_descr_init (void) {
138
-	/* Initialize Transmit Descriptor and Status array. */
139
-	uint32_t i;
140
-
141
-	for (i = 0; i < EMAC_NUM_TX_FRAG; i++) {
142
-		Tx_Desc[i].Packet = (uint32_t)&tx_buf[i];
143
-		Tx_Desc[i].Ctrl   = 0;
144
-		Tx_Stat[i].Info   = 0;
145
-	}
146
-
147
-	/* Set EMAC Transmit Descriptor Registers. */
148
-	LPC_EMAC->TxDescriptor       = (uint32_t)&Tx_Desc[0];
149
-	LPC_EMAC->TxStatus           = (uint32_t)&Tx_Stat[0];
150
-	LPC_EMAC->TxDescriptorNumber = EMAC_NUM_TX_FRAG - 1;
151
-
152
-	/* Tx Descriptors Point to 0 */
153
-	LPC_EMAC->TxProduceIndex  = 0;
154
-}
155
-
156
-
157
-/*--------------------------- write_PHY -------------------------------------*/
158
-/*********************************************************************//**
159
- * @brief 		Write value to PHY device
160
- * @param[in] 	PhyReg: PHY Register address
161
- * @param[in] 	Value:  Value to write
162
- * @return 		0 - if success
163
- * 				1 - if fail
164
- ***********************************************************************/
165
-static int32_t write_PHY (uint32_t PhyReg, uint16_t Value)
166
-{
167
-	/* Write a data 'Value' to PHY register 'PhyReg'. */
168
-	uint32_t tout;
169
-
170
-	LPC_EMAC->MADR = EMAC_DEF_ADR | PhyReg;
171
-	LPC_EMAC->MWTD = Value;
172
-
173
-	/* Wait until operation completed */
174
-	tout = 0;
175
-	for (tout = 0; tout < EMAC_MII_WR_TOUT; tout++) {
176
-		if ((LPC_EMAC->MIND & EMAC_MIND_BUSY) == 0) {
177
-			return (0);
178
-		}
179
-	}
180
-	// Time out!
181
-	return (-1);
182
-}
183
-
184
-
185
-/*--------------------------- read_PHY --------------------------------------*/
186
-/*********************************************************************//**
187
- * @brief 		Read value from PHY device
188
- * @param[in] 	PhyReg: PHY Register address
189
- * @return 		0 - if success
190
- * 				1 - if fail
191
- ***********************************************************************/
192
-static int32_t read_PHY (uint32_t PhyReg)
193
-{
194
-	/* Read a PHY register 'PhyReg'. */
195
-	uint32_t tout;
196
-
197
-	LPC_EMAC->MADR = EMAC_DEF_ADR | PhyReg;
198
-	LPC_EMAC->MCMD = EMAC_MCMD_READ;
199
-
200
-	/* Wait until operation completed */
201
-	tout = 0;
202
-	for (tout = 0; tout < EMAC_MII_RD_TOUT; tout++) {
203
-		if ((LPC_EMAC->MIND & EMAC_MIND_BUSY) == 0) {
204
-			LPC_EMAC->MCMD = 0;
205
-			return (LPC_EMAC->MRDD);
206
-		}
207
-	}
208
-	// Time out!
209
-	return (-1);
210
-}
211
-
212
-/*********************************************************************//**
213
- * @brief		Set Station MAC address for EMAC module
214
- * @param[in]	abStationAddr Pointer to Station address that contains 6-bytes
215
- * 				of MAC address (should be in order from MAC Address 1 to MAC Address 6)
216
- * @return		None
217
- **********************************************************************/
218
-static void setEmacAddr(uint8_t abStationAddr[])
219
-{
220
-	/* Set the Ethernet MAC Address registers */
221
-	LPC_EMAC->SA0 = ((uint32_t)abStationAddr[5] << 8) | (uint32_t)abStationAddr[4];
222
-	LPC_EMAC->SA1 = ((uint32_t)abStationAddr[3] << 8) | (uint32_t)abStationAddr[2];
223
-	LPC_EMAC->SA2 = ((uint32_t)abStationAddr[1] << 8) | (uint32_t)abStationAddr[0];
224
-}
225
-
226
-
227
-/*********************************************************************//**
228
- * @brief		Calculates CRC code for number of bytes in the frame
229
- * @param[in]	frame_no_fcs	Pointer to the first byte of the frame
230
- * @param[in]	frame_len		length of the frame without the FCS
231
- * @return		the CRC as a 32 bit integer
232
- **********************************************************************/
233
-static int32_t emac_CRCCalc(uint8_t frame_no_fcs[], int32_t frame_len)
234
-{
235
-	int i; 		// iterator
236
-	int j; 		// another iterator
237
-	char byte; 	// current byte
238
-	int crc; 	// CRC result
239
-	int q0, q1, q2, q3; // temporary variables
240
-	crc = 0xFFFFFFFF;
241
-	for (i = 0; i < frame_len; i++) {
242
-		byte = *frame_no_fcs++;
243
-		for (j = 0; j < 2; j++) {
244
-			if (((crc >> 28) ^ (byte >> 3)) & 0x00000001) {
245
-				q3 = 0x04C11DB7;
246
-			} else {
247
-				q3 = 0x00000000;
248
-			}
249
-			if (((crc >> 29) ^ (byte >> 2)) & 0x00000001) {
250
-				q2 = 0x09823B6E;
251
-			} else {
252
-				q2 = 0x00000000;
253
-			}
254
-			if (((crc >> 30) ^ (byte >> 1)) & 0x00000001) {
255
-				q1 = 0x130476DC;
256
-			} else {
257
-				q1 = 0x00000000;
258
-			}
259
-			if (((crc >> 31) ^ (byte >> 0)) & 0x00000001) {
260
-				q0 = 0x2608EDB8;
261
-			} else {
262
-				q0 = 0x00000000;
263
-			}
264
-			crc = (crc << 4) ^ q3 ^ q2 ^ q1 ^ q0;
265
-			byte >>= 4;
266
-		}
267
-	}
268
-	return crc;
269
-}
270
-/* End of Private Functions --------------------------------------------------- */
271
-
272
-
273
-/* Public Functions ----------------------------------------------------------- */
274
-/** @addtogroup EMAC_Public_Functions
275
- * @{
276
- */
277
-
278
-
279
-/*********************************************************************//**
280
- * @brief		Initializes the EMAC peripheral according to the specified
281
-*               parameters in the EMAC_ConfigStruct.
282
- * @param[in]	EMAC_ConfigStruct Pointer to a EMAC_CFG_Type structure
283
-*                    that contains the configuration information for the
284
-*                    specified EMAC peripheral.
285
- * @return		None
286
- *
287
- * Note: This function will initialize EMAC module according to procedure below:
288
- *  - Remove the soft reset condition from the MAC
289
- *  - Configure the PHY via the MIIM interface of the MAC
290
- *  - Select RMII mode
291
- *  - Configure the transmit and receive DMA engines, including the descriptor arrays
292
- *  - Configure the host registers (MAC1,MAC2 etc.) in the MAC
293
- *  - Enable the receive and transmit data paths
294
- *  In default state after initializing, only Rx Done and Tx Done interrupt are enabled,
295
- *  all remain interrupts are disabled
296
- *  (Ref. from LPC17xx UM)
297
- **********************************************************************/
298
-Status EMAC_Init(EMAC_CFG_Type *EMAC_ConfigStruct)
299
-{
300
-	/* Initialize the EMAC Ethernet controller. */
301
-	int32_t regv,tout, tmp;
302
-
303
-	/* Set up clock and power for Ethernet module */
304
-	CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCENET, ENABLE);
305
-
306
-	/* Reset all EMAC internal modules */
307
-	LPC_EMAC->MAC1    = EMAC_MAC1_RES_TX | EMAC_MAC1_RES_MCS_TX | EMAC_MAC1_RES_RX |
308
-					EMAC_MAC1_RES_MCS_RX | EMAC_MAC1_SIM_RES | EMAC_MAC1_SOFT_RES;
309
-
310
-	LPC_EMAC->Command = EMAC_CR_REG_RES | EMAC_CR_TX_RES | EMAC_CR_RX_RES | EMAC_CR_PASS_RUNT_FRM;
311
-
312
-	/* A short delay after reset. */
313
-	for (tout = 100; tout; tout--);
314
-
315
-	/* Initialize MAC control registers. */
316
-	LPC_EMAC->MAC1 = EMAC_MAC1_PASS_ALL;
317
-	LPC_EMAC->MAC2 = EMAC_MAC2_CRC_EN | EMAC_MAC2_PAD_EN;
318
-	LPC_EMAC->MAXF = EMAC_ETH_MAX_FLEN;
319
-	/*
320
-	 * Find the clock that close to desired target clock
321
-	 */
322
-	tmp = SystemCoreClock / EMAC_MCFG_MII_MAXCLK;
323
-	for (tout = 0; tout < sizeof (EMAC_clkdiv); tout++){
324
-		if (EMAC_clkdiv[tout] >= tmp) break;
325
-	}
326
-	tout++;
327
-	// Write to MAC configuration register and reset
328
-	LPC_EMAC->MCFG = EMAC_MCFG_CLK_SEL(tout) | EMAC_MCFG_RES_MII;
329
-	// release reset
330
-	LPC_EMAC->MCFG &= ~(EMAC_MCFG_RES_MII);
331
-	LPC_EMAC->CLRT = EMAC_CLRT_DEF;
332
-	LPC_EMAC->IPGR = EMAC_IPGR_P2_DEF;
333
-
334
-	/* Enable Reduced MII interface. */
335
-	LPC_EMAC->Command = EMAC_CR_RMII | EMAC_CR_PASS_RUNT_FRM;
336
-
337
-	/* Reset Reduced MII Logic. */
338
-//	LPC_EMAC->SUPP = EMAC_SUPP_RES_RMII;
339
-
340
-	for (tout = 100; tout; tout--);
341
-	LPC_EMAC->SUPP = 0;
342
-
343
-	/* Put the DP83848C in reset mode */
344
-	write_PHY (EMAC_PHY_REG_BMCR, EMAC_PHY_BMCR_RESET);
345
-
346
-	/* Wait for hardware reset to end. */
347
-	for (tout = EMAC_PHY_RESP_TOUT; tout>=0; tout--) {
348
-		regv = read_PHY (EMAC_PHY_REG_BMCR);
349
-		if (!(regv & (EMAC_PHY_BMCR_RESET | EMAC_PHY_BMCR_POWERDOWN))) {
350
-			/* Reset complete, device not Power Down. */
351
-			break;
352
-		}
353
-		if (tout == 0){
354
-			// Time out, return ERROR
355
-			return (ERROR);
356
-		}
357
-	}
358
-
359
-	// Set PHY mode
360
-	if (EMAC_SetPHYMode(EMAC_ConfigStruct->Mode) < 0){
361
-		return (ERROR);
362
-	}
363
-
364
-	// Set EMAC address
365
-	setEmacAddr(EMAC_ConfigStruct->pbEMAC_Addr);
366
-
367
-	/* Initialize Tx and Rx DMA Descriptors */
368
-	rx_descr_init ();
369
-	tx_descr_init ();
370
-
371
-	// Set Receive Filter register: enable broadcast and multicast
372
-	LPC_EMAC->RxFilterCtrl = EMAC_RFC_MCAST_EN | EMAC_RFC_BCAST_EN | EMAC_RFC_PERFECT_EN;
373
-
374
-	/* Enable Rx Done and Tx Done interrupt for EMAC */
375
-	LPC_EMAC->IntEnable = EMAC_INT_RX_DONE | EMAC_INT_TX_DONE;
376
-
377
-	/* Reset all interrupts */
378
-	LPC_EMAC->IntClear  = 0xFFFF;
379
-
380
-	/* Enable receive and transmit mode of MAC Ethernet core */
381
-	LPC_EMAC->Command  |= (EMAC_CR_RX_EN | EMAC_CR_TX_EN);
382
-	LPC_EMAC->MAC1     |= EMAC_MAC1_REC_EN;
383
-
384
-	return SUCCESS;
385
-}
386
-
387
-
388
-/*********************************************************************//**
389
- * @brief		De-initializes the EMAC peripheral registers to their
390
-*                  default reset values.
391
- * @param[in]	None
392
- * @return 		None
393
- **********************************************************************/
394
-void EMAC_DeInit(void)
395
-{
396
-	// Disable all interrupt
397
-	LPC_EMAC->IntEnable = 0x00;
398
-	// Clear all pending interrupt
399
-	LPC_EMAC->IntClear = (0xFF) | (EMAC_INT_SOFT_INT | EMAC_INT_WAKEUP);
400
-
401
-	/* TurnOff clock and power for Ethernet module */
402
-	CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCENET, DISABLE);
403
-}
404
-
405
-
406
-/*********************************************************************//**
407
- * @brief		Check specified PHY status in EMAC peripheral
408
- * @param[in]	ulPHYState	Specified PHY Status Type, should be:
409
- * 							- EMAC_PHY_STAT_LINK: Link Status
410
- * 							- EMAC_PHY_STAT_SPEED: Speed Status
411
- * 							- EMAC_PHY_STAT_DUP: Duplex Status
412
- * @return		Status of specified PHY status (0 or 1).
413
- * 				(-1) if error.
414
- *
415
- * Note:
416
- * For EMAC_PHY_STAT_LINK, return value:
417
- * - 0: Link Down
418
- * - 1: Link Up
419
- * For EMAC_PHY_STAT_SPEED, return value:
420
- * - 0: 10Mbps
421
- * - 1: 100Mbps
422
- * For EMAC_PHY_STAT_DUP, return value:
423
- * - 0: Half-Duplex
424
- * - 1: Full-Duplex
425
- **********************************************************************/
426
-int32_t EMAC_CheckPHYStatus(uint32_t ulPHYState)
427
-{
428
-	int32_t regv, tmp;
429
-#ifdef MCB_LPC_1768
430
-	regv = read_PHY (EMAC_PHY_REG_STS);
431
-	switch(ulPHYState){
432
-	case EMAC_PHY_STAT_LINK:
433
-		tmp = (regv & EMAC_PHY_SR_LINK) ? 1 : 0;
434
-		break;
435
-	case EMAC_PHY_STAT_SPEED:
436
-		tmp = (regv & EMAC_PHY_SR_SPEED) ? 0 : 1;
437
-		break;
438
-	case EMAC_PHY_STAT_DUP:
439
-		tmp = (regv & EMAC_PHY_SR_FULL_DUP) ? 1 : 0;
440
-		break;
441
-#elif defined(IAR_LPC_1768)
442
-	/* Use IAR_LPC_1768 board:
443
-	 * FSZ8721BL doesn't have Status Register
444
-	 * so we read Basic Mode Status Register (0x01h) instead
445
-	 */
446
-	regv = read_PHY (EMAC_PHY_REG_BMSR);
447
-	switch(ulPHYState){
448
-	case EMAC_PHY_STAT_LINK:
449
-		tmp = (regv & EMAC_PHY_BMSR_LINK_STATUS) ? 1 : 0;
450
-		break;
451
-	case EMAC_PHY_STAT_SPEED:
452
-		tmp = (regv & EMAC_PHY_SR_100_SPEED) ? 1 : 0;
453
-		break;
454
-	case EMAC_PHY_STAT_DUP:
455
-		tmp = (regv & EMAC_PHY_SR_FULL_DUP) ? 1 : 0;
456
-		break;
457
-#endif
458
-	default:
459
-		tmp = -1;
460
-		break;
461
-	}
462
-	return (tmp);
463
-}
464
-
465
-
466
-/*********************************************************************//**
467
- * @brief		Set specified PHY mode in EMAC peripheral
468
- * @param[in]	ulPHYMode	Specified PHY mode, should be:
469
- * 							- EMAC_MODE_AUTO
470
- * 							- EMAC_MODE_10M_FULL
471
- * 							- EMAC_MODE_10M_HALF
472
- * 							- EMAC_MODE_100M_FULL
473
- * 							- EMAC_MODE_100M_HALF
474
- * @return		Return (0) if no error, otherwise return (-1)
475
- **********************************************************************/
476
-int32_t EMAC_SetPHYMode(uint32_t ulPHYMode)
477
-{
478
-	int32_t id1, id2, tout;
479
-
480
-	/* Check if this is a DP83848C PHY. */
481
-	id1 = read_PHY (EMAC_PHY_REG_IDR1);
482
-	id2 = read_PHY (EMAC_PHY_REG_IDR2);
483
-
484
-#ifdef MCB_LPC_1768
485
-	if (((id1 << 16) | (id2 & 0xFFF0)) == EMAC_DP83848C_ID) {
486
-		switch(ulPHYMode){
487
-		case EMAC_MODE_AUTO:
488
-			write_PHY (EMAC_PHY_REG_BMCR, EMAC_PHY_AUTO_NEG);
489
-#elif defined(IAR_LPC_1768) /* Use IAR LPC1768 KickStart board */
490
-	if (((id1 << 16) | id2) == EMAC_KSZ8721BL_ID) {
491
-		/* Configure the PHY device */
492
-		switch(ulPHYMode){
493
-		case EMAC_MODE_AUTO:
494
-			/* Use auto-negotiation about the link speed. */
495
-			write_PHY (EMAC_PHY_REG_BMCR, EMAC_PHY_AUTO_NEG);
496
-//			write_PHY (EMAC_PHY_REG_BMCR, EMAC_PHY_BMCR_AN);
497
-#endif
498
-			/* Wait to complete Auto_Negotiation */
499
-			for (tout = EMAC_PHY_RESP_TOUT; tout>=0; tout--) {
500
-
501
-			}
502
-			break;
503
-		case EMAC_MODE_10M_FULL:
504
-			/* Connect at 10MBit full-duplex */
505
-			write_PHY (EMAC_PHY_REG_BMCR, EMAC_PHY_FULLD_10M);
506
-			break;
507
-		case EMAC_MODE_10M_HALF:
508
-			/* Connect at 10MBit half-duplex */
509
-			write_PHY (EMAC_PHY_REG_BMCR, EMAC_PHY_HALFD_10M);
510
-			break;
511
-		case EMAC_MODE_100M_FULL:
512
-			/* Connect at 100MBit full-duplex */
513
-			write_PHY (EMAC_PHY_REG_BMCR, EMAC_PHY_FULLD_100M);
514
-			break;
515
-		case EMAC_MODE_100M_HALF:
516
-			/* Connect at 100MBit half-duplex */
517
-			write_PHY (EMAC_PHY_REG_BMCR, EMAC_PHY_HALFD_100M);
518
-			break;
519
-		default:
520
-			// un-supported
521
-			return (-1);
522
-		}
523
-	}
524
-	// It's not correct module ID
525
-	else {
526
-		return (-1);
527
-	}
528
-
529
-	// Update EMAC configuration with current PHY status
530
-	if (EMAC_UpdatePHYStatus() < 0){
531
-		return (-1);
532
-	}
533
-
534
-	// Complete
535
-	return (0);
536
-}
537
-
538
-
539
-/*********************************************************************//**
540
- * @brief		Auto-Configures value for the EMAC configuration register to
541
- * 				match with current PHY mode
542
- * @param[in]	None
543
- * @return		Return (0) if no error, otherwise return (-1)
544
- *
545
- * Note: The EMAC configuration will be auto-configured:
546
- * 		- Speed mode.
547
- * 		- Half/Full duplex mode
548
- **********************************************************************/
549
-int32_t EMAC_UpdatePHYStatus(void)
550
-{
551
-	int32_t regv, tout;
552
-
553
-	/* Check the link status. */
554
-#ifdef MCB_LPC_1768
555
-	for (tout = EMAC_PHY_RESP_TOUT; tout>=0; tout--) {
556
-		regv = read_PHY (EMAC_PHY_REG_STS);
557
-		if (regv & EMAC_PHY_SR_LINK) {
558
-			/* Link is on. */
559
-			break;
560
-		}
561
-		if (tout == 0){
562
-			// time out
563
-			return (-1);
564
-		}
565
-	}
566
-	/* Configure Full/Half Duplex mode. */
567
-	if (regv & EMAC_PHY_SR_DUP) {
568
-	/* Full duplex is enabled. */
569
-			LPC_EMAC->MAC2    |= EMAC_MAC2_FULL_DUP;
570
-			LPC_EMAC->Command |= EMAC_CR_FULL_DUP;
571
-			LPC_EMAC->IPGT     = EMAC_IPGT_FULL_DUP;
572
-	} else {
573
-		/* Half duplex mode. */
574
-		LPC_EMAC->IPGT = EMAC_IPGT_HALF_DUP;
575
-	}
576
-	if (regv & EMAC_PHY_SR_SPEED) {
577
-	/* 10MBit mode. */
578
-		LPC_EMAC->SUPP = 0;
579
-	} else {
580
-		/* 100MBit mode. */
581
-		LPC_EMAC->SUPP = EMAC_SUPP_SPEED;
582
-	}
583
-#elif defined(IAR_LPC_1768)
584
-	for (tout = EMAC_PHY_RESP_TOUT; tout>=0; tout--) {
585
-		regv = read_PHY (EMAC_PHY_REG_BMSR);
586
-		if (regv & EMAC_PHY_BMSR_LINK_STATUS) {
587
-			/* Link is on. */
588
-			break;
589
-		}
590
-		if (tout == 0){
591
-			// time out
592
-			return (-1);
593
-		}
594
-	}
595
-
596
-	/* Configure Full/Half Duplex mode. */
597
-	if (regv & EMAC_PHY_SR_FULL_DUP) {
598
-		/* Full duplex is enabled. */
599
-		LPC_EMAC->MAC2    |= EMAC_MAC2_FULL_DUP;
600
-		LPC_EMAC->Command |= EMAC_CR_FULL_DUP;
601
-		LPC_EMAC->IPGT     = EMAC_IPGT_FULL_DUP;
602
-	} else {
603
-		/* Half duplex mode. */
604
-		LPC_EMAC->IPGT = EMAC_IPGT_HALF_DUP;
605
-	}
606
-
607
-	/* Configure 100MBit/10MBit mode. */
608
-	if (!(regv & EMAC_PHY_SR_100_SPEED)) {
609
-		/* 10MBit mode. */
610
-		LPC_EMAC->SUPP = 0;
611
-	} else {
612
-		/* 100MBit mode. */
613
-		LPC_EMAC->SUPP = EMAC_SUPP_SPEED;
614
-	}
615
-#endif
616
-	// Complete
617
-	return (0);
618
-}
619
-
620
-
621
-/*********************************************************************//**
622
- * @brief		Enable/Disable hash filter functionality for specified destination
623
- * 				MAC address in EMAC module
624
- * @param[in]	dstMAC_addr		Pointer to the first MAC destination address, should
625
- * 								be 6-bytes length, in order LSB to the MSB
626
- * @param[in]	NewState		New State of this command, should be:
627
- *									- ENABLE.
628
- *									- DISABLE.
629
- * @return		None
630
- *
631
- * Note:
632
- * The standard Ethernet cyclic redundancy check (CRC) function is calculated from
633
- * the 6 byte destination address in the Ethernet frame (this CRC is calculated
634
- * anyway as part of calculating the CRC of the whole frame), then bits [28:23] out of
635
- * the 32 bits CRC result are taken to form the hash. The 6 bit hash is used to access
636
- * the hash table: it is used as an index in the 64 bit HashFilter register that has been
637
- * programmed with accept values. If the selected accept value is 1, the frame is
638
- * accepted.
639
- **********************************************************************/
640
-void EMAC_SetHashFilter(uint8_t dstMAC_addr[], FunctionalState NewState)
641
-{
642
-	uint32_t *pReg;
643
-	uint32_t tmp;
644
-	int32_t crc;
645
-
646
-	// Calculate the CRC from the destination MAC address
647
-	crc = emac_CRCCalc(dstMAC_addr, 6);
648
-	// Extract the value from CRC to get index value for hash filter table
649
-	crc = (crc >> 23) & 0x3F;
650
-
651
-	pReg = (crc > 31) ? ((uint32_t *)&LPC_EMAC->HashFilterH) \
652
-								: ((uint32_t *)&LPC_EMAC->HashFilterL);
653
-	tmp = (crc > 31) ? (crc - 32) : crc;
654
-	if (NewState == ENABLE) {
655
-		(*pReg) |= (1UL << tmp);
656
-	} else {
657
-		(*pReg) &= ~(1UL << tmp);
658
-	}
659
-	// Enable Rx Filter
660
-	LPC_EMAC->Command &= ~EMAC_CR_PASS_RX_FILT;
661
-}
662
-
663
-/*********************************************************************//**
664
- * @brief		Enable/Disable Filter mode for each specified type EMAC peripheral
665
- * @param[in]	ulFilterMode	Filter mode, should be:
666
- * 								- EMAC_RFC_UCAST_EN: all frames of unicast types
667
- * 								will be accepted
668
- * 								- EMAC_RFC_BCAST_EN: broadcast frame will be
669
- * 								accepted
670
- * 								- EMAC_RFC_MCAST_EN: all frames of multicast
671
- * 								types will be accepted
672
- * 								- EMAC_RFC_UCAST_HASH_EN: The imperfect hash
673
- * 								filter will be applied to unicast addresses
674
- * 								- EMAC_RFC_MCAST_HASH_EN: The imperfect hash
675
- * 								filter will be applied to multicast addresses
676
- * 								- EMAC_RFC_PERFECT_EN: the destination address
677
- * 								will be compared with the 6 byte station address
678
- * 								programmed in the station address by the filter
679
- * 								- EMAC_RFC_MAGP_WOL_EN: the result of the magic
680
- * 								packet filter will generate a WoL interrupt when
681
- * 								there is a match
682
- * 								- EMAC_RFC_PFILT_WOL_EN: the result of the perfect address
683
- * 								matching filter and the imperfect hash filter will
684
- * 								generate a WoL interrupt when there is a match
685
- * @param[in]	NewState	New State of this command, should be:
686
- * 								- ENABLE
687
- * 								- DISABLE
688
- * @return		None
689
- **********************************************************************/
690
-void EMAC_SetFilterMode(uint32_t ulFilterMode, FunctionalState NewState)
691
-{
692
-	if (NewState == ENABLE){
693
-		LPC_EMAC->RxFilterCtrl |= ulFilterMode;
694
-	} else {
695
-		LPC_EMAC->RxFilterCtrl &= ~ulFilterMode;
696
-	}
697
-}
698
-
699
-/*********************************************************************//**
700
- * @brief		Get status of Wake On LAN Filter for each specified
701
- * 				type in EMAC peripheral, clear this status if it is set
702
- * @param[in]	ulWoLMode	WoL Filter mode, should be:
703
- * 								- EMAC_WOL_UCAST: unicast frames caused WoL
704
- * 								- EMAC_WOL_UCAST: broadcast frame caused WoL
705
- * 								- EMAC_WOL_MCAST: multicast frame caused WoL
706
- * 								- EMAC_WOL_UCAST_HASH: unicast frame that passes the
707
- * 								imperfect hash filter caused WoL
708
- * 								- EMAC_WOL_MCAST_HASH: multicast frame that passes the
709
- * 								imperfect hash filter caused WoL
710
- * 								- EMAC_WOL_PERFECT:perfect address matching filter
711
- * 								caused WoL
712
- * 								- EMAC_WOL_RX_FILTER: the receive filter caused WoL
713
- * 								- EMAC_WOL_MAG_PACKET: the magic packet filter caused WoL
714
- * @return		SET/RESET
715
- **********************************************************************/
716
-FlagStatus EMAC_GetWoLStatus(uint32_t ulWoLMode)
717
-{
718
-	if (LPC_EMAC->RxFilterWoLStatus & ulWoLMode) {
719
-		LPC_EMAC->RxFilterWoLClear = ulWoLMode;
720
-		return SET;
721
-	} else {
722
-		return RESET;
723
-	}
724
-}
725
-
726
-
727
-/*********************************************************************//**
728
- * @brief		Write data to Tx packet data buffer at current index due to
729
- * 				TxProduceIndex
730
- * @param[in]	pDataStruct		Pointer to a EMAC_PACKETBUF_Type structure
731
- * 							data that contain specified information about
732
- * 							Packet data buffer.
733
- * @return		None
734
- **********************************************************************/
735
-void EMAC_WritePacketBuffer(EMAC_PACKETBUF_Type *pDataStruct)
736
-{
737
-	uint32_t idx,len;
738
-	uint32_t *sp,*dp;
739
-
740
-	idx = LPC_EMAC->TxProduceIndex;
741
-	sp  = (uint32_t *)pDataStruct->pbDataBuf;
742
-	dp  = (uint32_t *)Tx_Desc[idx].Packet;
743
-	/* Copy frame data to EMAC packet buffers. */
744
-	for (len = (pDataStruct->ulDataLen + 3) >> 2; len; len--) {
745
-		*dp++ = *sp++;
746
-	}
747
-	Tx_Desc[idx].Ctrl = (pDataStruct->ulDataLen - 1) | (EMAC_TCTRL_INT | EMAC_TCTRL_LAST);
748
-}
749
-
750
-/*********************************************************************//**
751
- * @brief		Read data from Rx packet data buffer at current index due
752
- * 				to RxConsumeIndex
753
- * @param[in]	pDataStruct		Pointer to a EMAC_PACKETBUF_Type structure
754
- * 							data that contain specified information about
755
- * 							Packet data buffer.
756
- * @return		None
757
- **********************************************************************/
758
-void EMAC_ReadPacketBuffer(EMAC_PACKETBUF_Type *pDataStruct)
759
-{
760
-	uint32_t idx, len;
761
-	uint32_t *dp, *sp;
762
-
763
-	idx = LPC_EMAC->RxConsumeIndex;
764
-	dp = (uint32_t *)pDataStruct->pbDataBuf;
765
-	sp = (uint32_t *)Rx_Desc[idx].Packet;
766
-
767
-	if (pDataStruct->pbDataBuf != NULL) {
768
-		for (len = (pDataStruct->ulDataLen + 3) >> 2; len; len--) {
769
-			*dp++ = *sp++;
770
-		}
771
-	}
772
-}
773
-
774
-/*********************************************************************//**
775
- * @brief 		Enable/Disable interrupt for each type in EMAC
776
- * @param[in]	ulIntType	Interrupt Type, should be:
777
- * 							- EMAC_INT_RX_OVERRUN: Receive Overrun
778
- * 							- EMAC_INT_RX_ERR: Receive Error
779
- * 							- EMAC_INT_RX_FIN: Receive Descriptor Finish
780
- * 							- EMAC_INT_RX_DONE: Receive Done
781
- * 							- EMAC_INT_TX_UNDERRUN: Transmit Under-run
782
- * 							- EMAC_INT_TX_ERR: Transmit Error
783
- * 							- EMAC_INT_TX_FIN: Transmit descriptor finish
784
- * 							- EMAC_INT_TX_DONE: Transmit Done
785
- * 							- EMAC_INT_SOFT_INT: Software interrupt
786
- * 							- EMAC_INT_WAKEUP: Wakeup interrupt
787
- * @param[in]	NewState	New State of this function, should be:
788
- * 							- ENABLE.
789
- * 							- DISABLE.
790
- * @return		None
791
- **********************************************************************/
792
-void EMAC_IntCmd(uint32_t ulIntType, FunctionalState NewState)
793
-{
794
-	if (NewState == ENABLE) {
795
-		LPC_EMAC->IntEnable |= ulIntType;
796
-	} else {
797
-		LPC_EMAC->IntEnable &= ~(ulIntType);
798
-	}
799
-}
800
-
801
-/*********************************************************************//**
802
- * @brief 		Check whether if specified interrupt flag is set or not
803
- * 				for each interrupt type in EMAC and clear interrupt pending
804
- * 				if it is set.
805
- * @param[in]	ulIntType	Interrupt Type, should be:
806
- * 							- EMAC_INT_RX_OVERRUN: Receive Overrun
807
- * 							- EMAC_INT_RX_ERR: Receive Error
808
- * 							- EMAC_INT_RX_FIN: Receive Descriptor Finish
809
- * 							- EMAC_INT_RX_DONE: Receive Done
810
- * 							- EMAC_INT_TX_UNDERRUN: Transmit Under-run
811
- * 							- EMAC_INT_TX_ERR: Transmit Error
812
- * 							- EMAC_INT_TX_FIN: Transmit descriptor finish
813
- * 							- EMAC_INT_TX_DONE: Transmit Done
814
- * 							- EMAC_INT_SOFT_INT: Software interrupt
815
- * 							- EMAC_INT_WAKEUP: Wakeup interrupt
816
- * @return		New state of specified interrupt (SET or RESET)
817
- **********************************************************************/
818
-IntStatus EMAC_IntGetStatus(uint32_t ulIntType)
819
-{
820
-	if (LPC_EMAC->IntStatus & ulIntType) {
821
-		LPC_EMAC->IntClear = ulIntType;
822
-		return SET;
823
-	} else {
824
-		return RESET;
825
-	}
826
-}
827
-
828
-
829
-/*********************************************************************//**
830
- * @brief		Check whether if the current RxConsumeIndex is not equal to the
831
- * 				current RxProduceIndex.
832
- * @param[in]	None
833
- * @return		TRUE if they're not equal, otherwise return FALSE
834
- *
835
- * Note: In case the RxConsumeIndex is not equal to the RxProduceIndex,
836
- * it means there're available data has been received. They should be read
837
- * out and released the Receive Data Buffer by updating the RxConsumeIndex value.
838
- **********************************************************************/
839
-Bool EMAC_CheckReceiveIndex(void)
840
-{
841
-	if (LPC_EMAC->RxConsumeIndex != LPC_EMAC->RxProduceIndex) {
842
-		return TRUE;
843
-	} else {
844
-		return FALSE;
845
-	}
846
-}
847
-
848
-
849
-/*********************************************************************//**
850
- * @brief		Check whether if the current TxProduceIndex is not equal to the
851
- * 				current RxProduceIndex - 1.
852
- * @param[in]	None
853
- * @return		TRUE if they're not equal, otherwise return FALSE
854
- *
855
- * Note: In case the RxConsumeIndex is equal to the RxProduceIndex - 1,
856
- * it means the transmit buffer is available and data can be written to transmit
857
- * buffer to be sent.
858
- **********************************************************************/
859
-Bool EMAC_CheckTransmitIndex(void)
860
-{
861
-    uint32_t tmp = LPC_EMAC->TxConsumeIndex;
862
-    if (LPC_EMAC->TxProduceIndex == ( tmp - 1 ))
863
-    {
864
-        return FALSE;
865
-    }
866
-    else if( ( tmp == 0 ) && ( LPC_EMAC->TxProduceIndex == ( EMAC_NUM_TX_FRAG - 1 ) ) )
867
-    {
868
-        return FALSE;
869
-    }
870
-    else
871
-    {
872
-        return TRUE;
873
-    }
874
-}
875
-
876
-
877
-
878
-/*********************************************************************//**
879
- * @brief		Get current status value of receive data (due to RxConsumeIndex)
880
- * @param[in]	ulRxStatType	Received Status type, should be one of following:
881
- * 							- EMAC_RINFO_CTRL_FRAME: Control Frame
882
- * 							- EMAC_RINFO_VLAN: VLAN Frame
883
- * 							- EMAC_RINFO_FAIL_FILT: RX Filter Failed
884
- * 							- EMAC_RINFO_MCAST: Multicast Frame
885
- * 							- EMAC_RINFO_BCAST: Broadcast Frame
886
- * 							- EMAC_RINFO_CRC_ERR: CRC Error in Frame
887
- * 							- EMAC_RINFO_SYM_ERR: Symbol Error from PHY
888
- * 							- EMAC_RINFO_LEN_ERR: Length Error
889
- * 							- EMAC_RINFO_RANGE_ERR: Range error(exceeded max size)
890
- * 							- EMAC_RINFO_ALIGN_ERR: Alignment error
891
- * 							- EMAC_RINFO_OVERRUN: Receive overrun
892
- * 							- EMAC_RINFO_NO_DESCR: No new Descriptor available
893
- * 							- EMAC_RINFO_LAST_FLAG: last Fragment in Frame
894
- * 							- EMAC_RINFO_ERR: Error Occurred (OR of all error)
895
- * @return		Current value of receive data (due to RxConsumeIndex)
896
- **********************************************************************/
897
-FlagStatus EMAC_CheckReceiveDataStatus(uint32_t ulRxStatType)
898
-{
899
-	uint32_t idx;
900
-	idx = LPC_EMAC->RxConsumeIndex;
901
-	return (((Rx_Stat[idx].Info) & ulRxStatType) ? SET : RESET);
902
-}
903
-
904
-
905
-/*********************************************************************//**
906
- * @brief		Get size of current Received data in received buffer (due to
907
- * 				RxConsumeIndex)
908
- * @param[in]	None
909
- * @return		Size of received data
910
- **********************************************************************/
911
-uint32_t EMAC_GetReceiveDataSize(void)
912
-{
913
-	uint32_t idx;
914
-	idx =LPC_EMAC->RxConsumeIndex;
915
-	return ((Rx_Stat[idx].Info) & EMAC_RINFO_SIZE);
916
-}
917
-
918
-/*********************************************************************//**
919
- * @brief		Increase the RxConsumeIndex (after reading the Receive buffer
920
- * 				to release the Receive buffer) and wrap-around the index if
921
- * 				it reaches the maximum Receive Number
922
- * @param[in]	None
923
- * @return		None
924
- **********************************************************************/
925
-void EMAC_UpdateRxConsumeIndex(void)
926
-{
927
-	// Get current Rx consume index
928
-	uint32_t idx = LPC_EMAC->RxConsumeIndex;
929
-
930
-	/* Release frame from EMAC buffer */
931
-	if (++idx == EMAC_NUM_RX_FRAG) idx = 0;
932
-	LPC_EMAC->RxConsumeIndex = idx;
933
-}
934
-
935
-/*********************************************************************//**
936
- * @brief		Increase the TxProduceIndex (after writting to the Transmit buffer
937
- * 				to enable the Transmit buffer) and wrap-around the index if
938
- * 				it reaches the maximum Transmit Number
939
- * @param[in]	None
940
- * @return		None
941
- **********************************************************************/
942
-void EMAC_UpdateTxProduceIndex(void)
943
-{
944
-	// Get current Tx produce index
945
-	uint32_t idx = LPC_EMAC->TxProduceIndex;
946
-
947
-	/* Start frame transmission */
948
-	if (++idx == EMAC_NUM_TX_FRAG) idx = 0;
949
-	LPC_EMAC->TxProduceIndex = idx;
950
-}
951
-
952
-
953
-/**
954
- * @}
955
- */
956
-
957
-#endif /* _EMAC */
958
-
959
-/**
960
- * @}
961
- */
962
-
963
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 171
frameworks/CMSIS/LPC1768/driver/lpc17xx_exti.c Просмотреть файл

@@ -1,171 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_exti.c				2010-06-18
3
-*//**
4
-* @file		lpc17xx_exti.c
5
-* @brief	Contains all functions support for External interrupt firmware
6
-* 			library on LPC17xx
7
-* @version	3.0
8
-* @date		18. June. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @addtogroup EXTI
35
- * @{
36
- */
37
-
38
-/* Includes ------------------------------------------------------------------- */
39
-#include "lpc17xx_exti.h"
40
-
41
-/* If this source file built with example, the LPC17xx FW library configuration
42
- * file in each example directory ("lpc17xx_libcfg.h") must be included,
43
- * otherwise the default FW library configuration file must be included instead
44
- */
45
-#ifdef __BUILD_WITH_EXAMPLE__
46
-#include "lpc17xx_libcfg.h"
47
-#else
48
-#include "lpc17xx_libcfg_default.h"
49
-#endif /* __BUILD_WITH_EXAMPLE__ */
50
-
51
-
52
-#ifdef _EXTI
53
-
54
-/* Public Functions ----------------------------------------------------------- */
55
-/** @addtogroup EXTI_Public_Functions
56
- * @{
57
- */
58
-
59
-/*********************************************************************//**
60
- * @brief 		Initial for EXT
61
- * 				- Set EXTINT, EXTMODE, EXTPOLAR registers to default value
62
- * @param[in]	None
63
- * @return 		None
64
- **********************************************************************/
65
-void EXTI_Init(void)
66
-{
67
-	LPC_SC->EXTINT = 0xF;
68
-	LPC_SC->EXTMODE = 0x0;
69
-	LPC_SC->EXTPOLAR = 0x0;
70
-}
71
-
72
-
73
-/*********************************************************************//**
74
-* @brief 		Close EXT
75
-* @param[in]	None
76
-* @return 		None
77
-**********************************************************************/
78
-void	EXTI_DeInit(void)
79
-{
80
-	;
81
-}
82
-
83
-/*********************************************************************//**
84
- * @brief 		Configuration for EXT
85
- * 				- Set EXTINT, EXTMODE, EXTPOLAR register
86
- * @param[in]	EXTICfg	Pointer to a EXTI_InitTypeDef structure
87
- *              that contains the configuration information for the
88
- *              specified external interrupt
89
- * @return 		None
90
- **********************************************************************/
91
-void EXTI_Config(EXTI_InitTypeDef *EXTICfg)
92
-{
93
-	LPC_SC->EXTINT = 0x0;
94
-	EXTI_SetMode(EXTICfg->EXTI_Line, EXTICfg->EXTI_Mode);
95
-	EXTI_SetPolarity(EXTICfg->EXTI_Line, EXTICfg->EXTI_polarity);
96
-}
97
-
98
-/*********************************************************************//**
99
-* @brief 		Set mode for EXTI pin
100
-* @param[in]	EXTILine	 external interrupt line, should be:
101
-* 				- EXTI_EINT0: external interrupt line 0
102
-* 				- EXTI_EINT1: external interrupt line 1
103
-* 				- EXTI_EINT2: external interrupt line 2
104
-* 				- EXTI_EINT3: external interrupt line 3
105
-* @param[in]	mode 	external mode, should be:
106
-* 				- EXTI_MODE_LEVEL_SENSITIVE
107
-* 				- EXTI_MODE_EDGE_SENSITIVE
108
-* @return 		None
109
-*********************************************************************/
110
-void EXTI_SetMode(EXTI_LINE_ENUM EXTILine, EXTI_MODE_ENUM mode)
111
-{
112
-	if(mode == EXTI_MODE_EDGE_SENSITIVE)
113
-	{
114
-		LPC_SC->EXTMODE |= (1 << EXTILine);
115
-	}
116
-	else if(mode == EXTI_MODE_LEVEL_SENSITIVE)
117
-	{
118
-		LPC_SC->EXTMODE &= ~(1 << EXTILine);
119
-	}
120
-}
121
-
122
-/*********************************************************************//**
123
-* @brief 		Set polarity for EXTI pin
124
-* @param[in]	EXTILine	 external interrupt line, should be:
125
-* 				- EXTI_EINT0: external interrupt line 0
126
-* 				- EXTI_EINT1: external interrupt line 1
127
-* 				- EXTI_EINT2: external interrupt line 2
128
-* 				- EXTI_EINT3: external interrupt line 3
129
-* @param[in]	polarity	 external polarity value, should be:
130
-* 				- EXTI_POLARITY_LOW_ACTIVE_OR_FALLING_EDGE
131
-* 				- EXTI_POLARITY_LOW_ACTIVE_OR_FALLING_EDGE
132
-* @return 		None
133
-*********************************************************************/
134
-void EXTI_SetPolarity(EXTI_LINE_ENUM EXTILine, EXTI_POLARITY_ENUM polarity)
135
-{
136
-	if(polarity == EXTI_POLARITY_HIGH_ACTIVE_OR_RISING_EDGE)
137
-	{
138
-		LPC_SC->EXTPOLAR |= (1 << EXTILine);
139
-	}
140
-	else if(polarity == EXTI_POLARITY_LOW_ACTIVE_OR_FALLING_EDGE)
141
-	{
142
-		LPC_SC->EXTPOLAR &= ~(1 << EXTILine);
143
-	}
144
-}
145
-
146
-/*********************************************************************//**
147
-* @brief 		Clear External interrupt flag
148
-* @param[in]	EXTILine	 external interrupt line, should be:
149
-* 				- EXTI_EINT0: external interrupt line 0
150
-* 				- EXTI_EINT1: external interrupt line 1
151
-* 				- EXTI_EINT2: external interrupt line 2
152
-* 				- EXTI_EINT3: external interrupt line 3
153
-* @return 		None
154
-*********************************************************************/
155
-void EXTI_ClearEXTIFlag(EXTI_LINE_ENUM EXTILine)
156
-{
157
-		LPC_SC->EXTINT = (1 << EXTILine);
158
-}
159
-
160
-/**
161
- * @}
162
- */
163
-
164
-#endif /* _EXTI */
165
-
166
-/**
167
- * @}
168
- */
169
-
170
-/* --------------------------------- End Of File ------------------------------ */
171
-

+ 0
- 463
frameworks/CMSIS/LPC1768/driver/lpc17xx_gpdma.c Просмотреть файл

@@ -1,463 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_gpdma.c				2010-03-21
3
-*//**
4
-* @file		lpc17xx_gpdma.c
5
-* @brief	Contains all functions support for GPDMA firmware
6
-* 			library on LPC17xx
7
-* @version	2.1
8
-* @date		25. July. 2011
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @addtogroup GPDMA
35
- * @{
36
- */
37
-
38
-/* Includes ------------------------------------------------------------------- */
39
-#include "lpc17xx_gpdma.h"
40
-#include "lpc17xx_clkpwr.h"
41
-
42
-/* If this source file built with example, the LPC17xx FW library configuration
43
- * file in each example directory ("lpc17xx_libcfg.h") must be included,
44
- * otherwise the default FW library configuration file must be included instead
45
- */
46
-#ifdef __BUILD_WITH_EXAMPLE__
47
-#include "lpc17xx_libcfg.h"
48
-#else
49
-#include "lpc17xx_libcfg_default.h"
50
-#endif /* __BUILD_WITH_EXAMPLE__ */
51
-
52
-#ifdef _GPDMA
53
-
54
-
55
-/* Private Variables ---------------------------------------------------------- */
56
-/** @defgroup GPDMA_Private_Variables GPDMA Private Variables
57
- * @{
58
- */
59
-
60
-/**
61
- * @brief Lookup Table of Connection Type matched with
62
- * Peripheral Data (FIFO) register base address
63
- */
64
-//#ifdef __IAR_SYSTEMS_ICC__
65
-volatile const void *GPDMA_LUTPerAddr[] = {
66
-		(&LPC_SSP0->DR),				// SSP0 Tx
67
-		(&LPC_SSP0->DR),				// SSP0 Rx
68
-		(&LPC_SSP1->DR),				// SSP1 Tx
69
-		(&LPC_SSP1->DR),				// SSP1 Rx
70
-		(&LPC_ADC->ADGDR),			// ADC
71
-		(&LPC_I2S->I2STXFIFO), 		// I2S Tx
72
-		(&LPC_I2S->I2SRXFIFO), 		// I2S Rx
73
-		(&LPC_DAC->DACR),				// DAC
74
-		(&LPC_UART0->/*RBTHDLR.*/THR),	// UART0 Tx
75
-		(&LPC_UART0->/*RBTHDLR.*/RBR),	// UART0 Rx
76
-		(&LPC_UART1->/*RBTHDLR.*/THR),	// UART1 Tx
77
-		(&LPC_UART1->/*RBTHDLR.*/RBR),	// UART1 Rx
78
-		(&LPC_UART2->/*RBTHDLR.*/THR),	// UART2 Tx
79
-		(&LPC_UART2->/*RBTHDLR.*/RBR),	// UART2 Rx
80
-		(&LPC_UART3->/*RBTHDLR.*/THR),	// UART3 Tx
81
-		(&LPC_UART3->/*RBTHDLR.*/RBR),	// UART3 Rx
82
-		(&LPC_TIM0->MR0),				// MAT0.0
83
-		(&LPC_TIM0->MR1),				// MAT0.1
84
-		(&LPC_TIM1->MR0),				// MAT1.0
85
-		(&LPC_TIM1->MR1),				// MAT1.1
86
-		(&LPC_TIM2->MR0),				// MAT2.0
87
-		(&LPC_TIM2->MR1),				// MAT2.1
88
-		(&LPC_TIM3->MR0),				// MAT3.0
89
-		(&LPC_TIM3->MR1)				// MAT3.1
90
-};
91
-//#else
92
-//const uint32_t GPDMA_LUTPerAddr[] = {
93
-//		((uint32_t)&LPC_SSP0->DR), 				// SSP0 Tx
94
-//		((uint32_t)&LPC_SSP0->DR), 				// SSP0 Rx
95
-//		((uint32_t)&LPC_SSP1->DR),				// SSP1 Tx
96
-//		((uint32_t)&LPC_SSP1->DR),				// SSP1 Rx
97
-//		((uint32_t)&LPC_ADC->ADGDR),			// ADC
98
-//		((uint32_t)&LPC_I2S->I2STXFIFO), 		// I2S Tx
99
-//		((uint32_t)&LPC_I2S->I2SRXFIFO), 		// I2S Rx
100
-//		((uint32_t)&LPC_DAC->DACR),				// DAC
101
-//		((uint32_t)&LPC_UART0->/*RBTHDLR.*/THR),	// UART0 Tx
102
-//		((uint32_t)&LPC_UART0->/*RBTHDLR.*/RBR),	// UART0 Rx
103
-//		((uint32_t)&LPC_UART1->/*RBTHDLR.*/THR),	// UART1 Tx
104
-//		((uint32_t)&LPC_UART1->/*RBTHDLR.*/RBR),	// UART1 Rx
105
-//		((uint32_t)&LPC_UART2->/*RBTHDLR.*/THR),	// UART2 Tx
106
-//		((uint32_t)&LPC_UART2->/*RBTHDLR.*/RBR),	// UART2 Rx
107
-//		((uint32_t)&LPC_UART3->/*RBTHDLR.*/THR),	// UART3 Tx
108
-//		((uint32_t)&LPC_UART3->/*RBTHDLR.*/RBR),	// UART3 Rx
109
-//		((uint32_t)&LPC_TIM0->MR0),				// MAT0.0
110
-//		((uint32_t)&LPC_TIM0->MR1),				// MAT0.1
111
-//		((uint32_t)&LPC_TIM1->MR0),				// MAT1.0
112
-//		((uint32_t)&LPC_TIM1->MR1),				// MAT1.1
113
-//		((uint32_t)&LPC_TIM2->MR0),				// MAT2.0
114
-//		((uint32_t)&LPC_TIM2->MR1),				// MAT2.1
115
-//		((uint32_t)&LPC_TIM3->MR0),				// MAT3.0
116
-//		((uint32_t)&LPC_TIM3->MR1)				// MAT3.1
117
-//};
118
-//#endif
119
-/**
120
- * @brief Lookup Table of GPDMA Channel Number matched with
121
- * GPDMA channel pointer
122
- */
123
-const LPC_GPDMACH_TypeDef *pGPDMACh[8] = {
124
-		LPC_GPDMACH0,	// GPDMA Channel 0
125
-		LPC_GPDMACH1,	// GPDMA Channel 1
126
-		LPC_GPDMACH2,	// GPDMA Channel 2
127
-		LPC_GPDMACH3,	// GPDMA Channel 3
128
-		LPC_GPDMACH4,	// GPDMA Channel 4
129
-		LPC_GPDMACH5,	// GPDMA Channel 5
130
-		LPC_GPDMACH6,	// GPDMA Channel 6
131
-		LPC_GPDMACH7	// GPDMA Channel 7
132
-};
133
-/**
134
- * @brief Optimized Peripheral Source and Destination burst size
135
- */
136
-const uint8_t GPDMA_LUTPerBurst[] = {
137
-		GPDMA_BSIZE_4,				// SSP0 Tx
138
-		GPDMA_BSIZE_4,				// SSP0 Rx
139
-		GPDMA_BSIZE_4,				// SSP1 Tx
140
-		GPDMA_BSIZE_4,				// SSP1 Rx
141
-		GPDMA_BSIZE_1,				// ADC
142
-		GPDMA_BSIZE_32, 			// I2S channel 0
143
-		GPDMA_BSIZE_32, 			// I2S channel 1
144
-		GPDMA_BSIZE_1,				// DAC
145
-		GPDMA_BSIZE_1,				// UART0 Tx
146
-		GPDMA_BSIZE_1,				// UART0 Rx
147
-		GPDMA_BSIZE_1,				// UART1 Tx
148
-		GPDMA_BSIZE_1,				// UART1 Rx
149
-		GPDMA_BSIZE_1,				// UART2 Tx
150
-		GPDMA_BSIZE_1,				// UART2 Rx
151
-		GPDMA_BSIZE_1,				// UART3 Tx
152
-		GPDMA_BSIZE_1,				// UART3 Rx
153
-		GPDMA_BSIZE_1,				// MAT0.0
154
-		GPDMA_BSIZE_1,				// MAT0.1
155
-		GPDMA_BSIZE_1,				// MAT1.0
156
-		GPDMA_BSIZE_1,				// MAT1.1
157
-		GPDMA_BSIZE_1,				// MAT2.0
158
-		GPDMA_BSIZE_1,				// MAT2.1
159
-		GPDMA_BSIZE_1,				// MAT3.0
160
-		GPDMA_BSIZE_1				// MAT3.1
161
-};
162
-/**
163
- * @brief Optimized Peripheral Source and Destination transfer width
164
- */
165
-const uint8_t GPDMA_LUTPerWid[] = {
166
-		GPDMA_WIDTH_BYTE,				// SSP0 Tx
167
-		GPDMA_WIDTH_BYTE,				// SSP0 Rx
168
-		GPDMA_WIDTH_BYTE,				// SSP1 Tx
169
-		GPDMA_WIDTH_BYTE,				// SSP1 Rx
170
-		GPDMA_WIDTH_WORD,				// ADC
171
-		GPDMA_WIDTH_WORD, 				// I2S channel 0
172
-		GPDMA_WIDTH_WORD, 				// I2S channel 1
173
-		GPDMA_WIDTH_BYTE,				// DAC
174
-		GPDMA_WIDTH_BYTE,				// UART0 Tx
175
-		GPDMA_WIDTH_BYTE,				// UART0 Rx
176
-		GPDMA_WIDTH_BYTE,				// UART1 Tx
177
-		GPDMA_WIDTH_BYTE,				// UART1 Rx
178
-		GPDMA_WIDTH_BYTE,				// UART2 Tx
179
-		GPDMA_WIDTH_BYTE,				// UART2 Rx
180
-		GPDMA_WIDTH_BYTE,				// UART3 Tx
181
-		GPDMA_WIDTH_BYTE,				// UART3 Rx
182
-		GPDMA_WIDTH_WORD,				// MAT0.0
183
-		GPDMA_WIDTH_WORD,				// MAT0.1
184
-		GPDMA_WIDTH_WORD,				// MAT1.0
185
-		GPDMA_WIDTH_WORD,				// MAT1.1
186
-		GPDMA_WIDTH_WORD,				// MAT2.0
187
-		GPDMA_WIDTH_WORD,				// MAT2.1
188
-		GPDMA_WIDTH_WORD,				// MAT3.0
189
-		GPDMA_WIDTH_WORD				// MAT3.1
190
-};
191
-
192
-/**
193
- * @}
194
- */
195
-
196
-/* Public Functions ----------------------------------------------------------- */
197
-/** @addtogroup GPDMA_Public_Functions
198
- * @{
199
- */
200
-
201
-/********************************************************************//**
202
- * @brief 		Initialize GPDMA controller
203
- * @param 		None
204
- * @return 		None
205
- *********************************************************************/
206
-void GPDMA_Init(void)
207
-{
208
-	/* Enable GPDMA clock */
209
-	CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCGPDMA, ENABLE);
210
-
211
-	// Reset all channel configuration register
212
-	LPC_GPDMACH0->DMACCConfig = 0;
213
-	LPC_GPDMACH1->DMACCConfig = 0;
214
-	LPC_GPDMACH2->DMACCConfig = 0;
215
-	LPC_GPDMACH3->DMACCConfig = 0;
216
-	LPC_GPDMACH4->DMACCConfig = 0;
217
-	LPC_GPDMACH5->DMACCConfig = 0;
218
-	LPC_GPDMACH6->DMACCConfig = 0;
219
-	LPC_GPDMACH7->DMACCConfig = 0;
220
-
221
-	/* Clear all DMA interrupt and error flag */
222
-	LPC_GPDMA->DMACIntTCClear = 0xFF;
223
-	LPC_GPDMA->DMACIntErrClr = 0xFF;
224
-}
225
-
226
-/********************************************************************//**
227
- * @brief 		Setup GPDMA channel peripheral according to the specified
228
- *               parameters in the GPDMAChannelConfig.
229
- * @param[in]	GPDMAChannelConfig Pointer to a GPDMA_CH_CFG_Type
230
- * 									structure that contains the configuration
231
- * 									information for the specified GPDMA channel peripheral.
232
- * @return		ERROR if selected channel is enabled before
233
- * 				or SUCCESS if channel is configured successfully
234
- *********************************************************************/
235
-Status GPDMA_Setup(GPDMA_Channel_CFG_Type *GPDMAChannelConfig)
236
-{
237
-	LPC_GPDMACH_TypeDef *pDMAch;
238
-	uint32_t tmp1, tmp2;
239
-
240
-	if (LPC_GPDMA->DMACEnbldChns & (GPDMA_DMACEnbldChns_Ch(GPDMAChannelConfig->ChannelNum))) {
241
-		// This channel is enabled, return ERROR, need to release this channel first
242
-		return ERROR;
243
-	}
244
-
245
-	// Get Channel pointer
246
-	pDMAch = (LPC_GPDMACH_TypeDef *) pGPDMACh[GPDMAChannelConfig->ChannelNum];
247
-
248
-	// Reset the Interrupt status
249
-	LPC_GPDMA->DMACIntTCClear = GPDMA_DMACIntTCClear_Ch(GPDMAChannelConfig->ChannelNum);
250
-	LPC_GPDMA->DMACIntErrClr = GPDMA_DMACIntErrClr_Ch(GPDMAChannelConfig->ChannelNum);
251
-
252
-	// Clear DMA configure
253
-	pDMAch->DMACCControl = 0x00;
254
-	pDMAch->DMACCConfig = 0x00;
255
-
256
-	/* Assign Linker List Item value */
257
-	pDMAch->DMACCLLI = GPDMAChannelConfig->DMALLI;
258
-
259
-	/* Set value to Channel Control Registers */
260
-	switch (GPDMAChannelConfig->TransferType)
261
-	{
262
-	// Memory to memory
263
-	case GPDMA_TRANSFERTYPE_M2M:
264
-		// Assign physical source and destination address
265
-		pDMAch->DMACCSrcAddr = GPDMAChannelConfig->SrcMemAddr;
266
-		pDMAch->DMACCDestAddr = GPDMAChannelConfig->DstMemAddr;
267
-		pDMAch->DMACCControl
268
-				= GPDMA_DMACCxControl_TransferSize(GPDMAChannelConfig->TransferSize) \
269
-						| GPDMA_DMACCxControl_SBSize(GPDMA_BSIZE_32) \
270
-						| GPDMA_DMACCxControl_DBSize(GPDMA_BSIZE_32) \
271
-						| GPDMA_DMACCxControl_SWidth(GPDMAChannelConfig->TransferWidth) \
272
-						| GPDMA_DMACCxControl_DWidth(GPDMAChannelConfig->TransferWidth) \
273
-						| GPDMA_DMACCxControl_SI \
274
-						| GPDMA_DMACCxControl_DI \
275
-						| GPDMA_DMACCxControl_I;
276
-		break;
277
-	// Memory to peripheral
278
-	case GPDMA_TRANSFERTYPE_M2P:
279
-		// Assign physical source
280
-		pDMAch->DMACCSrcAddr = GPDMAChannelConfig->SrcMemAddr;
281
-		// Assign peripheral destination address
282
-		pDMAch->DMACCDestAddr = (uint32_t)GPDMA_LUTPerAddr[GPDMAChannelConfig->DstConn];
283
-		pDMAch->DMACCControl
284
-				= GPDMA_DMACCxControl_TransferSize((uint32_t)GPDMAChannelConfig->TransferSize) \
285
-						| GPDMA_DMACCxControl_SBSize((uint32_t)GPDMA_LUTPerBurst[GPDMAChannelConfig->DstConn]) \
286
-						| GPDMA_DMACCxControl_DBSize((uint32_t)GPDMA_LUTPerBurst[GPDMAChannelConfig->DstConn]) \
287
-						| GPDMA_DMACCxControl_SWidth((uint32_t)GPDMA_LUTPerWid[GPDMAChannelConfig->DstConn]) \
288
-						| GPDMA_DMACCxControl_DWidth((uint32_t)GPDMA_LUTPerWid[GPDMAChannelConfig->DstConn]) \
289
-						| GPDMA_DMACCxControl_SI \
290
-						| GPDMA_DMACCxControl_I;
291
-		break;
292
-	// Peripheral to memory
293
-	case GPDMA_TRANSFERTYPE_P2M:
294
-		// Assign peripheral source address
295
-		pDMAch->DMACCSrcAddr = (uint32_t)GPDMA_LUTPerAddr[GPDMAChannelConfig->SrcConn];
296
-		// Assign memory destination address
297
-		pDMAch->DMACCDestAddr = GPDMAChannelConfig->DstMemAddr;
298
-		pDMAch->DMACCControl
299
-				= GPDMA_DMACCxControl_TransferSize((uint32_t)GPDMAChannelConfig->TransferSize) \
300
-						| GPDMA_DMACCxControl_SBSize((uint32_t)GPDMA_LUTPerBurst[GPDMAChannelConfig->SrcConn]) \
301
-						| GPDMA_DMACCxControl_DBSize((uint32_t)GPDMA_LUTPerBurst[GPDMAChannelConfig->SrcConn]) \
302
-						| GPDMA_DMACCxControl_SWidth((uint32_t)GPDMA_LUTPerWid[GPDMAChannelConfig->SrcConn]) \
303
-						| GPDMA_DMACCxControl_DWidth((uint32_t)GPDMA_LUTPerWid[GPDMAChannelConfig->SrcConn]) \
304
-						| GPDMA_DMACCxControl_DI \
305
-						| GPDMA_DMACCxControl_I;
306
-		break;
307
-	// Peripheral to peripheral
308
-	case GPDMA_TRANSFERTYPE_P2P:
309
-		// Assign peripheral source address
310
-		pDMAch->DMACCSrcAddr = (uint32_t)GPDMA_LUTPerAddr[GPDMAChannelConfig->SrcConn];
311
-		// Assign peripheral destination address
312
-		pDMAch->DMACCDestAddr = (uint32_t)GPDMA_LUTPerAddr[GPDMAChannelConfig->DstConn];
313
-		pDMAch->DMACCControl
314
-				= GPDMA_DMACCxControl_TransferSize((uint32_t)GPDMAChannelConfig->TransferSize) \
315
-						| GPDMA_DMACCxControl_SBSize((uint32_t)GPDMA_LUTPerBurst[GPDMAChannelConfig->SrcConn]) \
316
-						| GPDMA_DMACCxControl_DBSize((uint32_t)GPDMA_LUTPerBurst[GPDMAChannelConfig->DstConn]) \
317
-						| GPDMA_DMACCxControl_SWidth((uint32_t)GPDMA_LUTPerWid[GPDMAChannelConfig->SrcConn]) \
318
-						| GPDMA_DMACCxControl_DWidth((uint32_t)GPDMA_LUTPerWid[GPDMAChannelConfig->DstConn]) \
319
-						| GPDMA_DMACCxControl_I;
320
-		break;
321
-	// Do not support any more transfer type, return ERROR
322
-	default:
323
-		return ERROR;
324
-	}
325
-
326
-	/* Re-Configure DMA Request Select for source peripheral */
327
-	if (GPDMAChannelConfig->SrcConn > 15)
328
-	{
329
-		LPC_SC->DMAREQSEL |= (1<<(GPDMAChannelConfig->SrcConn - 16));
330
-	} else {
331
-		LPC_SC->DMAREQSEL &= ~(1<<(GPDMAChannelConfig->SrcConn - 8));
332
-	}
333
-
334
-	/* Re-Configure DMA Request Select for Destination peripheral */
335
-	if (GPDMAChannelConfig->DstConn > 15)
336
-	{
337
-		LPC_SC->DMAREQSEL |= (1<<(GPDMAChannelConfig->DstConn - 16));
338
-	} else {
339
-		LPC_SC->DMAREQSEL &= ~(1<<(GPDMAChannelConfig->DstConn - 8));
340
-	}
341
-
342
-	/* Enable DMA channels, little endian */
343
-	LPC_GPDMA->DMACConfig = GPDMA_DMACConfig_E;
344
-	while (!(LPC_GPDMA->DMACConfig & GPDMA_DMACConfig_E));
345
-
346
-	// Calculate absolute value for Connection number
347
-	tmp1 = GPDMAChannelConfig->SrcConn;
348
-	tmp1 = ((tmp1 > 15) ? (tmp1 - 8) : tmp1);
349
-	tmp2 = GPDMAChannelConfig->DstConn;
350
-	tmp2 = ((tmp2 > 15) ? (tmp2 - 8) : tmp2);
351
-
352
-	// Configure DMA Channel, enable Error Counter and Terminate counter
353
-	pDMAch->DMACCConfig = GPDMA_DMACCxConfig_IE | GPDMA_DMACCxConfig_ITC /*| GPDMA_DMACCxConfig_E*/ \
354
-		| GPDMA_DMACCxConfig_TransferType((uint32_t)GPDMAChannelConfig->TransferType) \
355
-		| GPDMA_DMACCxConfig_SrcPeripheral(tmp1) \
356
-		| GPDMA_DMACCxConfig_DestPeripheral(tmp2);
357
-
358
-	return SUCCESS;
359
-}
360
-
361
-
362
-/*********************************************************************//**
363
- * @brief		Enable/Disable DMA channel
364
- * @param[in]	channelNum	GPDMA channel, should be in range from 0 to 7
365
- * @param[in]	NewState	New State of this command, should be:
366
- * 					- ENABLE.
367
- * 					- DISABLE.
368
- * @return		None
369
- **********************************************************************/
370
-void GPDMA_ChannelCmd(uint8_t channelNum, FunctionalState NewState)
371
-{
372
-	LPC_GPDMACH_TypeDef *pDMAch;
373
-
374
-	// Get Channel pointer
375
-	pDMAch = (LPC_GPDMACH_TypeDef *) pGPDMACh[channelNum];
376
-
377
-	if (NewState == ENABLE) {
378
-		pDMAch->DMACCConfig |= GPDMA_DMACCxConfig_E;
379
-	} else {
380
-		pDMAch->DMACCConfig &= ~GPDMA_DMACCxConfig_E;
381
-	}
382
-}
383
-/*********************************************************************//**
384
- * @brief		Check if corresponding channel does have an active interrupt
385
- * 				request or not
386
- * @param[in]	type		type of status, should be:
387
- * 					- GPDMA_STAT_INT: 		GPDMA Interrupt Status
388
- * 					- GPDMA_STAT_INTTC: 	GPDMA Interrupt Terminal Count Request Status
389
- * 					- GPDMA_STAT_INTERR:	GPDMA Interrupt Error Status
390
- * 					- GPDMA_STAT_RAWINTTC:	GPDMA Raw Interrupt Terminal Count Status
391
- * 					- GPDMA_STAT_RAWINTERR:	GPDMA Raw Error Interrupt Status
392
- * 					- GPDMA_STAT_ENABLED_CH:GPDMA Enabled Channel Status
393
- * @param[in]	channel		GPDMA channel, should be in range from 0 to 7
394
- * @return		IntStatus	status of DMA channel interrupt after masking
395
- * 				Should be:
396
- * 					- SET: the corresponding channel has no active interrupt request
397
- * 					- RESET: the corresponding channel does have an active interrupt request
398
- **********************************************************************/
399
-IntStatus GPDMA_IntGetStatus(GPDMA_Status_Type type, uint8_t channel)
400
-{
401
-	CHECK_PARAM(PARAM_GPDMA_STAT(type));
402
-	CHECK_PARAM(PARAM_GPDMA_CHANNEL(channel));
403
-
404
-	switch (type)
405
-	{
406
-	case GPDMA_STAT_INT: //check status of DMA channel interrupts
407
-		if (LPC_GPDMA->DMACIntStat & (GPDMA_DMACIntStat_Ch(channel)))
408
-			return SET;
409
-		return RESET;
410
-	case GPDMA_STAT_INTTC: // check terminal count interrupt request status for DMA
411
-		if (LPC_GPDMA->DMACIntTCStat & GPDMA_DMACIntTCStat_Ch(channel))
412
-			return SET;
413
-		return RESET;
414
-	case GPDMA_STAT_INTERR: //check interrupt status for DMA channels
415
-		if (LPC_GPDMA->DMACIntErrStat & GPDMA_DMACIntTCClear_Ch(channel))
416
-			return SET;
417
-		return RESET;
418
-	case GPDMA_STAT_RAWINTTC: //check status of the terminal count interrupt for DMA channels
419
-		if (LPC_GPDMA->DMACRawIntErrStat & GPDMA_DMACRawIntTCStat_Ch(channel))
420
-			return SET;
421
-		return RESET;
422
-	case GPDMA_STAT_RAWINTERR: //check status of the error interrupt for DMA channels
423
-		if (LPC_GPDMA->DMACRawIntTCStat & GPDMA_DMACRawIntErrStat_Ch(channel))
424
-			return SET;
425
-		return RESET;
426
-	default: //check enable status for DMA channels
427
-		if (LPC_GPDMA->DMACEnbldChns & GPDMA_DMACEnbldChns_Ch(channel))
428
-			return SET;
429
-		return RESET;
430
-	}
431
-}
432
-
433
-/*********************************************************************//**
434
- * @brief		Clear one or more interrupt requests on DMA channels
435
- * @param[in]	type		type of interrupt request, should be:
436
- * 					- GPDMA_STATCLR_INTTC: 	GPDMA Interrupt Terminal Count Request Clear
437
- * 					- GPDMA_STATCLR_INTERR: GPDMA Interrupt Error Clear
438
- * @param[in]	channel		GPDMA channel, should be in range from 0 to 7
439
- * @return		None
440
- **********************************************************************/
441
-void GPDMA_ClearIntPending(GPDMA_StateClear_Type type, uint8_t channel)
442
-{
443
-	CHECK_PARAM(PARAM_GPDMA_STATCLR(type));
444
-	CHECK_PARAM(PARAM_GPDMA_CHANNEL(channel));
445
-
446
-	if (type == GPDMA_STATCLR_INTTC) // clears the terminal count interrupt request on DMA channel
447
-		LPC_GPDMA->DMACIntTCClear = GPDMA_DMACIntTCClear_Ch(channel);
448
-	else // clear the error interrupt request
449
-		LPC_GPDMA->DMACIntErrClr = GPDMA_DMACIntErrClr_Ch(channel);
450
-}
451
-
452
-/**
453
- * @}
454
- */
455
-
456
-#endif /* _GPDMA */
457
-
458
-/**
459
- * @}
460
- */
461
-
462
-/* --------------------------------- End Of File ------------------------------ */
463
-

+ 0
- 762
frameworks/CMSIS/LPC1768/driver/lpc17xx_gpio.c Просмотреть файл

@@ -1,762 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_gpio.c				2010-05-21
3
-*//**
4
-* @file		lpc17xx_gpio.c
5
-* @brief	Contains all functions support for GPIO firmware
6
-* 			library on LPC17xx
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @addtogroup GPIO
35
- * @{
36
- */
37
-
38
-/* Includes ------------------------------------------------------------------- */
39
-#include "lpc17xx_gpio.h"
40
-
41
-/* If this source file built with example, the LPC17xx FW library configuration
42
- * file in each example directory ("lpc17xx_libcfg.h") must be included,
43
- * otherwise the default FW library configuration file must be included instead
44
- */
45
-#ifdef __BUILD_WITH_EXAMPLE__
46
-#include "lpc17xx_libcfg.h"
47
-#else
48
-#include "lpc17xx_libcfg_default.h"
49
-#endif /* __BUILD_WITH_EXAMPLE__ */
50
-
51
-
52
-#ifdef _GPIO
53
-
54
-/* Private Functions ---------------------------------------------------------- */
55
-
56
-static LPC_GPIO_TypeDef *GPIO_GetPointer(uint8_t portNum);
57
-static GPIO_HalfWord_TypeDef *FIO_HalfWordGetPointer(uint8_t portNum);
58
-static GPIO_Byte_TypeDef *FIO_ByteGetPointer(uint8_t portNum);
59
-
60
-/*********************************************************************//**
61
- * @brief		Get pointer to GPIO peripheral due to GPIO port
62
- * @param[in]	portNum		Port Number value, should be in range from 0 to 4.
63
- * @return		Pointer to GPIO peripheral
64
- **********************************************************************/
65
-static LPC_GPIO_TypeDef *GPIO_GetPointer(uint8_t portNum)
66
-{
67
-	LPC_GPIO_TypeDef *pGPIO = NULL;
68
-
69
-	switch (portNum) {
70
-	case 0:
71
-		pGPIO = LPC_GPIO0;
72
-		break;
73
-	case 1:
74
-		pGPIO = LPC_GPIO1;
75
-		break;
76
-	case 2:
77
-		pGPIO = LPC_GPIO2;
78
-		break;
79
-	case 3:
80
-		pGPIO = LPC_GPIO3;
81
-		break;
82
-	case 4:
83
-		pGPIO = LPC_GPIO4;
84
-		break;
85
-	default:
86
-		break;
87
-	}
88
-
89
-	return pGPIO;
90
-}
91
-
92
-/*********************************************************************//**
93
- * @brief		Get pointer to FIO peripheral in halfword accessible style
94
- * 				due to FIO port
95
- * @param[in]	portNum		Port Number value, should be in range from 0 to 4.
96
- * @return		Pointer to FIO peripheral
97
- **********************************************************************/
98
-static GPIO_HalfWord_TypeDef *FIO_HalfWordGetPointer(uint8_t portNum)
99
-{
100
-	GPIO_HalfWord_TypeDef *pFIO = NULL;
101
-
102
-	switch (portNum) {
103
-	case 0:
104
-		pFIO = GPIO0_HalfWord;
105
-		break;
106
-	case 1:
107
-		pFIO = GPIO1_HalfWord;
108
-		break;
109
-	case 2:
110
-		pFIO = GPIO2_HalfWord;
111
-		break;
112
-	case 3:
113
-		pFIO = GPIO3_HalfWord;
114
-		break;
115
-	case 4:
116
-		pFIO = GPIO4_HalfWord;
117
-		break;
118
-	default:
119
-		break;
120
-	}
121
-
122
-	return pFIO;
123
-}
124
-
125
-/*********************************************************************//**
126
- * @brief		Get pointer to FIO peripheral in byte accessible style
127
- * 				due to FIO port
128
- * @param[in]	portNum		Port Number value, should be in range from 0 to 4.
129
- * @return		Pointer to FIO peripheral
130
- **********************************************************************/
131
-static GPIO_Byte_TypeDef *FIO_ByteGetPointer(uint8_t portNum)
132
-{
133
-	GPIO_Byte_TypeDef *pFIO = NULL;
134
-
135
-	switch (portNum) {
136
-	case 0:
137
-		pFIO = GPIO0_Byte;
138
-		break;
139
-	case 1:
140
-		pFIO = GPIO1_Byte;
141
-		break;
142
-	case 2:
143
-		pFIO = GPIO2_Byte;
144
-		break;
145
-	case 3:
146
-		pFIO = GPIO3_Byte;
147
-		break;
148
-	case 4:
149
-		pFIO = GPIO4_Byte;
150
-		break;
151
-	default:
152
-		break;
153
-	}
154
-
155
-	return pFIO;
156
-}
157
-
158
-/* End of Private Functions --------------------------------------------------- */
159
-
160
-
161
-/* Public Functions ----------------------------------------------------------- */
162
-/** @addtogroup GPIO_Public_Functions
163
- * @{
164
- */
165
-
166
-
167
-/* GPIO ------------------------------------------------------------------------------ */
168
-
169
-/*********************************************************************//**
170
- * @brief		Set Direction for GPIO port.
171
- * @param[in]	portNum		Port Number value, should be in range from 0 to 4
172
- * @param[in]	bitValue	Value that contains all bits to set direction,
173
- * 							in range from 0 to 0xFFFFFFFF.
174
- * 							example: value 0x5 to set direction for bit 0 and bit 1.
175
- * @param[in]	dir			Direction value, should be:
176
- * 							- 0: Input.
177
- * 							- 1: Output.
178
- * @return		None
179
- *
180
- * Note: All remaining bits that are not activated in bitValue (value '0')
181
- * will not be effected by this function.
182
- **********************************************************************/
183
-void GPIO_SetDir(uint8_t portNum, uint32_t bitValue, uint8_t dir)
184
-{
185
-	LPC_GPIO_TypeDef *pGPIO = GPIO_GetPointer(portNum);
186
-
187
-	if (pGPIO != NULL) {
188
-		// Enable Output
189
-		if (dir) {
190
-			pGPIO->FIODIR |= bitValue;
191
-		}
192
-		// Enable Input
193
-		else {
194
-			pGPIO->FIODIR &= ~bitValue;
195
-		}
196
-	}
197
-}
198
-
199
-
200
-/*********************************************************************//**
201
- * @brief		Set Value for bits that have output direction on GPIO port.
202
- * @param[in]	portNum		Port number value, should be in range from 0 to 4
203
- * @param[in]	bitValue	Value that contains all bits on GPIO to set,
204
- * 							in range from 0 to 0xFFFFFFFF.
205
- * 							example: value 0x5 to set bit 0 and bit 1.
206
- * @return		None
207
- *
208
- * Note:
209
- * - For all bits that has been set as input direction, this function will
210
- * not effect.
211
- * - For all remaining bits that are not activated in bitValue (value '0')
212
- * will not be effected by this function.
213
- **********************************************************************/
214
-void GPIO_SetValue(uint8_t portNum, uint32_t bitValue)
215
-{
216
-	LPC_GPIO_TypeDef *pGPIO = GPIO_GetPointer(portNum);
217
-
218
-	if (pGPIO != NULL) {
219
-		pGPIO->FIOSET = bitValue;
220
-	}
221
-}
222
-
223
-/*********************************************************************//**
224
- * @brief		Clear Value for bits that have output direction on GPIO port.
225
- * @param[in]	portNum		Port number value, should be in range from 0 to 4
226
- * @param[in]	bitValue	Value that contains all bits on GPIO to clear,
227
- * 							in range from 0 to 0xFFFFFFFF.
228
- * 							example: value 0x5 to clear bit 0 and bit 1.
229
- * @return		None
230
- *
231
- * Note:
232
- * - For all bits that has been set as input direction, this function will
233
- * not effect.
234
- * - For all remaining bits that are not activated in bitValue (value '0')
235
- * will not be effected by this function.
236
- **********************************************************************/
237
-void GPIO_ClearValue(uint8_t portNum, uint32_t bitValue)
238
-{
239
-	LPC_GPIO_TypeDef *pGPIO = GPIO_GetPointer(portNum);
240
-
241
-	if (pGPIO != NULL) {
242
-		pGPIO->FIOCLR = bitValue;
243
-	}
244
-}
245
-
246
-/*********************************************************************//**
247
- * @brief		Read Current state on port pin that have input direction of GPIO
248
- * @param[in]	portNum		Port number to read value, in range from 0 to 4
249
- * @return		Current value of GPIO port.
250
- *
251
- * Note: Return value contain state of each port pin (bit) on that GPIO regardless
252
- * its direction is input or output.
253
- **********************************************************************/
254
-uint32_t GPIO_ReadValue(uint8_t portNum)
255
-{
256
-	LPC_GPIO_TypeDef *pGPIO = GPIO_GetPointer(portNum);
257
-
258
-	if (pGPIO != NULL) {
259
-		return pGPIO->FIOPIN;
260
-	}
261
-
262
-	return (0);
263
-}
264
-
265
-/*********************************************************************//**
266
- * @brief		Enable GPIO interrupt (just used for P0.0-P0.30, P2.0-P2.13)
267
- * @param[in]	portNum		Port number to read value, should be: 0 or 2
268
- * @param[in]	bitValue	Value that contains all bits on GPIO to enable,
269
- * 							in range from 0 to 0xFFFFFFFF.
270
- * @param[in]	edgeState	state of edge, should be:
271
- * 							- 0: Rising edge
272
- * 							- 1: Falling edge
273
- * @return		None
274
- **********************************************************************/
275
-void GPIO_IntCmd(uint8_t portNum, uint32_t bitValue, uint8_t edgeState)
276
-{
277
-	if((portNum == 0)&&(edgeState == 0))
278
-		LPC_GPIOINT->IO0IntEnR = bitValue;
279
-	else if ((portNum == 2)&&(edgeState == 0))
280
-		LPC_GPIOINT->IO2IntEnR = bitValue;
281
-	else if ((portNum == 0)&&(edgeState == 1))
282
-		LPC_GPIOINT->IO0IntEnF = bitValue;
283
-	else if ((portNum == 2)&&(edgeState == 1))
284
-		LPC_GPIOINT->IO2IntEnF = bitValue;
285
-	else
286
-		//Error
287
-		while(1);
288
-}
289
-
290
-/*********************************************************************//**
291
- * @brief		Get GPIO Interrupt Status (just used for P0.0-P0.30, P2.0-P2.13)
292
- * @param[in]	portNum		Port number to read value, should be: 0 or 2
293
- * @param[in]	pinNum		Pin number, should be: 0..30(with port 0) and 0..13
294
- * 							(with port 2)
295
- * @param[in]	edgeState	state of edge, should be:
296
- * 							- 0: Rising edge
297
- * 							- 1: Falling edge
298
- * @return		Bool	could be:
299
- * 						- ENABLE: Interrupt has been generated due to a rising
300
- * 								edge on P0.0
301
- * 						- DISABLE: A rising edge has not been detected on P0.0
302
- **********************************************************************/
303
-FunctionalState GPIO_GetIntStatus(uint8_t portNum, uint32_t pinNum, uint8_t edgeState)
304
-{
305
-	if((portNum == 0) && (edgeState == 0))//Rising Edge
306
-		return ((FunctionalState)(((LPC_GPIOINT->IO0IntStatR)>>pinNum)& 0x1));
307
-	else if ((portNum == 2) && (edgeState == 0))
308
-		return ((FunctionalState)(((LPC_GPIOINT->IO2IntStatR)>>pinNum)& 0x1));
309
-	else if ((portNum == 0) && (edgeState == 1))//Falling Edge
310
-		return ((FunctionalState)(((LPC_GPIOINT->IO0IntStatF)>>pinNum)& 0x1));
311
-	else if ((portNum == 2) && (edgeState == 1))
312
-		return ((FunctionalState)(((LPC_GPIOINT->IO2IntStatF)>>pinNum)& 0x1));
313
-	else
314
-		//Error
315
-		while(1);
316
-}
317
-/*********************************************************************//**
318
- * @brief		Clear GPIO interrupt (just used for P0.0-P0.30, P2.0-P2.13)
319
- * @param[in]	portNum		Port number to read value, should be: 0 or 2
320
- * @param[in]	bitValue	Value that contains all bits on GPIO to enable,
321
- * 							in range from 0 to 0xFFFFFFFF.
322
- * @return		None
323
- **********************************************************************/
324
-void GPIO_ClearInt(uint8_t portNum, uint32_t bitValue)
325
-{
326
-	if(portNum == 0)
327
-		LPC_GPIOINT->IO0IntClr = bitValue;
328
-	else if (portNum == 2)
329
-		LPC_GPIOINT->IO2IntClr = bitValue;
330
-	else
331
-		//Invalid portNum
332
-		while(1);
333
-}
334
-
335
-/* FIO word accessible ----------------------------------------------------------------- */
336
-/* Stub function for FIO (word-accessible) style */
337
-
338
-/**
339
- * @brief The same with GPIO_SetDir()
340
- */
341
-void FIO_SetDir(uint8_t portNum, uint32_t bitValue, uint8_t dir)
342
-{
343
-	GPIO_SetDir(portNum, bitValue, dir);
344
-}
345
-
346
-/**
347
- * @brief The same with GPIO_SetValue()
348
- */
349
-void FIO_SetValue(uint8_t portNum, uint32_t bitValue)
350
-{
351
-	GPIO_SetValue(portNum, bitValue);
352
-}
353
-
354
-/**
355
- * @brief The same with GPIO_ClearValue()
356
- */
357
-void FIO_ClearValue(uint8_t portNum, uint32_t bitValue)
358
-{
359
-	GPIO_ClearValue(portNum, bitValue);
360
-}
361
-
362
-/**
363
- * @brief The same with GPIO_ReadValue()
364
- */
365
-uint32_t FIO_ReadValue(uint8_t portNum)
366
-{
367
-	return (GPIO_ReadValue(portNum));
368
-}
369
-
370
-/**
371
- * @brief The same with GPIO_IntCmd()
372
- */
373
-void FIO_IntCmd(uint8_t portNum, uint32_t bitValue, uint8_t edgeState)
374
-{
375
-	GPIO_IntCmd(portNum, bitValue, edgeState);
376
-}
377
-
378
-/**
379
- * @brief The same with GPIO_GetIntStatus()
380
- */
381
-FunctionalState FIO_GetIntStatus(uint8_t portNum, uint32_t pinNum, uint8_t edgeState)
382
-{
383
-	return (GPIO_GetIntStatus(portNum, pinNum, edgeState));
384
-}
385
-
386
-/**
387
- * @brief The same with GPIO_ClearInt()
388
- */
389
-void FIO_ClearInt(uint8_t portNum, uint32_t bitValue)
390
-{
391
-	GPIO_ClearInt(portNum, bitValue);
392
-}
393
-/*********************************************************************//**
394
- * @brief		Set mask value for bits in FIO port
395
- * @param[in]	portNum		Port number, in range from 0 to 4
396
- * @param[in]	bitValue	Value that contains all bits in to set,
397
- * 							in range from 0 to 0xFFFFFFFF.
398
- * @param[in]	maskValue	Mask value contains state value for each bit:
399
- * 							- 0: not mask.
400
- * 							- 1: mask.
401
- * @return		None
402
- *
403
- * Note:
404
- * - All remaining bits that are not activated in bitValue (value '0')
405
- * will not be effected by this function.
406
- * - After executing this function, in mask register, value '0' on each bit
407
- * enables an access to the corresponding physical pin via a read or write access,
408
- * while value '1' on bit (masked) that corresponding pin will not be changed
409
- * with write access and if read, will not be reflected in the updated pin.
410
- **********************************************************************/
411
-void FIO_SetMask(uint8_t portNum, uint32_t bitValue, uint8_t maskValue)
412
-{
413
-	LPC_GPIO_TypeDef *pFIO = GPIO_GetPointer(portNum);
414
-	if(pFIO != NULL) {
415
-		// Mask
416
-		if (maskValue){
417
-			pFIO->FIOMASK |= bitValue;
418
-		}
419
-		// Un-mask
420
-		else {
421
-			pFIO->FIOMASK &= ~bitValue;
422
-		}
423
-	}
424
-}
425
-
426
-
427
-/* FIO halfword accessible ------------------------------------------------------------- */
428
-
429
-/*********************************************************************//**
430
- * @brief		Set direction for FIO port in halfword accessible style
431
- * @param[in]	portNum		Port number, in range from 0 to 4
432
- * @param[in]	halfwordNum	HalfWord part number, should be 0 (lower) or 1(upper)
433
- * @param[in]	bitValue	Value that contains all bits in to set direction,
434
- * 							in range from 0 to 0xFFFF.
435
- * @param[in]	dir			Direction value, should be:
436
- * 							- 0: Input.
437
- * 							- 1: Output.
438
- * @return		None
439
- *
440
- * Note: All remaining bits that are not activated in bitValue (value '0')
441
- * will not be effected by this function.
442
- **********************************************************************/
443
-void FIO_HalfWordSetDir(uint8_t portNum, uint8_t halfwordNum, uint16_t bitValue, uint8_t dir)
444
-{
445
-	GPIO_HalfWord_TypeDef *pFIO = FIO_HalfWordGetPointer(portNum);
446
-	if(pFIO != NULL) {
447
-		// Output direction
448
-		if (dir) {
449
-			// Upper
450
-			if(halfwordNum) {
451
-				pFIO->FIODIRU |= bitValue;
452
-			}
453
-			// lower
454
-			else {
455
-				pFIO->FIODIRL |= bitValue;
456
-			}
457
-		}
458
-		// Input direction
459
-		else {
460
-			// Upper
461
-			if(halfwordNum) {
462
-				pFIO->FIODIRU &= ~bitValue;
463
-			}
464
-			// lower
465
-			else {
466
-				pFIO->FIODIRL &= ~bitValue;
467
-			}
468
-		}
469
-	}
470
-}
471
-
472
-
473
-/*********************************************************************//**
474
- * @brief		Set mask value for bits in FIO port in halfword accessible style
475
- * @param[in]	portNum		Port number, in range from 0 to 4
476
- * @param[in]	halfwordNum	HalfWord part number, should be 0 (lower) or 1(upper)
477
- * @param[in]	bitValue	Value that contains all bits in to set,
478
- * 							in range from 0 to 0xFFFF.
479
- * @param[in]	maskValue	Mask value contains state value for each bit:
480
- * 					- 0: not mask.
481
- * 					- 1: mask.
482
- * @return		None
483
- *
484
- * Note:
485
- * - All remaining bits that are not activated in bitValue (value '0')
486
- * will not be effected by this function.
487
- * - After executing this function, in mask register, value '0' on each bit
488
- * enables an access to the corresponding physical pin via a read or write access,
489
- * while value '1' on bit (masked) that corresponding pin will not be changed
490
- * with write access and if read, will not be reflected in the updated pin.
491
- **********************************************************************/
492
-void FIO_HalfWordSetMask(uint8_t portNum, uint8_t halfwordNum, uint16_t bitValue, uint8_t maskValue)
493
-{
494
-	GPIO_HalfWord_TypeDef *pFIO = FIO_HalfWordGetPointer(portNum);
495
-	if(pFIO != NULL) {
496
-		// Mask
497
-		if (maskValue){
498
-			// Upper
499
-			if(halfwordNum) {
500
-				pFIO->FIOMASKU |= bitValue;
501
-			}
502
-			// lower
503
-			else {
504
-				pFIO->FIOMASKL |= bitValue;
505
-			}
506
-		}
507
-		// Un-mask
508
-		else {
509
-			// Upper
510
-			if(halfwordNum) {
511
-				pFIO->FIOMASKU &= ~bitValue;
512
-			}
513
-			// lower
514
-			else {
515
-				pFIO->FIOMASKL &= ~bitValue;
516
-			}
517
-		}
518
-	}
519
-}
520
-
521
-
522
-/*********************************************************************//**
523
- * @brief		Set bits for FIO port in halfword accessible style
524
- * @param[in]	portNum		Port number, in range from 0 to 4
525
- * @param[in]	halfwordNum	HalfWord part number, should be 0 (lower) or 1(upper)
526
- * @param[in]	bitValue	Value that contains all bits in to set,
527
- * 							in range from 0 to 0xFFFF.
528
- * @return		None
529
- *
530
- * Note:
531
- * - For all bits that has been set as input direction, this function will
532
- * not effect.
533
- * - For all remaining bits that are not activated in bitValue (value '0')
534
- * will not be effected by this function.
535
- **********************************************************************/
536
-void FIO_HalfWordSetValue(uint8_t portNum, uint8_t halfwordNum, uint16_t bitValue)
537
-{
538
-	GPIO_HalfWord_TypeDef *pFIO = FIO_HalfWordGetPointer(portNum);
539
-	if(pFIO != NULL) {
540
-		// Upper
541
-		if(halfwordNum) {
542
-			pFIO->FIOSETU = bitValue;
543
-		}
544
-		// lower
545
-		else {
546
-			pFIO->FIOSETL = bitValue;
547
-		}
548
-	}
549
-}
550
-
551
-
552
-/*********************************************************************//**
553
- * @brief		Clear bits for FIO port in halfword accessible style
554
- * @param[in]	portNum		Port number, in range from 0 to 4
555
- * @param[in]	halfwordNum	HalfWord part number, should be 0 (lower) or 1(upper)
556
- * @param[in]	bitValue	Value that contains all bits in to clear,
557
- * 							in range from 0 to 0xFFFF.
558
- * @return		None
559
- *
560
- * Note:
561
- * - For all bits that has been set as input direction, this function will
562
- * not effect.
563
- * - For all remaining bits that are not activated in bitValue (value '0')
564
- * will not be effected by this function.
565
- **********************************************************************/
566
-void FIO_HalfWordClearValue(uint8_t portNum, uint8_t halfwordNum, uint16_t bitValue)
567
-{
568
-	GPIO_HalfWord_TypeDef *pFIO = FIO_HalfWordGetPointer(portNum);
569
-	if(pFIO != NULL) {
570
-		// Upper
571
-		if(halfwordNum) {
572
-			pFIO->FIOCLRU = bitValue;
573
-		}
574
-		// lower
575
-		else {
576
-			pFIO->FIOCLRL = bitValue;
577
-		}
578
-	}
579
-}
580
-
581
-
582
-/*********************************************************************//**
583
- * @brief		Read Current state on port pin that have input direction of GPIO
584
- * 				in halfword accessible style.
585
- * @param[in]	portNum		Port number, in range from 0 to 4
586
- * @param[in]	halfwordNum	HalfWord part number, should be 0 (lower) or 1(upper)
587
- * @return		Current value of FIO port pin of specified halfword.
588
- * Note: Return value contain state of each port pin (bit) on that FIO regardless
589
- * its direction is input or output.
590
- **********************************************************************/
591
-uint16_t FIO_HalfWordReadValue(uint8_t portNum, uint8_t halfwordNum)
592
-{
593
-	GPIO_HalfWord_TypeDef *pFIO = FIO_HalfWordGetPointer(portNum);
594
-	if(pFIO != NULL) {
595
-		// Upper
596
-		if(halfwordNum) {
597
-			return (pFIO->FIOPINU);
598
-		}
599
-		// lower
600
-		else {
601
-			return (pFIO->FIOPINL);
602
-		}
603
-	}
604
-	return (0);
605
-}
606
-
607
-
608
-/* FIO Byte accessible ------------------------------------------------------------ */
609
-
610
-/*********************************************************************//**
611
- * @brief		Set direction for FIO port in byte accessible style
612
- * @param[in]	portNum		Port number, in range from 0 to 4
613
- * @param[in]	byteNum		Byte part number, should be in range from 0 to 3
614
- * @param[in]	bitValue	Value that contains all bits in to set direction,
615
- * 							in range from 0 to 0xFF.
616
- * @param[in]	dir			Direction value, should be:
617
- * 							- 0: Input.
618
- * 							- 1: Output.
619
- * @return		None
620
- *
621
- * Note: All remaining bits that are not activated in bitValue (value '0')
622
- * will not be effected by this function.
623
- **********************************************************************/
624
-void FIO_ByteSetDir(uint8_t portNum, uint8_t byteNum, uint8_t bitValue, uint8_t dir)
625
-{
626
-	GPIO_Byte_TypeDef *pFIO = FIO_ByteGetPointer(portNum);
627
-	if(pFIO != NULL) {
628
-		// Output direction
629
-		if (dir) {
630
-			if (byteNum <= 3) {
631
-				pFIO->FIODIR[byteNum] |= bitValue;
632
-			}
633
-		}
634
-		// Input direction
635
-		else {
636
-			if (byteNum <= 3) {
637
-				pFIO->FIODIR[byteNum] &= ~bitValue;
638
-			}
639
-		}
640
-	}
641
-}
642
-
643
-/*********************************************************************//**
644
- * @brief		Set mask value for bits in FIO port in byte accessible style
645
- * @param[in]	portNum		Port number, in range from 0 to 4
646
- * @param[in]	byteNum		Byte part number, should be in range from 0 to 3
647
- * @param[in]	bitValue	Value that contains all bits in to set mask,
648
- * 							in range from 0 to 0xFF.
649
- * @param[in]	maskValue	Mask value contains state value for each bit:
650
- * 							- 0: not mask.
651
- * 							- 1: mask.
652
- * @return		None
653
- *
654
- * Note:
655
- * - All remaining bits that are not activated in bitValue (value '0')
656
- * will not be effected by this function.
657
- * - After executing this function, in mask register, value '0' on each bit
658
- * enables an access to the corresponding physical pin via a read or write access,
659
- * while value '1' on bit (masked) that corresponding pin will not be changed
660
- * with write access and if read, will not be reflected in the updated pin.
661
- **********************************************************************/
662
-void FIO_ByteSetMask(uint8_t portNum, uint8_t byteNum, uint8_t bitValue, uint8_t maskValue)
663
-{
664
-	GPIO_Byte_TypeDef *pFIO = FIO_ByteGetPointer(portNum);
665
-	if(pFIO != NULL) {
666
-		// Mask
667
-		if (maskValue) {
668
-			if (byteNum <= 3) {
669
-				pFIO->FIOMASK[byteNum] |= bitValue;
670
-			}
671
-		}
672
-		// Un-mask
673
-		else {
674
-			if (byteNum <= 3) {
675
-				pFIO->FIOMASK[byteNum] &= ~bitValue;
676
-			}
677
-		}
678
-	}
679
-}
680
-
681
-
682
-/*********************************************************************//**
683
- * @brief		Set bits for FIO port in byte accessible style
684
- * @param[in]	portNum		Port number, in range from 0 to 4
685
- * @param[in]	byteNum		Byte part number, should be in range from 0 to 3
686
- * @param[in]	bitValue	Value that contains all bits in to set,
687
- * 							in range from 0 to 0xFF.
688
- * @return		None
689
- *
690
- * Note:
691
- * - For all bits that has been set as input direction, this function will
692
- * not effect.
693
- * - For all remaining bits that are not activated in bitValue (value '0')
694
- * will not be effected by this function.
695
- **********************************************************************/
696
-void FIO_ByteSetValue(uint8_t portNum, uint8_t byteNum, uint8_t bitValue)
697
-{
698
-	GPIO_Byte_TypeDef *pFIO = FIO_ByteGetPointer(portNum);
699
-	if (pFIO != NULL) {
700
-		if (byteNum <= 3){
701
-			pFIO->FIOSET[byteNum] = bitValue;
702
-		}
703
-	}
704
-}
705
-
706
-
707
-/*********************************************************************//**
708
- * @brief		Clear bits for FIO port in byte accessible style
709
- * @param[in]	portNum		Port number, in range from 0 to 4
710
- * @param[in]	byteNum		Byte part number, should be in range from 0 to 3
711
- * @param[in]	bitValue	Value that contains all bits in to clear,
712
- * 							in range from 0 to 0xFF.
713
- * @return		None
714
- *
715
- * Note:
716
- * - For all bits that has been set as input direction, this function will
717
- * not effect.
718
- * - For all remaining bits that are not activated in bitValue (value '0')
719
- * will not be effected by this function.
720
- **********************************************************************/
721
-void FIO_ByteClearValue(uint8_t portNum, uint8_t byteNum, uint8_t bitValue)
722
-{
723
-	GPIO_Byte_TypeDef *pFIO = FIO_ByteGetPointer(portNum);
724
-	if (pFIO != NULL) {
725
-		if (byteNum <= 3){
726
-			pFIO->FIOCLR[byteNum] = bitValue;
727
-		}
728
-	}
729
-}
730
-
731
-
732
-/*********************************************************************//**
733
- * @brief		Read Current state on port pin that have input direction of GPIO
734
- * 				in byte accessible style.
735
- * @param[in]	portNum		Port number, in range from 0 to 4
736
- * @param[in]	byteNum		Byte part number, should be in range from 0 to 3
737
- * @return		Current value of FIO port pin of specified byte part.
738
- * Note: Return value contain state of each port pin (bit) on that FIO regardless
739
- * its direction is input or output.
740
- **********************************************************************/
741
-uint8_t FIO_ByteReadValue(uint8_t portNum, uint8_t byteNum)
742
-{
743
-	GPIO_Byte_TypeDef *pFIO = FIO_ByteGetPointer(portNum);
744
-	if (pFIO != NULL) {
745
-		if (byteNum <= 3){
746
-			return (pFIO->FIOPIN[byteNum]);
747
-		}
748
-	}
749
-	return (0);
750
-}
751
-
752
-/**
753
- * @}
754
- */
755
-
756
-#endif /* _GPIO */
757
-
758
-/**
759
- * @}
760
- */
761
-
762
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 1344
frameworks/CMSIS/LPC1768/driver/lpc17xx_i2c.c
Разница между файлами не показана из-за своего большого размера
Просмотреть файл


+ 0
- 663
frameworks/CMSIS/LPC1768/driver/lpc17xx_i2s.c Просмотреть файл

@@ -1,663 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_i2s.c				2010-09-23
3
-*//**
4
-* @file		lpc17xx_i2s.c
5
-* @brief	Contains all functions support for I2S firmware
6
-* 			library on LPC17xx
7
-* @version	3.1
8
-* @date		23. Sep. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @addtogroup I2S
35
- * @{
36
- */
37
-
38
-/* Includes ------------------------------------------------------------------- */
39
-#include "lpc17xx_i2s.h"
40
-#include "lpc17xx_clkpwr.h"
41
-
42
-
43
-/* If this source file built with example, the LPC17xx FW library configuration
44
- * file in each example directory ("lpc17xx_libcfg.h") must be included,
45
- * otherwise the default FW library configuration file must be included instead
46
- */
47
-#ifdef __BUILD_WITH_EXAMPLE__
48
-#include "lpc17xx_libcfg.h"
49
-#else
50
-#include "lpc17xx_libcfg_default.h"
51
-#endif /* __BUILD_WITH_EXAMPLE__ */
52
-
53
-
54
-#ifdef _I2S
55
-
56
-/* Private Functions ---------------------------------------------------------- */
57
-
58
-static uint8_t i2s_GetWordWidth(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode);
59
-static uint8_t i2s_GetChannel(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode);
60
-
61
-/********************************************************************//**
62
- * @brief		Get I2S wordwidth value
63
- * @param[in]	I2Sx I2S peripheral selected, should be: LPC_I2S
64
- * @param[in]	TRMode is the I2S mode, should be:
65
- * 				- I2S_TX_MODE = 0: transmit mode
66
- * 				- I2S_RX_MODE = 1: receive mode
67
- * @return 		The wordwidth value, should be: 8,16 or 32
68
- *********************************************************************/
69
-static uint8_t i2s_GetWordWidth(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode) {
70
-	uint8_t value;
71
-
72
-	CHECK_PARAM(PARAM_I2Sx(I2Sx));
73
-	CHECK_PARAM(PARAM_I2S_TRX(TRMode));
74
-
75
-	if (TRMode == I2S_TX_MODE) {
76
-		value = (I2Sx->I2SDAO) & 0x03; /* get wordwidth bit */
77
-	} else {
78
-		value = (I2Sx->I2SDAI) & 0x03; /* get wordwidth bit */
79
-	}
80
-	switch (value) {
81
-	case I2S_WORDWIDTH_8:
82
-		return 8;
83
-	case I2S_WORDWIDTH_16:
84
-		return 16;
85
-	default:
86
-		return 32;
87
-	}
88
-}
89
-
90
-/********************************************************************//**
91
- * @brief		Get I2S channel value
92
- * @param[in]	I2Sx I2S peripheral selected, should be: LPC_I2S
93
- * @param[in]	TRMode is the I2S mode, should be:
94
- * 				- I2S_TX_MODE = 0: transmit mode
95
- * 				- I2S_RX_MODE = 1: receive mode
96
- * @return 		The channel value, should be: 1(mono) or 2(stereo)
97
- *********************************************************************/
98
-static uint8_t i2s_GetChannel(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode) {
99
-	uint8_t value;
100
-
101
-	CHECK_PARAM(PARAM_I2Sx(I2Sx));
102
-	CHECK_PARAM(PARAM_I2S_TRX(TRMode));
103
-
104
-	if (TRMode == I2S_TX_MODE) {
105
-		value = ((I2Sx->I2SDAO) & 0x04)>>2; /* get bit[2] */
106
-	} else {
107
-		value = ((I2Sx->I2SDAI) & 0x04)>>2; /* get bit[2] */
108
-	}
109
-        if(value == I2S_MONO) return 1;
110
-          return 2;
111
-}
112
-
113
-/* End of Private Functions --------------------------------------------------- */
114
-
115
-
116
-/* Public Functions ----------------------------------------------------------- */
117
-/** @addtogroup I2S_Public_Functions
118
- * @{
119
- */
120
-
121
-/********************************************************************//**
122
- * @brief		Initialize I2S
123
- * 					- Turn on power and clock
124
- * @param[in]	I2Sx I2S peripheral selected, should be: LPC_I2S
125
- * @return 		none
126
- *********************************************************************/
127
-void I2S_Init(LPC_I2S_TypeDef *I2Sx) {
128
-	CHECK_PARAM(PARAM_I2Sx(I2Sx));
129
-
130
-	// Turn on power and clock
131
-	CLKPWR_ConfigPPWR(CLKPWR_PCONP_PCI2S, ENABLE);
132
-	LPC_I2S->I2SDAI = LPC_I2S->I2SDAO = 0x00;
133
-}
134
-
135
-/********************************************************************//**
136
- * @brief		Configuration I2S, setting:
137
- * 					- master/slave mode
138
- * 					- wordwidth value
139
- * 					- channel mode
140
- * @param[in]	I2Sx I2S peripheral selected, should be: LPC_I2S
141
- * @param[in]	TRMode transmit/receive mode, should be:
142
- * 					- I2S_TX_MODE = 0: transmit mode
143
- * 					- I2S_RX_MODE = 1: receive mode
144
- * @param[in]	ConfigStruct pointer to I2S_CFG_Type structure
145
- *              which will be initialized.
146
- * @return 		none
147
- *********************************************************************/
148
-void I2S_Config(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode, I2S_CFG_Type* ConfigStruct)
149
-{
150
-	uint32_t bps, config;
151
-
152
-	CHECK_PARAM(PARAM_I2Sx(I2Sx));
153
-
154
-	CHECK_PARAM(PARAM_I2S_WORDWIDTH(ConfigStruct->wordwidth));
155
-	CHECK_PARAM(PARAM_I2S_CHANNEL(ConfigStruct->mono));
156
-	CHECK_PARAM(PARAM_I2S_STOP(ConfigStruct->stop));
157
-	CHECK_PARAM(PARAM_I2S_RESET(ConfigStruct->reset));
158
-	CHECK_PARAM(PARAM_I2S_WS_SEL(ConfigStruct->ws_sel));
159
-	CHECK_PARAM(PARAM_I2S_MUTE(ConfigStruct->mute));
160
-
161
-	/* Setup clock */
162
-	bps = (ConfigStruct->wordwidth +1)*8;
163
-
164
-	/* Calculate audio config */
165
-	config = (bps - 1)<<6 | (ConfigStruct->ws_sel)<<5 | (ConfigStruct->reset)<<4 |
166
-		(ConfigStruct->stop)<<3 | (ConfigStruct->mono)<<2 | (ConfigStruct->wordwidth);
167
-
168
-	if(TRMode == I2S_RX_MODE){
169
-		LPC_I2S->I2SDAI = config;
170
-	}else{
171
-		LPC_I2S->I2SDAO = config;
172
-	}
173
-}
174
-
175
-/********************************************************************//**
176
- * @brief		DeInitial both I2S transmit or receive
177
- * @param[in]	I2Sx I2S peripheral selected, should be: LPC_I2S
178
- * @return 		none
179
- *********************************************************************/
180
-void I2S_DeInit(LPC_I2S_TypeDef *I2Sx) {
181
-	CHECK_PARAM(PARAM_I2Sx(I2Sx));
182
-
183
-	// Turn off power and clock
184
-	CLKPWR_ConfigPPWR(CLKPWR_PCONP_PCI2S, DISABLE);
185
-}
186
-
187
-/********************************************************************//**
188
- * @brief		Get I2S Buffer Level
189
- * @param[in]	I2Sx I2S peripheral selected, should be: LPC_I2S
190
- * @param[in]	TRMode Transmit/receive mode, should be:
191
- * 					- I2S_TX_MODE = 0: transmit mode
192
- * 					- I2S_RX_MODE = 1: receive mode
193
- * @return 		current level of Transmit/Receive Buffer
194
- *********************************************************************/
195
-uint8_t I2S_GetLevel(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode)
196
-{
197
-	CHECK_PARAM(PARAM_I2Sx(I2Sx));
198
-	CHECK_PARAM(PARAM_I2S_TRX(TRMode));
199
-
200
-	if(TRMode == I2S_TX_MODE)
201
-	{
202
-		return ((I2Sx->I2SSTATE >> 16) & 0xFF);
203
-	}
204
-	else
205
-	{
206
-		return ((I2Sx->I2SSTATE >> 8) & 0xFF);
207
-	}
208
-}
209
-
210
-/********************************************************************//**
211
- * @brief		I2S Start: clear all STOP,RESET and MUTE bit, ready to operate
212
- * @param[in]	I2Sx I2S peripheral selected, should be: LPC_I2S
213
- * @return 		none
214
- *********************************************************************/
215
-void I2S_Start(LPC_I2S_TypeDef *I2Sx)
216
-{
217
-	//Clear STOP,RESET and MUTE bit
218
-	I2Sx->I2SDAO &= ~I2S_DAI_RESET;
219
-	I2Sx->I2SDAI &= ~I2S_DAI_RESET;
220
-	I2Sx->I2SDAO &= ~I2S_DAI_STOP;
221
-	I2Sx->I2SDAI &= ~I2S_DAI_STOP;
222
-	I2Sx->I2SDAO &= ~I2S_DAI_MUTE;
223
-}
224
-
225
-/********************************************************************//**
226
- * @brief		I2S Send data
227
- * @param[in]	I2Sx I2S peripheral selected, should be: LPC_I2S
228
- * @param[in]	BufferData pointer to uint32_t is the data will be send
229
- * @return 		none
230
- *********************************************************************/
231
-void I2S_Send(LPC_I2S_TypeDef *I2Sx, uint32_t BufferData) {
232
-	CHECK_PARAM(PARAM_I2Sx(I2Sx));
233
-
234
-	I2Sx->I2STXFIFO = BufferData;
235
-}
236
-
237
-/********************************************************************//**
238
- * @brief		I2S Receive Data
239
- * @param[in]	I2Sx pointer to LPC_I2S_TypeDef
240
- * @return 		received value
241
- *********************************************************************/
242
-uint32_t I2S_Receive(LPC_I2S_TypeDef* I2Sx) {
243
-	CHECK_PARAM(PARAM_I2Sx(I2Sx));
244
-
245
-	return (I2Sx->I2SRXFIFO);
246
-
247
-}
248
-
249
-/********************************************************************//**
250
- * @brief		I2S Pause
251
- * @param[in]	I2Sx I2S peripheral selected, should be: LPC_I2S
252
- * @param[in]	TRMode is transmit/receive mode, should be:
253
- * 				- I2S_TX_MODE = 0: transmit mode
254
- * 				- I2S_RX_MODE = 1: receive mode
255
- * @return 		none
256
- *********************************************************************/
257
-void I2S_Pause(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode) {
258
-	CHECK_PARAM(PARAM_I2Sx(I2Sx));
259
-	CHECK_PARAM(PARAM_I2S_TRX(TRMode));
260
-
261
-	if (TRMode == I2S_TX_MODE) //Transmit mode
262
-	{
263
-		I2Sx->I2SDAO |= I2S_DAO_STOP;
264
-	} else //Receive mode
265
-	{
266
-		I2Sx->I2SDAI |= I2S_DAI_STOP;
267
-	}
268
-}
269
-
270
-/********************************************************************//**
271
- * @brief		I2S Mute
272
- * @param[in]	I2Sx I2S peripheral selected, should be: LPC_I2S
273
- * @param[in]	TRMode is transmit/receive mode, should be:
274
- * 				- I2S_TX_MODE = 0: transmit mode
275
- * 				- I2S_RX_MODE = 1: receive mode
276
- * @return 		none
277
- *********************************************************************/
278
-void I2S_Mute(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode) {
279
-	CHECK_PARAM(PARAM_I2Sx(I2Sx));
280
-	CHECK_PARAM(PARAM_I2S_TRX(TRMode));
281
-
282
-	if (TRMode == I2S_TX_MODE) //Transmit mode
283
-	{
284
-		I2Sx->I2SDAO |= I2S_DAO_MUTE;
285
-	} else //Receive mode
286
-	{
287
-		I2Sx->I2SDAI |= I2S_DAI_MUTE;
288
-	}
289
-}
290
-
291
-/********************************************************************//**
292
- * @brief		I2S Stop
293
- * @param[in]	I2Sx I2S peripheral selected, should be: LPC_I2S
294
- * @param[in]	TRMode is transmit/receive mode, should be:
295
- * 				- I2S_TX_MODE = 0: transmit mode
296
- * 				- I2S_RX_MODE = 1: receive mode
297
- * @return 		none
298
- *********************************************************************/
299
-void I2S_Stop(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode) {
300
-	CHECK_PARAM(PARAM_I2Sx(I2Sx));
301
-	CHECK_PARAM(PARAM_I2S_TRX(TRMode));
302
-
303
-	if (TRMode == I2S_TX_MODE) //Transmit mode
304
-	{
305
-		I2Sx->I2SDAO &= ~I2S_DAO_MUTE;
306
-		I2Sx->I2SDAO |= I2S_DAO_STOP;
307
-		I2Sx->I2SDAO |= I2S_DAO_RESET;
308
-	} else //Receive mode
309
-	{
310
-		I2Sx->I2SDAI |= I2S_DAI_STOP;
311
-		I2Sx->I2SDAI |= I2S_DAI_RESET;
312
-	}
313
-}
314
-
315
-/********************************************************************//**
316
- * @brief		Set frequency for I2S
317
- * @param[in]	I2Sx I2S peripheral selected, should be: LPC_I2S
318
- * @param[in]	Freq is the frequency for I2S will be set. It can range
319
- * 				from 16-96 kHz(16, 22.05, 32, 44.1, 48, 96kHz)
320
- * @param[in]	TRMode is transmit/receive mode, should be:
321
- * 				- I2S_TX_MODE = 0: transmit mode
322
- * 				- I2S_RX_MODE = 1: receive mode
323
- * @return 		Status: ERROR or SUCCESS
324
- *********************************************************************/
325
-Status I2S_FreqConfig(LPC_I2S_TypeDef *I2Sx, uint32_t Freq, uint8_t TRMode) {
326
-
327
-	uint32_t i2s_clk;
328
-	uint8_t channel, wordwidth;
329
-	uint32_t x, y;
330
-	uint64_t divider;
331
-	uint16_t dif;
332
-	uint16_t x_divide, y_divide;
333
-	uint16_t err, ErrorOptimal = 0xFFFF;
334
-
335
-	uint32_t N;
336
-
337
-	CHECK_PARAM(PARAM_I2Sx(I2Sx));
338
-	CHECK_PARAM(PRAM_I2S_FREQ(Freq));
339
-	CHECK_PARAM(PARAM_I2S_TRX(TRMode));
340
-
341
-	//Get the frequency of PCLK_I2S
342
-	i2s_clk = CLKPWR_GetPCLK(CLKPWR_PCLKSEL_I2S);
343
-
344
-	if(TRMode == I2S_TX_MODE)
345
-	{
346
-		channel = i2s_GetChannel(I2Sx,I2S_TX_MODE);
347
-		wordwidth = i2s_GetWordWidth(I2Sx,I2S_TX_MODE);
348
-	}
349
-	else
350
-	{
351
-		channel = i2s_GetChannel(I2Sx,I2S_RX_MODE);
352
-		wordwidth = i2s_GetWordWidth(I2Sx,I2S_RX_MODE);
353
-	}
354
-
355
-	/* Calculate X and Y divider
356
-	 * The MCLK rate for the I2S transmitter is determined by the value
357
-	 * in the I2STXRATE/I2SRXRATE register. The required I2STXRATE/I2SRXRATE
358
-	 * setting depends on the desired audio sample rate desired, the format
359
-	 * (stereo/mono) used, and the data size.
360
-	 * The formula is:
361
-	 * 		I2S_MCLK = PCLK_I2S * (X/Y) / 2
362
-     * In that, Y must be greater than or equal to X. X should divides evenly
363
-     * into Y.
364
-	 * We have:
365
-	 * 		I2S_MCLK = Freq * channel*wordwidth * (I2STXBITRATE+1);
366
-	 * So: (X/Y) = (Freq * channel*wordwidth * (I2STXBITRATE+1))*2/PCLK_I2S
367
-	 * We use a loop function to chose the most suitable X,Y value
368
-	 */
369
-
370
-	/* divider is a fixed point number with 16 fractional bits */
371
-    divider = (((uint64_t)Freq *channel*wordwidth * 2)<<16) / i2s_clk;
372
-
373
-	/* find N that make x/y <= 1 -> divider <= 2^16 */
374
-	for(N=64;N>0;N--){
375
-		if((divider*N) < (1<<16)) break;
376
-	}
377
-
378
-	if(N == 0) return ERROR;
379
-
380
-	divider *= N;
381
-
382
-	for (y = 255; y > 0; y--) {
383
-		x = y * divider;
384
-		if(x & (0xFF000000)) continue;
385
-		dif = x & 0xFFFF;
386
-		if(dif>0x8000) err = 0x10000-dif;
387
-		else err = dif;
388
-		if (err == 0)
389
-		{
390
-			y_divide = y;
391
-			break;
392
-		}
393
-		else if (err < ErrorOptimal)
394
-		{
395
-			ErrorOptimal = err;
396
-			y_divide = y;
397
-		}
398
-	}
399
-	x_divide = ((uint64_t)y_divide * Freq *(channel*wordwidth)* N * 2)/i2s_clk;
400
-	if(x_divide >= 256) x_divide = 0xFF;
401
-	if(x_divide == 0) x_divide = 1;
402
-
403
-	if (TRMode == I2S_TX_MODE)// Transmitter
404
-	{
405
-		I2Sx->I2STXBITRATE = N-1;
406
-		I2Sx->I2STXRATE = y_divide | (x_divide << 8);
407
-	} else //Receiver
408
-	{
409
-		I2Sx->I2SRXBITRATE = N-1;
410
-		I2Sx->I2STXRATE = y_divide | (x_divide << 8);
411
-	}
412
-	return SUCCESS;
413
-}
414
-
415
-/********************************************************************//**
416
- * @brief		I2S set bitrate
417
- * @param[in]	I2Sx I2S peripheral selected, should be: LPC_I2S
418
- * @param[in]	bitrate value will be set
419
- * 				bitrate value should be in range: 0 .. 63
420
- * @param[in]	TRMode is transmit/receive mode, should be:
421
- * 				- I2S_TX_MODE = 0: transmit mode
422
- * 				- I2S_RX_MODE = 1: receive mode
423
- * @return 		none
424
- *********************************************************************/
425
-void I2S_SetBitRate(LPC_I2S_TypeDef *I2Sx, uint8_t bitrate, uint8_t TRMode)
426
-{
427
-	CHECK_PARAM(PARAM_I2Sx(I2Sx));
428
-	CHECK_PARAM(PARAM_I2S_BITRATE(bitrate));
429
-	CHECK_PARAM(PARAM_I2S_TRX(TRMode));
430
-
431
-	if(TRMode == I2S_TX_MODE)
432
-	{
433
-		I2Sx->I2STXBITRATE = bitrate;
434
-	}
435
-	else
436
-	{
437
-		I2Sx->I2SRXBITRATE = bitrate;
438
-	}
439
-}
440
-
441
-/********************************************************************//**
442
- * @brief		Configuration operating mode for I2S
443
- * @param[in]	I2Sx I2S peripheral selected, should be: LPC_I2S
444
- * @param[in]	ModeConfig pointer to I2S_MODEConf_Type will be used to
445
- * 				configure
446
- * @param[in]	TRMode is transmit/receive mode, should be:
447
- * 				- I2S_TX_MODE = 0: transmit mode
448
- * 				- I2S_RX_MODE = 1: receive mode
449
- * @return 		none
450
- *********************************************************************/
451
-void I2S_ModeConfig(LPC_I2S_TypeDef *I2Sx, I2S_MODEConf_Type* ModeConfig,
452
-		uint8_t TRMode)
453
-{
454
-	CHECK_PARAM(PARAM_I2Sx(I2Sx));
455
-	CHECK_PARAM(PARAM_I2S_CLKSEL(ModeConfig->clksel));
456
-	CHECK_PARAM(PARAM_I2S_4PIN(ModeConfig->fpin));
457
-	CHECK_PARAM(PARAM_I2S_MCLK(ModeConfig->mcena));
458
-	CHECK_PARAM(PARAM_I2S_TRX(TRMode));
459
-
460
-	if (TRMode == I2S_TX_MODE) {
461
-		I2Sx->I2STXMODE &= ~0x0F; //clear bit 3:0 in I2STXMODE register
462
-		if (ModeConfig->clksel == I2S_CLKSEL_MCLK) {
463
-			I2Sx->I2STXMODE |= 0x02;
464
-		}
465
-		if (ModeConfig->fpin == I2S_4PIN_ENABLE) {
466
-			I2Sx->I2STXMODE |= (1 << 2);
467
-		}
468
-		if (ModeConfig->mcena == I2S_MCLK_ENABLE) {
469
-			I2Sx->I2STXMODE |= (1 << 3);
470
-		}
471
-	} else {
472
-		I2Sx->I2SRXMODE &= ~0x0F; //clear bit 3:0 in I2STXMODE register
473
-		if (ModeConfig->clksel == I2S_CLKSEL_MCLK) {
474
-			I2Sx->I2SRXMODE |= 0x02;
475
-		}
476
-		if (ModeConfig->fpin == I2S_4PIN_ENABLE) {
477
-			I2Sx->I2SRXMODE |= (1 << 2);
478
-		}
479
-		if (ModeConfig->mcena == I2S_MCLK_ENABLE) {
480
-			I2Sx->I2SRXMODE |= (1 << 3);
481
-		}
482
-	}
483
-}
484
-
485
-/********************************************************************//**
486
- * @brief		Configure DMA operation for I2S
487
- * @param[in]	I2Sx I2S peripheral selected, should be: LPC_I2S
488
- * @param[in]	DMAConfig pointer to I2S_DMAConf_Type will be used to configure
489
- * @param[in]	TRMode is transmit/receive mode, should be:
490
- * 				- I2S_TX_MODE = 0: transmit mode
491
- * 				- I2S_RX_MODE = 1: receive mode
492
- * @return 		none
493
- *********************************************************************/
494
-void I2S_DMAConfig(LPC_I2S_TypeDef *I2Sx, I2S_DMAConf_Type* DMAConfig,
495
-		uint8_t TRMode)
496
-{
497
-	CHECK_PARAM(PARAM_I2Sx(I2Sx));
498
-	CHECK_PARAM(PARAM_I2S_DMA(DMAConfig->DMAIndex));
499
-	CHECK_PARAM(PARAM_I2S_DMA_DEPTH(DMAConfig->depth));
500
-	CHECK_PARAM(PARAM_I2S_TRX(TRMode));
501
-
502
-	if (TRMode == I2S_RX_MODE) {
503
-		if (DMAConfig->DMAIndex == I2S_DMA_1) {
504
-			LPC_I2S->I2SDMA1 = (DMAConfig->depth) << 8;
505
-		} else {
506
-			LPC_I2S->I2SDMA2 = (DMAConfig->depth) << 8;
507
-		}
508
-	} else {
509
-		if (DMAConfig->DMAIndex == I2S_DMA_1) {
510
-			LPC_I2S->I2SDMA1 = (DMAConfig->depth) << 16;
511
-		} else {
512
-			LPC_I2S->I2SDMA2 = (DMAConfig->depth) << 16;
513
-		}
514
-	}
515
-}
516
-
517
-/********************************************************************//**
518
- * @brief		Enable/Disable DMA operation for I2S
519
- * @param[in]	I2Sx: I2S peripheral selected, should be: LPC_I2S
520
- * @param[in]	DMAIndex chose what DMA is used, should be:
521
- * 				- I2S_DMA_1 = 0: DMA1
522
- * 				- I2S_DMA_2 = 1: DMA2
523
- * @param[in]	TRMode is transmit/receive mode, should be:
524
- * 				- I2S_TX_MODE = 0: transmit mode
525
- * 				- I2S_RX_MODE = 1: receive mode
526
- * @param[in]	NewState is new state of DMA operation, should be:
527
- * 				- ENABLE
528
- * 				- DISABLE
529
- * @return 		none
530
- *********************************************************************/
531
-void I2S_DMACmd(LPC_I2S_TypeDef *I2Sx, uint8_t DMAIndex, uint8_t TRMode,
532
-		FunctionalState NewState)
533
-{
534
-	CHECK_PARAM(PARAM_I2Sx(I2Sx));
535
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
536
-	CHECK_PARAM(PARAM_I2S_DMA(DMAIndex));
537
-	CHECK_PARAM(PARAM_I2S_TRX(TRMode));
538
-
539
-	if (TRMode == I2S_RX_MODE) {
540
-		if (DMAIndex == I2S_DMA_1) {
541
-			if (NewState == ENABLE)
542
-				I2Sx->I2SDMA1 |= 0x01;
543
-			else
544
-				I2Sx->I2SDMA1 &= ~0x01;
545
-		} else {
546
-			if (NewState == ENABLE)
547
-				I2Sx->I2SDMA2 |= 0x01;
548
-			else
549
-				I2Sx->I2SDMA2 &= ~0x01;
550
-		}
551
-	} else {
552
-		if (DMAIndex == I2S_DMA_1) {
553
-			if (NewState == ENABLE)
554
-				I2Sx->I2SDMA1 |= 0x02;
555
-			else
556
-				I2Sx->I2SDMA1 &= ~0x02;
557
-		} else {
558
-			if (NewState == ENABLE)
559
-				I2Sx->I2SDMA2 |= 0x02;
560
-			else
561
-				I2Sx->I2SDMA2 &= ~0x02;
562
-		}
563
-	}
564
-}
565
-
566
-/********************************************************************//**
567
- * @brief		Configure IRQ for I2S
568
- * @param[in]	I2Sx I2S peripheral selected, should be: LPC_I2S
569
- * @param[in]	TRMode is transmit/receive mode, should be:
570
- * 				- I2S_TX_MODE = 0: transmit mode
571
- * 				- I2S_RX_MODE = 1: receive mode
572
- * @param[in]	level is the FIFO level that triggers IRQ request
573
- * @return 		none
574
- *********************************************************************/
575
-void I2S_IRQConfig(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode, uint8_t level) {
576
-	CHECK_PARAM(PARAM_I2Sx(I2Sx));
577
-	CHECK_PARAM(PARAM_I2S_TRX(TRMode));
578
-	CHECK_PARAM(PARAM_I2S_IRQ_LEVEL(level));
579
-
580
-	if (TRMode == I2S_RX_MODE) {
581
-		I2Sx->I2SIRQ |= (level << 8);
582
-	} else {
583
-		I2Sx->I2SIRQ |= (level << 16);
584
-	}
585
-}
586
-
587
-/********************************************************************//**
588
- * @brief		Enable/Disable IRQ for I2S
589
- * @param[in]	I2Sx I2S peripheral selected, should be: LPC_I2S
590
- * @param[in]	TRMode is transmit/receive mode, should be:
591
- * 				- I2S_TX_MODE = 0: transmit mode
592
- * 				- I2S_RX_MODE = 1: receive mode
593
- * @param[in]	NewState is new state of DMA operation, should be:
594
- * 				- ENABLE
595
- * 				- DISABLE
596
- * @return 		none
597
- *********************************************************************/
598
-void I2S_IRQCmd(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode, FunctionalState NewState) {
599
-	CHECK_PARAM(PARAM_I2Sx(I2Sx));
600
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
601
-
602
-	if (TRMode == I2S_RX_MODE) {
603
-		if (NewState == ENABLE)
604
-			I2Sx->I2SIRQ |= 0x01;
605
-		else
606
-			I2Sx->I2SIRQ &= ~0x01;
607
-		//Enable DMA
608
-
609
-	} else {
610
-		if (NewState == ENABLE)
611
-			I2Sx->I2SIRQ |= 0x02;
612
-		else
613
-			I2Sx->I2SIRQ &= ~0x02;
614
-	}
615
-}
616
-
617
-/********************************************************************//**
618
- * @brief		Get I2S interrupt status
619
- * @param[in]	I2Sx I2S peripheral selected, should be: LPC_I2S
620
- * @param[in]	TRMode is transmit/receive mode, should be:
621
- * 				- I2S_TX_MODE = 0: transmit mode
622
- * 				- I2S_RX_MODE = 1: receive mode
623
- * @return 		FunctionState	should be:
624
- * 				- ENABLE: interrupt is enable
625
- * 				- DISABLE: interrupt is disable
626
- *********************************************************************/
627
-FunctionalState I2S_GetIRQStatus(LPC_I2S_TypeDef *I2Sx,uint8_t TRMode)
628
-{
629
-	CHECK_PARAM(PARAM_I2Sx(I2Sx));
630
-	if(TRMode == I2S_TX_MODE)
631
-		return ((FunctionalState)((I2Sx->I2SIRQ >> 1)&0x01));
632
-	else
633
-		return ((FunctionalState)((I2Sx->I2SIRQ)&0x01));
634
-}
635
-
636
-/********************************************************************//**
637
- * @brief		Get I2S interrupt depth
638
- * @param[in]	I2Sx I2S peripheral selected, should be: LPC_I2S
639
- * @param[in]	TRMode is transmit/receive mode, should be:
640
- * 				- I2S_TX_MODE = 0: transmit mode
641
- * 				- I2S_RX_MODE = 1: receive mode
642
- * @return 		depth of FIFO level on which to create an irq request
643
- *********************************************************************/
644
-uint8_t I2S_GetIRQDepth(LPC_I2S_TypeDef *I2Sx,uint8_t TRMode)
645
-{
646
-	CHECK_PARAM(PARAM_I2Sx(I2Sx));
647
-	if(TRMode == I2S_TX_MODE)
648
-		return (((I2Sx->I2SIRQ)>>16)&0xFF);
649
-	else
650
-		return (((I2Sx->I2SIRQ)>>8)&0xFF);
651
-}
652
-/**
653
- * @}
654
- */
655
-
656
-#endif /* _I2S */
657
-
658
-/**
659
- * @}
660
- */
661
-
662
-/* --------------------------------- End Of File ------------------------------ */
663
-

+ 0
- 308
frameworks/CMSIS/LPC1768/driver/lpc17xx_iap.c Просмотреть файл

@@ -1,308 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_iap.c			2012-04-18
3
-*//**
4
-* @file		lpc17xx_iap.c
5
- * @brief	Contains all functions support for IAP on lpc17xx
6
-* @version	1.0
7
-* @date		18. April. 2012
8
-* @author	NXP MCU SW Application Team
9
-*
10
-* Copyright(C) 2011, NXP Semiconductor
11
-* All rights reserved.
12
-*
13
-***********************************************************************
14
-* Software that is described herein is for illustrative purposes only
15
-* which provides customers with programming information regarding the
16
-* products. This software is supplied "AS IS" without any warranties.
17
-* NXP Semiconductors assumes no responsibility or liability for the
18
-* use of the software, conveys no license or title under any patent,
19
-* copyright, or mask work right to the product. NXP Semiconductors
20
-* reserves the right to make changes in the software without
21
-* notification. NXP Semiconductors also make no representation or
22
-* warranty that such application will be suitable for the specified
23
-* use without further testing or modification.
24
-* Permission to use, copy, modify, and distribute this software and its
25
-* documentation is hereby granted, under NXP Semiconductors'
26
-* relevant copyright in the software, without fee, provided that it
27
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
28
-* copyright, permission, and disclaimer notice must appear in all copies of
29
-* this code.
30
-**********************************************************************/
31
-#include "lpc17xx_iap.h"
32
-#include "system_LPC17xx.h"
33
-
34
-//  IAP Command
35
-typedef void (*IAP)(uint32_t *cmd,uint32_t *result);
36
-IAP iap_entry = (IAP) IAP_LOCATION;
37
-#define IAP_Call 	iap_entry
38
-
39
-/** @addtogroup IAP_Public_Functions IAP Public Function
40
- * @ingroup IAP
41
- * @{
42
- */
43
-
44
-
45
-/*********************************************************************//**
46
- * @brief		Get Sector Number
47
- *
48
- * @param[in] adr	           Sector Address
49
- *
50
- * @return 	Sector Number.
51
- *
52
- **********************************************************************/
53
- uint32_t GetSecNum (uint32_t adr)
54
-{
55
-    uint32_t n;
56
-
57
-    n = adr >> 12;                               //  4kB Sector
58
-    if (n >= 0x10) {
59
-      n = 0x0E + (n >> 3);                       // 32kB Sector
60
-    }
61
-
62
-    return (n);                                  // Sector Number
63
-}
64
-
65
-/*********************************************************************//**
66
- * @brief		Prepare sector(s) for write operation
67
- *
68
- * @param[in] start_sec	          The number of start sector
69
- * @param[in] end_sec	          The number of end sector
70
- *
71
- * @return 	CMD_SUCCESS/BUSY/INVALID_SECTOR.
72
- *
73
- **********************************************************************/
74
-IAP_STATUS_CODE PrepareSector(uint32_t start_sec, uint32_t end_sec)
75
-{
76
-    IAP_COMMAND_Type command;
77
-    command.cmd    = IAP_PREPARE;                    // Prepare Sector for Write
78
-    command.param[0] = start_sec;                    // Start Sector
79
-    command.param[1] = end_sec;                      // End Sector
80
-    IAP_Call (&command.cmd, &command.status);        // Call IAP Command
81
-    return (IAP_STATUS_CODE)command.status;
82
-}
83
-
84
-/*********************************************************************//**
85
- * @brief		 Copy RAM to Flash
86
- *
87
- * @param[in] dest	          destination buffer (in Flash memory).
88
- * @param[in] source	   source buffer (in RAM).
89
- * @param[in] size	          the write size.
90
- *
91
- * @return 	CMD_SUCCESS.
92
- *                  SRC_ADDR_ERROR/DST_ADDR_ERROR
93
- *                  SRC_ADDR_NOT_MAPPED/DST_ADDR_NOT_MAPPED
94
- *                  COUNT_ERROR/SECTOR_NOT_PREPARED_FOR_WRITE_OPERATION
95
- *                  BUSY
96
- *
97
- **********************************************************************/
98
-IAP_STATUS_CODE CopyRAM2Flash(uint8_t * dest, uint8_t* source, IAP_WRITE_SIZE size)
99
-{
100
-    uint32_t sec;
101
-    IAP_STATUS_CODE status;
102
-    IAP_COMMAND_Type command;
103
-
104
-	// Prepare sectors
105
-    sec = GetSecNum((uint32_t)dest);
106
-   	status = PrepareSector(sec, sec);
107
-	if(status != CMD_SUCCESS)
108
-        return status;
109
-
110
-	// write
111
-	command.cmd    = IAP_COPY_RAM2FLASH;             // Copy RAM to Flash
112
-    command.param[0] = (uint32_t)dest;                 // Destination Flash Address
113
-    command.param[1] = (uint32_t)source;               // Source RAM Address
114
-    command.param[2] =  size;                          // Number of bytes
115
-    command.param[3] =  SystemCoreClock / 1000;         // CCLK in kHz
116
-    IAP_Call (&command.cmd, &command.status);              // Call IAP Command
117
-
118
-    return (IAP_STATUS_CODE)command.status;             // Finished without Errors
119
-}
120
-
121
-/*********************************************************************//**
122
- * @brief		 Erase sector(s)
123
- *
124
- * @param[in] start_sec	   The number of start sector
125
- * @param[in] end_sec	   The number of end sector
126
- *
127
- * @return 	CMD_SUCCESS.
128
- *                  INVALID_SECTOR
129
- *                  SECTOR_NOT_PREPARED_FOR_WRITE_OPERATION
130
- *                  BUSY
131
- *
132
- **********************************************************************/
133
-IAP_STATUS_CODE EraseSector(uint32_t start_sec, uint32_t end_sec)
134
-{
135
-    IAP_COMMAND_Type command;
136
-    IAP_STATUS_CODE status;
137
-
138
-	// Prepare sectors
139
-   	status = PrepareSector(start_sec, end_sec);
140
-	if(status != CMD_SUCCESS)
141
-        return status;
142
-
143
-	// Erase sectors
144
-    command.cmd    = IAP_ERASE;                    // Prepare Sector for Write
145
-    command.param[0] = start_sec;                  // Start Sector
146
-    command.param[1] = end_sec;                    // End Sector
147
-    command.param[2] =  SystemCoreClock / 1000;         // CCLK in kHz
148
-    IAP_Call (&command.cmd, &command.status);      // Call IAP Command
149
-    return (IAP_STATUS_CODE)command.status;
150
-}
151
-
152
-/*********************************************************************//**
153
- * @brief		  Blank check sector(s)
154
- *
155
- * @param[in] start_sec	   The number of start sector
156
- * @param[in] end_sec	   The number of end sector
157
- * @param[out] first_nblank_loc  The offset of the first non-blank word
158
-  * @param[out] first_nblank_val  The value of the first non-blank word
159
- *
160
- * @return 	CMD_SUCCESS.
161
- *                  INVALID_SECTOR
162
- *                  SECTOR_NOT_BLANK
163
- *                  BUSY
164
- *
165
- **********************************************************************/
166
-IAP_STATUS_CODE BlankCheckSector(uint32_t start_sec, uint32_t end_sec,
167
-                                 uint32_t *first_nblank_loc,
168
-								 uint32_t *first_nblank_val)
169
-{
170
-    IAP_COMMAND_Type command;
171
-
172
-    command.cmd    = IAP_BLANK_CHECK;                // Prepare Sector for Write
173
-    command.param[0] = start_sec;                    // Start Sector
174
-    command.param[1] = end_sec;                      // End Sector
175
-    IAP_Call (&command.cmd, &command.status);        // Call IAP Command
176
-
177
-	if(command.status == SECTOR_NOT_BLANK)
178
-	{
179
-	  // Update out value
180
-	  if(first_nblank_loc != NULL)
181
-	      *first_nblank_loc =  command.result[0];
182
-	  if(first_nblank_val != NULL)
183
-	      *first_nblank_val =  command.result[1];
184
-    }
185
-
186
-    return (IAP_STATUS_CODE)command.status;
187
-}
188
-
189
-/*********************************************************************//**
190
- * @brief		   Read part identification number
191
- *
192
- * @param[out] partID  Part ID
193
- *
194
- * @return 	CMD_SUCCESS
195
- *
196
- **********************************************************************/
197
-IAP_STATUS_CODE ReadPartID(uint32_t *partID)
198
-{
199
-   IAP_COMMAND_Type command;
200
-   command.cmd = IAP_READ_PART_ID;
201
-   IAP_Call (&command.cmd, &command.status);        // Call IAP Command
202
-
203
-   if(command.status == CMD_SUCCESS)
204
-   {
205
-      if(partID != NULL)
206
-	     *partID = command.result[0];
207
-   }
208
-
209
-   return (IAP_STATUS_CODE)command.status;
210
-}
211
-
212
-/*********************************************************************//**
213
- * @brief		   Read boot code version. The version is interpreted as <major>.<minor>.
214
- *
215
- * @param[out] major  The major
216
- * @param[out] minor  The minor
217
- *
218
- * @return 	CMD_SUCCESS
219
- *
220
- **********************************************************************/
221
-IAP_STATUS_CODE ReadBootCodeVer(uint8_t *major, uint8_t* minor)
222
-{
223
-   IAP_COMMAND_Type command;
224
-   command.cmd = IAP_READ_BOOT_VER;
225
-   IAP_Call (&command.cmd, &command.status);        // Call IAP Command
226
-
227
-   if(command.status == CMD_SUCCESS)
228
-   {
229
-      if(major != NULL)
230
-	     *major = (command.result[0] >> 8) & 0xFF;
231
-      if(minor != NULL)
232
-	     *minor = (command.result[0]) & 0xFF;
233
-   }
234
-
235
-   return (IAP_STATUS_CODE)command.status;
236
-}
237
-
238
-/*********************************************************************//**
239
- * @brief		   Read Device serial number.
240
- *
241
- * @param[out] uid   Serial number.
242
- *
243
- * @return 	CMD_SUCCESS
244
- *
245
- **********************************************************************/
246
-IAP_STATUS_CODE ReadDeviceSerialNum(uint32_t *uid)
247
-{
248
-   IAP_COMMAND_Type command;
249
-   command.cmd = IAP_READ_SERIAL_NUMBER;
250
-   IAP_Call (&command.cmd, &command.status);        // Call IAP Command
251
-
252
-   if(command.status == CMD_SUCCESS)
253
-   {
254
-      if(uid != NULL)
255
-	  {
256
-	    uint32_t i = 0;
257
-		for(i = 0; i < 4; i++)
258
-	       uid[i] =  command.result[i];
259
-	  }
260
-   }
261
-
262
-   return (IAP_STATUS_CODE)command.status;
263
-}
264
-
265
-/*********************************************************************//**
266
- * @brief		   compare the memory contents at two locations.
267
- *
268
- * @param[in] addr1   The address of the 1st buffer (in RAM/Flash).
269
- * @param[in] addr2   The address of the 2nd buffer (in RAM/Flash).
270
- * @param[in] size      Number of bytes to be compared; should be a multiple of 4.
271
- *
272
- * @return 	CMD_SUCCESS
273
- *                  COMPARE_ERROR
274
- *                  COUNT_ERROR (Byte count is not a multiple of 4)
275
- *                  ADDR_ERROR
276
- *                  ADDR_NOT_MAPPED
277
- *
278
- **********************************************************************/
279
-IAP_STATUS_CODE Compare(uint8_t *addr1, uint8_t *addr2, uint32_t size)
280
-{
281
-   IAP_COMMAND_Type command;
282
-   command.cmd = IAP_COMPARE;
283
-   command.param[0] = (uint32_t)addr1;
284
-   command.param[1] = (uint32_t)addr2;
285
-   command.param[2] = size;
286
-   IAP_Call (&command.cmd, &command.status);        // Call IAP Command
287
-
288
-   return (IAP_STATUS_CODE)command.status;
289
-}
290
-
291
-/*********************************************************************//**
292
- * @brief		   Re-invoke ISP.
293
- *
294
- * @param[in] None.
295
- *
296
- * @return 	None.
297
- *
298
- **********************************************************************/
299
-void InvokeISP(void)
300
-{
301
-   IAP_COMMAND_Type command;
302
-   command.cmd = IAP_REINVOKE_ISP;
303
-   IAP_Call (&command.cmd, &command.status);        // Call IAP Command
304
-}
305
-
306
-/**
307
- * @}
308
- */

+ 0
- 76
frameworks/CMSIS/LPC1768/driver/lpc17xx_libcfg_default.c Просмотреть файл

@@ -1,76 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_libcfg_default.c				2010-05-21
3
-*//**
4
-* @file		lpc17xx_libcfg_default.c
5
-* @brief	Library configuration source file (default), used to build
6
-* 			library without examples
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Library group ----------------------------------------------------------- */
34
-/** @addtogroup LIBCFG_DEFAULT
35
- * @{
36
- */
37
-
38
-/* Includes ------------------------------------------------------------------- */
39
-#include "lpc17xx_libcfg_default.h"
40
-
41
-/* Public Functions ----------------------------------------------------------- */
42
-/** @addtogroup LIBCFG_DEFAULT_Public_Functions
43
- * @{
44
- */
45
-
46
-#ifndef __BUILD_WITH_EXAMPLE__
47
-
48
-#ifdef  DEBUG
49
-/*******************************************************************************
50
-* @brief		Reports the name of the source file and the source line number
51
-* 				where the CHECK_PARAM error has occurred.
52
-* @param[in]	file Pointer to the source file name
53
-* @param[in]    line assert_param error line source number
54
-* @return		None
55
-*******************************************************************************/
56
-void check_failed(uint8_t *file, uint32_t line)
57
-{
58
-	/* User can add his own implementation to report the file name and line number,
59
-	 ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
60
-
61
-	/* Infinite loop */
62
-	while(1);
63
-}
64
-#endif /* DEBUG */
65
-
66
-#endif /* __BUILD_WITH_EXAMPLE__ */
67
-
68
-/**
69
- * @}
70
- */
71
-
72
-/**
73
- * @}
74
- */
75
-
76
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 509
frameworks/CMSIS/LPC1768/driver/lpc17xx_mcpwm.c Просмотреть файл

@@ -1,509 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_mcpwm.c				2010-05-21
3
-*//**
4
-* @file		lpc17xx_mcpwm.c
5
-* @brief	Contains all functions support for Motor Control PWM firmware
6
-* 			library on LPC17xx
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @addtogroup MCPWM
35
- * @{
36
- */
37
-
38
-/* Includes ------------------------------------------------------------------- */
39
-#include "lpc17xx_mcpwm.h"
40
-#include "lpc17xx_clkpwr.h"
41
-
42
-/* If this source file built with example, the LPC17xx FW library configuration
43
- * file in each example directory ("lpc17xx_libcfg.h") must be included,
44
- * otherwise the default FW library configuration file must be included instead
45
- */
46
-#ifdef __BUILD_WITH_EXAMPLE__
47
-#include "lpc17xx_libcfg.h"
48
-#else
49
-#include "lpc17xx_libcfg_default.h"
50
-#endif /* __BUILD_WITH_EXAMPLE__ */
51
-
52
-
53
-#ifdef _MCPWM
54
-
55
-/* Public Functions ----------------------------------------------------------- */
56
-/** @addtogroup MCPWM_Public_Functions
57
- * @{
58
- */
59
-
60
-/*********************************************************************//**
61
- * @brief		Initializes the MCPWM peripheral
62
- * @param[in]	MCPWMx 		Motor Control PWM peripheral selected,
63
- * 				Should be: LPC_MCPWM
64
- * @return		None
65
- **********************************************************************/
66
-void MCPWM_Init(LPC_MCPWM_TypeDef *MCPWMx)
67
-{
68
-
69
-	/* Turn On MCPWM PCLK */
70
-	CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCMC, ENABLE);
71
-	/* As default, peripheral clock for MCPWM module
72
-	 * is set to FCCLK / 2 */
73
-	// CLKPWR_SetPCLKDiv(CLKPWR_PCLKSEL_MC, CLKPWR_PCLKSEL_CCLK_DIV_2);
74
-
75
-	MCPWMx->MCCAP_CLR = MCPWM_CAPCLR_CAP(0) | MCPWM_CAPCLR_CAP(1) | MCPWM_CAPCLR_CAP(2);
76
-	MCPWMx->MCINTFLAG_CLR = MCPWM_INT_ILIM(0) | MCPWM_INT_ILIM(1) | MCPWM_INT_ILIM(2) \
77
-							| MCPWM_INT_IMAT(0) | MCPWM_INT_IMAT(1) | MCPWM_INT_IMAT(2) \
78
-							| MCPWM_INT_ICAP(0) | MCPWM_INT_ICAP(1) | MCPWM_INT_ICAP(2);
79
-	MCPWMx->MCINTEN_CLR = MCPWM_INT_ILIM(0) | MCPWM_INT_ILIM(1) | MCPWM_INT_ILIM(2) \
80
-							| MCPWM_INT_IMAT(0) | MCPWM_INT_IMAT(1) | MCPWM_INT_IMAT(2) \
81
-							| MCPWM_INT_ICAP(0) | MCPWM_INT_ICAP(1) | MCPWM_INT_ICAP(2);
82
-}
83
-
84
-
85
-/*********************************************************************//**
86
- * @brief		Configures each channel in MCPWM peripheral according to the
87
- * 				specified parameters in the MCPWM_CHANNEL_CFG_Type.
88
- * @param[in]	MCPWMx 			Motor Control PWM peripheral selected
89
- * 								should be: LPC_MCPWM
90
- * @param[in]	channelNum		Channel number, should be: 0..2.
91
- * @param[in]	channelSetup	Pointer to a MCPWM_CHANNEL_CFG_Type structure
92
-*                    			that contains the configuration information for the
93
-*                    			specified MCPWM channel.
94
- * @return		None
95
- **********************************************************************/
96
-void MCPWM_ConfigChannel(LPC_MCPWM_TypeDef *MCPWMx, uint32_t channelNum,
97
-						MCPWM_CHANNEL_CFG_Type * channelSetup)
98
-{
99
-	if (channelNum <= 2) {
100
-		if (channelNum == 0) {
101
-			MCPWMx->MCTIM0 = channelSetup->channelTimercounterValue;
102
-			MCPWMx->MCPER0 = channelSetup->channelPeriodValue;
103
-			MCPWMx->MCPW0 = channelSetup->channelPulsewidthValue;
104
-		} else if (channelNum == 1) {
105
-			MCPWMx->MCTIM1 = channelSetup->channelTimercounterValue;
106
-			MCPWMx->MCPER1 = channelSetup->channelPeriodValue;
107
-			MCPWMx->MCPW1 = channelSetup->channelPulsewidthValue;
108
-		} else if (channelNum == 2) {
109
-			MCPWMx->MCTIM2 = channelSetup->channelTimercounterValue;
110
-			MCPWMx->MCPER2 = channelSetup->channelPeriodValue;
111
-			MCPWMx->MCPW2 = channelSetup->channelPulsewidthValue;
112
-		} else {
113
-			return;
114
-		}
115
-
116
-		if (channelSetup->channelType /* == MCPWM_CHANNEL_CENTER_MODE */){
117
-			MCPWMx->MCCON_SET = MCPWM_CON_CENTER(channelNum);
118
-		} else {
119
-			MCPWMx->MCCON_CLR = MCPWM_CON_CENTER(channelNum);
120
-		}
121
-
122
-		if (channelSetup->channelPolarity /* == MCPWM_CHANNEL_PASSIVE_HI */){
123
-			MCPWMx->MCCON_SET = MCPWM_CON_POLAR(channelNum);
124
-		} else {
125
-			MCPWMx->MCCON_CLR = MCPWM_CON_POLAR(channelNum);
126
-		}
127
-
128
-		if (channelSetup->channelDeadtimeEnable /* == ENABLE */){
129
-			MCPWMx->MCCON_SET = MCPWM_CON_DTE(channelNum);
130
-			MCPWMx->MCDEADTIME &= ~(MCPWM_DT(channelNum, 0x3FF));
131
-			MCPWMx->MCDEADTIME |= MCPWM_DT(channelNum, channelSetup->channelDeadtimeValue);
132
-		} else {
133
-			MCPWMx->MCCON_CLR = MCPWM_CON_DTE(channelNum);
134
-		}
135
-
136
-		if (channelSetup->channelUpdateEnable /* == ENABLE */){
137
-			MCPWMx->MCCON_CLR = MCPWM_CON_DISUP(channelNum);
138
-		} else {
139
-			MCPWMx->MCCON_SET = MCPWM_CON_DISUP(channelNum);
140
-		}
141
-	}
142
-}
143
-
144
-
145
-/*********************************************************************//**
146
- * @brief		Write to MCPWM shadow registers - Update the value for period
147
- * 				and pulse width in MCPWM peripheral.
148
- * @param[in]	MCPWMx 			Motor Control PWM peripheral selected
149
- * 								Should be: LPC_MCPWM
150
- * @param[in]	channelNum		Channel Number, should be: 0..2.
151
- * @param[in]	channelSetup	Pointer to a MCPWM_CHANNEL_CFG_Type structure
152
-*                    			that contains the configuration information for the
153
-*                    			specified MCPWM channel.
154
- * @return		None
155
- **********************************************************************/
156
-void MCPWM_WriteToShadow(LPC_MCPWM_TypeDef *MCPWMx, uint32_t channelNum,
157
-								MCPWM_CHANNEL_CFG_Type *channelSetup)
158
-{
159
-	if (channelNum == 0){
160
-		MCPWMx->MCPER0 = channelSetup->channelPeriodValue;
161
-		MCPWMx->MCPW0 = channelSetup->channelPulsewidthValue;
162
-	} else if (channelNum == 1) {
163
-		MCPWMx->MCPER1 = channelSetup->channelPeriodValue;
164
-		MCPWMx->MCPW1 = channelSetup->channelPulsewidthValue;
165
-	} else if (channelNum == 2) {
166
-		MCPWMx->MCPER2 = channelSetup->channelPeriodValue;
167
-		MCPWMx->MCPW2 = channelSetup->channelPulsewidthValue;
168
-	}
169
-}
170
-
171
-
172
-
173
-/*********************************************************************//**
174
- * @brief		Configures capture function in MCPWM peripheral
175
- * @param[in]	MCPWMx 			Motor Control PWM peripheral selected
176
- * 								Should be: LPC_MCPWM
177
- * @param[in]	channelNum		MCI (Motor Control Input pin) number
178
- * 								Should be: 0..2
179
- * @param[in]	captureConfig	Pointer to a MCPWM_CAPTURE_CFG_Type structure
180
-*                    			that contains the configuration information for the
181
-*                    			specified MCPWM capture.
182
- * @return
183
- **********************************************************************/
184
-void MCPWM_ConfigCapture(LPC_MCPWM_TypeDef *MCPWMx, uint32_t channelNum,
185
-						MCPWM_CAPTURE_CFG_Type *captureConfig)
186
-{
187
-	if (channelNum <= 2) {
188
-
189
-		if (captureConfig->captureFalling /* == ENABLE */) {
190
-			MCPWMx->MCCAPCON_SET = MCPWM_CAPCON_CAPMCI_FE(captureConfig->captureChannel, channelNum);
191
-		} else {
192
-			MCPWMx->MCCAPCON_CLR = MCPWM_CAPCON_CAPMCI_FE(captureConfig->captureChannel, channelNum);
193
-		}
194
-
195
-		if (captureConfig->captureRising /* == ENABLE */) {
196
-			MCPWMx->MCCAPCON_SET = MCPWM_CAPCON_CAPMCI_RE(captureConfig->captureChannel, channelNum);
197
-		} else {
198
-			MCPWMx->MCCAPCON_CLR = MCPWM_CAPCON_CAPMCI_RE(captureConfig->captureChannel, channelNum);
199
-		}
200
-
201
-		if (captureConfig->timerReset /* == ENABLE */){
202
-			MCPWMx->MCCAPCON_SET = MCPWM_CAPCON_RT(captureConfig->captureChannel);
203
-		} else {
204
-			MCPWMx->MCCAPCON_CLR = MCPWM_CAPCON_RT(captureConfig->captureChannel);
205
-		}
206
-
207
-		if (captureConfig->hnfEnable /* == ENABLE */){
208
-			MCPWMx->MCCAPCON_SET = MCPWM_CAPCON_HNFCAP(channelNum);
209
-		} else {
210
-			MCPWMx->MCCAPCON_CLR = MCPWM_CAPCON_HNFCAP(channelNum);
211
-		}
212
-	}
213
-}
214
-
215
-
216
-/*********************************************************************//**
217
- * @brief		Clears current captured value in specified capture channel
218
- * @param[in]	MCPWMx 		Motor Control PWM peripheral selected
219
- * 							Should be: LPC_MCPWM
220
- * @param[in]	captureChannel	Capture channel number, should be: 0..2
221
- * @return		None
222
- **********************************************************************/
223
-void MCPWM_ClearCapture(LPC_MCPWM_TypeDef *MCPWMx, uint32_t captureChannel)
224
-{
225
-	MCPWMx->MCCAP_CLR = MCPWM_CAPCLR_CAP(captureChannel);
226
-}
227
-
228
-/*********************************************************************//**
229
- * @brief		Get current captured value in specified capture channel
230
- * @param[in]	MCPWMx 		Motor Control PWM peripheral selected,
231
- * 							Should be: LPC_MCPWM
232
- * @param[in]	captureChannel	Capture channel number, should be: 0..2
233
- * @return		None
234
- **********************************************************************/
235
-uint32_t MCPWM_GetCapture(LPC_MCPWM_TypeDef *MCPWMx, uint32_t captureChannel)
236
-{
237
-	if (captureChannel == 0){
238
-		return (MCPWMx->MCCR0);
239
-	} else if (captureChannel == 1) {
240
-		return (MCPWMx->MCCR1);
241
-	} else if (captureChannel == 2) {
242
-		return (MCPWMx->MCCR2);
243
-	}
244
-	return (0);
245
-}
246
-
247
-
248
-/*********************************************************************//**
249
- * @brief		Configures Count control in MCPWM peripheral
250
- * @param[in]	MCPWMx 		Motor Control PWM peripheral selected
251
- * 							Should be: LPC_MCPWM
252
- * @param[in]	channelNum	Channel number, should be: 0..2
253
- * @param[in]	countMode	Count mode, should be:
254
- * 							- ENABLE: Enables count mode.
255
- * 							- DISABLE: Disable count mode, the channel is in timer mode.
256
- * @param[in]	countConfig	Pointer to a MCPWM_COUNT_CFG_Type structure
257
-*                    		that contains the configuration information for the
258
-*                    		specified MCPWM count control.
259
- * @return		None
260
- **********************************************************************/
261
-void MCPWM_CountConfig(LPC_MCPWM_TypeDef *MCPWMx, uint32_t channelNum,
262
-					uint32_t countMode, MCPWM_COUNT_CFG_Type *countConfig)
263
-{
264
-	if (channelNum <= 2) {
265
-		if (countMode /* == ENABLE */){
266
-			MCPWMx->MCCNTCON_SET = MCPWM_CNTCON_CNTR(channelNum);
267
-			if (countConfig->countFalling /* == ENABLE */) {
268
-				MCPWMx->MCCNTCON_SET = MCPWM_CNTCON_TCMCI_FE(countConfig->counterChannel,channelNum);
269
-			} else {
270
-				MCPWMx->MCCNTCON_CLR = MCPWM_CNTCON_TCMCI_FE(countConfig->counterChannel,channelNum);
271
-			}
272
-			if (countConfig->countRising /* == ENABLE */) {
273
-				MCPWMx->MCCNTCON_SET = MCPWM_CNTCON_TCMCI_RE(countConfig->counterChannel,channelNum);
274
-			} else {
275
-				MCPWMx->MCCNTCON_CLR = MCPWM_CNTCON_TCMCI_RE(countConfig->counterChannel,channelNum);
276
-			}
277
-		} else {
278
-			MCPWMx->MCCNTCON_CLR = MCPWM_CNTCON_CNTR(channelNum);
279
-		}
280
-	}
281
-}
282
-
283
-
284
-/*********************************************************************//**
285
- * @brief		Start MCPWM activity for each MCPWM channel
286
- * @param[in]	MCPWMx 		Motor Control PWM peripheral selected
287
- * 							Should be: LPC_MCPWM
288
- * @param[in]	channel0	State of this command on channel 0:
289
- * 							- ENABLE: 'Start' command will effect on channel 0
290
- * 							- DISABLE: 'Start' command will not effect on channel 0
291
- * @param[in]	channel1	State of this command on channel 1:
292
- * 							- ENABLE: 'Start' command will effect on channel 1
293
- * 							- DISABLE: 'Start' command will not effect on channel 1
294
- * @param[in]	channel2	State of this command on channel 2:
295
- * 							- ENABLE: 'Start' command will effect on channel 2
296
- * 							- DISABLE: 'Start' command will not effect on channel 2
297
- * @return		None
298
- **********************************************************************/
299
-void MCPWM_Start(LPC_MCPWM_TypeDef *MCPWMx, uint32_t channel0,
300
-					uint32_t channel1, uint32_t channel2)
301
-{
302
-	uint32_t regVal = 0;
303
-	regVal = (channel0 ? MCPWM_CON_RUN(0) : 0) | (channel1 ? MCPWM_CON_RUN(1) : 0) \
304
-				| (channel2 ? MCPWM_CON_RUN(2) : 0);
305
-	MCPWMx->MCCON_SET = regVal;
306
-}
307
-
308
-
309
-/*********************************************************************//**
310
- * @brief		Stop MCPWM activity for each MCPWM channel
311
- * @param[in]	MCPWMx 		Motor Control PWM peripheral selected
312
- * 							Should be: LPC_MCPWM
313
- * @param[in]	channel0	State of this command on channel 0:
314
- * 							- ENABLE: 'Stop' command will effect on channel 0
315
- * 							- DISABLE: 'Stop' command will not effect on channel 0
316
- * @param[in]	channel1	State of this command on channel 1:
317
- * 							- ENABLE: 'Stop' command will effect on channel 1
318
- * 							- DISABLE: 'Stop' command will not effect on channel 1
319
- * @param[in]	channel2	State of this command on channel 2:
320
- * 							- ENABLE: 'Stop' command will effect on channel 2
321
- * 							- DISABLE: 'Stop' command will not effect on channel 2
322
- * @return		None
323
- **********************************************************************/
324
-void MCPWM_Stop(LPC_MCPWM_TypeDef *MCPWMx, uint32_t channel0,
325
-		uint32_t channel1, uint32_t channel2)
326
-{
327
-	uint32_t regVal = 0;
328
-	regVal = (channel0 ? MCPWM_CON_RUN(0) : 0) | (channel1 ? MCPWM_CON_RUN(1) : 0) \
329
-				| (channel2 ? MCPWM_CON_RUN(2) : 0);
330
-	MCPWMx->MCCON_CLR = regVal;
331
-}
332
-
333
-
334
-/*********************************************************************//**
335
- * @brief		Enables/Disables 3-phase AC motor mode on MCPWM peripheral
336
- * @param[in]	MCPWMx 		Motor Control PWM peripheral selected
337
- * 							Should be: LPC_MCPWM
338
- * @param[in]	acMode		State of this command, should be:
339
- * 							- ENABLE.
340
- * 							- DISABLE.
341
- * @return		None
342
- **********************************************************************/
343
-void MCPWM_ACMode(LPC_MCPWM_TypeDef *MCPWMx, uint32_t acMode)
344
-{
345
-	if (acMode){
346
-		MCPWMx->MCCON_SET = MCPWM_CON_ACMODE;
347
-	} else {
348
-		MCPWMx->MCCON_CLR = MCPWM_CON_ACMODE;
349
-	}
350
-}
351
-
352
-
353
-/*********************************************************************//**
354
- * @brief		Enables/Disables 3-phase DC motor mode on MCPWM peripheral
355
- * @param[in]	MCPWMx 			Motor Control PWM peripheral selected
356
- * 								Should be: LPC_MCPWM
357
- * @param[in]	dcMode			State of this command, should be:
358
- * 								- ENABLE.
359
- * 								- DISABLE.
360
- * @param[in]	outputInvered	Polarity of the MCOB outputs for all 3 channels,
361
- * 								should be:
362
- * 								- ENABLE: The MCOB outputs have opposite polarity
363
- * 									from the MCOA outputs.
364
- * 								- DISABLE: The MCOB outputs have the same basic
365
- * 									polarity as the MCOA outputs.
366
- * @param[in]	outputPattern	A value contains bits that enables/disables the specified
367
- * 								output pins route to the internal MCOA0 signal, should be:
368
-								- MCPWM_PATENT_A0: 	 MCOA0 tracks internal MCOA0
369
-								- MCPWM_PATENT_B0: 	 MCOB0 tracks internal MCOA0
370
-								- MCPWM_PATENT_A1: 	 MCOA1 tracks internal MCOA0
371
-								- MCPWM_PATENT_B1: 	 MCOB1 tracks internal MCOA0
372
-								- MCPWM_PATENT_A2: 	 MCOA2 tracks internal MCOA0
373
-								- MCPWM_PATENT_B2: 	 MCOB2 tracks internal MCOA0
374
- * @return		None
375
- *
376
- * Note: all these outputPatent values above can be ORed together for using as input parameter.
377
- **********************************************************************/
378
-void MCPWM_DCMode(LPC_MCPWM_TypeDef *MCPWMx, uint32_t dcMode,
379
-					uint32_t outputInvered, uint32_t outputPattern)
380
-{
381
-	if (dcMode){
382
-		MCPWMx->MCCON_SET = MCPWM_CON_DCMODE;
383
-	} else {
384
-		MCPWMx->MCCON_CLR = MCPWM_CON_DCMODE;
385
-	}
386
-
387
-	if (outputInvered) {
388
-		MCPWMx->MCCON_SET = MCPWM_CON_INVBDC;
389
-	} else {
390
-		MCPWMx->MCCON_CLR = MCPWM_CON_INVBDC;
391
-	}
392
-
393
-	MCPWMx->MCCCP = outputPattern;
394
-}
395
-
396
-
397
-/*********************************************************************//**
398
- * @brief		Configures the specified interrupt in MCPWM peripheral
399
- * @param[in]	MCPWMx 		Motor Control PWM peripheral selected
400
- * 							Should be: LPC_MCPWM
401
- * @param[in]	ulIntType	Interrupt type, should be:
402
- * 							- MCPWM_INTFLAG_LIM0: Limit interrupt for channel (0)
403
- * 							- MCPWM_INTFLAG_MAT0: Match interrupt for channel (0)
404
- * 							- MCPWM_INTFLAG_CAP0: Capture interrupt for channel (0)
405
- * 							- MCPWM_INTFLAG_LIM1: Limit interrupt for channel (1)
406
- * 							- MCPWM_INTFLAG_MAT1: Match interrupt for channel (1)
407
- * 							- MCPWM_INTFLAG_CAP1: Capture interrupt for channel (1)
408
- * 							- MCPWM_INTFLAG_LIM2: Limit interrupt for channel (2)
409
- * 							- MCPWM_INTFLAG_MAT2: Match interrupt for channel (2)
410
- * 							- MCPWM_INTFLAG_CAP2: Capture interrupt for channel (2)
411
- * 							- MCPWM_INTFLAG_ABORT: Fast abort interrupt
412
- * @param[in]	NewState	New State of this command, should be:
413
- * 							- ENABLE.
414
- * 							- DISABLE.
415
- * @return		None
416
- *
417
- * Note: all these ulIntType values above can be ORed together for using as input parameter.
418
- **********************************************************************/
419
-void MCPWM_IntConfig(LPC_MCPWM_TypeDef *MCPWMx, uint32_t ulIntType, FunctionalState NewState)
420
-{
421
-	if (NewState) {
422
-		MCPWMx->MCINTEN_SET = ulIntType;
423
-	} else {
424
-		MCPWMx->MCINTEN_CLR = ulIntType;
425
-	}
426
-}
427
-
428
-
429
-/*********************************************************************//**
430
- * @brief		Sets/Forces the specified interrupt for MCPWM peripheral
431
- * @param[in]	MCPWMx 		Motor Control PWM peripheral selected
432
- * 							Should be LPC_MCPWM
433
- * @param[in]	ulIntType	Interrupt type, should be:
434
- * 							- MCPWM_INTFLAG_LIM0: Limit interrupt for channel (0)
435
- * 							- MCPWM_INTFLAG_MAT0: Match interrupt for channel (0)
436
- * 							- MCPWM_INTFLAG_CAP0: Capture interrupt for channel (0)
437
- * 							- MCPWM_INTFLAG_LIM1: Limit interrupt for channel (1)
438
- * 							- MCPWM_INTFLAG_MAT1: Match interrupt for channel (1)
439
- * 							- MCPWM_INTFLAG_CAP1: Capture interrupt for channel (1)
440
- * 							- MCPWM_INTFLAG_LIM2: Limit interrupt for channel (2)
441
- * 							- MCPWM_INTFLAG_MAT2: Match interrupt for channel (2)
442
- * 							- MCPWM_INTFLAG_CAP2: Capture interrupt for channel (2)
443
- * 							- MCPWM_INTFLAG_ABORT: Fast abort interrupt
444
- * @return		None
445
- * Note: all these ulIntType values above can be ORed together for using as input parameter.
446
- **********************************************************************/
447
-void MCPWM_IntSet(LPC_MCPWM_TypeDef *MCPWMx, uint32_t ulIntType)
448
-{
449
-	MCPWMx->MCINTFLAG_SET = ulIntType;
450
-}
451
-
452
-
453
-/*********************************************************************//**
454
- * @brief		Clear the specified interrupt pending for MCPWM peripheral
455
- * @param[in]	MCPWMx 		Motor Control PWM peripheral selected,
456
- * 							should be: LPC_MCPWM
457
- * @param[in]	ulIntType	Interrupt type, should be:
458
- * 							- MCPWM_INTFLAG_LIM0: Limit interrupt for channel (0)
459
- * 							- MCPWM_INTFLAG_MAT0: Match interrupt for channel (0)
460
- * 							- MCPWM_INTFLAG_CAP0: Capture interrupt for channel (0)
461
- * 							- MCPWM_INTFLAG_LIM1: Limit interrupt for channel (1)
462
- * 							- MCPWM_INTFLAG_MAT1: Match interrupt for channel (1)
463
- * 							- MCPWM_INTFLAG_CAP1: Capture interrupt for channel (1)
464
- * 							- MCPWM_INTFLAG_LIM2: Limit interrupt for channel (2)
465
- * 							- MCPWM_INTFLAG_MAT2: Match interrupt for channel (2)
466
- * 							- MCPWM_INTFLAG_CAP2: Capture interrupt for channel (2)
467
- * 							- MCPWM_INTFLAG_ABORT: Fast abort interrupt
468
- * @return		None
469
- * Note: all these ulIntType values above can be ORed together for using as input parameter.
470
- **********************************************************************/
471
-void MCPWM_IntClear(LPC_MCPWM_TypeDef *MCPWMx, uint32_t ulIntType)
472
-{
473
-	MCPWMx->MCINTFLAG_CLR = ulIntType;
474
-}
475
-
476
-
477
-/*********************************************************************//**
478
- * @brief		Check whether if the specified interrupt in MCPWM is set or not
479
- * @param[in]	MCPWMx 		Motor Control PWM peripheral selected,
480
- * 							should be: LPC_MCPWM
481
- * @param[in]	ulIntType	Interrupt type, should be:
482
- * 							- MCPWM_INTFLAG_LIM0: Limit interrupt for channel (0)
483
- * 							- MCPWM_INTFLAG_MAT0: Match interrupt for channel (0)
484
- * 							- MCPWM_INTFLAG_CAP0: Capture interrupt for channel (0)
485
- * 							- MCPWM_INTFLAG_LIM1: Limit interrupt for channel (1)
486
- * 							- MCPWM_INTFLAG_MAT1: Match interrupt for channel (1)
487
- * 							- MCPWM_INTFLAG_CAP1: Capture interrupt for channel (1)
488
- * 							- MCPWM_INTFLAG_LIM2: Limit interrupt for channel (2)
489
- * 							- MCPWM_INTFLAG_MAT2: Match interrupt for channel (2)
490
- * 							- MCPWM_INTFLAG_CAP2: Capture interrupt for channel (2)
491
- * 							- MCPWM_INTFLAG_ABORT: Fast abort interrupt
492
- * @return		None
493
- **********************************************************************/
494
-FlagStatus MCPWM_GetIntStatus(LPC_MCPWM_TypeDef *MCPWMx, uint32_t ulIntType)
495
-{
496
-	return ((MCPWMx->MCINTFLAG & ulIntType) ? SET : RESET);
497
-}
498
-
499
-/**
500
- * @}
501
- */
502
-
503
-#endif /* _MCPWM */
504
-
505
-/**
506
- * @}
507
- */
508
-
509
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 148
frameworks/CMSIS/LPC1768/driver/lpc17xx_nvic.c Просмотреть файл

@@ -1,148 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_nvic.c				2010-05-21
3
-*//**
4
-* @file		lpc17xx_nvic.c
5
-* @brief	Contains all expansion functions support for
6
-* 			NVIC firmware library on LPC17xx. The main
7
-* 			NVIC functions are defined in core_cm3.h
8
-* @version	2.0
9
-* @date		21. May. 2010
10
-* @author	NXP MCU SW Application Team
11
-*
12
-* Copyright(C) 2010, NXP Semiconductor
13
-* All rights reserved.
14
-*
15
-***********************************************************************
16
-* Software that is described herein is for illustrative purposes only
17
-* which provides customers with programming information regarding the
18
-* products. This software is supplied "AS IS" without any warranties.
19
-* NXP Semiconductors assumes no responsibility or liability for the
20
-* use of the software, conveys no license or title under any patent,
21
-* copyright, or mask work right to the product. NXP Semiconductors
22
-* reserves the right to make changes in the software without
23
-* notification. NXP Semiconductors also make no representation or
24
-* warranty that such application will be suitable for the specified
25
-* use without further testing or modification.
26
-* Permission to use, copy, modify, and distribute this software and its
27
-* documentation is hereby granted, under NXP Semiconductors'
28
-* relevant copyright in the software, without fee, provided that it
29
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
30
-* copyright, permission, and disclaimer notice must appear in all copies of
31
-* this code.
32
-**********************************************************************/
33
-
34
-/* Peripheral group ----------------------------------------------------------- */
35
-/** @addtogroup NVIC
36
- * @{
37
- */
38
-
39
-/* Includes ------------------------------------------------------------------- */
40
-#include "lpc17xx_nvic.h"
41
-
42
-
43
-/* Private Macros ------------------------------------------------------------- */
44
-/** @addtogroup NVIC_Private_Macros
45
- * @{
46
- */
47
-
48
-/* Vector table offset bit mask */
49
-#define NVIC_VTOR_MASK              0x3FFFFF80
50
-
51
-/**
52
- * @}
53
- */
54
-
55
-
56
-/* Public Functions ----------------------------------------------------------- */
57
-/** @addtogroup NVIC_Public_Functions
58
- * @{
59
- */
60
-
61
-
62
-/*****************************************************************************//**
63
- * @brief		De-initializes the NVIC peripheral registers to their default
64
- * 				reset values.
65
- * @param		None
66
- * @return      None
67
- *
68
- * These following NVIC peripheral registers will be de-initialized:
69
- * - Disable Interrupt (32 IRQ interrupt sources that matched with LPC17xx)
70
- * - Clear all Pending Interrupts (32 IRQ interrupt source that matched with LPC17xx)
71
- * - Clear all Interrupt Priorities (32 IRQ interrupt source that matched with LPC17xx)
72
- *******************************************************************************/
73
-void NVIC_DeInit(void)
74
-{
75
-	uint8_t tmp;
76
-
77
-	/* Disable all interrupts */
78
-	NVIC->ICER[0] = 0xFFFFFFFF;
79
-	NVIC->ICER[1] = 0x00000001;
80
-	/* Clear all pending interrupts */
81
-	NVIC->ICPR[0] = 0xFFFFFFFF;
82
-	NVIC->ICPR[1] = 0x00000001;
83
-
84
-	/* Clear all interrupt priority */
85
-	for (tmp = 0; tmp < 32; tmp++) {
86
-		NVIC->IP[tmp] = 0x00;
87
-	}
88
-}
89
-
90
-/*****************************************************************************//**
91
- * @brief			De-initializes the SCB peripheral registers to their default
92
- *                  reset values.
93
- * @param			none
94
- * @return 			none
95
- *
96
- * These following SCB NVIC peripheral registers will be de-initialized:
97
- * - Interrupt Control State register
98
- * - Interrupt Vector Table Offset register
99
- * - Application Interrupt/Reset Control register
100
- * - System Control register
101
- * - Configuration Control register
102
- * - System Handlers Priority Registers
103
- * - System Handler Control and State Register
104
- * - Configurable Fault Status Register
105
- * - Hard Fault Status Register
106
- * - Debug Fault Status Register
107
- *******************************************************************************/
108
-void NVIC_SCBDeInit(void)
109
-{
110
-	uint8_t tmp;
111
-
112
-	SCB->ICSR = 0x0A000000;
113
-	SCB->VTOR = 0x00000000;
114
-	SCB->AIRCR = 0x05FA0000;
115
-	SCB->SCR = 0x00000000;
116
-	SCB->CCR = 0x00000000;
117
-
118
-	for (tmp = 0; tmp < (sizeof(SCB->SHP) / sizeof(SCB->SHP[0])); tmp++) {
119
-		SCB->SHP[tmp] = 0x00;
120
-	}
121
-
122
-	SCB->SHCSR = 0x00000000;
123
-	SCB->CFSR = 0xFFFFFFFF;
124
-	SCB->HFSR = 0xFFFFFFFF;
125
-	SCB->DFSR = 0xFFFFFFFF;
126
-}
127
-
128
-
129
-/*****************************************************************************//**
130
- * @brief		Set Vector Table Offset value
131
- * @param		offset Offset value
132
- * @return      None
133
- *******************************************************************************/
134
-void NVIC_SetVTOR(uint32_t offset)
135
-{
136
-//	SCB->VTOR  = (offset & NVIC_VTOR_MASK);
137
-	SCB->VTOR  = offset;
138
-}
139
-
140
-/**
141
- * @}
142
- */
143
-
144
-/**
145
- * @}
146
- */
147
-
148
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 318
frameworks/CMSIS/LPC1768/driver/lpc17xx_pinsel.c Просмотреть файл

@@ -1,318 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_pinsel.c				2010-05-21
3
-*//**
4
-* @file		lpc17xx_pinsel.c
5
-* @brief	Contains all functions support for Pin connect block firmware
6
-* 			library on LPC17xx
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @addtogroup PINSEL
35
- * @{
36
- */
37
-
38
-/* Includes ------------------------------------------------------------------- */
39
-#include "lpc17xx_pinsel.h"
40
-
41
-/* Public Functions ----------------------------------------------------------- */
42
-
43
-static void set_PinFunc ( uint8_t portnum, uint8_t pinnum, uint8_t funcnum);
44
-static void set_ResistorMode ( uint8_t portnum, uint8_t pinnum, uint8_t modenum);
45
-static void set_OpenDrainMode( uint8_t portnum, uint8_t pinnum, uint8_t modenum);
46
-
47
-/*********************************************************************//**
48
- * @brief 		Setup the pin selection function
49
- * @param[in]	portnum PORT number,
50
- * 				should be one of the following:
51
- * 				- PINSEL_PORT_0	: Port 0
52
- * 				- PINSEL_PORT_1	: Port 1
53
- * 				- PINSEL_PORT_2	: Port 2
54
- * 				- PINSEL_PORT_3	: Port 3
55
- *
56
- * @param[in]	pinnum	Pin number,
57
- * 				should be one of the following:
58
-				- PINSEL_PIN_0 : Pin 0
59
-				- PINSEL_PIN_1 : Pin 1
60
-				- PINSEL_PIN_2 : Pin 2
61
-				- PINSEL_PIN_3 : Pin 3
62
-				- PINSEL_PIN_4 : Pin 4
63
-				- PINSEL_PIN_5 : Pin 5
64
-				- PINSEL_PIN_6 : Pin 6
65
-				- PINSEL_PIN_7 : Pin 7
66
-				- PINSEL_PIN_8 : Pin 8
67
-				- PINSEL_PIN_9 : Pin 9
68
-				- PINSEL_PIN_10 : Pin 10
69
-				- PINSEL_PIN_11 : Pin 11
70
-				- PINSEL_PIN_12 : Pin 12
71
-				- PINSEL_PIN_13 : Pin 13
72
-				- PINSEL_PIN_14 : Pin 14
73
-				- PINSEL_PIN_15 : Pin 15
74
-				- PINSEL_PIN_16 : Pin 16
75
-				- PINSEL_PIN_17 : Pin 17
76
-				- PINSEL_PIN_18 : Pin 18
77
-				- PINSEL_PIN_19 : Pin 19
78
-				- PINSEL_PIN_20 : Pin 20
79
-				- PINSEL_PIN_21 : Pin 21
80
-				- PINSEL_PIN_22 : Pin 22
81
-				- PINSEL_PIN_23 : Pin 23
82
-				- PINSEL_PIN_24 : Pin 24
83
-				- PINSEL_PIN_25 : Pin 25
84
-				- PINSEL_PIN_26 : Pin 26
85
-				- PINSEL_PIN_27 : Pin 27
86
-				- PINSEL_PIN_28 : Pin 28
87
-				- PINSEL_PIN_29 : Pin 29
88
-				- PINSEL_PIN_30 : Pin 30
89
-				- PINSEL_PIN_31 : Pin 31
90
-
91
- * @param[in] 	funcnum Function number,
92
- * 				should be one of the following:
93
- *				- PINSEL_FUNC_0 : default function
94
- *				- PINSEL_FUNC_1 : first alternate function
95
- *				- PINSEL_FUNC_2 : second alternate function
96
- *				- PINSEL_FUNC_3 : third alternate function
97
- *
98
- * @return 		None
99
- **********************************************************************/
100
-static void set_PinFunc ( uint8_t portnum, uint8_t pinnum, uint8_t funcnum)
101
-{
102
-	uint32_t pinnum_t = pinnum;
103
-	uint32_t pinselreg_idx = 2 * portnum;
104
-	uint32_t *pPinCon = (uint32_t *)&LPC_PINCON->PINSEL0;
105
-
106
-	if (pinnum_t >= 16) {
107
-		pinnum_t -= 16;
108
-		pinselreg_idx++;
109
-	}
110
-	*(uint32_t *)(pPinCon + pinselreg_idx) &= ~(0x03UL << (pinnum_t * 2));
111
-	*(uint32_t *)(pPinCon + pinselreg_idx) |= ((uint32_t)funcnum) << (pinnum_t * 2);
112
-}
113
-
114
-/*********************************************************************//**
115
- * @brief 		Setup resistor mode for each pin
116
- * @param[in]	portnum PORT number,
117
- * 				should be one of the following:
118
- * 				- PINSEL_PORT_0	: Port 0
119
- * 				- PINSEL_PORT_1	: Port 1
120
- * 				- PINSEL_PORT_2	: Port 2
121
- * 				- PINSEL_PORT_3	: Port 3
122
- * @param[in]	pinnum	Pin number,
123
- * 				should be one of the following:
124
-				- PINSEL_PIN_0 : Pin 0
125
-				- PINSEL_PIN_1 : Pin 1
126
-				- PINSEL_PIN_2 : Pin 2
127
-				- PINSEL_PIN_3 : Pin 3
128
-				- PINSEL_PIN_4 : Pin 4
129
-				- PINSEL_PIN_5 : Pin 5
130
-				- PINSEL_PIN_6 : Pin 6
131
-				- PINSEL_PIN_7 : Pin 7
132
-				- PINSEL_PIN_8 : Pin 8
133
-				- PINSEL_PIN_9 : Pin 9
134
-				- PINSEL_PIN_10 : Pin 10
135
-				- PINSEL_PIN_11 : Pin 11
136
-				- PINSEL_PIN_12 : Pin 12
137
-				- PINSEL_PIN_13 : Pin 13
138
-				- PINSEL_PIN_14 : Pin 14
139
-				- PINSEL_PIN_15 : Pin 15
140
-				- PINSEL_PIN_16 : Pin 16
141
-				- PINSEL_PIN_17 : Pin 17
142
-				- PINSEL_PIN_18 : Pin 18
143
-				- PINSEL_PIN_19 : Pin 19
144
-				- PINSEL_PIN_20 : Pin 20
145
-				- PINSEL_PIN_21 : Pin 21
146
-				- PINSEL_PIN_22 : Pin 22
147
-				- PINSEL_PIN_23 : Pin 23
148
-				- PINSEL_PIN_24 : Pin 24
149
-				- PINSEL_PIN_25 : Pin 25
150
-				- PINSEL_PIN_26 : Pin 26
151
-				- PINSEL_PIN_27 : Pin 27
152
-				- PINSEL_PIN_28 : Pin 28
153
-				- PINSEL_PIN_29 : Pin 29
154
-				- PINSEL_PIN_30 : Pin 30
155
-				- PINSEL_PIN_31 : Pin 31
156
-
157
- * @param[in] 	modenum: Mode number,
158
- * 				should be one of the following:
159
-				- PINSEL_PINMODE_PULLUP	: Internal pull-up resistor
160
-				- PINSEL_PINMODE_TRISTATE : Tri-state
161
-				- PINSEL_PINMODE_PULLDOWN : Internal pull-down resistor
162
-
163
- * @return 		None
164
- **********************************************************************/
165
-void set_ResistorMode ( uint8_t portnum, uint8_t pinnum, uint8_t modenum)
166
-{
167
-	uint32_t pinnum_t = pinnum;
168
-	uint32_t pinmodereg_idx = 2 * portnum;
169
-	uint32_t *pPinCon = (uint32_t *)&LPC_PINCON->PINMODE0;
170
-
171
-	if (pinnum_t >= 16) {
172
-		pinnum_t -= 16;
173
-		pinmodereg_idx++ ;
174
-	}
175
-
176
-	*(uint32_t *)(pPinCon + pinmodereg_idx) &= ~(0x03UL << (pinnum_t * 2));
177
-	*(uint32_t *)(pPinCon + pinmodereg_idx) |= ((uint32_t)modenum) << (pinnum_t * 2);
178
-}
179
-
180
-/*********************************************************************//**
181
- * @brief 		Setup Open drain mode for each pin
182
- * @param[in]	portnum PORT number,
183
- * 				should be one of the following:
184
- * 				- PINSEL_PORT_0	: Port 0
185
- * 				- PINSEL_PORT_1	: Port 1
186
- * 				- PINSEL_PORT_2	: Port 2
187
- * 				- PINSEL_PORT_3	: Port 3
188
- *
189
- * @param[in]	pinnum	Pin number,
190
- * 				should be one of the following:
191
-				- PINSEL_PIN_0 : Pin 0
192
-				- PINSEL_PIN_1 : Pin 1
193
-				- PINSEL_PIN_2 : Pin 2
194
-				- PINSEL_PIN_3 : Pin 3
195
-				- PINSEL_PIN_4 : Pin 4
196
-				- PINSEL_PIN_5 : Pin 5
197
-				- PINSEL_PIN_6 : Pin 6
198
-				- PINSEL_PIN_7 : Pin 7
199
-				- PINSEL_PIN_8 : Pin 8
200
-				- PINSEL_PIN_9 : Pin 9
201
-				- PINSEL_PIN_10 : Pin 10
202
-				- PINSEL_PIN_11 : Pin 11
203
-				- PINSEL_PIN_12 : Pin 12
204
-				- PINSEL_PIN_13 : Pin 13
205
-				- PINSEL_PIN_14 : Pin 14
206
-				- PINSEL_PIN_15 : Pin 15
207
-				- PINSEL_PIN_16 : Pin 16
208
-				- PINSEL_PIN_17 : Pin 17
209
-				- PINSEL_PIN_18 : Pin 18
210
-				- PINSEL_PIN_19 : Pin 19
211
-				- PINSEL_PIN_20 : Pin 20
212
-				- PINSEL_PIN_21 : Pin 21
213
-				- PINSEL_PIN_22 : Pin 22
214
-				- PINSEL_PIN_23 : Pin 23
215
-				- PINSEL_PIN_24 : Pin 24
216
-				- PINSEL_PIN_25 : Pin 25
217
-				- PINSEL_PIN_26 : Pin 26
218
-				- PINSEL_PIN_27 : Pin 27
219
-				- PINSEL_PIN_28 : Pin 28
220
-				- PINSEL_PIN_29 : Pin 29
221
-				- PINSEL_PIN_30 : Pin 30
222
-				- PINSEL_PIN_31 : Pin 31
223
-
224
- * @param[in]	modenum  Open drain mode number,
225
- * 				should be one of the following:
226
- * 				- PINSEL_PINMODE_NORMAL : Pin is in the normal (not open drain) mode
227
- * 				- PINSEL_PINMODE_OPENDRAIN : Pin is in the open drain mode
228
- *
229
- * @return 		None
230
- **********************************************************************/
231
-void set_OpenDrainMode( uint8_t portnum, uint8_t pinnum, uint8_t modenum)
232
-{
233
-	uint32_t *pPinCon = (uint32_t *)&LPC_PINCON->PINMODE_OD0;
234
-
235
-	if (modenum == PINSEL_PINMODE_OPENDRAIN){
236
-		*(uint32_t *)(pPinCon + portnum) |= (0x01UL << pinnum);
237
-	} else {
238
-		*(uint32_t *)(pPinCon + portnum) &= ~(0x01UL << pinnum);
239
-	}
240
-}
241
-
242
-/* End of Public Functions ---------------------------------------------------- */
243
-
244
-/* Public Functions ----------------------------------------------------------- */
245
-/** @addtogroup PINSEL_Public_Functions
246
- * @{
247
- */
248
-/*********************************************************************//**
249
- * @brief 		Configure trace function
250
- * @param[in] 	NewState State of the Trace function configuration,
251
- * 				should be one of the following:
252
- * 				- ENABLE : Enable Trace Function
253
- * 				- DISABLE : Disable Trace Function
254
- *
255
- * @return 		None
256
- **********************************************************************/
257
-void PINSEL_ConfigTraceFunc(FunctionalState NewState)
258
-{
259
-	if (NewState == ENABLE) {
260
-		LPC_PINCON->PINSEL10 |= (0x01UL << 3);
261
-	} else if (NewState == DISABLE) {
262
-		LPC_PINCON->PINSEL10 &= ~(0x01UL << 3);
263
-	}
264
-}
265
-
266
-/*********************************************************************//**
267
- * @brief 		Setup I2C0 pins
268
- * @param[in]	i2cPinMode I2C pin mode,
269
- * 				should be one of the following:
270
- * 				- PINSEL_I2C_Normal_Mode : The standard drive mode
271
- * 				- PINSEL_I2C_Fast_Mode : Fast Mode Plus drive mode
272
- *
273
- * @param[in]	filterSlewRateEnable  should be:
274
- * 				- ENABLE: Enable filter and slew rate.
275
- * 				- DISABLE: Disable filter and slew rate.
276
- *
277
- * @return 		None
278
- **********************************************************************/
279
-void PINSEL_SetI2C0Pins(uint8_t i2cPinMode, FunctionalState filterSlewRateEnable)
280
-{
281
-	uint32_t regVal;
282
-
283
-	if (i2cPinMode == PINSEL_I2C_Fast_Mode){
284
-		regVal = PINSEL_I2CPADCFG_SCLDRV0 | PINSEL_I2CPADCFG_SDADRV0;
285
-	}
286
-
287
-	if (filterSlewRateEnable == DISABLE){
288
-		regVal = PINSEL_I2CPADCFG_SCLI2C0 | PINSEL_I2CPADCFG_SDAI2C0;
289
-	}
290
-	LPC_PINCON->I2CPADCFG = regVal;
291
-}
292
-
293
-
294
-/*********************************************************************//**
295
- * @brief 		Configure Pin corresponding to specified parameters passed
296
- * 				in the PinCfg
297
- * @param[in]	PinCfg	Pointer to a PINSEL_CFG_Type structure
298
- *                    that contains the configuration information for the
299
- *                    specified pin.
300
- * @return 		None
301
- **********************************************************************/
302
-void PINSEL_ConfigPin(PINSEL_CFG_Type *PinCfg)
303
-{
304
-	set_PinFunc(PinCfg->Portnum, PinCfg->Pinnum, PinCfg->Funcnum);
305
-	set_ResistorMode(PinCfg->Portnum, PinCfg->Pinnum, PinCfg->Pinmode);
306
-	set_OpenDrainMode(PinCfg->Portnum, PinCfg->Pinnum, PinCfg->OpenDrain);
307
-}
308
-
309
-
310
-/**
311
- * @}
312
- */
313
-
314
-/**
315
- * @}
316
- */
317
-
318
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 588
frameworks/CMSIS/LPC1768/driver/lpc17xx_pwm.c Просмотреть файл

@@ -1,588 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_pwm.c				2011-03-31
3
-*//**
4
-* @file		lpc17xx_pwm.c
5
-* @brief	Contains all functions support for PWM firmware library on LPC17xx
6
-* @version	2.1
7
-* @date		31. Mar. 2011
8
-* @author	NXP MCU SW Application Team
9
-*
10
-* Copyright(C) 2011, NXP Semiconductor
11
-* All rights reserved.
12
-*
13
-***********************************************************************
14
-* Software that is described herein is for illustrative purposes only
15
-* which provides customers with programming information regarding the
16
-* products. This software is supplied "AS IS" without any warranties.
17
-* NXP Semiconductors assumes no responsibility or liability for the
18
-* use of the software, conveys no license or title under any patent,
19
-* copyright, or mask work right to the product. NXP Semiconductors
20
-* reserves the right to make changes in the software without
21
-* notification. NXP Semiconductors also make no representation or
22
-* warranty that such application will be suitable for the specified
23
-* use without further testing or modification.
24
-* Permission to use, copy, modify, and distribute this software and its
25
-* documentation is hereby granted, under NXP Semiconductors'
26
-* relevant copyright in the software, without fee, provided that it
27
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
28
-* copyright, permission, and disclaimer notice must appear in all copies of
29
-* this code.
30
-**********************************************************************/
31
-
32
-/* Peripheral group ----------------------------------------------------------- */
33
-/** @addtogroup PWM
34
- * @{
35
- */
36
-
37
-/* Includes ------------------------------------------------------------------- */
38
-#include "lpc17xx_pwm.h"
39
-#include "lpc17xx_clkpwr.h"
40
-
41
-/* If this source file built with example, the LPC17xx FW library configuration
42
- * file in each example directory ("lpc17xx_libcfg.h") must be included,
43
- * otherwise the default FW library configuration file must be included instead
44
- */
45
-#ifdef __BUILD_WITH_EXAMPLE__
46
-#include "lpc17xx_libcfg.h"
47
-#else
48
-#include "lpc17xx_libcfg_default.h"
49
-#endif /* __BUILD_WITH_EXAMPLE__ */
50
-
51
-
52
-#ifdef _PWM
53
-
54
-
55
-/* Public Functions ----------------------------------------------------------- */
56
-/** @addtogroup PWM_Public_Functions
57
- * @{
58
- */
59
-
60
-
61
-/*********************************************************************//**
62
- * @brief 		Check whether specified interrupt flag in PWM is set or not
63
- * @param[in]	PWMx: PWM peripheral, should be LPC_PWM1
64
- * @param[in]	IntFlag: PWM interrupt flag, should be:
65
- * 				- PWM_INTSTAT_MR0: Interrupt flag for PWM match channel 0
66
- * 				- PWM_INTSTAT_MR1: Interrupt flag for PWM match channel 1
67
- * 				- PWM_INTSTAT_MR2: Interrupt flag for PWM match channel 2
68
- * 				- PWM_INTSTAT_MR3: Interrupt flag for PWM match channel 3
69
- * 				- PWM_INTSTAT_MR4: Interrupt flag for PWM match channel 4
70
- * 				- PWM_INTSTAT_MR5: Interrupt flag for PWM match channel 5
71
- * 				- PWM_INTSTAT_MR6: Interrupt flag for PWM match channel 6
72
- * 				- PWM_INTSTAT_CAP0: Interrupt flag for capture input 0
73
- * 				- PWM_INTSTAT_CAP1: Interrupt flag for capture input 1
74
- * @return 		New State of PWM interrupt flag (SET or RESET)
75
- **********************************************************************/
76
-IntStatus PWM_GetIntStatus(LPC_PWM_TypeDef *PWMx, uint32_t IntFlag)
77
-{
78
-	CHECK_PARAM(PARAM_PWMx(PWMx));
79
-	CHECK_PARAM(PARAM_PWM_INTSTAT(IntFlag));
80
-
81
-	return ((PWMx->IR & IntFlag) ? SET : RESET);
82
-}
83
-
84
-
85
-
86
-/*********************************************************************//**
87
- * @brief 		Clear specified PWM Interrupt pending
88
- * @param[in]	PWMx: PWM peripheral, should be LPC_PWM1
89
- * @param[in]	IntFlag: PWM interrupt flag, should be:
90
- * 				- PWM_INTSTAT_MR0: Interrupt flag for PWM match channel 0
91
- * 				- PWM_INTSTAT_MR1: Interrupt flag for PWM match channel 1
92
- * 				- PWM_INTSTAT_MR2: Interrupt flag for PWM match channel 2
93
- * 				- PWM_INTSTAT_MR3: Interrupt flag for PWM match channel 3
94
- * 				- PWM_INTSTAT_MR4: Interrupt flag for PWM match channel 4
95
- * 				- PWM_INTSTAT_MR5: Interrupt flag for PWM match channel 5
96
- * 				- PWM_INTSTAT_MR6: Interrupt flag for PWM match channel 6
97
- * 				- PWM_INTSTAT_CAP0: Interrupt flag for capture input 0
98
- * 				- PWM_INTSTAT_CAP1: Interrupt flag for capture input 1
99
- * @return 		None
100
- **********************************************************************/
101
-void PWM_ClearIntPending(LPC_PWM_TypeDef *PWMx, uint32_t IntFlag)
102
-{
103
-	CHECK_PARAM(PARAM_PWMx(PWMx));
104
-	CHECK_PARAM(PARAM_PWM_INTSTAT(IntFlag));
105
-	PWMx->IR = IntFlag;
106
-}
107
-
108
-
109
-
110
-/*****************************************************************************//**
111
-* @brief		Fills each PWM_InitStruct member with its default value:
112
-* 				- If PWMCounterMode = PWM_MODE_TIMER:
113
-* 					+ PrescaleOption = PWM_TIMER_PRESCALE_USVAL
114
-* 					+ PrescaleValue = 1
115
-* 				- If PWMCounterMode = PWM_MODE_COUNTER:
116
-* 					+ CountInputSelect = PWM_COUNTER_PCAP1_0
117
-* 					+ CounterOption = PWM_COUNTER_RISING
118
-* @param[in]	PWMTimerCounterMode Timer or Counter mode, should be:
119
-* 				- PWM_MODE_TIMER: Counter of PWM peripheral is in Timer mode
120
-* 				- PWM_MODE_COUNTER: Counter of PWM peripheral is in Counter mode
121
-* @param[in]	PWM_InitStruct Pointer to structure (PWM_TIMERCFG_Type or
122
-* 				 PWM_COUNTERCFG_Type) which will be initialized.
123
-* @return		None
124
-* Note: PWM_InitStruct pointer will be assigned to corresponding structure
125
-* 		(PWM_TIMERCFG_Type or PWM_COUNTERCFG_Type) due to PWMTimerCounterMode.
126
-*******************************************************************************/
127
-void PWM_ConfigStructInit(uint8_t PWMTimerCounterMode, void *PWM_InitStruct)
128
-{
129
-	PWM_TIMERCFG_Type *pTimeCfg;
130
-	PWM_COUNTERCFG_Type *pCounterCfg;
131
-	CHECK_PARAM(PARAM_PWM_TC_MODE(PWMTimerCounterMode));
132
-
133
-	pTimeCfg = (PWM_TIMERCFG_Type *) PWM_InitStruct;
134
-	pCounterCfg = (PWM_COUNTERCFG_Type *) PWM_InitStruct;
135
-
136
-	if (PWMTimerCounterMode == PWM_MODE_TIMER )
137
-	{
138
-		pTimeCfg->PrescaleOption = PWM_TIMER_PRESCALE_USVAL;
139
-		pTimeCfg->PrescaleValue = 1;
140
-	}
141
-	else if (PWMTimerCounterMode == PWM_MODE_COUNTER)
142
-	{
143
-		pCounterCfg->CountInputSelect = PWM_COUNTER_PCAP1_0;
144
-		pCounterCfg->CounterOption = PWM_COUNTER_RISING;
145
-	}
146
-}
147
-
148
-
149
-/*********************************************************************//**
150
- * @brief 		Initializes the PWMx peripheral corresponding to the specified
151
- *               parameters in the PWM_ConfigStruct.
152
- * @param[in]	PWMx PWM peripheral, should be LPC_PWM1
153
- * @param[in]	PWMTimerCounterMode Timer or Counter mode, should be:
154
- * 				- PWM_MODE_TIMER: Counter of PWM peripheral is in Timer mode
155
- * 				- PWM_MODE_COUNTER: Counter of PWM peripheral is in Counter mode
156
- * @param[in]	PWM_ConfigStruct Pointer to structure (PWM_TIMERCFG_Type or
157
- * 				 PWM_COUNTERCFG_Type) which will be initialized.
158
- * @return 		None
159
- * Note: PWM_ConfigStruct pointer will be assigned to corresponding structure
160
- * 		(PWM_TIMERCFG_Type or PWM_COUNTERCFG_Type) due to PWMTimerCounterMode.
161
- **********************************************************************/
162
-void PWM_Init(LPC_PWM_TypeDef *PWMx, uint32_t PWMTimerCounterMode, void *PWM_ConfigStruct)
163
-{
164
-	PWM_TIMERCFG_Type *pTimeCfg;
165
-	PWM_COUNTERCFG_Type *pCounterCfg;
166
-	uint64_t clkdlycnt;
167
-
168
-	CHECK_PARAM(PARAM_PWMx(PWMx));
169
-	CHECK_PARAM(PARAM_PWM_TC_MODE(PWMTimerCounterMode));
170
-
171
-	pTimeCfg = (PWM_TIMERCFG_Type *)PWM_ConfigStruct;
172
-	pCounterCfg = (PWM_COUNTERCFG_Type *)PWM_ConfigStruct;
173
-
174
-
175
-	CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCPWM1, ENABLE);
176
-	CLKPWR_SetPCLKDiv (CLKPWR_PCLKSEL_PWM1, CLKPWR_PCLKSEL_CCLK_DIV_4);
177
-	// Get peripheral clock of PWM1
178
-	clkdlycnt = (uint64_t) CLKPWR_GetPCLK (CLKPWR_PCLKSEL_PWM1);
179
-
180
-
181
-	// Clear all interrupts pending
182
-	PWMx->IR = 0xFF & PWM_IR_BITMASK;
183
-	PWMx->TCR = 0x00;
184
-	PWMx->CTCR = 0x00;
185
-	PWMx->MCR = 0x00;
186
-	PWMx->CCR = 0x00;
187
-	PWMx->PCR = 0x00;
188
-	PWMx->LER = 0x00;
189
-
190
-	if (PWMTimerCounterMode == PWM_MODE_TIMER)
191
-	{
192
-		CHECK_PARAM(PARAM_PWM_TIMER_PRESCALE(pTimeCfg->PrescaleOption));
193
-
194
-		/* Absolute prescale value */
195
-		if (pTimeCfg->PrescaleOption == PWM_TIMER_PRESCALE_TICKVAL)
196
-		{
197
-			PWMx->PR   = pTimeCfg->PrescaleValue - 1;
198
-		}
199
-		/* uSecond prescale value */
200
-		else
201
-		{
202
-			clkdlycnt = (clkdlycnt * pTimeCfg->PrescaleValue) / 1000000;
203
-			PWMx->PR = ((uint32_t) clkdlycnt) - 1;
204
-		}
205
-
206
-	}
207
-	else if (PWMTimerCounterMode == PWM_MODE_COUNTER)
208
-	{
209
-		CHECK_PARAM(PARAM_PWM_COUNTER_INPUTSEL(pCounterCfg->CountInputSelect));
210
-		CHECK_PARAM(PARAM_PWM_COUNTER_EDGE(pCounterCfg->CounterOption));
211
-
212
-		PWMx->CTCR |= (PWM_CTCR_MODE((uint32_t)pCounterCfg->CounterOption)) \
213
-						| (PWM_CTCR_SELECT_INPUT((uint32_t)pCounterCfg->CountInputSelect));
214
-	}
215
-}
216
-
217
-/*********************************************************************//**
218
- * @brief		De-initializes the PWM peripheral registers to their
219
-*                  default reset values.
220
- * @param[in]	PWMx	PWM peripheral selected, should be LPC_PWM1
221
- * @return 		None
222
- **********************************************************************/
223
-void PWM_DeInit (LPC_PWM_TypeDef *PWMx)
224
-{
225
-	CHECK_PARAM(PARAM_PWMx(PWMx));
226
-
227
-	// Disable PWM control (timer, counter and PWM)
228
-	PWMx->TCR = 0x00;
229
-	CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCPWM1, DISABLE);
230
-
231
-}
232
-
233
-
234
-/*********************************************************************//**
235
- * @brief	 	Enable/Disable PWM peripheral
236
- * @param[in]	PWMx	PWM peripheral selected, should be LPC_PWM1
237
- * @param[in]	NewState	New State of this function, should be:
238
- * 							- ENABLE: Enable PWM peripheral
239
- * 							- DISABLE: Disable PWM peripheral
240
- * @return 		None
241
- **********************************************************************/
242
-void PWM_Cmd(LPC_PWM_TypeDef *PWMx, FunctionalState NewState)
243
-{
244
-	CHECK_PARAM(PARAM_PWMx(PWMx));
245
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
246
-
247
-	if (NewState == ENABLE)
248
-	{
249
-		PWMx->TCR	|=  PWM_TCR_PWM_ENABLE;
250
-	}
251
-	else
252
-	{
253
-		PWMx->TCR &= (~PWM_TCR_PWM_ENABLE) & PWM_TCR_BITMASK;
254
-	}
255
-}
256
-
257
-
258
-/*********************************************************************//**
259
- * @brief 		Enable/Disable Counter in PWM peripheral
260
- * @param[in]	PWMx	PWM peripheral selected, should be LPC_PWM1
261
- * @param[in]	NewState New State of this function, should be:
262
- * 							- ENABLE: Enable Counter in PWM peripheral
263
- * 							- DISABLE: Disable Counter in PWM peripheral
264
- * @return 		None
265
- **********************************************************************/
266
-void PWM_CounterCmd(LPC_PWM_TypeDef *PWMx, FunctionalState NewState)
267
-{
268
-	CHECK_PARAM(PARAM_PWMx(PWMx));
269
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
270
-	if (NewState == ENABLE)
271
-	{
272
-		PWMx->TCR	|=  PWM_TCR_COUNTER_ENABLE;
273
-	}
274
-	else
275
-	{
276
-		PWMx->TCR &= (~PWM_TCR_COUNTER_ENABLE) & PWM_TCR_BITMASK;
277
-	}
278
-}
279
-
280
-
281
-/*********************************************************************//**
282
- * @brief 		Reset Counter in PWM peripheral
283
- * @param[in]	PWMx	PWM peripheral selected, should be LPC_PWM1
284
- * @return 		None
285
- **********************************************************************/
286
-void PWM_ResetCounter(LPC_PWM_TypeDef *PWMx)
287
-{
288
-	CHECK_PARAM(PARAM_PWMx(PWMx));
289
-	PWMx->TCR |= PWM_TCR_COUNTER_RESET;
290
-	PWMx->TCR &= (~PWM_TCR_COUNTER_RESET) & PWM_TCR_BITMASK;
291
-}
292
-
293
-
294
-/*********************************************************************//**
295
- * @brief 		Configures match for PWM peripheral
296
- * @param[in]	PWMx	PWM peripheral selected, should be LPC_PWM1
297
- * @param[in]   PWM_MatchConfigStruct	Pointer to a PWM_MATCHCFG_Type structure
298
-*                    that contains the configuration information for the
299
-*                    specified PWM match function.
300
- * @return 		None
301
- **********************************************************************/
302
-void PWM_ConfigMatch(LPC_PWM_TypeDef *PWMx, PWM_MATCHCFG_Type *PWM_MatchConfigStruct)
303
-{
304
-	CHECK_PARAM(PARAM_PWMx(PWMx));
305
-	CHECK_PARAM(PARAM_PWM1_MATCH_CHANNEL(PWM_MatchConfigStruct->MatchChannel));
306
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(PWM_MatchConfigStruct->IntOnMatch));
307
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(PWM_MatchConfigStruct->ResetOnMatch));
308
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(PWM_MatchConfigStruct->StopOnMatch));
309
-
310
-	//interrupt on MRn
311
-	if (PWM_MatchConfigStruct->IntOnMatch == ENABLE)
312
-	{
313
-		PWMx->MCR |= PWM_MCR_INT_ON_MATCH(PWM_MatchConfigStruct->MatchChannel);
314
-	}
315
-	else
316
-	{
317
-		PWMx->MCR &= (~PWM_MCR_INT_ON_MATCH(PWM_MatchConfigStruct->MatchChannel)) \
318
-					& PWM_MCR_BITMASK;
319
-	}
320
-
321
-	//reset on MRn
322
-	if (PWM_MatchConfigStruct->ResetOnMatch == ENABLE)
323
-	{
324
-		PWMx->MCR |= PWM_MCR_RESET_ON_MATCH(PWM_MatchConfigStruct->MatchChannel);
325
-	}
326
-	else
327
-	{
328
-		PWMx->MCR &= (~PWM_MCR_RESET_ON_MATCH(PWM_MatchConfigStruct->MatchChannel)) \
329
-					& PWM_MCR_BITMASK;
330
-	}
331
-
332
-	//stop on MRn
333
-	if (PWM_MatchConfigStruct->StopOnMatch == ENABLE)
334
-	{
335
-		PWMx->MCR |= PWM_MCR_STOP_ON_MATCH(PWM_MatchConfigStruct->MatchChannel);
336
-	}
337
-	else
338
-	{
339
-		PWMx->MCR &= (~PWM_MCR_STOP_ON_MATCH(PWM_MatchConfigStruct->MatchChannel)) \
340
-					& PWM_MCR_BITMASK;
341
-	}
342
-}
343
-
344
-
345
-/*********************************************************************//**
346
- * @brief 		Configures capture input for PWM peripheral
347
- * @param[in]	PWMx	PWM peripheral selected, should be LPC_PWM1
348
- * @param[in]   PWM_CaptureConfigStruct	Pointer to a PWM_CAPTURECFG_Type structure
349
-*                    that contains the configuration information for the
350
-*                    specified PWM capture input function.
351
- * @return 		None
352
- **********************************************************************/
353
-void PWM_ConfigCapture(LPC_PWM_TypeDef *PWMx, PWM_CAPTURECFG_Type *PWM_CaptureConfigStruct)
354
-{
355
-	CHECK_PARAM(PARAM_PWMx(PWMx));
356
-	CHECK_PARAM(PARAM_PWM1_CAPTURE_CHANNEL(PWM_CaptureConfigStruct->CaptureChannel));
357
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(PWM_CaptureConfigStruct->FallingEdge));
358
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(PWM_CaptureConfigStruct->IntOnCaption));
359
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(PWM_CaptureConfigStruct->RisingEdge));
360
-
361
-	if (PWM_CaptureConfigStruct->RisingEdge == ENABLE)
362
-	{
363
-		PWMx->CCR |= PWM_CCR_CAP_RISING(PWM_CaptureConfigStruct->CaptureChannel);
364
-	}
365
-	else
366
-	{
367
-		PWMx->CCR &= (~PWM_CCR_CAP_RISING(PWM_CaptureConfigStruct->CaptureChannel)) \
368
-					& PWM_CCR_BITMASK;
369
-	}
370
-
371
-	if (PWM_CaptureConfigStruct->FallingEdge == ENABLE)
372
-	{
373
-		PWMx->CCR |= PWM_CCR_CAP_FALLING(PWM_CaptureConfigStruct->CaptureChannel);
374
-	}
375
-	else
376
-	{
377
-		PWMx->CCR &= (~PWM_CCR_CAP_FALLING(PWM_CaptureConfigStruct->CaptureChannel)) \
378
-					& PWM_CCR_BITMASK;
379
-	}
380
-
381
-	if (PWM_CaptureConfigStruct->IntOnCaption == ENABLE)
382
-	{
383
-		PWMx->CCR |= PWM_CCR_INT_ON_CAP(PWM_CaptureConfigStruct->CaptureChannel);
384
-	}
385
-	else
386
-	{
387
-		PWMx->CCR &= (~PWM_CCR_INT_ON_CAP(PWM_CaptureConfigStruct->CaptureChannel)) \
388
-					& PWM_CCR_BITMASK;
389
-	}
390
-}
391
-
392
-
393
-/*********************************************************************//**
394
- * @brief 		Read value of capture register PWM peripheral
395
- * @param[in]	PWMx	PWM peripheral selected, should be LPC_PWM1
396
- * @param[in]	CaptureChannel: capture channel number, should be in
397
- * 				range 0 to 1
398
- * @return 		Value of capture register
399
- **********************************************************************/
400
-uint32_t PWM_GetCaptureValue(LPC_PWM_TypeDef *PWMx, uint8_t CaptureChannel)
401
-{
402
-	CHECK_PARAM(PARAM_PWMx(PWMx));
403
-	CHECK_PARAM(PARAM_PWM1_CAPTURE_CHANNEL(CaptureChannel));
404
-
405
-	switch (CaptureChannel)
406
-	{
407
-	case 0:
408
-		return PWMx->CR0;
409
-
410
-	case 1:
411
-		return PWMx->CR1;
412
-
413
-	default:
414
-		return (0);
415
-	}
416
-}
417
-
418
-
419
-/********************************************************************//**
420
- * @brief 		Update value for each PWM channel with update type option
421
- * @param[in]	PWMx	PWM peripheral selected, should be LPC_PWM1
422
- * @param[in]	MatchChannel Match channel
423
- * @param[in]	MatchValue Match value
424
- * @param[in]	UpdateType Type of Update, should be:
425
- * 				- PWM_MATCH_UPDATE_NOW: The update value will be updated for
426
- * 					this channel immediately
427
- * 				- PWM_MATCH_UPDATE_NEXT_RST: The update value will be updated for
428
- * 					this channel on next reset by a PWM Match event.
429
- * @return		None
430
- *********************************************************************/
431
-void PWM_MatchUpdate(LPC_PWM_TypeDef *PWMx, uint8_t MatchChannel, \
432
-					uint32_t MatchValue, uint8_t UpdateType)
433
-{
434
-	CHECK_PARAM(PARAM_PWMx(PWMx));
435
-	CHECK_PARAM(PARAM_PWM1_MATCH_CHANNEL(MatchChannel));
436
-	CHECK_PARAM(PARAM_PWM_MATCH_UPDATE(UpdateType));
437
-
438
-	switch (MatchChannel)
439
-	{
440
-	case 0:
441
-		PWMx->MR0 = MatchValue;
442
-		break;
443
-
444
-	case 1:
445
-		PWMx->MR1 = MatchValue;
446
-		break;
447
-
448
-	case 2:
449
-		PWMx->MR2 = MatchValue;
450
-		break;
451
-
452
-	case 3:
453
-		PWMx->MR3 = MatchValue;
454
-		break;
455
-
456
-	case 4:
457
-		PWMx->MR4 = MatchValue;
458
-		break;
459
-
460
-	case 5:
461
-		PWMx->MR5 = MatchValue;
462
-		break;
463
-
464
-	case 6:
465
-		PWMx->MR6 = MatchValue;
466
-		break;
467
-	}
468
-
469
-	// Write Latch register
470
-	PWMx->LER |= PWM_LER_EN_MATCHn_LATCH(MatchChannel);
471
-
472
-	// In case of update now
473
-	if (UpdateType == PWM_MATCH_UPDATE_NOW)
474
-	{
475
-		PWMx->TCR |= PWM_TCR_COUNTER_RESET;
476
-		PWMx->TCR &= (~PWM_TCR_COUNTER_RESET) & PWM_TCR_BITMASK;
477
-	}
478
-}
479
-
480
-/********************************************************************//**
481
- * @brief 		Update value for multi PWM channel with update type option
482
- * 				at the same time
483
- * @param[in]	PWMx	PWM peripheral selected, should be LPC_PWM1
484
- * @param[in]	MatchStruct Structure that contents match value of 7 pwm channels
485
- * @param[in]	UpdateType Type of Update, should be:
486
- * 				- PWM_MATCH_UPDATE_NOW: The update value will be updated for
487
- * 					this channel immediately
488
- * 				- PWM_MATCH_UPDATE_NEXT_RST: The update value will be updated for
489
- * 					this channel on next reset by a PWM Match event.
490
- * @return		None
491
- *********************************************************************/
492
-void PWM_MultiMatchUpdate(LPC_PWM_TypeDef *PWMx, PWM_Match_T *MatchStruct , uint8_t UpdateType)
493
-{
494
-	uint8_t LatchValue = 0;
495
-	uint8_t i;
496
-
497
-	CHECK_PARAM(PARAM_PWMx(PWMx));
498
-	CHECK_PARAM(PARAM_PWM_MATCH_UPDATE(UpdateType));
499
-
500
-	//Update match value
501
-	for(i=0;i<7;i++)
502
-	{
503
-		if(MatchStruct[i].Status == SET)
504
-		{
505
-			if(i<4)
506
-				*((volatile unsigned int *)(&(PWMx->MR0) + i)) = MatchStruct[i].Matchvalue;
507
-			else
508
-			{
509
-				*((volatile unsigned int *)(&(PWMx->MR4) + (i-4))) = MatchStruct[i].Matchvalue;
510
-			}
511
-			LatchValue |=(1<<i);
512
-		}
513
-	}
514
-	//set update for multi-channel at the same time
515
-	PWMx->LER = LatchValue;
516
-
517
-	// In case of update now
518
-	if (UpdateType == PWM_MATCH_UPDATE_NOW)
519
-	{
520
-		PWMx->TCR |= PWM_TCR_COUNTER_RESET;
521
-		PWMx->TCR &= (~PWM_TCR_COUNTER_RESET) & PWM_TCR_BITMASK;
522
-	}
523
-}
524
-/********************************************************************//**
525
- * @brief 		Configure Edge mode for each PWM channel
526
- * @param[in]	PWMx	PWM peripheral selected, should be LPC_PWM1
527
- * @param[in]	PWMChannel PWM channel, should be in range from 2 to 6
528
- * @param[in]	ModeOption PWM mode option, should be:
529
- * 				- PWM_CHANNEL_SINGLE_EDGE: Single Edge mode
530
- * 				- PWM_CHANNEL_DUAL_EDGE: Dual Edge mode
531
- * @return 		None
532
- * Note: PWM Channel 1 can not be selected for mode option
533
- *********************************************************************/
534
-void PWM_ChannelConfig(LPC_PWM_TypeDef *PWMx, uint8_t PWMChannel, uint8_t ModeOption)
535
-{
536
-	CHECK_PARAM(PARAM_PWMx(PWMx));
537
-	CHECK_PARAM(PARAM_PWM1_EDGE_MODE_CHANNEL(PWMChannel));
538
-	CHECK_PARAM(PARAM_PWM_CHANNEL_EDGE(ModeOption));
539
-
540
-	// Single edge mode
541
-	if (ModeOption == PWM_CHANNEL_SINGLE_EDGE)
542
-	{
543
-		PWMx->PCR &= (~PWM_PCR_PWMSELn(PWMChannel)) & PWM_PCR_BITMASK;
544
-	}
545
-	// Double edge mode
546
-	else if (PWM_CHANNEL_DUAL_EDGE)
547
-	{
548
-		PWMx->PCR |= PWM_PCR_PWMSELn(PWMChannel);
549
-	}
550
-}
551
-
552
-
553
-
554
-/********************************************************************//**
555
- * @brief 		Enable/Disable PWM channel output
556
- * @param[in]	PWMx	PWM peripheral selected, should be LPC_PWM1
557
- * @param[in]	PWMChannel PWM channel, should be in range from 1 to 6
558
- * @param[in]	NewState New State of this function, should be:
559
- * 				- ENABLE: Enable this PWM channel output
560
- * 				- DISABLE: Disable this PWM channel output
561
- * @return		None
562
- *********************************************************************/
563
-void PWM_ChannelCmd(LPC_PWM_TypeDef *PWMx, uint8_t PWMChannel, FunctionalState NewState)
564
-{
565
-	CHECK_PARAM(PARAM_PWMx(PWMx));
566
-	CHECK_PARAM(PARAM_PWM1_CHANNEL(PWMChannel));
567
-
568
-	if (NewState == ENABLE)
569
-	{
570
-		PWMx->PCR |= PWM_PCR_PWMENAn(PWMChannel);
571
-	}
572
-	else
573
-	{
574
-		PWMx->PCR &= (~PWM_PCR_PWMENAn(PWMChannel)) & PWM_PCR_BITMASK;
575
-	}
576
-}
577
-
578
-/**
579
- * @}
580
- */
581
-
582
-#endif /* _PWM */
583
-
584
-/**
585
- * @}
586
- */
587
-
588
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 514
frameworks/CMSIS/LPC1768/driver/lpc17xx_qei.c Просмотреть файл

@@ -1,514 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_qei.c				2010-05-21
3
-*//**
4
-* @file		lpc17xx_qei.c
5
-* @brief	Contains all functions support for QEI firmware library on LPC17xx
6
-* @version	2.0
7
-* @date		21. May. 2010
8
-* @author	NXP MCU SW Application Team
9
-*
10
-* Copyright(C) 2010, NXP Semiconductor
11
-* All rights reserved.
12
-*
13
-***********************************************************************
14
-* Software that is described herein is for illustrative purposes only
15
-* which provides customers with programming information regarding the
16
-* products. This software is supplied "AS IS" without any warranties.
17
-* NXP Semiconductors assumes no responsibility or liability for the
18
-* use of the software, conveys no license or title under any patent,
19
-* copyright, or mask work right to the product. NXP Semiconductors
20
-* reserves the right to make changes in the software without
21
-* notification. NXP Semiconductors also make no representation or
22
-* warranty that such application will be suitable for the specified
23
-* use without further testing or modification.
24
-* Permission to use, copy, modify, and distribute this software and its
25
-* documentation is hereby granted, under NXP Semiconductors'
26
-* relevant copyright in the software, without fee, provided that it
27
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
28
-* copyright, permission, and disclaimer notice must appear in all copies of
29
-* this code.
30
-**********************************************************************/
31
-
32
-/* Peripheral group ----------------------------------------------------------- */
33
-/** @addtogroup QEI
34
- * @{
35
- */
36
-
37
-/* Includes ------------------------------------------------------------------- */
38
-#include "lpc17xx_qei.h"
39
-#include "lpc17xx_clkpwr.h"
40
-
41
-
42
-/* If this source file built with example, the LPC17xx FW library configuration
43
- * file in each example directory ("lpc17xx_libcfg.h") must be included,
44
- * otherwise the default FW library configuration file must be included instead
45
- */
46
-#ifdef __BUILD_WITH_EXAMPLE__
47
-#include "lpc17xx_libcfg.h"
48
-#else
49
-#include "lpc17xx_libcfg_default.h"
50
-#endif /* __BUILD_WITH_EXAMPLE__ */
51
-
52
-
53
-#ifdef _QEI
54
-
55
-/* Private Types -------------------------------------------------------------- */
56
-/** @defgroup QEI_Private_Types QEI Private Types
57
- * @{
58
- */
59
-
60
-/**
61
- * @brief QEI configuration union type definition
62
- */
63
-typedef union {
64
-	QEI_CFG_Type bmQEIConfig;
65
-	uint32_t ulQEIConfig;
66
-} QEI_CFGOPT_Type;
67
-
68
-/**
69
- * @}
70
- */
71
-
72
-
73
-/* Public Functions ----------------------------------------------------------- */
74
-/** @addtogroup QEI_Public_Functions
75
- * @{
76
- */
77
-
78
-/*********************************************************************//**
79
- * @brief		Resets value for each type of QEI value, such as velocity,
80
- * 				counter, position, etc..
81
- * @param[in]	QEIx			QEI peripheral, should be LPC_QEI
82
- * @param[in]	ulResetType		QEI Reset Type, should be one of the following:
83
- * 								- QEI_RESET_POS: Reset Position Counter
84
- * 								- QEI_RESET_POSOnIDX: Reset Position Counter on Index signal
85
- * 								- QEI_RESET_VEL: Reset Velocity
86
- * 								- QEI_RESET_IDX: Reset Index Counter
87
- * @return		None
88
- **********************************************************************/
89
-void QEI_Reset(LPC_QEI_TypeDef *QEIx, uint32_t ulResetType)
90
-{
91
-	CHECK_PARAM(PARAM_QEIx(QEIx));
92
-	CHECK_PARAM(PARAM_QEI_RESET(ulResetType));
93
-
94
-	QEIx->QEICON = ulResetType;
95
-}
96
-
97
-/*********************************************************************//**
98
- * @brief		Initializes the QEI peripheral according to the specified
99
-*               parameters in the QEI_ConfigStruct.
100
- * @param[in]	QEIx				QEI peripheral, should be LPC_QEI
101
- * @param[in]	QEI_ConfigStruct	Pointer to a QEI_CFG_Type structure
102
-*                    that contains the configuration information for the
103
-*                    specified QEI peripheral
104
- * @return		None
105
- **********************************************************************/
106
-void QEI_Init(LPC_QEI_TypeDef *QEIx, QEI_CFG_Type *QEI_ConfigStruct)
107
-{
108
-
109
-	CHECK_PARAM(PARAM_QEIx(QEIx));
110
-	CHECK_PARAM(PARAM_QEI_DIRINV(QEI_ConfigStruct->DirectionInvert));
111
-	CHECK_PARAM(PARAM_QEI_SIGNALMODE(QEI_ConfigStruct->SignalMode));
112
-	CHECK_PARAM(PARAM_QEI_CAPMODE(QEI_ConfigStruct->CaptureMode));
113
-	CHECK_PARAM(PARAM_QEI_INVINX(QEI_ConfigStruct->InvertIndex));
114
-
115
-	/* Set up clock and power for QEI module */
116
-	CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCQEI, ENABLE);
117
-
118
-	/* As default, peripheral clock for QEI module
119
-	 * is set to FCCLK / 2 */
120
-	CLKPWR_SetPCLKDiv(CLKPWR_PCLKSEL_QEI, CLKPWR_PCLKSEL_CCLK_DIV_1);
121
-
122
-	// Reset all remaining value in QEI peripheral
123
-	QEIx->QEICON = QEI_CON_RESP | QEI_CON_RESV | QEI_CON_RESI;
124
-	QEIx->QEIMAXPOS = 0x00;
125
-	QEIx->CMPOS0 = 0x00;
126
-	QEIx->CMPOS1 = 0x00;
127
-	QEIx->CMPOS2 = 0x00;
128
-	QEIx->INXCMP = 0x00;
129
-	QEIx->QEILOAD = 0x00;
130
-	QEIx->VELCOMP = 0x00;
131
-	QEIx->FILTER = 0x00;
132
-	// Disable all Interrupt
133
-	QEIx->QEIIEC = QEI_IECLR_BITMASK;
134
-	// Clear all Interrupt pending
135
-	QEIx->QEICLR = QEI_INTCLR_BITMASK;
136
-	// Set QEI configuration value corresponding to its setting up value
137
-	QEIx->QEICONF = ((QEI_CFGOPT_Type *)QEI_ConfigStruct)->ulQEIConfig;
138
-}
139
-
140
-
141
-/*********************************************************************//**
142
- * @brief		De-initializes the QEI peripheral registers to their
143
-*                  default reset values.
144
- * @param[in]	QEIx	QEI peripheral, should be LPC_QEI
145
- * @return 		None
146
- **********************************************************************/
147
-void QEI_DeInit(LPC_QEI_TypeDef *QEIx)
148
-{
149
-	CHECK_PARAM(PARAM_QEIx(QEIx));
150
-
151
-	/* Turn off clock and power for QEI module */
152
-	CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCQEI, DISABLE);
153
-}
154
-
155
-
156
-/*****************************************************************************//**
157
-* @brief		Fills each QIE_InitStruct member with its default value:
158
-* 				- DirectionInvert = QEI_DIRINV_NONE
159
-* 				- SignalMode = QEI_SIGNALMODE_QUAD
160
-* 				- CaptureMode = QEI_CAPMODE_4X
161
-* 				- InvertIndex = QEI_INVINX_NONE
162
-* @param[in]	QIE_InitStruct Pointer to a QEI_CFG_Type structure
163
-*                    which will be initialized.
164
-* @return		None
165
-*******************************************************************************/
166
-void QEI_ConfigStructInit(QEI_CFG_Type *QIE_InitStruct)
167
-{
168
-	QIE_InitStruct->CaptureMode = QEI_CAPMODE_4X;
169
-	QIE_InitStruct->DirectionInvert = QEI_DIRINV_NONE;
170
-	QIE_InitStruct->InvertIndex = QEI_INVINX_NONE;
171
-	QIE_InitStruct->SignalMode = QEI_SIGNALMODE_QUAD;
172
-}
173
-
174
-
175
-/*********************************************************************//**
176
- * @brief		Check whether if specified flag status is set or not
177
- * @param[in]	QEIx		QEI peripheral, should be LPC_QEI
178
- * @param[in]	ulFlagType	Status Flag Type, should be one of the following:
179
- * 							- QEI_STATUS_DIR: Direction Status
180
- * @return		New Status of this status flag (SET or RESET)
181
- **********************************************************************/
182
-FlagStatus QEI_GetStatus(LPC_QEI_TypeDef *QEIx, uint32_t ulFlagType)
183
-{
184
-	CHECK_PARAM(PARAM_QEIx(QEIx));
185
-	CHECK_PARAM(PARAM_QEI_STATUS(ulFlagType));
186
-	return ((QEIx->QEISTAT & ulFlagType) ? SET : RESET);
187
-}
188
-
189
-/*********************************************************************//**
190
- * @brief		Get current position value in QEI peripheral
191
- * @param[in]	QEIx	QEI peripheral, should be LPC_QEI
192
- * @return		Current position value of QEI peripheral
193
- **********************************************************************/
194
-uint32_t QEI_GetPosition(LPC_QEI_TypeDef *QEIx)
195
-{
196
-	CHECK_PARAM(PARAM_QEIx(QEIx));
197
-	return (QEIx->QEIPOS);
198
-}
199
-
200
-/*********************************************************************//**
201
- * @brief		Set max position value for QEI peripheral
202
- * @param[in]	QEIx		QEI peripheral, should be LPC_QEI
203
- * @param[in]	ulMaxPos	Max position value to set
204
- * @return		None
205
- **********************************************************************/
206
-void QEI_SetMaxPosition(LPC_QEI_TypeDef *QEIx, uint32_t ulMaxPos)
207
-{
208
-	CHECK_PARAM(PARAM_QEIx(QEIx));
209
-	QEIx->QEIMAXPOS = ulMaxPos;
210
-}
211
-
212
-/*********************************************************************//**
213
- * @brief		Set position compare value for QEI peripheral
214
- * @param[in]	QEIx		QEI peripheral, should be LPC_QEI
215
- * @param[in]	bPosCompCh	Compare Position channel, should be:
216
- * 							- QEI_COMPPOS_CH_0: QEI compare position channel 0
217
- * 							- QEI_COMPPOS_CH_1: QEI compare position channel 1
218
- * 							- QEI_COMPPOS_CH_2: QEI compare position channel 2
219
- * @param[in]	ulPosComp	Compare Position value to set
220
- * @return		None
221
- **********************************************************************/
222
-void QEI_SetPositionComp(LPC_QEI_TypeDef *QEIx, uint8_t bPosCompCh, uint32_t ulPosComp)
223
-{
224
-	uint32_t *tmp;
225
-
226
-	CHECK_PARAM(PARAM_QEIx(QEIx));
227
-	CHECK_PARAM(PARAM_QEI_COMPPOS_CH(bPosCompCh));
228
-	tmp = (uint32_t *) (&(QEIx->CMPOS0) + bPosCompCh * 4);
229
-	*tmp = ulPosComp;
230
-
231
-}
232
-
233
-/*********************************************************************//**
234
- * @brief		Get current index counter of QEI peripheral
235
- * @param[in]	QEIx		QEI peripheral, should be LPC_QEI
236
- * @return		Current value of QEI index counter
237
- **********************************************************************/
238
-uint32_t QEI_GetIndex(LPC_QEI_TypeDef *QEIx)
239
-{
240
-	CHECK_PARAM(PARAM_QEIx(QEIx));
241
-	return (QEIx->INXCNT);
242
-}
243
-
244
-/*********************************************************************//**
245
- * @brief		Set value for index compare in QEI peripheral
246
- * @param[in]	QEIx		QEI peripheral, should be LPC_QEI
247
- * @param[in]	ulIndexComp		Compare Index Value to set
248
- * @return		None
249
- **********************************************************************/
250
-void QEI_SetIndexComp(LPC_QEI_TypeDef *QEIx, uint32_t ulIndexComp)
251
-{
252
-	CHECK_PARAM(PARAM_QEIx(QEIx));
253
-	QEIx->INXCMP = ulIndexComp;
254
-}
255
-
256
-/*********************************************************************//**
257
- * @brief		Set timer reload value for QEI peripheral. When the velocity timer is
258
- * 				over-flow, the value that set for Timer Reload register will be loaded
259
- * 				into the velocity timer for next period. The calculated velocity in RPM
260
- * 				therefore will be affect by this value.
261
- * @param[in]	QEIx			QEI peripheral, should be LPC_QEI
262
- * @param[in]	QEIReloadStruct	QEI reload structure
263
- * @return		None
264
- **********************************************************************/
265
-void QEI_SetTimerReload(LPC_QEI_TypeDef *QEIx, QEI_RELOADCFG_Type *QEIReloadStruct)
266
-{
267
-	uint64_t pclk;
268
-
269
-	CHECK_PARAM(PARAM_QEIx(QEIx));
270
-	CHECK_PARAM(PARAM_QEI_TIMERRELOAD(QEIReloadStruct->ReloadOption));
271
-
272
-	if (QEIReloadStruct->ReloadOption == QEI_TIMERRELOAD_TICKVAL) {
273
-		QEIx->QEILOAD = QEIReloadStruct->ReloadValue - 1;
274
-	} else {
275
-		pclk = (uint64_t)CLKPWR_GetPCLK(CLKPWR_PCLKSEL_QEI);
276
-		pclk = (pclk /(1000000/QEIReloadStruct->ReloadValue)) - 1;
277
-		QEIx->QEILOAD = (uint32_t)pclk;
278
-	}
279
-}
280
-
281
-/*********************************************************************//**
282
- * @brief		Get current timer counter in QEI peripheral
283
- * @param[in]	QEIx			QEI peripheral, should be LPC_QEI
284
- * @return		Current timer counter in QEI peripheral
285
- **********************************************************************/
286
-uint32_t QEI_GetTimer(LPC_QEI_TypeDef *QEIx)
287
-{
288
-	CHECK_PARAM(PARAM_QEIx(QEIx));
289
-	return (QEIx->QEITIME);
290
-}
291
-
292
-/*********************************************************************//**
293
- * @brief		Get current velocity pulse counter in current time period
294
- * @param[in]	QEIx			QEI peripheral, should be LPC_QEI
295
- * @return		Current velocity pulse counter value
296
- **********************************************************************/
297
-uint32_t QEI_GetVelocity(LPC_QEI_TypeDef *QEIx)
298
-{
299
-	CHECK_PARAM(PARAM_QEIx(QEIx));
300
-	return (QEIx->QEIVEL);
301
-}
302
-
303
-/*********************************************************************//**
304
- * @brief		Get the most recently measured velocity of the QEI. When
305
- * 				the Velocity timer in QEI is over-flow, the current velocity
306
- * 				value will be loaded into Velocity Capture register.
307
- * @param[in]	QEIx			QEI peripheral, should be LPC_QEI
308
- * @return		The most recently measured velocity value
309
- **********************************************************************/
310
-uint32_t QEI_GetVelocityCap(LPC_QEI_TypeDef *QEIx)
311
-{
312
-	CHECK_PARAM(PARAM_QEIx(QEIx));
313
-	return (QEIx->QEICAP);
314
-}
315
-
316
-/*********************************************************************//**
317
- * @brief		Set Velocity Compare value for QEI peripheral
318
- * @param[in]	QEIx			QEI peripheral, should be LPC_QEI
319
- * @param[in]	ulVelComp		Compare Velocity value to set
320
- * @return		None
321
- **********************************************************************/
322
-void QEI_SetVelocityComp(LPC_QEI_TypeDef *QEIx, uint32_t ulVelComp)
323
-{
324
-	CHECK_PARAM(PARAM_QEIx(QEIx));
325
-	QEIx->VELCOMP = ulVelComp;
326
-}
327
-
328
-/*********************************************************************//**
329
- * @brief		Set value of sampling count for the digital filter in
330
- * 				QEI peripheral
331
- * @param[in]	QEIx			QEI peripheral, should be LPC_QEI
332
- * @param[in]	ulSamplingPulse	Value of sampling count to set
333
- * @return		None
334
- **********************************************************************/
335
-void QEI_SetDigiFilter(LPC_QEI_TypeDef *QEIx, uint32_t ulSamplingPulse)
336
-{
337
-	CHECK_PARAM(PARAM_QEIx(QEIx));
338
-	QEIx->FILTER = ulSamplingPulse;
339
-}
340
-
341
-/*********************************************************************//**
342
- * @brief		Check whether if specified interrupt flag status in QEI
343
- * 				peripheral is set or not
344
- * @param[in]	QEIx			QEI peripheral, should be LPC_QEI
345
- * @param[in]	ulIntType		Interrupt Flag Status type, should be:
346
-								- QEI_INTFLAG_INX_Int: index pulse was detected interrupt
347
-								- QEI_INTFLAG_TIM_Int: Velocity timer over flow interrupt
348
-								- QEI_INTFLAG_VELC_Int: Capture velocity is less than compare interrupt
349
-								- QEI_INTFLAG_DIR_Int: Change of direction interrupt
350
-								- QEI_INTFLAG_ERR_Int: An encoder phase error interrupt
351
-								- QEI_INTFLAG_ENCLK_Int: An encoder clock pulse was detected interrupt
352
-								- QEI_INTFLAG_POS0_Int: position 0 compare value is equal to the
353
-														current position interrupt
354
-								- QEI_INTFLAG_POS1_Int: position 1 compare value is equal to the
355
-														current position interrupt
356
-								- QEI_INTFLAG_POS2_Int: position 2 compare value is equal to the
357
-														current position interrupt
358
-								- QEI_INTFLAG_REV_Int: Index compare value is equal to the current
359
-														index count interrupt
360
-								- QEI_INTFLAG_POS0REV_Int: Combined position 0 and revolution count interrupt
361
-								- QEI_INTFLAG_POS1REV_Int: Combined position 1 and revolution count interrupt
362
-								- QEI_INTFLAG_POS2REV_Int: Combined position 2 and revolution count interrupt
363
- * @return		New State of specified interrupt flag status (SET or RESET)
364
- **********************************************************************/
365
-FlagStatus QEI_GetIntStatus(LPC_QEI_TypeDef *QEIx, uint32_t ulIntType)
366
-{
367
-	CHECK_PARAM(PARAM_QEIx(QEIx));
368
-	CHECK_PARAM(PARAM_QEI_INTFLAG(ulIntType));
369
-
370
-	return((QEIx->QEIINTSTAT & ulIntType) ? SET : RESET);
371
-}
372
-
373
-/*********************************************************************//**
374
- * @brief		Enable/Disable specified interrupt in QEI peripheral
375
- * @param[in]	QEIx			QEI peripheral, should be LPC_QEI
376
- * @param[in]	ulIntType		Interrupt Flag Status type, should be:
377
- * 								- QEI_INTFLAG_INX_Int: index pulse was detected interrupt
378
- *								- QEI_INTFLAG_TIM_Int: Velocity timer over flow interrupt
379
- *								- QEI_INTFLAG_VELC_Int: Capture velocity is less than compare interrupt
380
- * 								- QEI_INTFLAG_DIR_Int: Change of direction interrupt
381
- *  							- QEI_INTFLAG_ERR_Int: An encoder phase error interrupt
382
- * 								- QEI_INTFLAG_ENCLK_Int: An encoder clock pulse was detected interrupt
383
- *								- QEI_INTFLAG_POS0_Int: position 0 compare value is equal to the
384
- *														current position interrupt
385
- *								- QEI_INTFLAG_POS1_Int: position 1 compare value is equal to the
386
- *														current position interrupt
387
- *								- QEI_INTFLAG_POS2_Int: position 2 compare value is equal to the
388
- *														current position interrupt
389
- *								- QEI_INTFLAG_REV_Int: Index compare value is equal to the current
390
- *														index count interrupt
391
- *								- QEI_INTFLAG_POS0REV_Int: Combined position 0 and revolution count interrupt
392
- *								- QEI_INTFLAG_POS1REV_Int: Combined position 1 and revolution count interrupt
393
- *								- QEI_INTFLAG_POS2REV_Int: Combined position 2 and revolution count interrupt
394
- * @param[in]	NewState		New function state, should be:
395
- *								- DISABLE
396
- *								- ENABLE
397
- * @return		None
398
- **********************************************************************/
399
-void QEI_IntCmd(LPC_QEI_TypeDef *QEIx, uint32_t ulIntType, FunctionalState NewState)
400
-{
401
-	CHECK_PARAM(PARAM_QEIx(QEIx));
402
-	CHECK_PARAM(PARAM_QEI_INTFLAG(ulIntType));
403
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
404
-
405
-	if (NewState == ENABLE) {
406
-		QEIx->QEIIES = ulIntType;
407
-	} else {
408
-		QEIx->QEIIEC = ulIntType;
409
-	}
410
-}
411
-
412
-
413
-/*********************************************************************//**
414
- * @brief		Sets (forces) specified interrupt in QEI peripheral
415
- * @param[in]	QEIx			QEI peripheral, should be LPC_QEI
416
- * @param[in]	ulIntType		Interrupt Flag Status type, should be:
417
-								- QEI_INTFLAG_INX_Int: index pulse was detected interrupt
418
-								- QEI_INTFLAG_TIM_Int: Velocity timer over flow interrupt
419
-								- QEI_INTFLAG_VELC_Int: Capture velocity is less than compare interrupt
420
-								- QEI_INTFLAG_DIR_Int: Change of direction interrupt
421
-								- QEI_INTFLAG_ERR_Int: An encoder phase error interrupt
422
-								- QEI_INTFLAG_ENCLK_Int: An encoder clock pulse was detected interrupt
423
-								- QEI_INTFLAG_POS0_Int: position 0 compare value is equal to the
424
-														current position interrupt
425
-								- QEI_INTFLAG_POS1_Int: position 1 compare value is equal to the
426
-														current position interrupt
427
-								- QEI_INTFLAG_POS2_Int: position 2 compare value is equal to the
428
-														current position interrupt
429
-								- QEI_INTFLAG_REV_Int: Index compare value is equal to the current
430
-														index count interrupt
431
-								- QEI_INTFLAG_POS0REV_Int: Combined position 0 and revolution count interrupt
432
-								- QEI_INTFLAG_POS1REV_Int: Combined position 1 and revolution count interrupt
433
-								- QEI_INTFLAG_POS2REV_Int: Combined position 2 and revolution count interrupt
434
- * @return		None
435
- **********************************************************************/
436
-void QEI_IntSet(LPC_QEI_TypeDef *QEIx, uint32_t ulIntType)
437
-{
438
-	CHECK_PARAM(PARAM_QEIx(QEIx));
439
-	CHECK_PARAM(PARAM_QEI_INTFLAG(ulIntType));
440
-
441
-	QEIx->QEISET = ulIntType;
442
-}
443
-
444
-/*********************************************************************//**
445
- * @brief		Clear (force) specified interrupt (pending) in QEI peripheral
446
- * @param[in]	QEIx			QEI peripheral, should be LPC_QEI
447
- * @param[in]	ulIntType		Interrupt Flag Status type, should be:
448
-								- QEI_INTFLAG_INX_Int: index pulse was detected interrupt
449
-								- QEI_INTFLAG_TIM_Int: Velocity timer over flow interrupt
450
-								- QEI_INTFLAG_VELC_Int: Capture velocity is less than compare interrupt
451
-								- QEI_INTFLAG_DIR_Int: Change of direction interrupt
452
-								- QEI_INTFLAG_ERR_Int: An encoder phase error interrupt
453
-								- QEI_INTFLAG_ENCLK_Int: An encoder clock pulse was detected interrupt
454
-								- QEI_INTFLAG_POS0_Int: position 0 compare value is equal to the
455
-														current position interrupt
456
-								- QEI_INTFLAG_POS1_Int: position 1 compare value is equal to the
457
-														current position interrupt
458
-								- QEI_INTFLAG_POS2_Int: position 2 compare value is equal to the
459
-														current position interrupt
460
-								- QEI_INTFLAG_REV_Int: Index compare value is equal to the current
461
-														index count interrupt
462
-								- QEI_INTFLAG_POS0REV_Int: Combined position 0 and revolution count interrupt
463
-								- QEI_INTFLAG_POS1REV_Int: Combined position 1 and revolution count interrupt
464
-								- QEI_INTFLAG_POS2REV_Int: Combined position 2 and revolution count interrupt
465
- * @return		None
466
- **********************************************************************/
467
-void QEI_IntClear(LPC_QEI_TypeDef *QEIx, uint32_t ulIntType)
468
-{
469
-	CHECK_PARAM(PARAM_QEIx(QEIx));
470
-	CHECK_PARAM(PARAM_QEI_INTFLAG(ulIntType));
471
-
472
-	QEIx->QEICLR = ulIntType;
473
-}
474
-
475
-
476
-/*********************************************************************//**
477
- * @brief		Calculates the actual velocity in RPM passed via velocity
478
- * 				capture value and Pulse Per Round (of the encoder) value
479
- * 				parameter input.
480
- * @param[in]	QEIx			QEI peripheral, should be LPC_QEI
481
- * @param[in]	ulVelCapValue	Velocity capture input value that can
482
- * 								be got from QEI_GetVelocityCap() function
483
- * @param[in]	ulPPR			Pulse per round of encoder
484
- * @return		The actual value of velocity in RPM (Round per minute)
485
- **********************************************************************/
486
-uint32_t QEI_CalculateRPM(LPC_QEI_TypeDef *QEIx, uint32_t ulVelCapValue, uint32_t ulPPR)
487
-{
488
-	uint64_t rpm, clock, Load, edges;
489
-
490
-	// Get current Clock rate for timer input
491
-	clock = (uint64_t)CLKPWR_GetPCLK(CLKPWR_PCLKSEL_QEI);
492
-	// Get Timer load value (velocity capture period)
493
-	Load  = (uint64_t)(QEIx->QEILOAD + 1);
494
-	// Get Edge
495
-	edges = (uint64_t)((QEIx->QEICONF & QEI_CONF_CAPMODE) ? 4 : 2);
496
-	// Calculate RPM
497
-	rpm = ((clock * ulVelCapValue * 60) / (Load * ulPPR * edges));
498
-
499
-	return (uint32_t)(rpm);
500
-}
501
-
502
-
503
-/**
504
- * @}
505
- */
506
-
507
-#endif /* _QEI */
508
-
509
-/**
510
- * @}
511
- */
512
-
513
-/* --------------------------------- End Of File ------------------------------ */
514
-

+ 0
- 199
frameworks/CMSIS/LPC1768/driver/lpc17xx_rit.c Просмотреть файл

@@ -1,199 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_rit.c				2010-05-21
3
-*//**
4
-* @file		lpc17xx_rit.c
5
-* @brief	Contains all functions support for RIT firmware library on LPC17xx
6
-* @version	2.0
7
-* @date		21. May. 2010
8
-* @author	NXP MCU SW Application Team
9
-*
10
-* Copyright(C) 2010, NXP Semiconductor
11
-* All rights reserved.
12
-*
13
-***********************************************************************
14
-* Software that is described herein is for illustrative purposes only
15
-* which provides customers with programming information regarding the
16
-* products. This software is supplied "AS IS" without any warranties.
17
-* NXP Semiconductors assumes no responsibility or liability for the
18
-* use of the software, conveys no license or title under any patent,
19
-* copyright, or mask work right to the product. NXP Semiconductors
20
-* reserves the right to make changes in the software without
21
-* notification. NXP Semiconductors also make no representation or
22
-* warranty that such application will be suitable for the specified
23
-* use without further testing or modification.
24
-* Permission to use, copy, modify, and distribute this software and its
25
-* documentation is hereby granted, under NXP Semiconductors'
26
-* relevant copyright in the software, without fee, provided that it
27
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
28
-* copyright, permission, and disclaimer notice must appear in all copies of
29
-* this code.
30
-**********************************************************************/
31
-
32
-/* Peripheral group ----------------------------------------------------------- */
33
-/** @addtogroup RIT
34
- * @{
35
- */
36
-
37
-/* Includes ------------------------------------------------------------------- */
38
-#include "lpc17xx_rit.h"
39
-#include "lpc17xx_clkpwr.h"
40
-
41
-/* If this source file built with example, the LPC17xx FW library configuration
42
- * file in each example directory ("lpc17xx_libcfg.h") must be included,
43
- * otherwise the default FW library configuration file must be included instead
44
- */
45
-#ifdef __BUILD_WITH_EXAMPLE__
46
-#include "lpc17xx_libcfg.h"
47
-#else
48
-#include "lpc17xx_libcfg_default.h"
49
-#endif /* __BUILD_WITH_EXAMPLE__ */
50
-
51
-#ifdef _RIT
52
-
53
-/* Public Functions ----------------------------------------------------------- */
54
-/** @addtogroup RIT_Public_Functions
55
- * @{
56
- */
57
-
58
-/******************************************************************************//*
59
- * @brief 		Initial for RIT
60
- * 					- Turn on power and clock
61
- * 					- Setup default register values
62
- * @param[in]	RITx is RIT peripheral selected, should be: LPC_RIT
63
- * @return 		None
64
- *******************************************************************************/
65
-void RIT_Init(LPC_RIT_TypeDef *RITx)
66
-{
67
-	CHECK_PARAM(PARAM_RITx(RITx));
68
-	CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCRIT, ENABLE);
69
-	//Set up default register values
70
-	RITx->RICOMPVAL = 0xFFFFFFFF;
71
-	RITx->RIMASK	= 0x00000000;
72
-	RITx->RICTRL	= 0x0C;
73
-	RITx->RICOUNTER	= 0x00000000;
74
-	// Turn on power and clock
75
-
76
-}
77
-/******************************************************************************//*
78
- * @brief 		DeInitial for RIT
79
- * 					- Turn off power and clock
80
- * 					- ReSetup default register values
81
- * @param[in]	RITx is RIT peripheral selected, should be: LPC_RIT
82
- * @return 		None
83
- *******************************************************************************/
84
-void RIT_DeInit(LPC_RIT_TypeDef *RITx)
85
-{
86
-	CHECK_PARAM(PARAM_RITx(RITx));
87
-
88
-	// Turn off power and clock
89
-	CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCRIT, DISABLE);
90
-	//ReSetup default register values
91
-	RITx->RICOMPVAL = 0xFFFFFFFF;
92
-	RITx->RIMASK	= 0x00000000;
93
-	RITx->RICTRL	= 0x0C;
94
-	RITx->RICOUNTER	= 0x00000000;
95
-}
96
-
97
-/******************************************************************************//*
98
- * @brief 		Set compare value, mask value and time counter value
99
- * @param[in]	RITx is RIT peripheral selected, should be: LPC_RIT
100
- * @param[in]	time_interval: timer interval value (ms)
101
- * @return 		None
102
- *******************************************************************************/
103
-void RIT_TimerConfig(LPC_RIT_TypeDef *RITx, uint32_t time_interval)
104
-{
105
-	uint32_t clock_rate, cmp_value;
106
-	CHECK_PARAM(PARAM_RITx(RITx));
107
-
108
-	// Get PCLK value of RIT
109
-	clock_rate = CLKPWR_GetPCLK(CLKPWR_PCLKSEL_RIT);
110
-
111
-	/* calculate compare value for RIT to generate interrupt at
112
-	 * specified time interval
113
-	 * COMPVAL = (RIT_PCLK * time_interval)/1000
114
-	 * (with time_interval unit is millisecond)
115
-	 */
116
-	cmp_value = (clock_rate /1000) * time_interval;
117
-	RITx->RICOMPVAL = cmp_value;
118
-
119
-	/* Set timer enable clear bit to clear timer to 0 whenever
120
-	 * counter value equals the contents of RICOMPVAL
121
-	 */
122
-	RITx->RICTRL |= (1<<1);
123
-}
124
-
125
-
126
-/******************************************************************************//*
127
- * @brief 		Enable/Disable Timer
128
- * @param[in]	RITx is RIT peripheral selected, should be: LPC_RIT
129
- * @param[in]	NewState 	New State of this function
130
- * 					-ENABLE: Enable Timer
131
- * 					-DISABLE: Disable Timer
132
- * @return 		None
133
- *******************************************************************************/
134
-void RIT_Cmd(LPC_RIT_TypeDef *RITx, FunctionalState NewState)
135
-{
136
-	CHECK_PARAM(PARAM_RITx(RITx));
137
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
138
-
139
-	//Enable or Disable Timer
140
-	if(NewState==ENABLE)
141
-	{
142
-		RITx->RICTRL |= RIT_CTRL_TEN;
143
-	}
144
-	else
145
-	{
146
-		RITx->RICTRL &= ~RIT_CTRL_TEN;
147
-	}
148
-}
149
-
150
-/******************************************************************************//*
151
- * @brief 		Timer Enable/Disable on debug
152
- * @param[in]	RITx is RIT peripheral selected, should be: LPC_RIT
153
- * @param[in]	NewState 	New State of this function
154
- * 					-ENABLE: The timer is halted whenever a hardware break condition occurs
155
- * 					-DISABLE: Hardware break has no effect on the timer operation
156
- * @return 		None
157
- *******************************************************************************/
158
-void RIT_TimerDebugCmd(LPC_RIT_TypeDef *RITx, FunctionalState NewState)
159
-{
160
-	CHECK_PARAM(PARAM_RITx(RITx));
161
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
162
-
163
-	//Timer Enable/Disable on break
164
-	if(NewState==ENABLE)
165
-	{
166
-		RITx->RICTRL |= RIT_CTRL_ENBR;
167
-	}
168
-	else
169
-	{
170
-		RITx->RICTRL &= ~RIT_CTRL_ENBR;
171
-	}
172
-}
173
-/******************************************************************************//*
174
- * @brief 		Check whether interrupt flag is set or not
175
- * @param[in]	RITx is RIT peripheral selected, should be: LPC_RIT
176
- * @return 		Current interrupt status, could be: SET/RESET
177
- *******************************************************************************/
178
-IntStatus RIT_GetIntStatus(LPC_RIT_TypeDef *RITx)
179
-{
180
-	IntStatus result;
181
-	CHECK_PARAM(PARAM_RITx(RITx));
182
-	if((RITx->RICTRL&RIT_CTRL_INTEN)==1)	result= SET;
183
-	else return RESET;
184
-	//clear interrupt flag
185
-	RITx->RICTRL |= RIT_CTRL_INTEN;
186
-	return result;
187
-}
188
-
189
-/**
190
- * @}
191
- */
192
-
193
-#endif /* _RIT */
194
-
195
-/**
196
- * @}
197
- */
198
-
199
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 783
frameworks/CMSIS/LPC1768/driver/lpc17xx_rtc.c Просмотреть файл

@@ -1,783 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_rtc.c				2011-06-06
3
-*//**
4
-* @file		lpc17xx_rtc.c
5
-* @brief	Contains all functions support for RTC firmware library on LPC17xx
6
-* @version	3.1
7
-* @date		6. June. 2011
8
-* @author	NXP MCU SW Application Team
9
-*
10
-* Copyright(C) 2011, NXP Semiconductor
11
-* All rights reserved.
12
-*
13
-***********************************************************************
14
-* Software that is described herein is for illustrative purposes only
15
-* which provides customers with programming information regarding the
16
-* products. This software is supplied "AS IS" without any warranties.
17
-* NXP Semiconductors assumes no responsibility or liability for the
18
-* use of the software, conveys no license or title under any patent,
19
-* copyright, or mask work right to the product. NXP Semiconductors
20
-* reserves the right to make changes in the software without
21
-* notification. NXP Semiconductors also make no representation or
22
-* warranty that such application will be suitable for the specified
23
-* use without further testing or modification.
24
-* Permission to use, copy, modify, and distribute this software and its
25
-* documentation is hereby granted, under NXP Semiconductors'
26
-* relevant copyright in the software, without fee, provided that it
27
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
28
-* copyright, permission, and disclaimer notice must appear in all copies of
29
-* this code.
30
-**********************************************************************/
31
-
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @addtogroup RTC
35
- * @{
36
- */
37
-
38
-/* Includes ------------------------------------------------------------------- */
39
-#include "lpc17xx_rtc.h"
40
-#include "lpc17xx_clkpwr.h"
41
-
42
-
43
-/* If this source file built with example, the LPC17xx FW library configuration
44
- * file in each example directory ("lpc17xx_libcfg.h") must be included,
45
- * otherwise the default FW library configuration file must be included instead
46
- */
47
-#ifdef __BUILD_WITH_EXAMPLE__
48
-#include "lpc17xx_libcfg.h"
49
-#else
50
-#include "lpc17xx_libcfg_default.h"
51
-#endif /* __BUILD_WITH_EXAMPLE__ */
52
-
53
-
54
-#ifdef _RTC
55
-
56
-/* Public Functions ----------------------------------------------------------- */
57
-/** @addtogroup RTC_Public_Functions
58
- * @{
59
- */
60
-
61
-/********************************************************************//**
62
- * @brief		Initializes the RTC peripheral.
63
- * @param[in]	RTCx	RTC peripheral selected, should be LPC_RTC
64
- * @return 		None
65
- *********************************************************************/
66
-void RTC_Init (LPC_RTC_TypeDef *RTCx)
67
-{
68
-	CHECK_PARAM(PARAM_RTCx(RTCx));
69
-
70
-	/* Set up clock and power for RTC module */
71
-	CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCRTC, ENABLE);
72
-
73
-	// Clear all register to be default
74
-	RTCx->ILR = 0x00;
75
-	RTCx->CCR = 0x00;
76
-	RTCx->CIIR = 0x00;
77
-	RTCx->AMR = 0xFF;
78
-	RTCx->CALIBRATION = 0x00;
79
-}
80
-
81
-
82
-/*********************************************************************//**
83
- * @brief		De-initializes the RTC peripheral registers to their
84
-*                  default reset values.
85
- * @param[in]	RTCx	RTC peripheral selected, should be LPC_RTC
86
- * @return 		None
87
- **********************************************************************/
88
-void RTC_DeInit(LPC_RTC_TypeDef *RTCx)
89
-{
90
-	CHECK_PARAM(PARAM_RTCx(RTCx));
91
-
92
-	RTCx->CCR = 0x00;
93
-	// Disable power and clock for RTC module
94
-	CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCRTC, DISABLE);
95
-}
96
-
97
-/*********************************************************************//**
98
- * @brief 		Reset clock tick counter in RTC peripheral
99
- * @param[in]	RTCx	RTC peripheral selected, should be LPC_RTC
100
- * @return 		None
101
- **********************************************************************/
102
-void RTC_ResetClockTickCounter(LPC_RTC_TypeDef *RTCx)
103
-{
104
-	CHECK_PARAM(PARAM_RTCx(RTCx));
105
-
106
-	RTCx->CCR |= RTC_CCR_CTCRST;
107
-	RTCx->CCR &= (~RTC_CCR_CTCRST) & RTC_CCR_BITMASK;
108
-}
109
-
110
-/*********************************************************************//**
111
- * @brief 		Start/Stop RTC peripheral
112
- * @param[in]	RTCx	RTC peripheral selected, should be LPC_RTC
113
- * @param[in]	NewState New State of this function, should be:
114
- * 				- ENABLE: The time counters are enabled
115
- * 				- DISABLE: The time counters are disabled
116
- * @return 		None
117
- **********************************************************************/
118
-void RTC_Cmd (LPC_RTC_TypeDef *RTCx, FunctionalState NewState)
119
-{
120
-	CHECK_PARAM(PARAM_RTCx(RTCx));
121
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
122
-
123
-	if (NewState == ENABLE)
124
-	{
125
-		RTCx->CCR |= RTC_CCR_CLKEN;
126
-	}
127
-	else
128
-	{
129
-		RTCx->CCR &= (~RTC_CCR_CLKEN) & RTC_CCR_BITMASK;
130
-	}
131
-}
132
-
133
-
134
-/*********************************************************************//**
135
- * @brief 		Enable/Disable Counter increment interrupt for each time type
136
- * 				in RTC peripheral
137
- * @param[in]	RTCx	RTC peripheral selected, should be LPC_RTC
138
- * @param[in]	CntIncrIntType: Counter Increment Interrupt type,
139
- * 				an increment of this type value below will generates
140
- * 				an interrupt, should be:
141
- * 				- RTC_TIMETYPE_SECOND
142
- * 				- RTC_TIMETYPE_MINUTE
143
- * 				- RTC_TIMETYPE_HOUR
144
- * 				- RTC_TIMETYPE_DAYOFWEEK
145
- * 				- RTC_TIMETYPE_DAYOFMONTH
146
- * 				- RTC_TIMETYPE_DAYOFYEAR
147
- * 				- RTC_TIMETYPE_MONTH
148
- * 				- RTC_TIMETYPE_YEAR
149
- * @param[in]	NewState New State of this function, should be:
150
- * 				- ENABLE: Counter Increment interrupt for this
151
- * 					time type are enabled
152
- * 				- DISABLE: Counter Increment interrupt for this
153
- * 					time type are disabled
154
- * @return 		None
155
- **********************************************************************/
156
-void RTC_CntIncrIntConfig (LPC_RTC_TypeDef *RTCx, uint32_t CntIncrIntType, \
157
-								FunctionalState NewState)
158
-{
159
-	CHECK_PARAM(PARAM_RTCx(RTCx));
160
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
161
-	CHECK_PARAM(PARAM_RTC_TIMETYPE(CntIncrIntType));
162
-
163
-	if (NewState ==  ENABLE)
164
-	{
165
-		switch (CntIncrIntType)
166
-		{
167
-		case RTC_TIMETYPE_SECOND:
168
-			RTCx->CIIR |= RTC_CIIR_IMSEC;
169
-			break;
170
-		case RTC_TIMETYPE_MINUTE:
171
-			RTCx->CIIR |= RTC_CIIR_IMMIN;
172
-			break;
173
-		case RTC_TIMETYPE_HOUR:
174
-			RTCx->CIIR |= RTC_CIIR_IMHOUR;
175
-			break;
176
-		case RTC_TIMETYPE_DAYOFWEEK:
177
-			RTCx->CIIR |= RTC_CIIR_IMDOW;
178
-			break;
179
-		case RTC_TIMETYPE_DAYOFMONTH:
180
-			RTCx->CIIR |= RTC_CIIR_IMDOM;
181
-			break;
182
-		case RTC_TIMETYPE_DAYOFYEAR:
183
-			RTCx->CIIR |= RTC_CIIR_IMDOY;
184
-			break;
185
-		case RTC_TIMETYPE_MONTH:
186
-			RTCx->CIIR |= RTC_CIIR_IMMON;
187
-			break;
188
-		case RTC_TIMETYPE_YEAR:
189
-			RTCx->CIIR |= RTC_CIIR_IMYEAR;
190
-			break;
191
-		}
192
-	}
193
-	else
194
-	{
195
-		switch (CntIncrIntType)
196
-		{
197
-		case RTC_TIMETYPE_SECOND:
198
-			RTCx->CIIR &= (~RTC_CIIR_IMSEC) & RTC_CIIR_BITMASK;
199
-			break;
200
-		case RTC_TIMETYPE_MINUTE:
201
-			RTCx->CIIR &= (~RTC_CIIR_IMMIN) & RTC_CIIR_BITMASK;
202
-			break;
203
-		case RTC_TIMETYPE_HOUR:
204
-			RTCx->CIIR &= (~RTC_CIIR_IMHOUR) & RTC_CIIR_BITMASK;
205
-			break;
206
-		case RTC_TIMETYPE_DAYOFWEEK:
207
-			RTCx->CIIR &= (~RTC_CIIR_IMDOW) & RTC_CIIR_BITMASK;
208
-			break;
209
-		case RTC_TIMETYPE_DAYOFMONTH:
210
-			RTCx->CIIR &= (~RTC_CIIR_IMDOM) & RTC_CIIR_BITMASK;
211
-			break;
212
-		case RTC_TIMETYPE_DAYOFYEAR:
213
-			RTCx->CIIR &= (~RTC_CIIR_IMDOY) & RTC_CIIR_BITMASK;
214
-			break;
215
-		case RTC_TIMETYPE_MONTH:
216
-			RTCx->CIIR &= (~RTC_CIIR_IMMON) & RTC_CIIR_BITMASK;
217
-			break;
218
-		case RTC_TIMETYPE_YEAR:
219
-			RTCx->CIIR &= (~RTC_CIIR_IMYEAR) & RTC_CIIR_BITMASK;
220
-			break;
221
-		}
222
-	}
223
-}
224
-
225
-
226
-/*********************************************************************//**
227
- * @brief 		Enable/Disable Alarm interrupt for each time type
228
- * 				in RTC peripheral
229
- * @param[in]	RTCx	RTC peripheral selected, should be LPC_RTC
230
- * @param[in]	AlarmTimeType: Alarm Time Interrupt type,
231
- * 				an matching of this type value below with current time
232
- * 				in RTC will generates an interrupt, should be:
233
- * 				- RTC_TIMETYPE_SECOND
234
- * 				- RTC_TIMETYPE_MINUTE
235
- * 				- RTC_TIMETYPE_HOUR
236
- * 				- RTC_TIMETYPE_DAYOFWEEK
237
- * 				- RTC_TIMETYPE_DAYOFMONTH
238
- * 				- RTC_TIMETYPE_DAYOFYEAR
239
- * 				- RTC_TIMETYPE_MONTH
240
- * 				- RTC_TIMETYPE_YEAR
241
- * @param[in]	NewState New State of this function, should be:
242
- * 				- ENABLE: Alarm interrupt for this
243
- * 					time type are enabled
244
- * 				- DISABLE: Alarm interrupt for this
245
- * 					time type are disabled
246
- * @return 		None
247
- **********************************************************************/
248
-void RTC_AlarmIntConfig (LPC_RTC_TypeDef *RTCx, uint32_t AlarmTimeType, \
249
-								FunctionalState NewState)
250
-{
251
-	CHECK_PARAM(PARAM_RTCx(RTCx));
252
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
253
-	CHECK_PARAM(PARAM_RTC_TIMETYPE(AlarmTimeType));
254
-
255
-	if (NewState == ENABLE)
256
-	{
257
-		switch (AlarmTimeType)
258
-		{
259
-		case RTC_TIMETYPE_SECOND:
260
-			RTCx->AMR &= (~RTC_AMR_AMRSEC) & RTC_AMR_BITMASK;
261
-			break;
262
-		case RTC_TIMETYPE_MINUTE:
263
-			RTCx->AMR &= (~RTC_AMR_AMRMIN) & RTC_AMR_BITMASK;
264
-			break;
265
-		case RTC_TIMETYPE_HOUR:
266
-			RTCx->AMR &= (~RTC_AMR_AMRHOUR) & RTC_AMR_BITMASK;
267
-			break;
268
-		case RTC_TIMETYPE_DAYOFWEEK:
269
-			RTCx->AMR &= (~RTC_AMR_AMRDOW) & RTC_AMR_BITMASK;
270
-			break;
271
-		case RTC_TIMETYPE_DAYOFMONTH:
272
-			RTCx->AMR &= (~RTC_AMR_AMRDOM) & RTC_AMR_BITMASK;
273
-			break;
274
-		case RTC_TIMETYPE_DAYOFYEAR:
275
-			RTCx->AMR &= (~RTC_AMR_AMRDOY) & RTC_AMR_BITMASK;
276
-			break;
277
-		case RTC_TIMETYPE_MONTH:
278
-			RTCx->AMR &= (~RTC_AMR_AMRMON) & RTC_AMR_BITMASK;
279
-			break;
280
-		case RTC_TIMETYPE_YEAR:
281
-			RTCx->AMR &= (~RTC_AMR_AMRYEAR) & RTC_AMR_BITMASK;
282
-			break;
283
-		}
284
-	}
285
-	else
286
-	{
287
-		switch (AlarmTimeType)
288
-		{
289
-		case RTC_TIMETYPE_SECOND:
290
-			RTCx->AMR |= (RTC_AMR_AMRSEC);
291
-			break;
292
-		case RTC_TIMETYPE_MINUTE:
293
-			RTCx->AMR |= (RTC_AMR_AMRMIN);
294
-			break;
295
-		case RTC_TIMETYPE_HOUR:
296
-			RTCx->AMR |= (RTC_AMR_AMRHOUR);
297
-			break;
298
-		case RTC_TIMETYPE_DAYOFWEEK:
299
-			RTCx->AMR |= (RTC_AMR_AMRDOW);
300
-			break;
301
-		case RTC_TIMETYPE_DAYOFMONTH:
302
-			RTCx->AMR |= (RTC_AMR_AMRDOM);
303
-			break;
304
-		case RTC_TIMETYPE_DAYOFYEAR:
305
-			RTCx->AMR |= (RTC_AMR_AMRDOY);
306
-			break;
307
-		case RTC_TIMETYPE_MONTH:
308
-			RTCx->AMR |= (RTC_AMR_AMRMON);
309
-			break;
310
-		case RTC_TIMETYPE_YEAR:
311
-			RTCx->AMR |= (RTC_AMR_AMRYEAR);
312
-			break;
313
-		}
314
-	}
315
-}
316
-
317
-
318
-/*********************************************************************//**
319
- * @brief 		Set current time value for each time type in RTC peripheral
320
- * @param[in]	RTCx	RTC peripheral selected, should be LPC_RTC
321
- * @param[in]	Timetype: Time Type, should be:
322
- * 				- RTC_TIMETYPE_SECOND
323
- * 				- RTC_TIMETYPE_MINUTE
324
- * 				- RTC_TIMETYPE_HOUR
325
- * 				- RTC_TIMETYPE_DAYOFWEEK
326
- * 				- RTC_TIMETYPE_DAYOFMONTH
327
- * 				- RTC_TIMETYPE_DAYOFYEAR
328
- * 				- RTC_TIMETYPE_MONTH
329
- * 				- RTC_TIMETYPE_YEAR
330
- * @param[in]	TimeValue Time value to set
331
- * @return 		None
332
- **********************************************************************/
333
-void RTC_SetTime (LPC_RTC_TypeDef *RTCx, uint32_t Timetype, uint32_t TimeValue)
334
-{
335
-	CHECK_PARAM(PARAM_RTCx(RTCx));
336
-	CHECK_PARAM(PARAM_RTC_TIMETYPE(Timetype));
337
-
338
-	switch ( Timetype)
339
-	{
340
-	case RTC_TIMETYPE_SECOND:
341
-		CHECK_PARAM(TimeValue <= RTC_SECOND_MAX);
342
-
343
-		RTCx->SEC = TimeValue & RTC_SEC_MASK;
344
-		break;
345
-
346
-	case RTC_TIMETYPE_MINUTE:
347
-		CHECK_PARAM(TimeValue <= RTC_MINUTE_MAX);
348
-
349
-		RTCx->MIN = TimeValue & RTC_MIN_MASK;
350
-		break;
351
-
352
-	case RTC_TIMETYPE_HOUR:
353
-		CHECK_PARAM(TimeValue <= RTC_HOUR_MAX);
354
-
355
-		RTCx->HOUR = TimeValue & RTC_HOUR_MASK;
356
-		break;
357
-
358
-	case RTC_TIMETYPE_DAYOFWEEK:
359
-		CHECK_PARAM(TimeValue <= RTC_DAYOFWEEK_MAX);
360
-
361
-		RTCx->DOW = TimeValue & RTC_DOW_MASK;
362
-		break;
363
-
364
-	case RTC_TIMETYPE_DAYOFMONTH:
365
-		CHECK_PARAM((TimeValue <= RTC_DAYOFMONTH_MAX) \
366
-				&& (TimeValue >= RTC_DAYOFMONTH_MIN));
367
-
368
-		RTCx->DOM = TimeValue & RTC_DOM_MASK;
369
-		break;
370
-
371
-	case RTC_TIMETYPE_DAYOFYEAR:
372
-		CHECK_PARAM((TimeValue >= RTC_DAYOFYEAR_MIN) \
373
-				&& (TimeValue <= RTC_DAYOFYEAR_MAX));
374
-
375
-		RTCx->DOY = TimeValue & RTC_DOY_MASK;
376
-		break;
377
-
378
-	case RTC_TIMETYPE_MONTH:
379
-		CHECK_PARAM((TimeValue >= RTC_MONTH_MIN) \
380
-				&& (TimeValue <= RTC_MONTH_MAX));
381
-
382
-		RTCx->MONTH = TimeValue & RTC_MONTH_MASK;
383
-		break;
384
-
385
-	case RTC_TIMETYPE_YEAR:
386
-		CHECK_PARAM(TimeValue <= RTC_YEAR_MAX);
387
-
388
-		RTCx->YEAR = TimeValue & RTC_YEAR_MASK;
389
-		break;
390
-	}
391
-}
392
-
393
-/*********************************************************************//**
394
- * @brief 		Get current time value for each type time type
395
- * @param[in]	RTCx	RTC peripheral selected, should be LPC_RTC
396
- * @param[in]	Timetype: Time Type, should be:
397
- * 				- RTC_TIMETYPE_SECOND
398
- * 				- RTC_TIMETYPE_MINUTE
399
- * 				- RTC_TIMETYPE_HOUR
400
- * 				- RTC_TIMETYPE_DAYOFWEEK
401
- * 				- RTC_TIMETYPE_DAYOFMONTH
402
- * 				- RTC_TIMETYPE_DAYOFYEAR
403
- * 				- RTC_TIMETYPE_MONTH
404
- * 				- RTC_TIMETYPE_YEAR
405
- * @return 		Value of time according to specified time type
406
- **********************************************************************/
407
-uint32_t RTC_GetTime(LPC_RTC_TypeDef *RTCx, uint32_t Timetype)
408
-{
409
-	CHECK_PARAM(PARAM_RTCx(RTCx));
410
-	CHECK_PARAM(PARAM_RTC_TIMETYPE(Timetype));
411
-
412
-	switch (Timetype)
413
-	{
414
-	case RTC_TIMETYPE_SECOND:
415
-		return (RTCx->SEC & RTC_SEC_MASK);
416
-	case RTC_TIMETYPE_MINUTE:
417
-		return (RTCx->MIN & RTC_MIN_MASK);
418
-	case RTC_TIMETYPE_HOUR:
419
-		return (RTCx->HOUR & RTC_HOUR_MASK);
420
-	case RTC_TIMETYPE_DAYOFWEEK:
421
-		return (RTCx->DOW & RTC_DOW_MASK);
422
-	case RTC_TIMETYPE_DAYOFMONTH:
423
-		return (RTCx->DOM & RTC_DOM_MASK);
424
-	case RTC_TIMETYPE_DAYOFYEAR:
425
-		return (RTCx->DOY & RTC_DOY_MASK);
426
-	case RTC_TIMETYPE_MONTH:
427
-		return (RTCx->MONTH & RTC_MONTH_MASK);
428
-	case RTC_TIMETYPE_YEAR:
429
-		return (RTCx->YEAR & RTC_YEAR_MASK);
430
-	default:
431
-		return (0);
432
-	}
433
-}
434
-
435
-
436
-/*********************************************************************//**
437
- * @brief 		Set full of time in RTC peripheral
438
- * @param[in]	RTCx	RTC peripheral selected, should be LPC_RTC
439
- * @param[in]	pFullTime Pointer to a RTC_TIME_Type structure that
440
- * 				contains time value in full.
441
- * @return 		None
442
- **********************************************************************/
443
-void RTC_SetFullTime (LPC_RTC_TypeDef *RTCx, RTC_TIME_Type *pFullTime)
444
-{
445
-	CHECK_PARAM(PARAM_RTCx(RTCx));
446
-
447
-	RTCx->DOM = pFullTime->DOM & RTC_DOM_MASK;
448
-	RTCx->DOW = pFullTime->DOW & RTC_DOW_MASK;
449
-	RTCx->DOY = pFullTime->DOY & RTC_DOY_MASK;
450
-	RTCx->HOUR = pFullTime->HOUR & RTC_HOUR_MASK;
451
-	RTCx->MIN = pFullTime->MIN & RTC_MIN_MASK;
452
-	RTCx->SEC = pFullTime->SEC & RTC_SEC_MASK;
453
-	RTCx->MONTH = pFullTime->MONTH & RTC_MONTH_MASK;
454
-	RTCx->YEAR = pFullTime->YEAR & RTC_YEAR_MASK;
455
-}
456
-
457
-
458
-/*********************************************************************//**
459
- * @brief 		Get full of time in RTC peripheral
460
- * @param[in]	RTCx	RTC peripheral selected, should be LPC_RTC
461
- * @param[in]	pFullTime Pointer to a RTC_TIME_Type structure that
462
- * 				will be stored time in full.
463
- * @return 		None
464
- **********************************************************************/
465
-void RTC_GetFullTime (LPC_RTC_TypeDef *RTCx, RTC_TIME_Type *pFullTime)
466
-{
467
-	CHECK_PARAM(PARAM_RTCx(RTCx));
468
-
469
-	pFullTime->DOM = RTCx->DOM & RTC_DOM_MASK;
470
-	pFullTime->DOW = RTCx->DOW & RTC_DOW_MASK;
471
-	pFullTime->DOY = RTCx->DOY & RTC_DOY_MASK;
472
-	pFullTime->HOUR = RTCx->HOUR & RTC_HOUR_MASK;
473
-	pFullTime->MIN = RTCx->MIN & RTC_MIN_MASK;
474
-	pFullTime->SEC = RTCx->SEC & RTC_SEC_MASK;
475
-	pFullTime->MONTH = RTCx->MONTH & RTC_MONTH_MASK;
476
-	pFullTime->YEAR = RTCx->YEAR & RTC_YEAR_MASK;
477
-}
478
-
479
-
480
-/*********************************************************************//**
481
- * @brief 		Set alarm time value for each time type
482
- * @param[in]	RTCx	RTC peripheral selected, should be LPC_RTC
483
- * @param[in]	Timetype: Time Type, should be:
484
- * 				- RTC_TIMETYPE_SECOND
485
- * 				- RTC_TIMETYPE_MINUTE
486
- * 				- RTC_TIMETYPE_HOUR
487
- * 				- RTC_TIMETYPE_DAYOFWEEK
488
- * 				- RTC_TIMETYPE_DAYOFMONTH
489
- * 				- RTC_TIMETYPE_DAYOFYEAR
490
- * 				- RTC_TIMETYPE_MONTH
491
- * 				- RTC_TIMETYPE_YEAR
492
- * @param[in]	ALValue Alarm time value to set
493
- * @return 		None
494
- **********************************************************************/
495
-void RTC_SetAlarmTime (LPC_RTC_TypeDef *RTCx, uint32_t Timetype, uint32_t ALValue)
496
-{
497
-	CHECK_PARAM(PARAM_RTCx(RTCx));
498
-
499
-	switch (Timetype)
500
-	{
501
-	case RTC_TIMETYPE_SECOND:
502
-		CHECK_PARAM(ALValue <= RTC_SECOND_MAX);
503
-
504
-		RTCx->ALSEC = ALValue & RTC_SEC_MASK;
505
-		break;
506
-
507
-	case RTC_TIMETYPE_MINUTE:
508
-		CHECK_PARAM(ALValue <= RTC_MINUTE_MAX);
509
-
510
-		RTCx->ALMIN = ALValue & RTC_MIN_MASK;
511
-		break;
512
-
513
-	case RTC_TIMETYPE_HOUR:
514
-		CHECK_PARAM(ALValue <= RTC_HOUR_MAX);
515
-
516
-		RTCx->ALHOUR = ALValue & RTC_HOUR_MASK;
517
-		break;
518
-
519
-	case RTC_TIMETYPE_DAYOFWEEK:
520
-		CHECK_PARAM(ALValue <= RTC_DAYOFWEEK_MAX);
521
-
522
-		RTCx->ALDOW = ALValue & RTC_DOW_MASK;
523
-		break;
524
-
525
-	case RTC_TIMETYPE_DAYOFMONTH:
526
-		CHECK_PARAM((ALValue <= RTC_DAYOFMONTH_MAX) \
527
-				&& (ALValue >= RTC_DAYOFMONTH_MIN));
528
-
529
-		RTCx->ALDOM = ALValue & RTC_DOM_MASK;
530
-		break;
531
-
532
-	case RTC_TIMETYPE_DAYOFYEAR:
533
-		CHECK_PARAM((ALValue >= RTC_DAYOFYEAR_MIN) \
534
-				&& (ALValue <= RTC_DAYOFYEAR_MAX));
535
-
536
-		RTCx->ALDOY = ALValue & RTC_DOY_MASK;
537
-		break;
538
-
539
-	case RTC_TIMETYPE_MONTH:
540
-		CHECK_PARAM((ALValue >= RTC_MONTH_MIN) \
541
-				&& (ALValue <= RTC_MONTH_MAX));
542
-
543
-		RTCx->ALMON = ALValue & RTC_MONTH_MASK;
544
-		break;
545
-
546
-	case RTC_TIMETYPE_YEAR:
547
-		CHECK_PARAM(ALValue <= RTC_YEAR_MAX);
548
-
549
-		RTCx->ALYEAR = ALValue & RTC_YEAR_MASK;
550
-		break;
551
-	}
552
-}
553
-
554
-
555
-
556
-/*********************************************************************//**
557
- * @brief 		Get alarm time value for each time type
558
- * @param[in]	RTCx	RTC peripheral selected, should be LPC_RTC
559
- * @param[in]	Timetype: Time Type, should be:
560
- * 				- RTC_TIMETYPE_SECOND
561
- * 				- RTC_TIMETYPE_MINUTE
562
- * 				- RTC_TIMETYPE_HOUR
563
- * 				- RTC_TIMETYPE_DAYOFWEEK
564
- * 				- RTC_TIMETYPE_DAYOFMONTH
565
- * 				- RTC_TIMETYPE_DAYOFYEAR
566
- * 				- RTC_TIMETYPE_MONTH
567
- * 				- RTC_TIMETYPE_YEAR
568
-  * @return 	Value of Alarm time according to specified time type
569
- **********************************************************************/
570
-uint32_t RTC_GetAlarmTime (LPC_RTC_TypeDef *RTCx, uint32_t Timetype)
571
-{
572
-	switch (Timetype)
573
-	{
574
-	case RTC_TIMETYPE_SECOND:
575
-		return (RTCx->ALSEC & RTC_SEC_MASK);
576
-	case RTC_TIMETYPE_MINUTE:
577
-		return (RTCx->ALMIN & RTC_MIN_MASK);
578
-	case RTC_TIMETYPE_HOUR:
579
-		return (RTCx->ALHOUR & RTC_HOUR_MASK);
580
-	case RTC_TIMETYPE_DAYOFWEEK:
581
-		return (RTCx->ALDOW & RTC_DOW_MASK);
582
-	case RTC_TIMETYPE_DAYOFMONTH:
583
-		return (RTCx->ALDOM & RTC_DOM_MASK);
584
-	case RTC_TIMETYPE_DAYOFYEAR:
585
-		return (RTCx->ALDOY & RTC_DOY_MASK);
586
-	case RTC_TIMETYPE_MONTH:
587
-		return (RTCx->ALMON & RTC_MONTH_MASK);
588
-	case RTC_TIMETYPE_YEAR:
589
-		return (RTCx->ALYEAR & RTC_YEAR_MASK);
590
-	default:
591
-		return (0);
592
-	}
593
-}
594
-
595
-
596
-/*********************************************************************//**
597
- * @brief 		Set full of alarm time in RTC peripheral
598
- * @param[in]	RTCx	RTC peripheral selected, should be LPC_RTC
599
- * @param[in]	pFullTime Pointer to a RTC_TIME_Type structure that
600
- * 				contains alarm time value in full.
601
- * @return 		None
602
- **********************************************************************/
603
-void RTC_SetFullAlarmTime (LPC_RTC_TypeDef *RTCx, RTC_TIME_Type *pFullTime)
604
-{
605
-	CHECK_PARAM(PARAM_RTCx(RTCx));
606
-
607
-	RTCx->ALDOM = pFullTime->DOM & RTC_DOM_MASK;
608
-	RTCx->ALDOW = pFullTime->DOW & RTC_DOW_MASK;
609
-	RTCx->ALDOY = pFullTime->DOY & RTC_DOY_MASK;
610
-	RTCx->ALHOUR = pFullTime->HOUR & RTC_HOUR_MASK;
611
-	RTCx->ALMIN = pFullTime->MIN & RTC_MIN_MASK;
612
-	RTCx->ALSEC = pFullTime->SEC & RTC_SEC_MASK;
613
-	RTCx->ALMON = pFullTime->MONTH & RTC_MONTH_MASK;
614
-	RTCx->ALYEAR = pFullTime->YEAR & RTC_YEAR_MASK;
615
-}
616
-
617
-
618
-/*********************************************************************//**
619
- * @brief 		Get full of alarm time in RTC peripheral
620
- * @param[in]	RTCx	RTC peripheral selected, should be LPC_RTC
621
- * @param[in]	pFullTime Pointer to a RTC_TIME_Type structure that
622
- * 				will be stored alarm time in full.
623
- * @return 		None
624
- **********************************************************************/
625
-void RTC_GetFullAlarmTime (LPC_RTC_TypeDef *RTCx, RTC_TIME_Type *pFullTime)
626
-{
627
-	CHECK_PARAM(PARAM_RTCx(RTCx));
628
-
629
-	pFullTime->DOM = RTCx->ALDOM & RTC_DOM_MASK;
630
-	pFullTime->DOW = RTCx->ALDOW & RTC_DOW_MASK;
631
-	pFullTime->DOY = RTCx->ALDOY & RTC_DOY_MASK;
632
-	pFullTime->HOUR = RTCx->ALHOUR & RTC_HOUR_MASK;
633
-	pFullTime->MIN = RTCx->ALMIN & RTC_MIN_MASK;
634
-	pFullTime->SEC = RTCx->ALSEC & RTC_SEC_MASK;
635
-	pFullTime->MONTH = RTCx->ALMON & RTC_MONTH_MASK;
636
-	pFullTime->YEAR = RTCx->ALYEAR & RTC_YEAR_MASK;
637
-}
638
-
639
-
640
-/*********************************************************************//**
641
- * @brief 		Check whether if specified Location interrupt in
642
- * 				RTC peripheral is set or not
643
- * @param[in]	RTCx	RTC peripheral selected, should be LPC_RTC
644
- * @param[in]	IntType Interrupt location type, should be:
645
- * 						- RTC_INT_COUNTER_INCREASE: Counter Increment Interrupt
646
- * 							block generated an interrupt.
647
- * 						- RTC_INT_ALARM: Alarm generated an
648
- * 							interrupt.
649
- * @return 		New state of specified Location interrupt in RTC peripheral
650
- * 				(SET or RESET)
651
- **********************************************************************/
652
-IntStatus RTC_GetIntPending (LPC_RTC_TypeDef *RTCx, uint32_t IntType)
653
-{
654
-	CHECK_PARAM(PARAM_RTCx(RTCx));
655
-	CHECK_PARAM(PARAM_RTC_INT(IntType));
656
-
657
-	return ((RTCx->ILR & IntType) ? SET : RESET);
658
-}
659
-
660
-
661
-/*********************************************************************//**
662
- * @brief 		Clear specified Location interrupt pending in
663
- * 				RTC peripheral
664
- * @param[in]	RTCx	RTC peripheral selected, should be LPC_RTC
665
- * @param[in]	IntType Interrupt location type, should be:
666
- * 						- RTC_INT_COUNTER_INCREASE: Clear Counter Increment
667
- * 						Interrupt pending.
668
- * 						- RTC_INT_ALARM: Clear alarm interrupt pending
669
- * @return 		None
670
- **********************************************************************/
671
-void RTC_ClearIntPending (LPC_RTC_TypeDef *RTCx, uint32_t IntType)
672
-{
673
-	CHECK_PARAM(PARAM_RTCx(RTCx));
674
-	CHECK_PARAM(PARAM_RTC_INT(IntType));
675
-
676
-	RTCx->ILR |= IntType;
677
-}
678
-
679
-/*********************************************************************//**
680
- * @brief 		Enable/Disable calibration counter in RTC peripheral
681
- * @param[in]	RTCx	RTC peripheral selected, should be LPC_RTC
682
- * @param[in]	NewState New State of this function, should be:
683
- * 				- ENABLE: The calibration counter is enabled and counting
684
- * 				- DISABLE: The calibration counter is disabled and reset to zero
685
- * @return 		None
686
- **********************************************************************/
687
-void RTC_CalibCounterCmd(LPC_RTC_TypeDef *RTCx, FunctionalState NewState)
688
-{
689
-	CHECK_PARAM(PARAM_RTCx(RTCx));
690
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
691
-
692
-	if (NewState == ENABLE)
693
-	{
694
-		RTCx->CCR &= (~RTC_CCR_CCALEN) & RTC_CCR_BITMASK;
695
-	}
696
-	else
697
-	{
698
-		RTCx->CCR |= RTC_CCR_CCALEN;
699
-	}
700
-}
701
-
702
-
703
-/*********************************************************************//**
704
- * @brief 		Configures Calibration in RTC peripheral
705
- * @param[in]	RTCx	RTC peripheral selected, should be LPC_RTC
706
- * @param[in]	CalibValue Calibration value, should be in range from
707
- * 					0 to 131,072
708
- * @param[in]	CalibDir Calibration Direction, should be:
709
- * 					- RTC_CALIB_DIR_FORWARD: Forward calibration
710
- * 					- RTC_CALIB_DIR_BACKWARD: Backward calibration
711
- * @return 		None
712
- **********************************************************************/
713
-void RTC_CalibConfig(LPC_RTC_TypeDef *RTCx, uint32_t CalibValue, uint8_t CalibDir)
714
-{
715
-	CHECK_PARAM(PARAM_RTCx(RTCx));
716
-	CHECK_PARAM(PARAM_RTC_CALIB_DIR(CalibDir));
717
-	CHECK_PARAM(CalibValue < RTC_CALIBRATION_MAX);
718
-
719
-	RTCx->CALIBRATION = ((CalibValue) & RTC_CALIBRATION_CALVAL_MASK) \
720
-			| ((CalibDir == RTC_CALIB_DIR_BACKWARD) ? RTC_CALIBRATION_LIBDIR : 0);
721
-}
722
-
723
-
724
-/*********************************************************************//**
725
- * @brief 		Write value to General purpose registers
726
- * @param[in]	RTCx	RTC peripheral selected, should be LPC_RTC
727
- * @param[in]	Channel General purpose registers Channel number,
728
- * 				should be in range from 0 to 4.
729
- * @param[in]	Value Value to write
730
- * @return 		None
731
- * Note: These General purpose registers can be used to store important
732
- * information when the main power supply is off. The value in these
733
- * registers is not affected by chip reset.
734
- **********************************************************************/
735
-void RTC_WriteGPREG (LPC_RTC_TypeDef *RTCx, uint8_t Channel, uint32_t Value)
736
-{
737
-	uint32_t *preg;
738
-
739
-	CHECK_PARAM(PARAM_RTCx(RTCx));
740
-	CHECK_PARAM(PARAM_RTC_GPREG_CH(Channel));
741
-
742
-	preg = (uint32_t *)&RTCx->GPREG0;
743
-	preg += Channel;
744
-	*preg = Value;
745
-}
746
-
747
-
748
-/*********************************************************************//**
749
- * @brief 		Read value from General purpose registers
750
- * @param[in]	RTCx	RTC peripheral selected, should be LPC_RTC
751
- * @param[in]	Channel General purpose registers Channel number,
752
- * 				should be in range from 0 to 4.
753
- * @return 		Read Value
754
- * Note: These General purpose registers can be used to store important
755
- * information when the main power supply is off. The value in these
756
- * registers is not affected by chip reset.
757
- **********************************************************************/
758
-uint32_t RTC_ReadGPREG (LPC_RTC_TypeDef *RTCx, uint8_t Channel)
759
-{
760
-	uint32_t *preg;
761
-	uint32_t value;
762
-
763
-	CHECK_PARAM(PARAM_RTCx(RTCx));
764
-	CHECK_PARAM(PARAM_RTC_GPREG_CH(Channel));
765
-
766
-	preg = (uint32_t *)&RTCx->GPREG0;
767
-	preg += Channel;
768
-	value = *preg;
769
-	return (value);
770
-}
771
-
772
-/**
773
- * @}
774
- */
775
-
776
-#endif /* _RTC */
777
-
778
-/**
779
- * @}
780
- */
781
-
782
-/* --------------------------------- End Of File ------------------------------ */
783
-

+ 0
- 443
frameworks/CMSIS/LPC1768/driver/lpc17xx_spi.c Просмотреть файл

@@ -1,443 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_spi.c				2010-05-21
3
-*//**
4
-* @file		lpc17xx_spi.c
5
-* @brief	Contains all functions support for SPI firmware library on LPC17xx
6
-* @version	2.0
7
-* @date		21. May. 2010
8
-* @author	NXP MCU SW Application Team
9
-*
10
-* Copyright(C) 2010, NXP Semiconductor
11
-* All rights reserved.
12
-*
13
-***********************************************************************
14
-* Software that is described herein is for illustrative purposes only
15
-* which provides customers with programming information regarding the
16
-* products. This software is supplied "AS IS" without any warranties.
17
-* NXP Semiconductors assumes no responsibility or liability for the
18
-* use of the software, conveys no license or title under any patent,
19
-* copyright, or mask work right to the product. NXP Semiconductors
20
-* reserves the right to make changes in the software without
21
-* notification. NXP Semiconductors also make no representation or
22
-* warranty that such application will be suitable for the specified
23
-* use without further testing or modification.
24
-* Permission to use, copy, modify, and distribute this software and its
25
-* documentation is hereby granted, under NXP Semiconductors'
26
-* relevant copyright in the software, without fee, provided that it
27
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
28
-* copyright, permission, and disclaimer notice must appear in all copies of
29
-* this code.
30
-**********************************************************************/
31
-
32
-/* Peripheral group ----------------------------------------------------------- */
33
-/** @addtogroup SPI
34
- * @{
35
- */
36
-
37
-/* Includes ------------------------------------------------------------------- */
38
-#include "lpc17xx_spi.h"
39
-#include "lpc17xx_clkpwr.h"
40
-
41
-/* If this source file built with example, the LPC17xx FW library configuration
42
- * file in each example directory ("lpc17xx_libcfg.h") must be included,
43
- * otherwise the default FW library configuration file must be included instead
44
- */
45
-#ifdef __BUILD_WITH_EXAMPLE__
46
-#include "lpc17xx_libcfg.h"
47
-#else
48
-#include "lpc17xx_libcfg_default.h"
49
-#endif /* __BUILD_WITH_EXAMPLE__ */
50
-
51
-#ifdef _SPI
52
-
53
-
54
-/* Public Functions ----------------------------------------------------------- */
55
-/** @addtogroup SPI_Public_Functions
56
- * @{
57
- */
58
-
59
-/*********************************************************************//**
60
- * @brief 		Setup clock rate for SPI device
61
- * @param[in] 	SPIx	SPI peripheral definition, should be LPC_SPI
62
- * @param[in]	target_clock : clock of SPI (Hz)
63
- * @return 		None
64
- ***********************************************************************/
65
-void SPI_SetClock (LPC_SPI_TypeDef *SPIx, uint32_t target_clock)
66
-{
67
-	uint32_t spi_pclk;
68
-	uint32_t prescale, temp;
69
-
70
-	CHECK_PARAM(PARAM_SPIx(SPIx));
71
-
72
-	if (SPIx == LPC_SPI){
73
-		spi_pclk =  CLKPWR_GetPCLK (CLKPWR_PCLKSEL_SPI);
74
-	} else {
75
-		return;
76
-	}
77
-
78
-	prescale = 8;
79
-	// Find closest clock to target clock
80
-	while (1){
81
-		temp = target_clock * prescale;
82
-		if (temp >= spi_pclk){
83
-			break;
84
-		}
85
-		prescale += 2;
86
-		if(prescale >= 254){
87
-			break;
88
-		}
89
-	}
90
-
91
-	// Write to register
92
-	SPIx->SPCCR = SPI_SPCCR_COUNTER(prescale);
93
-}
94
-
95
-
96
-/*********************************************************************//**
97
- * @brief		De-initializes the SPIx peripheral registers to their
98
-*                  default reset values.
99
- * @param[in]	SPIx	SPI peripheral selected, should be LPC_SPI
100
- * @return 		None
101
- **********************************************************************/
102
-void SPI_DeInit(LPC_SPI_TypeDef *SPIx)
103
-{
104
-	CHECK_PARAM(PARAM_SPIx(SPIx));
105
-
106
-	if (SPIx == LPC_SPI){
107
-		/* Set up clock and power for SPI module */
108
-		CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCSPI, DISABLE);
109
-	}
110
-}
111
-
112
-/*********************************************************************//**
113
- * @brief		Get data bit size per transfer
114
- * @param[in]	SPIx	SPI peripheral selected, should be LPC_SPI
115
- * @return 		number of bit per transfer, could be 8-16
116
- **********************************************************************/
117
-uint8_t SPI_GetDataSize (LPC_SPI_TypeDef *SPIx)
118
-{
119
-	CHECK_PARAM(PARAM_SPIx(SPIx));
120
-	return ((SPIx->SPCR)>>8 & 0xF);
121
-}
122
-
123
-/********************************************************************//**
124
- * @brief		Initializes the SPIx peripheral according to the specified
125
-*               parameters in the UART_ConfigStruct.
126
- * @param[in]	SPIx	SPI peripheral selected, should be LPC_SPI
127
- * @param[in]	SPI_ConfigStruct Pointer to a SPI_CFG_Type structure
128
-*                    that contains the configuration information for the
129
-*                    specified SPI peripheral.
130
- * @return 		None
131
- *********************************************************************/
132
-void SPI_Init(LPC_SPI_TypeDef *SPIx, SPI_CFG_Type *SPI_ConfigStruct)
133
-{
134
-	uint32_t tmp;
135
-
136
-	CHECK_PARAM(PARAM_SPIx(SPIx));
137
-
138
-	if(SPIx == LPC_SPI){
139
-		/* Set up clock and power for UART module */
140
-		CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCSPI, ENABLE);
141
-	} else {
142
-		return;
143
-	}
144
-
145
-	// Configure SPI, interrupt is disable as default
146
-	tmp = ((SPI_ConfigStruct->CPHA) | (SPI_ConfigStruct->CPOL) \
147
-		| (SPI_ConfigStruct->DataOrder) | (SPI_ConfigStruct->Databit) \
148
-		| (SPI_ConfigStruct->Mode) | SPI_SPCR_BIT_EN) & SPI_SPCR_BITMASK;
149
-	// write back to SPI control register
150
-	SPIx->SPCR = tmp;
151
-
152
-	// Set clock rate for SPI peripheral
153
-	SPI_SetClock(SPIx, SPI_ConfigStruct->ClockRate);
154
-
155
-	// If interrupt flag is set, Write '1' to Clear interrupt flag
156
-	if (SPIx->SPINT & SPI_SPINT_INTFLAG){
157
-		SPIx->SPINT = SPI_SPINT_INTFLAG;
158
-	}
159
-}
160
-
161
-
162
-
163
-/*****************************************************************************//**
164
-* @brief		Fills each SPI_InitStruct member with its default value:
165
-* 				- CPHA = SPI_CPHA_FIRST
166
-* 				- CPOL = SPI_CPOL_HI
167
-* 				- ClockRate = 1000000
168
-* 				- DataOrder = SPI_DATA_MSB_FIRST
169
-* 				- Databit = SPI_DATABIT_8
170
-* 				- Mode = SPI_MASTER_MODE
171
-* @param[in]	SPI_InitStruct Pointer to a SPI_CFG_Type structure
172
-*                    which will be initialized.
173
-* @return		None
174
-*******************************************************************************/
175
-void SPI_ConfigStructInit(SPI_CFG_Type *SPI_InitStruct)
176
-{
177
-	SPI_InitStruct->CPHA = SPI_CPHA_FIRST;
178
-	SPI_InitStruct->CPOL = SPI_CPOL_HI;
179
-	SPI_InitStruct->ClockRate = 1000000;
180
-	SPI_InitStruct->DataOrder = SPI_DATA_MSB_FIRST;
181
-	SPI_InitStruct->Databit = SPI_DATABIT_8;
182
-	SPI_InitStruct->Mode = SPI_MASTER_MODE;
183
-}
184
-
185
-/*********************************************************************//**
186
- * @brief		Transmit a single data through SPIx peripheral
187
- * @param[in]	SPIx	SPI peripheral selected, should be LPC_SPI
188
- * @param[in]	Data	Data to transmit (must be 16 or 8-bit long,
189
- * 						this depend on SPI data bit number configured)
190
- * @return 		none
191
- **********************************************************************/
192
-void SPI_SendData(LPC_SPI_TypeDef* SPIx, uint16_t Data)
193
-{
194
-	CHECK_PARAM(PARAM_SPIx(SPIx));
195
-
196
-	SPIx->SPDR = Data & SPI_SPDR_BITMASK;
197
-}
198
-
199
-
200
-
201
-/*********************************************************************//**
202
- * @brief		Receive a single data from SPIx peripheral
203
- * @param[in]	SPIx	SPI peripheral selected, should be LPC_SPI
204
- * @return 		Data received (16-bit long)
205
- **********************************************************************/
206
-uint16_t SPI_ReceiveData(LPC_SPI_TypeDef* SPIx)
207
-{
208
-	CHECK_PARAM(PARAM_SPIx(SPIx));
209
-
210
-	return ((uint16_t) (SPIx->SPDR & SPI_SPDR_BITMASK));
211
-}
212
-
213
-/*********************************************************************//**
214
- * @brief 		SPI 	Read write data function
215
- * @param[in]	SPIx 	Pointer to SPI peripheral, should be LPC_SPI
216
- * @param[in]	dataCfg	Pointer to a SPI_DATA_SETUP_Type structure that
217
- * 						contains specified information about transmit
218
- * 						data configuration.
219
- * @param[in]	xfType	Transfer type, should be:
220
- * 						- SPI_TRANSFER_POLLING: Polling mode
221
- * 						- SPI_TRANSFER_INTERRUPT: Interrupt mode
222
- * @return 		Actual Data length has been transferred in polling mode.
223
- * 				In interrupt mode, always return (0)
224
- * 				Return (-1) if error.
225
- * Note: This function can be used in both master and slave mode.
226
- ***********************************************************************/
227
-int32_t SPI_ReadWrite (LPC_SPI_TypeDef *SPIx, SPI_DATA_SETUP_Type *dataCfg, \
228
-						SPI_TRANSFER_Type xfType)
229
-{
230
-	uint8_t *rdata8;
231
-    uint8_t *wdata8;
232
-	uint16_t *rdata16;
233
-    uint16_t *wdata16;
234
-    uint32_t stat;
235
-    uint32_t temp;
236
-    uint8_t dataword;
237
-
238
-	//read for empty buffer
239
-	temp = SPIx->SPDR;
240
-	//dummy to clear status
241
-	temp = SPIx->SPSR;
242
-	dataCfg->counter = 0;
243
-	dataCfg->status = 0;
244
-
245
-	if(SPI_GetDataSize (SPIx) == 8)
246
-		dataword = 0;
247
-	else dataword = 1;
248
-	if (xfType == SPI_TRANSFER_POLLING){
249
-
250
-		if (dataword == 0){
251
-			rdata8 = (uint8_t *)dataCfg->rx_data;
252
-			wdata8 = (uint8_t *)dataCfg->tx_data;
253
-		} else {
254
-			rdata16 = (uint16_t *)dataCfg->rx_data;
255
-			wdata16 = (uint16_t *)dataCfg->tx_data;
256
-		}
257
-
258
-		while(dataCfg->counter < dataCfg->length)
259
-		{
260
-			// Write data to buffer
261
-			if(dataCfg->tx_data == NULL){
262
-				if (dataword == 0){
263
-					SPI_SendData(SPIx, 0xFF);
264
-				} else {
265
-					SPI_SendData(SPIx, 0xFFFF);
266
-				}
267
-			} else {
268
-				if (dataword == 0){
269
-					SPI_SendData(SPIx, *wdata8);
270
-					wdata8++;
271
-				} else {
272
-					SPI_SendData(SPIx, *wdata16);
273
-					wdata16++;
274
-				}
275
-			}
276
-			// Wait for transfer complete
277
-			while (!((stat = SPIx->SPSR) & SPI_SPSR_SPIF));
278
-			// Check for error
279
-			if (stat & (SPI_SPSR_ABRT | SPI_SPSR_MODF | SPI_SPSR_ROVR | SPI_SPSR_WCOL)){
280
-				// save status
281
-				dataCfg->status = stat | SPI_STAT_ERROR;
282
-				return (dataCfg->counter);
283
-			}
284
-			// Read data from SPI dat
285
-			temp = (uint32_t) SPI_ReceiveData(SPIx);
286
-
287
-			// Store data to destination
288
-			if (dataCfg->rx_data != NULL)
289
-			{
290
-				if (dataword == 0){
291
-					*(rdata8) = (uint8_t) temp;
292
-					rdata8++;
293
-				} else {
294
-					*(rdata16) = (uint16_t) temp;
295
-					rdata16++;
296
-				}
297
-			}
298
-			// Increase counter
299
-			if (dataword == 0){
300
-				dataCfg->counter++;
301
-			} else {
302
-				dataCfg->counter += 2;
303
-			}
304
-		}
305
-
306
-		// Return length of actual data transferred
307
-		// save status
308
-		dataCfg->status = stat | SPI_STAT_DONE;
309
-		return (dataCfg->counter);
310
-	}
311
-	// Interrupt mode
312
-	else {
313
-
314
-		// Check if interrupt flag is already set
315
-		if(SPIx->SPINT & SPI_SPINT_INTFLAG){
316
-			SPIx->SPINT = SPI_SPINT_INTFLAG;
317
-		}
318
-		if (dataCfg->counter < dataCfg->length){
319
-			// Write data to buffer
320
-			if(dataCfg->tx_data == NULL){
321
-				if (dataword == 0){
322
-					SPI_SendData(SPIx, 0xFF);
323
-				} else {
324
-					SPI_SendData(SPIx, 0xFFFF);
325
-				}
326
-			} else {
327
-				if (dataword == 0){
328
-					SPI_SendData(SPIx, (*(uint8_t *)dataCfg->tx_data));
329
-				} else {
330
-					SPI_SendData(SPIx, (*(uint16_t *)dataCfg->tx_data));
331
-				}
332
-			}
333
-			SPI_IntCmd(SPIx, ENABLE);
334
-		} else {
335
-			// Save status
336
-			dataCfg->status = SPI_STAT_DONE;
337
-		}
338
-		return (0);
339
-	}
340
-}
341
-
342
-
343
-/********************************************************************//**
344
- * @brief 		Enable or disable SPIx interrupt.
345
- * @param[in]	SPIx	SPI peripheral selected, should be LPC_SPI
346
- * @param[in]	NewState New state of specified UART interrupt type,
347
- * 				should be:
348
- * 				- ENALBE: Enable this SPI interrupt.
349
-* 				- DISALBE: Disable this SPI interrupt.
350
- * @return 		None
351
- *********************************************************************/
352
-void SPI_IntCmd(LPC_SPI_TypeDef *SPIx, FunctionalState NewState)
353
-{
354
-	CHECK_PARAM(PARAM_SPIx(SPIx));
355
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
356
-
357
-	if (NewState == ENABLE)
358
-	{
359
-		SPIx->SPCR |= SPI_SPCR_SPIE;
360
-	}
361
-	else
362
-	{
363
-		SPIx->SPCR &= (~SPI_SPCR_SPIE) & SPI_SPCR_BITMASK;
364
-	}
365
-}
366
-
367
-
368
-/********************************************************************//**
369
- * @brief 		Checks whether the SPI interrupt flag is set or not.
370
- * @param[in]	SPIx	SPI peripheral selected, should be LPC_SPI
371
- * @return 		The new state of SPI Interrupt Flag (SET or RESET)
372
- *********************************************************************/
373
-IntStatus SPI_GetIntStatus (LPC_SPI_TypeDef *SPIx)
374
-{
375
-	CHECK_PARAM(PARAM_SPIx(SPIx));
376
-
377
-	return ((SPIx->SPINT & SPI_SPINT_INTFLAG) ? SET : RESET);
378
-}
379
-
380
-/********************************************************************//**
381
- * @brief 		Clear SPI interrupt flag.
382
- * @param[in]	SPIx	SPI peripheral selected, should be LPC_SPI
383
- * @return 		None
384
- *********************************************************************/
385
-void SPI_ClearIntPending(LPC_SPI_TypeDef *SPIx)
386
-{
387
-	CHECK_PARAM(PARAM_SPIx(SPIx));
388
-
389
-	SPIx->SPINT = SPI_SPINT_INTFLAG;
390
-}
391
-
392
-/********************************************************************//**
393
- * @brief 		Get current value of SPI Status register in SPIx peripheral.
394
- * @param[in]	SPIx	SPI peripheral selected, should be LPC_SPI
395
- * @return		Current value of SPI Status register in SPI peripheral.
396
- * Note:	The return value of this function must be used with
397
- * 			SPI_CheckStatus() to determine current flag status
398
- * 			corresponding to each SPI status type. Because some flags in
399
- * 			SPI Status register will be cleared after reading, the next reading
400
- * 			SPI Status register could not be correct. So this function used to
401
- * 			read SPI status register in one time only, then the return value
402
- * 			used to check all flags.
403
- *********************************************************************/
404
-uint32_t SPI_GetStatus(LPC_SPI_TypeDef* SPIx)
405
-{
406
-	CHECK_PARAM(PARAM_SPIx(SPIx));
407
-
408
-	return (SPIx->SPSR & SPI_SPSR_BITMASK);
409
-}
410
-
411
-/********************************************************************//**
412
- * @brief 		Checks whether the specified SPI Status flag is set or not
413
- * 				via inputSPIStatus parameter.
414
- * @param[in]	inputSPIStatus Value to check status of each flag type.
415
- * 				This value is the return value from SPI_GetStatus().
416
- * @param[in]	SPIStatus	Specifies the SPI status flag to check,
417
- * 				should be one of the following:
418
-				- SPI_STAT_ABRT: Slave abort.
419
-				- SPI_STAT_MODF: Mode fault.
420
-				- SPI_STAT_ROVR: Read overrun.
421
-				- SPI_STAT_WCOL: Write collision.
422
-				- SPI_STAT_SPIF: SPI transfer complete.
423
- * @return 		The new state of SPIStatus (SET or RESET)
424
- *********************************************************************/
425
-FlagStatus SPI_CheckStatus (uint32_t inputSPIStatus,  uint8_t SPIStatus)
426
-{
427
-	CHECK_PARAM(PARAM_SPI_STAT(SPIStatus));
428
-
429
-	return ((inputSPIStatus & SPIStatus) ? SET : RESET);
430
-}
431
-
432
-
433
-/**
434
- * @}
435
- */
436
-
437
-#endif /* _SPI */
438
-
439
-/**
440
- * @}
441
- */
442
-
443
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 694
frameworks/CMSIS/LPC1768/driver/lpc17xx_ssp.c Просмотреть файл

@@ -1,694 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_ssp.c				2010-06-18
3
-*//**
4
-* @file		lpc17xx_ssp.c
5
-* @brief	Contains all functions support for SSP firmware library on LPC17xx
6
-* @version	3.0
7
-* @date		18. June. 2010
8
-* @author	NXP MCU SW Application Team
9
-*
10
-* Copyright(C) 2010, NXP Semiconductor
11
-* All rights reserved.
12
-*
13
-***********************************************************************
14
-* Software that is described herein is for illustrative purposes only
15
-* which provides customers with programming information regarding the
16
-* products. This software is supplied "AS IS" without any warranties.
17
-* NXP Semiconductors assumes no responsibility or liability for the
18
-* use of the software, conveys no license or title under any patent,
19
-* copyright, or mask work right to the product. NXP Semiconductors
20
-* reserves the right to make changes in the software without
21
-* notification. NXP Semiconductors also make no representation or
22
-* warranty that such application will be suitable for the specified
23
-* use without further testing or modification.
24
-* Permission to use, copy, modify, and distribute this software and its
25
-* documentation is hereby granted, under NXP Semiconductors'
26
-* relevant copyright in the software, without fee, provided that it
27
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
28
-* copyright, permission, and disclaimer notice must appear in all copies of
29
-* this code.
30
-**********************************************************************/
31
-
32
-/* Peripheral group ----------------------------------------------------------- */
33
-/** @addtogroup SSP
34
- * @{
35
- */
36
-
37
-/* Includes ------------------------------------------------------------------- */
38
-#include "lpc17xx_ssp.h"
39
-#include "lpc17xx_clkpwr.h"
40
-
41
-
42
-/* If this source file built with example, the LPC17xx FW library configuration
43
- * file in each example directory ("lpc17xx_libcfg.h") must be included,
44
- * otherwise the default FW library configuration file must be included instead
45
- */
46
-#ifdef __BUILD_WITH_EXAMPLE__
47
-#include "lpc17xx_libcfg.h"
48
-#else
49
-#include "lpc17xx_libcfg_default.h"
50
-#endif /* __BUILD_WITH_EXAMPLE__ */
51
-
52
-
53
-#ifdef _SSP
54
-
55
-/* Public Functions ----------------------------------------------------------- */
56
-/** @addtogroup SSP_Public_Functions
57
- * @{
58
- */
59
-static void setSSPclock (LPC_SSP_TypeDef *SSPx, uint32_t target_clock);
60
-
61
-/*********************************************************************//**
62
- * @brief 		Setup clock rate for SSP device
63
- * @param[in] 	SSPx	SSP peripheral definition, should be:
64
- * 						- LPC_SSP0: SSP0 peripheral
65
- * 						- LPC_SSP1: SSP1 peripheral
66
- * @param[in]	target_clock : clock of SSP (Hz)
67
- * @return 		None
68
- ***********************************************************************/
69
-static void setSSPclock (LPC_SSP_TypeDef *SSPx, uint32_t target_clock)
70
-{
71
-    uint32_t prescale, cr0_div, cmp_clk, ssp_clk;
72
-
73
-    CHECK_PARAM(PARAM_SSPx(SSPx));
74
-
75
-    /* The SSP clock is derived from the (main system oscillator / 2),
76
-       so compute the best divider from that clock */
77
-    if (SSPx == LPC_SSP0){
78
-    	ssp_clk = CLKPWR_GetPCLK (CLKPWR_PCLKSEL_SSP0);
79
-    } else if (SSPx == LPC_SSP1) {
80
-    	ssp_clk = CLKPWR_GetPCLK (CLKPWR_PCLKSEL_SSP1);
81
-    } else {
82
-    	return;
83
-    }
84
-
85
-	/* Find closest divider to get at or under the target frequency.
86
-	   Use smallest prescale possible and rely on the divider to get
87
-	   the closest target frequency */
88
-	cr0_div = 0;
89
-	cmp_clk = 0xFFFFFFFF;
90
-	prescale = 2;
91
-	while (cmp_clk > target_clock)
92
-	{
93
-		cmp_clk = ssp_clk / ((cr0_div + 1) * prescale);
94
-		if (cmp_clk > target_clock)
95
-		{
96
-			cr0_div++;
97
-			if (cr0_div > 0xFF)
98
-			{
99
-				cr0_div = 0;
100
-				prescale += 2;
101
-			}
102
-		}
103
-	}
104
-
105
-    /* Write computed prescaler and divider back to register */
106
-    SSPx->CR0 &= (~SSP_CR0_SCR(0xFF)) & SSP_CR0_BITMASK;
107
-    SSPx->CR0 |= (SSP_CR0_SCR(cr0_div)) & SSP_CR0_BITMASK;
108
-    SSPx->CPSR = prescale & SSP_CPSR_BITMASK;
109
-}
110
-
111
-/**
112
- * @}
113
- */
114
-
115
-/* Public Functions ----------------------------------------------------------- */
116
-/** @addtogroup SSP_Public_Functions
117
- * @{
118
- */
119
-
120
-/********************************************************************//**
121
- * @brief		Initializes the SSPx peripheral according to the specified
122
-*               parameters in the SSP_ConfigStruct.
123
- * @param[in]	SSPx	SSP peripheral selected, should be:
124
- * 				 		- LPC_SSP0: SSP0 peripheral
125
- * 						- LPC_SSP1: SSP1 peripheral
126
- * @param[in]	SSP_ConfigStruct Pointer to a SSP_CFG_Type structure
127
-*                    that contains the configuration information for the
128
-*                    specified SSP peripheral.
129
- * @return 		None
130
- *********************************************************************/
131
-void SSP_Init(LPC_SSP_TypeDef *SSPx, SSP_CFG_Type *SSP_ConfigStruct)
132
-{
133
-	uint32_t tmp;
134
-
135
-	CHECK_PARAM(PARAM_SSPx(SSPx));
136
-
137
-	if(SSPx == LPC_SSP0) {
138
-		/* Set up clock and power for SSP0 module */
139
-		CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCSSP0, ENABLE);
140
-	} else if(SSPx == LPC_SSP1) {
141
-		/* Set up clock and power for SSP1 module */
142
-		CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCSSP1, ENABLE);
143
-	} else {
144
-		return;
145
-	}
146
-
147
-	/* Configure SSP, interrupt is disable, LoopBack mode is disable,
148
-	 * SSP is disable, Slave output is disable as default
149
-	 */
150
-	tmp = ((SSP_ConfigStruct->CPHA) | (SSP_ConfigStruct->CPOL) \
151
-		| (SSP_ConfigStruct->FrameFormat) | (SSP_ConfigStruct->Databit))
152
-		& SSP_CR0_BITMASK;
153
-	// write back to SSP control register
154
-	SSPx->CR0 = tmp;
155
-
156
-	tmp = SSP_ConfigStruct->Mode & SSP_CR1_BITMASK;
157
-	// Write back to CR1
158
-	SSPx->CR1 = tmp;
159
-
160
-	// Set clock rate for SSP peripheral
161
-	setSSPclock(SSPx, SSP_ConfigStruct->ClockRate);
162
-}
163
-
164
-/*********************************************************************//**
165
- * @brief		De-initializes the SSPx peripheral registers to their
166
-*                  default reset values.
167
- * @param[in]	SSPx	SSP peripheral selected, should be:
168
- * 				 		- LPC_SSP0: SSP0 peripheral
169
- * 						- LPC_SSP1: SSP1 peripheral
170
- * @return 		None
171
- **********************************************************************/
172
-void SSP_DeInit(LPC_SSP_TypeDef* SSPx)
173
-{
174
-	CHECK_PARAM(PARAM_SSPx(SSPx));
175
-
176
-	if (SSPx == LPC_SSP0){
177
-		/* Set up clock and power for SSP0 module */
178
-		CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCSSP0, DISABLE);
179
-	} else if (SSPx == LPC_SSP1) {
180
-		/* Set up clock and power for SSP1 module */
181
-		CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCSSP1, DISABLE);
182
-	}
183
-}
184
-
185
-/*****************************************************************************//**
186
-* @brief		Get data size bit selected
187
-* @param[in]	SSPx pointer to LPC_SSP_TypeDef structure, should be:
188
-* 				- LPC_SSP0: SSP0 peripheral
189
-* 				- LPC_SSP1: SSP1 peripheral
190
-* @return		Data size, could be:
191
-*				- SSP_DATABIT_4: 4 bit transfer
192
-*				- SSP_DATABIT_5: 5 bit transfer
193
-*				...
194
-*				- SSP_DATABIT_16: 16 bit transfer
195
-*******************************************************************************/
196
-uint8_t SSP_GetDataSize(LPC_SSP_TypeDef* SSPx)
197
-{
198
-	CHECK_PARAM(PARAM_SSPx(SSPx));
199
-	return (SSPx->CR0 & (0xF));
200
-}
201
-
202
-/*****************************************************************************//**
203
-* @brief		Fills each SSP_InitStruct member with its default value:
204
-* 				- CPHA = SSP_CPHA_FIRST
205
-* 				- CPOL = SSP_CPOL_HI
206
-* 				- ClockRate = 1000000
207
-* 				- Databit = SSP_DATABIT_8
208
-* 				- Mode = SSP_MASTER_MODE
209
-* 				- FrameFormat = SSP_FRAME_SSP
210
-* @param[in]	SSP_InitStruct Pointer to a SSP_CFG_Type structure
211
-*                    which will be initialized.
212
-* @return		None
213
-*******************************************************************************/
214
-void SSP_ConfigStructInit(SSP_CFG_Type *SSP_InitStruct)
215
-{
216
-	SSP_InitStruct->CPHA = SSP_CPHA_FIRST;
217
-	SSP_InitStruct->CPOL = SSP_CPOL_HI;
218
-	SSP_InitStruct->ClockRate = 1000000;
219
-	SSP_InitStruct->Databit = SSP_DATABIT_8;
220
-	SSP_InitStruct->Mode = SSP_MASTER_MODE;
221
-	SSP_InitStruct->FrameFormat = SSP_FRAME_SPI;
222
-}
223
-
224
-
225
-/*********************************************************************//**
226
- * @brief		Enable or disable SSP peripheral's operation
227
- * @param[in]	SSPx	SSP peripheral, should be:
228
- * 				- LPC_SSP0: SSP0 peripheral
229
- * 				- LPC_SSP1: SSP1 peripheral
230
- * @param[in]	NewState New State of SSPx peripheral's operation
231
- * @return 		none
232
- **********************************************************************/
233
-void SSP_Cmd(LPC_SSP_TypeDef* SSPx, FunctionalState NewState)
234
-{
235
-	CHECK_PARAM(PARAM_SSPx(SSPx));
236
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
237
-
238
-	if (NewState == ENABLE)
239
-	{
240
-		SSPx->CR1 |= SSP_CR1_SSP_EN;
241
-	}
242
-	else
243
-	{
244
-		SSPx->CR1 &= (~SSP_CR1_SSP_EN) & SSP_CR1_BITMASK;
245
-	}
246
-}
247
-
248
-/*********************************************************************//**
249
- * @brief		Enable or disable Loop Back mode function in SSP peripheral
250
- * @param[in]	SSPx	SSP peripheral selected, should be:
251
- *  					- LPC_SSP0: SSP0 peripheral
252
- * 						- LPC_SSP1: SSP1 peripheral
253
- * @param[in]	NewState	New State of Loop Back mode, should be:
254
- * 							- ENABLE: Enable this function
255
- * 							- DISABLE: Disable this function
256
- * @return 		None
257
- **********************************************************************/
258
-void SSP_LoopBackCmd(LPC_SSP_TypeDef* SSPx, FunctionalState NewState)
259
-{
260
-	CHECK_PARAM(PARAM_SSPx(SSPx));
261
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
262
-
263
-	if (NewState == ENABLE)
264
-	{
265
-		SSPx->CR1 |= SSP_CR1_LBM_EN;
266
-	}
267
-	else
268
-	{
269
-		SSPx->CR1 &= (~SSP_CR1_LBM_EN) & SSP_CR1_BITMASK;
270
-	}
271
-}
272
-
273
-/*********************************************************************//**
274
- * @brief		Enable or disable Slave Output function in SSP peripheral
275
- * @param[in]	SSPx	SSP peripheral selected, should be:
276
- * 						- LPC_SSP0: SSP0 peripheral
277
- * 						- LPC_SSP1: SSP1 peripheral
278
- * @param[in]	NewState	New State of Slave Output function, should be:
279
- * 							- ENABLE: Slave Output in normal operation
280
- * 							- DISABLE: Slave Output is disabled. This blocks
281
- * 							SSP controller from driving the transmit data
282
- * 							line (MISO)
283
- * Note: 		This function is available when SSP peripheral in Slave mode
284
- * @return 		None
285
- **********************************************************************/
286
-void SSP_SlaveOutputCmd(LPC_SSP_TypeDef* SSPx, FunctionalState NewState)
287
-{
288
-	CHECK_PARAM(PARAM_SSPx(SSPx));
289
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
290
-
291
-	if (NewState == ENABLE)
292
-	{
293
-		SSPx->CR1 &= (~SSP_CR1_SO_DISABLE) & SSP_CR1_BITMASK;
294
-	}
295
-	else
296
-	{
297
-		SSPx->CR1 |= SSP_CR1_SO_DISABLE;
298
-	}
299
-}
300
-
301
-
302
-
303
-/*********************************************************************//**
304
- * @brief		Transmit a single data through SSPx peripheral
305
- * @param[in]	SSPx	SSP peripheral selected, should be:
306
- * 						- LPC_SSP0: SSP0 peripheral
307
- * 						- LPC_SSP1: SSP1 peripheral
308
- * @param[in]	Data	Data to transmit (must be 16 or 8-bit long,
309
- * 						this depend on SSP data bit number configured)
310
- * @return 		none
311
- **********************************************************************/
312
-void SSP_SendData(LPC_SSP_TypeDef* SSPx, uint16_t Data)
313
-{
314
-	CHECK_PARAM(PARAM_SSPx(SSPx));
315
-
316
-	SSPx->DR = SSP_DR_BITMASK(Data);
317
-}
318
-
319
-
320
-
321
-/*********************************************************************//**
322
- * @brief		Receive a single data from SSPx peripheral
323
- * @param[in]	SSPx	SSP peripheral selected, should be
324
- * 						- LPC_SSP0: SSP0 peripheral
325
- * 						- LPC_SSP1: SSP1 peripheral
326
- * @return 		Data received (16-bit long)
327
- **********************************************************************/
328
-uint16_t SSP_ReceiveData(LPC_SSP_TypeDef* SSPx)
329
-{
330
-	CHECK_PARAM(PARAM_SSPx(SSPx));
331
-
332
-	return ((uint16_t) (SSP_DR_BITMASK(SSPx->DR)));
333
-}
334
-
335
-/*********************************************************************//**
336
- * @brief 		SSP Read write data function
337
- * @param[in]	SSPx 	Pointer to SSP peripheral, should be
338
- * 						- LPC_SSP0: SSP0 peripheral
339
- * 						- LPC_SSP1: SSP1 peripheral
340
- * @param[in]	dataCfg	Pointer to a SSP_DATA_SETUP_Type structure that
341
- * 						contains specified information about transmit
342
- * 						data configuration.
343
- * @param[in]	xfType	Transfer type, should be:
344
- * 						- SSP_TRANSFER_POLLING: Polling mode
345
- * 						- SSP_TRANSFER_INTERRUPT: Interrupt mode
346
- * @return 		Actual Data length has been transferred in polling mode.
347
- * 				In interrupt mode, always return (0)
348
- * 				Return (-1) if error.
349
- * Note: This function can be used in both master and slave mode.
350
- ***********************************************************************/
351
-int32_t SSP_ReadWrite (LPC_SSP_TypeDef *SSPx, SSP_DATA_SETUP_Type *dataCfg, \
352
-						SSP_TRANSFER_Type xfType)
353
-{
354
-	uint8_t *rdata8;
355
-    uint8_t *wdata8;
356
-	uint16_t *rdata16;
357
-    uint16_t *wdata16;
358
-    uint32_t stat;
359
-    uint32_t tmp;
360
-    int32_t dataword;
361
-
362
-    dataCfg->rx_cnt = 0;
363
-    dataCfg->tx_cnt = 0;
364
-    dataCfg->status = 0;
365
-
366
-
367
-	/* Clear all remaining data in RX FIFO */
368
-	while (SSPx->SR & SSP_SR_RNE){
369
-		tmp = (uint32_t) SSP_ReceiveData(SSPx);
370
-	}
371
-
372
-	// Clear status
373
-	SSPx->ICR = SSP_ICR_BITMASK;
374
-	if(SSP_GetDataSize(SSPx)>SSP_DATABIT_8)
375
-		dataword = 1;
376
-	else dataword = 0;
377
-
378
-	// Polling mode ----------------------------------------------------------------------
379
-	if (xfType == SSP_TRANSFER_POLLING){
380
-		if (dataword == 0){
381
-			rdata8 = (uint8_t *)dataCfg->rx_data;
382
-			wdata8 = (uint8_t *)dataCfg->tx_data;
383
-		} else {
384
-			rdata16 = (uint16_t *)dataCfg->rx_data;
385
-			wdata16 = (uint16_t *)dataCfg->tx_data;
386
-		}
387
-		while ((dataCfg->tx_cnt < dataCfg->length) || (dataCfg->rx_cnt < dataCfg->length)){
388
-			if ((SSPx->SR & SSP_SR_TNF) && (dataCfg->tx_cnt < dataCfg->length)){
389
-				// Write data to buffer
390
-				if(dataCfg->tx_data == NULL){
391
-					if (dataword == 0){
392
-						SSP_SendData(SSPx, 0xFF);
393
-						dataCfg->tx_cnt++;
394
-					} else {
395
-						SSP_SendData(SSPx, 0xFFFF);
396
-						dataCfg->tx_cnt += 2;
397
-					}
398
-				} else {
399
-					if (dataword == 0){
400
-						SSP_SendData(SSPx, *wdata8);
401
-						wdata8++;
402
-						dataCfg->tx_cnt++;
403
-					} else {
404
-						SSP_SendData(SSPx, *wdata16);
405
-						wdata16++;
406
-						dataCfg->tx_cnt += 2;
407
-					}
408
-				}
409
-			}
410
-
411
-			// Check overrun error
412
-			if ((stat = SSPx->RIS) & SSP_RIS_ROR){
413
-				// save status and return
414
-				dataCfg->status = stat | SSP_STAT_ERROR;
415
-				return (-1);
416
-			}
417
-
418
-			// Check for any data available in RX FIFO
419
-			while ((SSPx->SR & SSP_SR_RNE) && (dataCfg->rx_cnt < dataCfg->length)){
420
-				// Read data from SSP data
421
-				tmp = SSP_ReceiveData(SSPx);
422
-
423
-				// Store data to destination
424
-				if (dataCfg->rx_data != NULL)
425
-				{
426
-					if (dataword == 0){
427
-						*(rdata8) = (uint8_t) tmp;
428
-						rdata8++;
429
-					} else {
430
-						*(rdata16) = (uint16_t) tmp;
431
-						rdata16++;
432
-					}
433
-				}
434
-				// Increase counter
435
-				if (dataword == 0){
436
-					dataCfg->rx_cnt++;
437
-				} else {
438
-					dataCfg->rx_cnt += 2;
439
-				}
440
-			}
441
-		}
442
-
443
-		// save status
444
-		dataCfg->status = SSP_STAT_DONE;
445
-
446
-		if (dataCfg->tx_data != NULL){
447
-			return dataCfg->tx_cnt;
448
-		} else if (dataCfg->rx_data != NULL){
449
-			return dataCfg->rx_cnt;
450
-		} else {
451
-			return (0);
452
-		}
453
-	}
454
-
455
-	// Interrupt mode ----------------------------------------------------------------------
456
-	else if (xfType == SSP_TRANSFER_INTERRUPT){
457
-
458
-		while ((SSPx->SR & SSP_SR_TNF) && (dataCfg->tx_cnt < dataCfg->length)){
459
-			// Write data to buffer
460
-			if(dataCfg->tx_data == NULL){
461
-				if (dataword == 0){
462
-					SSP_SendData(SSPx, 0xFF);
463
-					dataCfg->tx_cnt++;
464
-				} else {
465
-					SSP_SendData(SSPx, 0xFFFF);
466
-					dataCfg->tx_cnt += 2;
467
-				}
468
-			} else {
469
-				if (dataword == 0){
470
-					SSP_SendData(SSPx, (*(uint8_t *)((uint32_t)dataCfg->tx_data + dataCfg->tx_cnt)));
471
-					dataCfg->tx_cnt++;
472
-				} else {
473
-					SSP_SendData(SSPx, (*(uint16_t *)((uint32_t)dataCfg->tx_data + dataCfg->tx_cnt)));
474
-					dataCfg->tx_cnt += 2;
475
-				}
476
-			}
477
-
478
-			// Check error
479
-			if ((stat = SSPx->RIS) & SSP_RIS_ROR){
480
-				// save status and return
481
-				dataCfg->status = stat | SSP_STAT_ERROR;
482
-				return (-1);
483
-			}
484
-
485
-			// Check for any data available in RX FIFO
486
-			while ((SSPx->SR & SSP_SR_RNE) && (dataCfg->rx_cnt < dataCfg->length)){
487
-				// Read data from SSP data
488
-				tmp = SSP_ReceiveData(SSPx);
489
-
490
-				// Store data to destination
491
-				if (dataCfg->rx_data != NULL)
492
-				{
493
-					if (dataword == 0){
494
-						*(uint8_t *)((uint32_t)dataCfg->rx_data + dataCfg->rx_cnt) = (uint8_t) tmp;
495
-					} else {
496
-						*(uint16_t *)((uint32_t)dataCfg->rx_data + dataCfg->rx_cnt) = (uint16_t) tmp;
497
-					}
498
-				}
499
-				// Increase counter
500
-				if (dataword == 0){
501
-					dataCfg->rx_cnt++;
502
-				} else {
503
-					dataCfg->rx_cnt += 2;
504
-				}
505
-			}
506
-		}
507
-
508
-		// If there more data to sent or receive
509
-		if ((dataCfg->rx_cnt < dataCfg->length) || (dataCfg->tx_cnt < dataCfg->length)){
510
-			// Enable all interrupt
511
-			SSPx->IMSC = SSP_IMSC_BITMASK;
512
-		} else {
513
-			// Save status
514
-			dataCfg->status = SSP_STAT_DONE;
515
-		}
516
-		return (0);
517
-	}
518
-
519
-	return (-1);
520
-}
521
-
522
-/*********************************************************************//**
523
- * @brief		Checks whether the specified SSP status flag is set or not
524
- * @param[in]	SSPx	SSP peripheral selected, should be:
525
- * 		 				- LPC_SSP0: SSP0 peripheral
526
- * 						- LPC_SSP1: SSP1 peripheral
527
- * @param[in]	FlagType	Type of flag to check status, should be one
528
- * 							of following:
529
- *							- SSP_STAT_TXFIFO_EMPTY: TX FIFO is empty
530
- *							- SSP_STAT_TXFIFO_NOTFULL: TX FIFO is not full
531
- *							- SSP_STAT_RXFIFO_NOTEMPTY: RX FIFO is not empty
532
- *							- SSP_STAT_RXFIFO_FULL: RX FIFO is full
533
- *							- SSP_STAT_BUSY: SSP peripheral is busy
534
- * @return		New State of specified SSP status flag
535
- **********************************************************************/
536
-FlagStatus SSP_GetStatus(LPC_SSP_TypeDef* SSPx, uint32_t FlagType)
537
-{
538
-	CHECK_PARAM(PARAM_SSPx(SSPx));
539
-	CHECK_PARAM(PARAM_SSP_STAT(FlagType));
540
-
541
-	return ((SSPx->SR & FlagType) ? SET : RESET);
542
-}
543
-
544
-/*********************************************************************//**
545
- * @brief		Enable or disable specified interrupt type in SSP peripheral
546
- * @param[in]	SSPx	SSP peripheral selected, should be:
547
- * 						- LPC_SSP0: SSP0 peripheral
548
- * 						- LPC_SSP1: SSP1 peripheral
549
- * @param[in]	IntType	Interrupt type in SSP peripheral, should be:
550
- * 				- SSP_INTCFG_ROR: Receive Overrun interrupt
551
- * 				- SSP_INTCFG_RT: Receive Time out interrupt
552
- * 				- SSP_INTCFG_RX: RX FIFO is at least half full interrupt
553
- * 				- SSP_INTCFG_TX: TX FIFO is at least half empty interrupt
554
- * @param[in]	NewState New State of specified interrupt type, should be:
555
- * 				- ENABLE: Enable this interrupt type
556
- * 				- DISABLE: Disable this interrupt type
557
- * @return		None
558
- * Note: We can enable/disable multi-interrupt type by OR multi value
559
- **********************************************************************/
560
-void SSP_IntConfig(LPC_SSP_TypeDef *SSPx, uint32_t IntType, FunctionalState NewState)
561
-{
562
-	CHECK_PARAM(PARAM_SSPx(SSPx));
563
-
564
-	if (NewState == ENABLE)
565
-	{
566
-		SSPx->IMSC |= IntType;
567
-	}
568
-	else
569
-	{
570
-		SSPx->IMSC &= (~IntType) & SSP_IMSC_BITMASK;
571
-	}
572
-}
573
-
574
-/*********************************************************************//**
575
- * @brief	Check whether the specified Raw interrupt status flag is
576
- * 			set or not
577
- * @param[in]	SSPx	SSP peripheral selected, should be:
578
- * 						- LPC_SSP0: SSP0 peripheral
579
- * 						- LPC_SSP1: SSP1 peripheral
580
- * @param[in]	RawIntType	Raw Interrupt Type, should be:
581
- * 				- SSP_INTSTAT_RAW_ROR: Receive Overrun interrupt
582
- * 				- SSP_INTSTAT_RAW_RT: Receive Time out interrupt
583
- * 				- SSP_INTSTAT_RAW_RX: RX FIFO is at least half full interrupt
584
- * 				- SSP_INTSTAT_RAW_TX: TX FIFO is at least half empty interrupt
585
- * @return	New State of specified Raw interrupt status flag in SSP peripheral
586
- * Note: Enabling/Disabling specified interrupt in SSP peripheral does not
587
- * 		effect to Raw Interrupt Status flag.
588
- **********************************************************************/
589
-IntStatus SSP_GetRawIntStatus(LPC_SSP_TypeDef *SSPx, uint32_t RawIntType)
590
-{
591
-	CHECK_PARAM(PARAM_SSPx(SSPx));
592
-	CHECK_PARAM(PARAM_SSP_INTSTAT_RAW(RawIntType));
593
-
594
-	return ((SSPx->RIS & RawIntType) ? SET : RESET);
595
-}
596
-
597
-/*********************************************************************//**
598
- * @brief		Get Raw Interrupt Status register
599
- * @param[in]	SSPx	SSP peripheral selected, should be:
600
- * 						- LPC_SSP0: SSP0 peripheral
601
- * 						- LPC_SSP1: SSP1 peripheral
602
- * @return		Raw Interrupt Status (RIS) register value
603
- **********************************************************************/
604
-uint32_t SSP_GetRawIntStatusReg(LPC_SSP_TypeDef *SSPx)
605
-{
606
-	CHECK_PARAM(PARAM_SSPx(SSPx));
607
-	return (SSPx->RIS);
608
-}
609
-
610
-/*********************************************************************//**
611
- * @brief	Check whether the specified interrupt status flag is
612
- * 			set or not
613
- * @param[in]	SSPx	SSP peripheral selected, should be:
614
- * 						- LPC_SSP0: SSP0 peripheral
615
- * 						- LPC_SSP1: SSP1 peripheral
616
- * @param[in]	IntType	Raw Interrupt Type, should be:
617
- * 				- SSP_INTSTAT_ROR: Receive Overrun interrupt
618
- * 				- SSP_INTSTAT_RT: Receive Time out interrupt
619
- * 				- SSP_INTSTAT_RX: RX FIFO is at least half full interrupt
620
- * 				- SSP_INTSTAT_TX: TX FIFO is at least half empty interrupt
621
- * @return	New State of specified interrupt status flag in SSP peripheral
622
- * Note: Enabling/Disabling specified interrupt in SSP peripheral effects
623
- * 			to Interrupt Status flag.
624
- **********************************************************************/
625
-IntStatus SSP_GetIntStatus (LPC_SSP_TypeDef *SSPx, uint32_t IntType)
626
-{
627
-	CHECK_PARAM(PARAM_SSPx(SSPx));
628
-	CHECK_PARAM(PARAM_SSP_INTSTAT(IntType));
629
-
630
-	return ((SSPx->MIS & IntType) ? SET :RESET);
631
-}
632
-
633
-/*********************************************************************//**
634
- * @brief				Clear specified interrupt pending in SSP peripheral
635
- * @param[in]	SSPx	SSP peripheral selected, should be:
636
- *  					- LPC_SSP0: SSP0 peripheral
637
- * 						- LPC_SSP1: SSP1 peripheral
638
- * @param[in]	IntType	Interrupt pending to clear, should be:
639
- * 						- SSP_INTCLR_ROR: clears the "frame was received when
640
- * 						RxFIFO was full" interrupt.
641
- * 						- SSP_INTCLR_RT: clears the "Rx FIFO was not empty and
642
- * 						has not been read for a timeout period" interrupt.
643
- * @return		None
644
- **********************************************************************/
645
-void SSP_ClearIntPending(LPC_SSP_TypeDef *SSPx, uint32_t IntType)
646
-{
647
-	CHECK_PARAM(PARAM_SSPx(SSPx));
648
-	CHECK_PARAM(PARAM_SSP_INTCLR(IntType));
649
-
650
-	SSPx->ICR = IntType;
651
-}
652
-
653
-/*********************************************************************//**
654
- * @brief				Enable/Disable DMA function for SSP peripheral
655
- * @param[in]	SSPx	SSP peripheral selected, should be:
656
- *  					- LPC_SSP0: SSP0 peripheral
657
- * 						- LPC_SSP1: SSP1 peripheral
658
- * @param[in]	DMAMode	Type of DMA, should be:
659
- * 						- SSP_DMA_TX: DMA for the transmit FIFO
660
- * 						- SSP_DMA_RX: DMA for the Receive FIFO
661
- * @param[in]	NewState	New State of DMA function on SSP peripheral,
662
- * 						should be:
663
- * 						- ENALBE: Enable this function
664
- * 						- DISABLE: Disable this function
665
- * @return		None
666
- **********************************************************************/
667
-void SSP_DMACmd(LPC_SSP_TypeDef *SSPx, uint32_t DMAMode, FunctionalState NewState)
668
-{
669
-	CHECK_PARAM(PARAM_SSPx(SSPx));
670
-	CHECK_PARAM(PARAM_SSP_DMA(DMAMode));
671
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
672
-
673
-	if (NewState == ENABLE)
674
-	{
675
-		SSPx->DMACR |= DMAMode;
676
-	}
677
-	else
678
-	{
679
-		SSPx->DMACR &= (~DMAMode) & SSP_DMA_BITMASK;
680
-	}
681
-}
682
-
683
-/**
684
- * @}
685
- */
686
-
687
-#endif /* _SSP */
688
-
689
-/**
690
- * @}
691
- */
692
-
693
-/* --------------------------------- End Of File ------------------------------ */
694
-

+ 0
- 193
frameworks/CMSIS/LPC1768/driver/lpc17xx_systick.c Просмотреть файл

@@ -1,193 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_systick.c				2010-05-21
3
-*//**
4
-* @file		lpc17xx_systick.c
5
-* @brief	Contains all functions support for SYSTICK firmware library
6
-* 			on LPC17xx
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @addtogroup SYSTICK
35
- * @{
36
- */
37
-
38
-/* Includes ------------------------------------------------------------------- */
39
-#include "lpc17xx_systick.h"
40
-#include "lpc17xx_clkpwr.h"
41
-
42
-/* If this source file built with example, the LPC17xx FW library configuration
43
- * file in each example directory ("lpc17xx_libcfg.h") must be included,
44
- * otherwise the default FW library configuration file must be included instead
45
- */
46
-#ifdef __BUILD_WITH_EXAMPLE__
47
-#include "lpc17xx_libcfg.h"
48
-#else
49
-#include "lpc17xx_libcfg_default.h"
50
-#endif /* __BUILD_WITH_EXAMPLE__ */
51
-
52
-
53
-#ifdef _SYSTICK
54
-
55
-/* Public Functions ----------------------------------------------------------- */
56
-/** @addtogroup SYSTICK_Public_Functions
57
- * @{
58
- */
59
-/*********************************************************************//**
60
- * @brief 		Initial System Tick with using internal CPU clock source
61
- * @param[in]	time	time interval(ms)
62
- * @return 		None
63
- **********************************************************************/
64
-void SYSTICK_InternalInit(uint32_t time)
65
-{
66
-	uint32_t cclk;
67
-	float maxtime;
68
-
69
-	cclk = SystemCoreClock;
70
-	/* With internal CPU clock frequency for LPC17xx is 'SystemCoreClock'
71
-	 * And limit 24 bit for RELOAD value
72
-	 * So the maximum time can be set:
73
-	 * 1/SystemCoreClock * (2^24) * 1000 (ms)
74
-	 */
75
-	//check time value is available or not
76
-	maxtime = (1<<24)/(SystemCoreClock / 1000);
77
-	if(time > maxtime)
78
-		//Error loop
79
-		while(1);
80
-	else
81
-	{
82
-		//Select CPU clock is System Tick clock source
83
-		SysTick->CTRL |= ST_CTRL_CLKSOURCE;
84
-		/* Set RELOAD value
85
-		 * RELOAD = (SystemCoreClock/1000) * time - 1
86
-		 * with time base is millisecond
87
-		 */
88
-		SysTick->LOAD = (cclk/1000)*time - 1;
89
-	}
90
-}
91
-
92
-/*********************************************************************//**
93
- * @brief 		Initial System Tick with using external clock source
94
- * @param[in]	freq	external clock frequency(Hz)
95
- * @param[in]	time	time interval(ms)
96
- * @return 		None
97
- **********************************************************************/
98
-void SYSTICK_ExternalInit(uint32_t freq, uint32_t time)
99
-{
100
-	float maxtime;
101
-
102
-	/* With external clock frequency for LPC17xx is 'freq'
103
-	 * And limit 24 bit for RELOAD value
104
-	 * So the maximum time can be set:
105
-	 * 1/freq * (2^24) * 1000 (ms)
106
-	 */
107
-	//check time value is available or not
108
-	maxtime = (1<<24)/(freq / 1000);
109
-	if (time>maxtime)
110
-		//Error Loop
111
-		while(1);
112
-	else
113
-	{
114
-		//Select external clock is System Tick clock source
115
-		SysTick->CTRL &= ~ ST_CTRL_CLKSOURCE;
116
-		/* Set RELOAD value
117
-		 * RELOAD = (freq/1000) * time - 1
118
-		 * with time base is millisecond
119
-		 */
120
-		maxtime = (freq/1000)*time - 1;
121
-		SysTick->LOAD = (freq/1000)*time - 1;
122
-	}
123
-}
124
-
125
-/*********************************************************************//**
126
- * @brief 		Enable/disable System Tick counter
127
- * @param[in]	NewState	System Tick counter status, should be:
128
- * 					- ENABLE
129
- * 					- DISABLE
130
- * @return 		None
131
- **********************************************************************/
132
-void SYSTICK_Cmd(FunctionalState NewState)
133
-{
134
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
135
-
136
-	if(NewState == ENABLE)
137
-		//Enable System Tick counter
138
-		SysTick->CTRL |= ST_CTRL_ENABLE;
139
-	else
140
-		//Disable System Tick counter
141
-		SysTick->CTRL &= ~ST_CTRL_ENABLE;
142
-}
143
-
144
-/*********************************************************************//**
145
- * @brief 		Enable/disable System Tick interrupt
146
- * @param[in]	NewState	System Tick interrupt status, should be:
147
- * 					- ENABLE
148
- * 					- DISABLE
149
- * @return 		None
150
- **********************************************************************/
151
-void SYSTICK_IntCmd(FunctionalState NewState)
152
-{
153
-	CHECK_PARAM(PARAM_FUNCTIONALSTATE(NewState));
154
-
155
-	if(NewState == ENABLE)
156
-		//Enable System Tick counter
157
-		SysTick->CTRL |= ST_CTRL_TICKINT;
158
-	else
159
-		//Disable System Tick counter
160
-		SysTick->CTRL &= ~ST_CTRL_TICKINT;
161
-}
162
-
163
-/*********************************************************************//**
164
- * @brief 		Get current value of System Tick counter
165
- * @param[in]	None
166
- * @return 		current value of System Tick counter
167
- **********************************************************************/
168
-uint32_t SYSTICK_GetCurrentValue(void)
169
-{
170
-	return (SysTick->VAL);
171
-}
172
-
173
-/*********************************************************************//**
174
- * @brief 		Clear Counter flag
175
- * @param[in]	None
176
- * @return 		None
177
- **********************************************************************/
178
-void SYSTICK_ClearCounterFlag(void)
179
-{
180
-	SysTick->CTRL &= ~ST_CTRL_COUNTFLAG;
181
-}
182
-/**
183
- * @}
184
- */
185
-
186
-#endif /* _SYSTICK */
187
-
188
-/**
189
- * @}
190
- */
191
-
192
-/* --------------------------------- End Of File ------------------------------ */
193
-

+ 0
- 609
frameworks/CMSIS/LPC1768/driver/lpc17xx_timer.c Просмотреть файл

@@ -1,609 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_timer.c				2011-03-10
3
-*//**
4
-* @file		lpc17xx_timer.c
5
-* @brief	Contains all functions support for Timer firmware library
6
-* 			on LPC17xx
7
-* @version	3.1
8
-* @date		10. March. 2011
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2011, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @addtogroup TIM
35
- * @{
36
- */
37
-
38
-/* Includes ------------------------------------------------------------------- */
39
-#include "lpc17xx_timer.h"
40
-#include "lpc17xx_clkpwr.h"
41
-#include "lpc17xx_pinsel.h"
42
-
43
-/* If this source file built with example, the LPC17xx FW library configuration
44
- * file in each example directory ("lpc17xx_libcfg.h") must be included,
45
- * otherwise the default FW library configuration file must be included instead
46
- */
47
-#ifdef __BUILD_WITH_EXAMPLE__
48
-#include "lpc17xx_libcfg.h"
49
-#else
50
-#include "lpc17xx_libcfg_default.h"
51
-#endif /* __BUILD_WITH_EXAMPLE__ */
52
-
53
-#ifdef _TIM
54
-
55
-/* Private Functions ---------------------------------------------------------- */
56
-
57
-static uint32_t getPClock (uint32_t timernum);
58
-static uint32_t converUSecToVal (uint32_t timernum, uint32_t usec);
59
-static uint32_t converPtrToTimeNum (LPC_TIM_TypeDef *TIMx);
60
-
61
-
62
-/*********************************************************************//**
63
- * @brief 		Get peripheral clock of each timer controller
64
- * @param[in]	timernum Timer number
65
- * @return 		Peripheral clock of timer
66
- **********************************************************************/
67
-static uint32_t getPClock (uint32_t timernum)
68
-{
69
-	uint32_t clkdlycnt;
70
-	switch (timernum)
71
-	{
72
-	case 0:
73
-		clkdlycnt = CLKPWR_GetPCLK (CLKPWR_PCLKSEL_TIMER0);
74
-		break;
75
-
76
-	case 1:
77
-		clkdlycnt = CLKPWR_GetPCLK (CLKPWR_PCLKSEL_TIMER1);
78
-		break;
79
-
80
-	case 2:
81
-		clkdlycnt = CLKPWR_GetPCLK (CLKPWR_PCLKSEL_TIMER2);
82
-		break;
83
-
84
-	case 3:
85
-		clkdlycnt = CLKPWR_GetPCLK (CLKPWR_PCLKSEL_TIMER3);
86
-		break;
87
-	}
88
-	return clkdlycnt;
89
-}
90
-
91
-
92
-/*********************************************************************//**
93
- * @brief 		Convert a time to a timer count value
94
- * @param[in]	timernum Timer number
95
- * @param[in]	usec Time in microseconds
96
- * @return 		The number of required clock ticks to give the time delay
97
- **********************************************************************/
98
-uint32_t converUSecToVal (uint32_t timernum, uint32_t usec)
99
-{
100
-	uint64_t clkdlycnt;
101
-
102
-	// Get Pclock of timer
103
-	clkdlycnt = (uint64_t) getPClock(timernum);
104
-
105
-	clkdlycnt = (clkdlycnt * usec) / 1000000;
106
-	return (uint32_t) clkdlycnt;
107
-}
108
-
109
-
110
-/*********************************************************************//**
111
- * @brief 		Convert a timer register pointer to a timer number
112
- * @param[in]	TIMx Pointer to LPC_TIM_TypeDef, should be:
113
- * 				- LPC_TIM0: TIMER0 peripheral
114
- * 				- LPC_TIM1: TIMER1 peripheral
115
- * 				- LPC_TIM2: TIMER2 peripheral
116
- * 				- LPC_TIM3: TIMER3 peripheral
117
- * @return 		The timer number (0 to 3) or 0xFFFF FFFF if register pointer is bad
118
- **********************************************************************/
119
-uint32_t converPtrToTimeNum (LPC_TIM_TypeDef *TIMx)
120
-{
121
-	uint32_t tnum = 0xFFFFFFFF;
122
-
123
-	if (TIMx == LPC_TIM0)
124
-	{
125
-		tnum = 0;
126
-	}
127
-	else if (TIMx == LPC_TIM1)
128
-	{
129
-		tnum = 1;
130
-	}
131
-	else if (TIMx == LPC_TIM2)
132
-	{
133
-		tnum = 2;
134
-	}
135
-	else if (TIMx == LPC_TIM3)
136
-	{
137
-		tnum = 3;
138
-	}
139
-
140
-	return tnum;
141
-}
142
-
143
-/* End of Private Functions ---------------------------------------------------- */
144
-
145
-
146
-/* Public Functions ----------------------------------------------------------- */
147
-/** @addtogroup TIM_Public_Functions
148
- * @{
149
- */
150
-
151
-/*********************************************************************//**
152
- * @brief 		Get Interrupt Status
153
- * @param[in]	TIMx Timer selection, should be:
154
- *   			- LPC_TIM0: TIMER0 peripheral
155
- * 				- LPC_TIM1: TIMER1 peripheral
156
- * 				- LPC_TIM2: TIMER2 peripheral
157
- * 				- LPC_TIM3: TIMER3 peripheral
158
- * @param[in]	IntFlag: interrupt type, should be:
159
- * 				- TIM_MR0_INT: Interrupt for Match channel 0
160
- * 				- TIM_MR1_INT: Interrupt for Match channel 1
161
- * 				- TIM_MR2_INT: Interrupt for Match channel 2
162
- * 				- TIM_MR3_INT: Interrupt for Match channel 3
163
- * 				- TIM_CR0_INT: Interrupt for Capture channel 0
164
- * 				- TIM_CR1_INT: Interrupt for Capture channel 1
165
- * @return 		FlagStatus
166
- * 				- SET : interrupt
167
- * 				- RESET : no interrupt
168
- **********************************************************************/
169
-FlagStatus TIM_GetIntStatus(LPC_TIM_TypeDef *TIMx, TIM_INT_TYPE IntFlag)
170
-{
171
-	uint8_t temp;
172
-	CHECK_PARAM(PARAM_TIMx(TIMx));
173
-	CHECK_PARAM(PARAM_TIM_INT_TYPE(IntFlag));
174
-	temp = (TIMx->IR)& TIM_IR_CLR(IntFlag);
175
-	if (temp)
176
-		return SET;
177
-
178
-	return RESET;
179
-
180
-}
181
-/*********************************************************************//**
182
- * @brief 		Get Capture Interrupt Status
183
- * @param[in]	TIMx Timer selection, should be:
184
- *  	   		- LPC_TIM0: TIMER0 peripheral
185
- * 				- LPC_TIM1: TIMER1 peripheral
186
- * 				- LPC_TIM2: TIMER2 peripheral
187
- * 				- LPC_TIM3: TIMER3 peripheral
188
- * @param[in]	IntFlag: interrupt type, should be:
189
- * 				- TIM_MR0_INT: Interrupt for Match channel 0
190
- * 				- TIM_MR1_INT: Interrupt for Match channel 1
191
- * 				- TIM_MR2_INT: Interrupt for Match channel 2
192
- * 				- TIM_MR3_INT: Interrupt for Match channel 3
193
- * 				- TIM_CR0_INT: Interrupt for Capture channel 0
194
- * 				- TIM_CR1_INT: Interrupt for Capture channel 1
195
- * @return 		FlagStatus
196
- * 				- SET : interrupt
197
- * 				- RESET : no interrupt
198
- **********************************************************************/
199
-FlagStatus TIM_GetIntCaptureStatus(LPC_TIM_TypeDef *TIMx, TIM_INT_TYPE IntFlag)
200
-{
201
-	uint8_t temp;
202
-	CHECK_PARAM(PARAM_TIMx(TIMx));
203
-	CHECK_PARAM(PARAM_TIM_INT_TYPE(IntFlag));
204
-	temp = (TIMx->IR) & (1<<(4+IntFlag));
205
-	if(temp)
206
-		return SET;
207
-	return RESET;
208
-}
209
-/*********************************************************************//**
210
- * @brief 		Clear Interrupt pending
211
- * @param[in]	TIMx Timer selection, should be:
212
- *    			- LPC_TIM0: TIMER0 peripheral
213
- * 				- LPC_TIM1: TIMER1 peripheral
214
- * 				- LPC_TIM2: TIMER2 peripheral
215
- * 				- LPC_TIM3: TIMER3 peripheral
216
- * @param[in]	IntFlag: interrupt type, should be:
217
- * 				- TIM_MR0_INT: Interrupt for Match channel 0
218
- * 				- TIM_MR1_INT: Interrupt for Match channel 1
219
- * 				- TIM_MR2_INT: Interrupt for Match channel 2
220
- * 				- TIM_MR3_INT: Interrupt for Match channel 3
221
- * 				- TIM_CR0_INT: Interrupt for Capture channel 0
222
- * 				- TIM_CR1_INT: Interrupt for Capture channel 1
223
- * @return 		None
224
- **********************************************************************/
225
-void TIM_ClearIntPending(LPC_TIM_TypeDef *TIMx, TIM_INT_TYPE IntFlag)
226
-{
227
-	CHECK_PARAM(PARAM_TIMx(TIMx));
228
-	CHECK_PARAM(PARAM_TIM_INT_TYPE(IntFlag));
229
-	TIMx->IR = TIM_IR_CLR(IntFlag);
230
-}
231
-
232
-/*********************************************************************//**
233
- * @brief 		Clear Capture Interrupt pending
234
- * @param[in]	TIMx Timer selection, should be
235
- *    			- LPC_TIM0: TIMER0 peripheral
236
- * 				- LPC_TIM1: TIMER1 peripheral
237
- * 				- LPC_TIM2: TIMER2 peripheral
238
- * 				- LPC_TIM3: TIMER3 peripheral
239
- * @param[in]	IntFlag interrupt type, should be:
240
- *				- TIM_MR0_INT: Interrupt for Match channel 0
241
- * 				- TIM_MR1_INT: Interrupt for Match channel 1
242
- * 				- TIM_MR2_INT: Interrupt for Match channel 2
243
- * 				- TIM_MR3_INT: Interrupt for Match channel 3
244
- * 				- TIM_CR0_INT: Interrupt for Capture channel 0
245
- * 				- TIM_CR1_INT: Interrupt for Capture channel 1
246
- * @return 		None
247
- **********************************************************************/
248
-void TIM_ClearIntCapturePending(LPC_TIM_TypeDef *TIMx, TIM_INT_TYPE IntFlag)
249
-{
250
-	CHECK_PARAM(PARAM_TIMx(TIMx));
251
-	CHECK_PARAM(PARAM_TIM_INT_TYPE(IntFlag));
252
-	TIMx->IR = (1<<(4+IntFlag));
253
-}
254
-
255
-/*********************************************************************//**
256
- * @brief 		Configuration for Timer at initial time
257
- * @param[in] 	TimerCounterMode timer counter mode, should be:
258
- * 				- TIM_TIMER_MODE: Timer mode
259
- * 				- TIM_COUNTER_RISING_MODE: Counter rising mode
260
- * 				- TIM_COUNTER_FALLING_MODE: Counter falling mode
261
- * 				- TIM_COUNTER_ANY_MODE:Counter on both edges
262
- * @param[in] 	TIM_ConfigStruct pointer to TIM_TIMERCFG_Type or
263
- * 				TIM_COUNTERCFG_Type
264
- * @return 		None
265
- **********************************************************************/
266
-void TIM_ConfigStructInit(TIM_MODE_OPT TimerCounterMode, void *TIM_ConfigStruct)
267
-{
268
-	if (TimerCounterMode == TIM_TIMER_MODE )
269
-	{
270
-		TIM_TIMERCFG_Type * pTimeCfg = (TIM_TIMERCFG_Type *)TIM_ConfigStruct;
271
-		pTimeCfg->PrescaleOption = TIM_PRESCALE_USVAL;
272
-		pTimeCfg->PrescaleValue = 1;
273
-	}
274
-	else
275
-	{
276
-		TIM_COUNTERCFG_Type * pCounterCfg = (TIM_COUNTERCFG_Type *)TIM_ConfigStruct;
277
-		pCounterCfg->CountInputSelect = TIM_COUNTER_INCAP0;
278
-	}
279
-}
280
-
281
-/*********************************************************************//**
282
- * @brief 		Initial Timer/Counter device
283
- * 				 	Set Clock frequency for Timer
284
- * 					Set initial configuration for Timer
285
- * @param[in]	TIMx  Timer selection, should be:
286
- * 				- LPC_TIM0: TIMER0 peripheral
287
- * 				- LPC_TIM1: TIMER1 peripheral
288
- * 				- LPC_TIM2: TIMER2 peripheral
289
- * 				- LPC_TIM3: TIMER3 peripheral
290
- * @param[in]	TimerCounterMode Timer counter mode, should be:
291
- * 				- TIM_TIMER_MODE: Timer mode
292
- * 				- TIM_COUNTER_RISING_MODE: Counter rising mode
293
- * 				- TIM_COUNTER_FALLING_MODE: Counter falling mode
294
- * 				- TIM_COUNTER_ANY_MODE:Counter on both edges
295
- * @param[in]	TIM_ConfigStruct pointer to TIM_TIMERCFG_Type
296
- * 				that contains the configuration information for the
297
- *                    specified Timer peripheral.
298
- * @return 		None
299
- **********************************************************************/
300
-void TIM_Init(LPC_TIM_TypeDef *TIMx, TIM_MODE_OPT TimerCounterMode, void *TIM_ConfigStruct)
301
-{
302
-	TIM_TIMERCFG_Type *pTimeCfg;
303
-	TIM_COUNTERCFG_Type *pCounterCfg;
304
-
305
-	CHECK_PARAM(PARAM_TIMx(TIMx));
306
-	CHECK_PARAM(PARAM_TIM_MODE_OPT(TimerCounterMode));
307
-
308
-	//set power
309
-
310
-	if (TIMx== LPC_TIM0)
311
-	{
312
-		CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCTIM0, ENABLE);
313
-		//PCLK_Timer0 = CCLK/4
314
-		CLKPWR_SetPCLKDiv (CLKPWR_PCLKSEL_TIMER0, CLKPWR_PCLKSEL_CCLK_DIV_4);
315
-	}
316
-	else if (TIMx== LPC_TIM1)
317
-	{
318
-		CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCTIM1, ENABLE);
319
-		//PCLK_Timer1 = CCLK/4
320
-		CLKPWR_SetPCLKDiv (CLKPWR_PCLKSEL_TIMER1, CLKPWR_PCLKSEL_CCLK_DIV_4);
321
-
322
-	}
323
-
324
-	else if (TIMx== LPC_TIM2)
325
-	{
326
-		CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCTIM2, ENABLE);
327
-		//PCLK_Timer2= CCLK/4
328
-		CLKPWR_SetPCLKDiv (CLKPWR_PCLKSEL_TIMER2, CLKPWR_PCLKSEL_CCLK_DIV_4);
329
-	}
330
-	else if (TIMx== LPC_TIM3)
331
-	{
332
-		CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCTIM3, ENABLE);
333
-		//PCLK_Timer3= CCLK/4
334
-		CLKPWR_SetPCLKDiv (CLKPWR_PCLKSEL_TIMER3, CLKPWR_PCLKSEL_CCLK_DIV_4);
335
-
336
-	}
337
-
338
-	TIMx->CCR &= ~TIM_CTCR_MODE_MASK;
339
-	TIMx->CCR |= TIM_TIMER_MODE;
340
-
341
-	TIMx->TC =0;
342
-	TIMx->PC =0;
343
-	TIMx->PR =0;
344
-	TIMx->TCR |= (1<<1); //Reset Counter
345
-	TIMx->TCR &= ~(1<<1); //release reset
346
-	if (TimerCounterMode == TIM_TIMER_MODE )
347
-	{
348
-		pTimeCfg = (TIM_TIMERCFG_Type *)TIM_ConfigStruct;
349
-		if (pTimeCfg->PrescaleOption  == TIM_PRESCALE_TICKVAL)
350
-		{
351
-			TIMx->PR   = pTimeCfg->PrescaleValue -1  ;
352
-		}
353
-		else
354
-		{
355
-			TIMx->PR   = converUSecToVal (converPtrToTimeNum(TIMx),pTimeCfg->PrescaleValue)-1;
356
-		}
357
-	}
358
-	else
359
-	{
360
-
361
-		pCounterCfg = (TIM_COUNTERCFG_Type *)TIM_ConfigStruct;
362
-		TIMx->CCR  &= ~TIM_CTCR_INPUT_MASK;
363
-		if (pCounterCfg->CountInputSelect == TIM_COUNTER_INCAP1)
364
-			TIMx->CCR |= _BIT(2);
365
-	}
366
-
367
-	// Clear interrupt pending
368
-	TIMx->IR = 0xFFFFFFFF;
369
-
370
-}
371
-
372
-/*********************************************************************//**
373
- * @brief 		Close Timer/Counter device
374
- * @param[in]	TIMx  Pointer to timer device, should be:
375
- * 				- LPC_TIM0: TIMER0 peripheral
376
- * 				- LPC_TIM1: TIMER1 peripheral
377
- * 				- LPC_TIM2: TIMER2 peripheral
378
- * 				- LPC_TIM3: TIMER3 peripheral
379
- * @return 		None
380
- **********************************************************************/
381
-void TIM_DeInit (LPC_TIM_TypeDef *TIMx)
382
-{
383
-	CHECK_PARAM(PARAM_TIMx(TIMx));
384
-	// Disable timer/counter
385
-	TIMx->TCR = 0x00;
386
-
387
-	// Disable power
388
-	if (TIMx== LPC_TIM0)
389
-		CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCTIM0, DISABLE);
390
-
391
-	else if (TIMx== LPC_TIM1)
392
-		CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCTIM1, DISABLE);
393
-
394
-	else if (TIMx== LPC_TIM2)
395
-		CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCTIM2, DISABLE);
396
-
397
-	else if (TIMx== LPC_TIM3)
398
-		CLKPWR_ConfigPPWR (CLKPWR_PCONP_PCTIM2, DISABLE);
399
-
400
-}
401
-
402
-/*********************************************************************//**
403
- * @brief	 	Start/Stop Timer/Counter device
404
- * @param[in]	TIMx Pointer to timer device, should be:
405
- *  			- LPC_TIM0: TIMER0 peripheral
406
- * 				- LPC_TIM1: TIMER1 peripheral
407
- * 				- LPC_TIM2: TIMER2 peripheral
408
- * 				- LPC_TIM3: TIMER3 peripheral
409
- * @param[in]	NewState
410
- * 				-	ENABLE  : set timer enable
411
- * 				-	DISABLE : disable timer
412
- * @return 		None
413
- **********************************************************************/
414
-void TIM_Cmd(LPC_TIM_TypeDef *TIMx, FunctionalState NewState)
415
-{
416
-	CHECK_PARAM(PARAM_TIMx(TIMx));
417
-	if (NewState == ENABLE)
418
-	{
419
-		TIMx->TCR	|=  TIM_ENABLE;
420
-	}
421
-	else
422
-	{
423
-		TIMx->TCR &= ~TIM_ENABLE;
424
-	}
425
-}
426
-
427
-/*********************************************************************//**
428
- * @brief 		Reset Timer/Counter device,
429
- * 					Make TC and PC are synchronously reset on the next
430
- * 					positive edge of PCLK
431
- * @param[in]	TIMx Pointer to timer device, should be:
432
- *   			- LPC_TIM0: TIMER0 peripheral
433
- * 				- LPC_TIM1: TIMER1 peripheral
434
- * 				- LPC_TIM2: TIMER2 peripheral
435
- * 				- LPC_TIM3: TIMER3 peripheral
436
- * @return 		None
437
- **********************************************************************/
438
-void TIM_ResetCounter(LPC_TIM_TypeDef *TIMx)
439
-{
440
-	CHECK_PARAM(PARAM_TIMx(TIMx));
441
-	TIMx->TCR |= TIM_RESET;
442
-	TIMx->TCR &= ~TIM_RESET;
443
-}
444
-
445
-/*********************************************************************//**
446
- * @brief 		Configuration for Match register
447
- * @param[in]	TIMx Pointer to timer device, should be:
448
- *   			- LPC_TIM0: TIMER0 peripheral
449
- * 				- LPC_TIM1: TIMER1 peripheral
450
- * 				- LPC_TIM2: TIMER2 peripheral
451
- * 				- LPC_TIM3: TIMER3 peripheral
452
- * @param[in]   TIM_MatchConfigStruct Pointer to TIM_MATCHCFG_Type
453
- * 					- MatchChannel : choose channel 0 or 1
454
- * 					- IntOnMatch	 : if SET, interrupt will be generated when MRxx match
455
- * 									the value in TC
456
- * 					- StopOnMatch	 : if SET, TC and PC will be stopped whenM Rxx match
457
- * 									the value in TC
458
- * 					- ResetOnMatch : if SET, Reset on MR0 when MRxx match
459
- * 									the value in TC
460
- * 					-ExtMatchOutputType: Select output for external match
461
- * 						 +	 0:	Do nothing for external output pin if match
462
- *						 +   1:	Force external output pin to low if match
463
- *						 + 	 2: Force external output pin to high if match
464
- *						 + 	 3: Toggle external output pin if match
465
- *					MatchValue: Set the value to be compared with TC value
466
- * @return 		None
467
- **********************************************************************/
468
-void TIM_ConfigMatch(LPC_TIM_TypeDef *TIMx, TIM_MATCHCFG_Type *TIM_MatchConfigStruct)
469
-{
470
-
471
-	CHECK_PARAM(PARAM_TIMx(TIMx));
472
-	CHECK_PARAM(PARAM_TIM_EXTMATCH_OPT(TIM_MatchConfigStruct->ExtMatchOutputType));
473
-
474
-	switch(TIM_MatchConfigStruct->MatchChannel)
475
-	{
476
-	case 0:
477
-		TIMx->MR0 = TIM_MatchConfigStruct->MatchValue;
478
-		break;
479
-	case 1:
480
-		TIMx->MR1 = TIM_MatchConfigStruct->MatchValue;
481
-		break;
482
-	case 2:
483
-		TIMx->MR2 = TIM_MatchConfigStruct->MatchValue;
484
-		break;
485
-	case 3:
486
-		TIMx->MR3 = TIM_MatchConfigStruct->MatchValue;
487
-		break;
488
-	default:
489
-		//Error match value
490
-		//Error loop
491
-		while(1);
492
-	}
493
-	//interrupt on MRn
494
-	TIMx->MCR &=~TIM_MCR_CHANNEL_MASKBIT(TIM_MatchConfigStruct->MatchChannel);
495
-
496
-	if (TIM_MatchConfigStruct->IntOnMatch)
497
-		TIMx->MCR |= TIM_INT_ON_MATCH(TIM_MatchConfigStruct->MatchChannel);
498
-
499
-	//reset on MRn
500
-	if (TIM_MatchConfigStruct->ResetOnMatch)
501
-		TIMx->MCR |= TIM_RESET_ON_MATCH(TIM_MatchConfigStruct->MatchChannel);
502
-
503
-	//stop on MRn
504
-	if (TIM_MatchConfigStruct->StopOnMatch)
505
-		TIMx->MCR |= TIM_STOP_ON_MATCH(TIM_MatchConfigStruct->MatchChannel);
506
-
507
-	// match output type
508
-
509
-	TIMx->EMR 	&= ~TIM_EM_MASK(TIM_MatchConfigStruct->MatchChannel);
510
-	TIMx->EMR   |= TIM_EM_SET(TIM_MatchConfigStruct->MatchChannel,TIM_MatchConfigStruct->ExtMatchOutputType);
511
-}
512
-/*********************************************************************//**
513
- * @brief 		Update Match value
514
- * @param[in]	TIMx Pointer to timer device, should be:
515
- *   			- LPC_TIM0: TIMER0 peripheral
516
- * 				- LPC_TIM1: TIMER1 peripheral
517
- * 				- LPC_TIM2: TIMER2 peripheral
518
- * 				- LPC_TIM3: TIMER3 peripheral
519
- * @param[in]	MatchChannel	Match channel, should be: 0..3
520
- * @param[in]	MatchValue		updated match value
521
- * @return 		None
522
- **********************************************************************/
523
-void TIM_UpdateMatchValue(LPC_TIM_TypeDef *TIMx,uint8_t MatchChannel, uint32_t MatchValue)
524
-{
525
-	CHECK_PARAM(PARAM_TIMx(TIMx));
526
-	switch(MatchChannel)
527
-	{
528
-	case 0:
529
-		TIMx->MR0 = MatchValue;
530
-		break;
531
-	case 1:
532
-		TIMx->MR1 = MatchValue;
533
-		break;
534
-	case 2:
535
-		TIMx->MR2 = MatchValue;
536
-		break;
537
-	case 3:
538
-		TIMx->MR3 = MatchValue;
539
-		break;
540
-	default:
541
-		//Error Loop
542
-		while(1);
543
-	}
544
-
545
-}
546
-/*********************************************************************//**
547
- * @brief 		Configuration for Capture register
548
- * @param[in]	TIMx Pointer to timer device, should be:
549
- *   			- LPC_TIM0: TIMER0 peripheral
550
- * 				- LPC_TIM1: TIMER1 peripheral
551
- * 				- LPC_TIM2: TIMER2 peripheral
552
- * 				- LPC_TIM3: TIMER3 peripheral
553
- * 					- CaptureChannel: set the channel to capture data
554
- * 					- RisingEdge    : if SET, Capture at rising edge
555
- * 					- FallingEdge	: if SET, Capture at falling edge
556
- * 					- IntOnCaption  : if SET, Capture generate interrupt
557
- * @param[in]   TIM_CaptureConfigStruct	Pointer to TIM_CAPTURECFG_Type
558
- * @return 		None
559
- **********************************************************************/
560
-void TIM_ConfigCapture(LPC_TIM_TypeDef *TIMx, TIM_CAPTURECFG_Type *TIM_CaptureConfigStruct)
561
-{
562
-
563
-	CHECK_PARAM(PARAM_TIMx(TIMx));
564
-	TIMx->CCR &= ~TIM_CCR_CHANNEL_MASKBIT(TIM_CaptureConfigStruct->CaptureChannel);
565
-
566
-	if (TIM_CaptureConfigStruct->RisingEdge)
567
-		TIMx->CCR |= TIM_CAP_RISING(TIM_CaptureConfigStruct->CaptureChannel);
568
-
569
-	if (TIM_CaptureConfigStruct->FallingEdge)
570
-		TIMx->CCR |= TIM_CAP_FALLING(TIM_CaptureConfigStruct->CaptureChannel);
571
-
572
-	if (TIM_CaptureConfigStruct->IntOnCaption)
573
-		TIMx->CCR |= TIM_INT_ON_CAP(TIM_CaptureConfigStruct->CaptureChannel);
574
-}
575
-
576
-/*********************************************************************//**
577
- * @brief 		Read value of capture register in timer/counter device
578
- * @param[in]	TIMx Pointer to timer/counter device, should be:
579
- *  			- LPC_TIM0: TIMER0 peripheral
580
- * 				- LPC_TIM1: TIMER1 peripheral
581
- * 				- LPC_TIM2: TIMER2 peripheral
582
- * 				- LPC_TIM3: TIMER3 peripheral
583
- * @param[in]	CaptureChannel: capture channel number, should be:
584
- * 				- TIM_COUNTER_INCAP0: CAPn.0 input pin for TIMERn
585
- * 				- TIM_COUNTER_INCAP1: CAPn.1 input pin for TIMERn
586
- * @return 		Value of capture register
587
- **********************************************************************/
588
-uint32_t TIM_GetCaptureValue(LPC_TIM_TypeDef *TIMx, TIM_COUNTER_INPUT_OPT CaptureChannel)
589
-{
590
-	CHECK_PARAM(PARAM_TIMx(TIMx));
591
-	CHECK_PARAM(PARAM_TIM_COUNTER_INPUT_OPT(CaptureChannel));
592
-
593
-	if(CaptureChannel==0)
594
-		return TIMx->CR0;
595
-	else
596
-		return TIMx->CR1;
597
-}
598
-
599
-/**
600
- * @}
601
- */
602
-
603
-#endif /* _TIMER */
604
-
605
-/**
606
- * @}
607
- */
608
-
609
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 1382
frameworks/CMSIS/LPC1768/driver/lpc17xx_uart.c
Разница между файлами не показана из-за своего большого размера
Просмотреть файл


+ 0
- 274
frameworks/CMSIS/LPC1768/driver/lpc17xx_wdt.c Просмотреть файл

@@ -1,274 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_wdt.c			2010-05-21
3
-*//**
4
-* @file		lpc17xx_wdt.c
5
-* @brief	Contains all functions support for WDT firmware library
6
-* 			on LPC17xx
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @addtogroup WDT
35
- * @{
36
- */
37
-
38
-/* Includes ------------------------------------------------------------------- */
39
-#include "lpc17xx_wdt.h"
40
-#include "lpc17xx_clkpwr.h"
41
-#include "lpc17xx_pinsel.h"
42
-
43
-
44
-/* If this source file built with example, the LPC17xx FW library configuration
45
- * file in each example directory ("lpc17xx_libcfg.h") must be included,
46
- * otherwise the default FW library configuration file must be included instead
47
- */
48
-#ifdef __BUILD_WITH_EXAMPLE__
49
-#include "lpc17xx_libcfg.h"
50
-#else
51
-#include "lpc17xx_libcfg_default.h"
52
-#endif /* __BUILD_WITH_EXAMPLE__ */
53
-
54
-
55
-#ifdef _WDT
56
-
57
-/* Private Functions ---------------------------------------------------------- */
58
-
59
-static uint8_t WDT_SetTimeOut (uint8_t clk_source, uint32_t timeout);
60
-
61
-/********************************************************************//**
62
- * @brief 		Set WDT time out value and WDT mode
63
- * @param[in]	clk_source select Clock source for WDT device
64
- * @param[in]	timeout value of time-out for WDT (us)
65
- * @return		None
66
- *********************************************************************/
67
-static uint8_t WDT_SetTimeOut (uint8_t clk_source, uint32_t timeout)
68
-{
69
-
70
-	uint32_t pclk_wdt = 0;
71
-	uint32_t tempval = 0;
72
-
73
-	switch ((WDT_CLK_OPT) clk_source)
74
-    {
75
-    case WDT_CLKSRC_IRC:
76
-    	pclk_wdt = 4000000;
77
-    	// Calculate TC in WDT
78
-    	tempval  = ((((uint64_t)pclk_wdt * (uint64_t)timeout / 4) / (uint64_t)WDT_US_INDEX));
79
-    	// Check if it valid
80
-    	if (tempval >= WDT_TIMEOUT_MIN)
81
-    	{
82
-    		LPC_WDT->WDTC = tempval;
83
-    		return	SUCCESS;
84
-    	}
85
-
86
-    	break;
87
-
88
-    case WDT_CLKSRC_PCLK:
89
-
90
-    	// Get WDT clock with CCLK divider = 4
91
-		pclk_wdt = SystemCoreClock / 4;
92
-		// Calculate TC in WDT
93
-		tempval  = ((((uint64_t)pclk_wdt * (uint64_t)timeout / 4) / (uint64_t)WDT_US_INDEX));
94
-
95
-		if (tempval >= WDT_TIMEOUT_MIN)
96
-		{
97
-			CLKPWR_SetPCLKDiv (CLKPWR_PCLKSEL_WDT, CLKPWR_PCLKSEL_CCLK_DIV_4);
98
-			LPC_WDT->WDTC = (uint32_t) tempval;
99
-			return SUCCESS;
100
-		}
101
-
102
-		// Get WDT clock with CCLK divider = 2
103
-		pclk_wdt = SystemCoreClock / 2;
104
-		// Calculate TC in WDT
105
-		tempval  = ((((uint64_t)pclk_wdt * (uint64_t)timeout / 4) / (uint64_t)WDT_US_INDEX));
106
-
107
-		if (tempval >= WDT_TIMEOUT_MIN)
108
-		{
109
-			CLKPWR_SetPCLKDiv (CLKPWR_PCLKSEL_WDT, CLKPWR_PCLKSEL_CCLK_DIV_2);
110
-			LPC_WDT->WDTC = (uint32_t) tempval;
111
-			return	SUCCESS;
112
-		}
113
-
114
-		// Get WDT clock with CCLK divider = 1
115
-		pclk_wdt = SystemCoreClock;
116
-		// Calculate TC in WDT
117
-		tempval  = ((((uint64_t)pclk_wdt * (uint64_t)timeout / 4) / (uint64_t)WDT_US_INDEX));
118
-
119
-		if (tempval >= WDT_TIMEOUT_MIN)
120
-		{
121
-			CLKPWR_SetPCLKDiv (CLKPWR_PCLKSEL_WDT, CLKPWR_PCLKSEL_CCLK_DIV_1);
122
-			LPC_WDT->WDTC = (uint32_t) tempval;
123
-			return	SUCCESS;
124
-		}
125
-		break ;
126
-
127
-
128
-    case WDT_CLKSRC_RTC:
129
-		pclk_wdt = 32768;
130
-		// Calculate TC in WDT
131
-		tempval  = ((((uint64_t)pclk_wdt * (uint64_t)timeout / 4) / (uint64_t)WDT_US_INDEX));
132
-		// Check if it valid
133
-		if (tempval >= WDT_TIMEOUT_MIN)
134
-		{
135
-			LPC_WDT->WDTC = (uint32_t) tempval;
136
-			return	SUCCESS;
137
-		}
138
-
139
-		break;
140
-
141
-// Error parameter
142
-		default:
143
-			break;
144
-}
145
-
146
-	return ERROR;
147
-}
148
-
149
-/* End of Private Functions --------------------------------------------------- */
150
-
151
-
152
-/* Public Functions ----------------------------------------------------------- */
153
-/** @addtogroup WDT_Public_Functions
154
- * @{
155
- */
156
-
157
-
158
-/*********************************************************************//**
159
-* @brief 		Initial for Watchdog function
160
-* 					Clock source = RTC ,
161
-* @param[in]	ClkSrc  Select clock source, should be:
162
-* 				- WDT_CLKSRC_IRC: Clock source from Internal RC oscillator
163
-* 				- WDT_CLKSRC_PCLK: Selects the APB peripheral clock (PCLK)
164
-* 				- WDT_CLKSRC_RTC: Selects the RTC oscillator
165
-* @param[in]	WDTMode WDT mode, should be:
166
-* 				- WDT_MODE_INT_ONLY: Use WDT to generate interrupt only
167
-* 				- WDT_MODE_RESET: Use WDT to generate interrupt and reset MCU
168
-* @return 		None
169
- **********************************************************************/
170
-void WDT_Init (WDT_CLK_OPT ClkSrc, WDT_MODE_OPT WDTMode)
171
-{
172
-	CHECK_PARAM(PARAM_WDT_CLK_OPT(ClkSrc));
173
-	CHECK_PARAM(PARAM_WDT_MODE_OPT(WDTMode));
174
-	CLKPWR_SetPCLKDiv (CLKPWR_PCLKSEL_WDT, CLKPWR_PCLKSEL_CCLK_DIV_4);
175
-
176
-	//Set clock source
177
-	LPC_WDT->WDCLKSEL &= ~WDT_WDCLKSEL_MASK;
178
-	LPC_WDT->WDCLKSEL |= ClkSrc;
179
-	//Set WDT mode
180
-	if (WDTMode == WDT_MODE_RESET){
181
-		LPC_WDT->WDMOD |= WDT_WDMOD(WDTMode);
182
-	}
183
-}
184
-
185
-/*********************************************************************//**
186
-* @brief 		Start WDT activity with given timeout value
187
-* @param[in]	TimeOut WDT reset after timeout if it is not feed
188
-* @return 		None
189
- **********************************************************************/
190
-void WDT_Start(uint32_t TimeOut)
191
-{
192
-	uint32_t ClkSrc;
193
-
194
-	ClkSrc = LPC_WDT->WDCLKSEL;
195
-	ClkSrc &=WDT_WDCLKSEL_MASK;
196
-	WDT_SetTimeOut(ClkSrc,TimeOut);
197
-	//enable watchdog
198
-	LPC_WDT->WDMOD |= WDT_WDMOD_WDEN;
199
-	WDT_Feed();
200
-}
201
-
202
-/********************************************************************//**
203
- * @brief 		Read WDT Time out flag
204
- * @param[in]	None
205
- * @return		Time out flag status of WDT
206
- *********************************************************************/
207
-FlagStatus WDT_ReadTimeOutFlag (void)
208
-{
209
-	return ((FlagStatus)((LPC_WDT->WDMOD & WDT_WDMOD_WDTOF) >>2));
210
-}
211
-
212
-/********************************************************************//**
213
- * @brief 		Clear WDT Time out flag
214
- * @param[in]	None
215
- * @return		None
216
- *********************************************************************/
217
-void WDT_ClrTimeOutFlag (void)
218
-{
219
-	LPC_WDT->WDMOD &=~WDT_WDMOD_WDTOF;
220
-}
221
-
222
-/********************************************************************//**
223
- * @brief 		Update WDT timeout value and feed
224
- * @param[in]	TimeOut	TimeOut value to be updated
225
- * @return		None
226
- *********************************************************************/
227
-void WDT_UpdateTimeOut ( uint32_t TimeOut)
228
-{
229
-	uint32_t ClkSrc;
230
-	ClkSrc = LPC_WDT->WDCLKSEL;
231
-	ClkSrc &=WDT_WDCLKSEL_MASK;
232
-	WDT_SetTimeOut(ClkSrc,TimeOut);
233
-	WDT_Feed();
234
-}
235
-
236
-
237
-/********************************************************************//**
238
- * @brief 		After set WDTEN, call this function to start Watchdog
239
- * 				or reload the Watchdog timer
240
- * @param[in]	None
241
- *
242
- * @return		None
243
- *********************************************************************/
244
-void WDT_Feed (void)
245
-{
246
-	// Disable irq interrupt
247
-	__disable_irq();
248
-	LPC_WDT->WDFEED = 0xAA;
249
-	LPC_WDT->WDFEED = 0x55;
250
-	// Then enable irq interrupt
251
-	__enable_irq();
252
-}
253
-
254
-/********************************************************************//**
255
- * @brief 		Get the current value of WDT
256
- * @param[in]	None
257
- * @return		current value of WDT
258
- *********************************************************************/
259
-uint32_t WDT_GetCurrentCount(void)
260
-{
261
-	return LPC_WDT->WDTV;
262
-}
263
-
264
-/**
265
- * @}
266
- */
267
-
268
-#endif /* _WDT */
269
-
270
-/**
271
- * @}
272
- */
273
-
274
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 1078
frameworks/CMSIS/LPC1768/include/LPC17xx.h
Разница между файлами не показана из-за своего большого размера
Просмотреть файл


+ 0
- 35
frameworks/CMSIS/LPC1768/include/arm_common_tables.h Просмотреть файл

@@ -1,35 +0,0 @@
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
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];
33
-extern const q31_t realCoefBQ31[1024];
34
-
35
-#endif /*  ARM_COMMON_TABLES_H */

+ 0
- 7064
frameworks/CMSIS/LPC1768/include/arm_math.h
Разница между файлами не показана из-за своего большого размера
Просмотреть файл


+ 0
- 1227
frameworks/CMSIS/LPC1768/include/core_cm3.h
Разница между файлами не показана из-за своего большого размера
Просмотреть файл


+ 0
- 609
frameworks/CMSIS/LPC1768/include/core_cmFunc.h Просмотреть файл

@@ -1,609 +0,0 @@
1
-/**************************************************************************//**
2
- * @file     core_cmFunc.h
3
- * @brief    CMSIS Cortex-M Core Function Access Header File
4
- * @version  V2.10
5
- * @date     26. July 2011
6
- *
7
- * @note
8
- * Copyright (C) 2009-2011 ARM Limited. All rights reserved.
9
- *
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.
14
- *
15
- * @par
16
- * THIS SOFTWARE IS PROVIDED "AS IS".  NO WARRANTIES, WHETHER EXPRESS, IMPLIED
17
- * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
18
- * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
19
- * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
20
- * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
21
- *
22
- ******************************************************************************/
23
-
24
-#ifndef __CORE_CMFUNC_H
25
-#define __CORE_CMFUNC_H
26
-
27
-
28
-/* ###########################  Core Function Access  ########################### */
29
-/** \ingroup  CMSIS_Core_FunctionInterface
30
-    \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions
31
-  @{
32
- */
33
-
34
-#if   defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
35
-/* ARM armcc specific functions */
36
-
37
-#if (__ARMCC_VERSION < 400677)
38
-  #error "Please use ARM Compiler Toolchain V4.0.677 or later!"
39
-#endif
40
-
41
-/* intrinsic void __enable_irq();     */
42
-/* intrinsic void __disable_irq();    */
43
-
44
-/** \brief  Get Control Register
45
-
46
-    This function returns the content of the Control Register.
47
-
48
-    \return               Control Register value
49
- */
50
-static __INLINE uint32_t __get_CONTROL(void)
51
-{
52
-  register uint32_t __regControl         __ASM("control");
53
-  return(__regControl);
54
-}
55
-
56
-
57
-/** \brief  Set Control Register
58
-
59
-    This function writes the given value to the Control Register.
60
-
61
-    \param [in]    control  Control Register value to set
62
- */
63
-static __INLINE void __set_CONTROL(uint32_t control)
64
-{
65
-  register uint32_t __regControl         __ASM("control");
66
-  __regControl = control;
67
-}
68
-
69
-
70
-/** \brief  Get ISPR Register
71
-
72
-    This function returns the content of the ISPR Register.
73
-
74
-    \return               ISPR Register value
75
- */
76
-static __INLINE uint32_t __get_IPSR(void)
77
-{
78
-  register uint32_t __regIPSR          __ASM("ipsr");
79
-  return(__regIPSR);
80
-}
81
-
82
-
83
-/** \brief  Get APSR Register
84
-
85
-    This function returns the content of the APSR Register.
86
-
87
-    \return               APSR Register value
88
- */
89
-static __INLINE uint32_t __get_APSR(void)
90
-{
91
-  register uint32_t __regAPSR          __ASM("apsr");
92
-  return(__regAPSR);
93
-}
94
-
95
-
96
-/** \brief  Get xPSR Register
97
-
98
-    This function returns the content of the xPSR Register.
99
-
100
-    \return               xPSR Register value
101
- */
102
-static __INLINE uint32_t __get_xPSR(void)
103
-{
104
-  register uint32_t __regXPSR          __ASM("xpsr");
105
-  return(__regXPSR);
106
-}
107
-
108
-
109
-/** \brief  Get Process Stack Pointer
110
-
111
-    This function returns the current value of the Process Stack Pointer (PSP).
112
-
113
-    \return               PSP Register value
114
- */
115
-static __INLINE uint32_t __get_PSP(void)
116
-{
117
-  register uint32_t __regProcessStackPointer  __ASM("psp");
118
-  return(__regProcessStackPointer);
119
-}
120
-
121
-
122
-/** \brief  Set Process Stack Pointer
123
-
124
-    This function assigns the given value to the Process Stack Pointer (PSP).
125
-
126
-    \param [in]    topOfProcStack  Process Stack Pointer value to set
127
- */
128
-static __INLINE void __set_PSP(uint32_t topOfProcStack)
129
-{
130
-  register uint32_t __regProcessStackPointer  __ASM("psp");
131
-  __regProcessStackPointer = topOfProcStack;
132
-}
133
-
134
-
135
-/** \brief  Get Main Stack Pointer
136
-
137
-    This function returns the current value of the Main Stack Pointer (MSP).
138
-
139
-    \return               MSP Register value
140
- */
141
-static __INLINE uint32_t __get_MSP(void)
142
-{
143
-  register uint32_t __regMainStackPointer     __ASM("msp");
144
-  return(__regMainStackPointer);
145
-}
146
-
147
-
148
-/** \brief  Set Main Stack Pointer
149
-
150
-    This function assigns the given value to the Main Stack Pointer (MSP).
151
-
152
-    \param [in]    topOfMainStack  Main Stack Pointer value to set
153
- */
154
-static __INLINE void __set_MSP(uint32_t topOfMainStack)
155
-{
156
-  register uint32_t __regMainStackPointer     __ASM("msp");
157
-  __regMainStackPointer = topOfMainStack;
158
-}
159
-
160
-
161
-/** \brief  Get Priority Mask
162
-
163
-    This function returns the current state of the priority mask bit from the Priority Mask Register.
164
-
165
-    \return               Priority Mask value
166
- */
167
-static __INLINE uint32_t __get_PRIMASK(void)
168
-{
169
-  register uint32_t __regPriMask         __ASM("primask");
170
-  return(__regPriMask);
171
-}
172
-
173
-
174
-/** \brief  Set Priority Mask
175
-
176
-    This function assigns the given value to the Priority Mask Register.
177
-
178
-    \param [in]    priMask  Priority Mask
179
- */
180
-static __INLINE void __set_PRIMASK(uint32_t priMask)
181
-{
182
-  register uint32_t __regPriMask         __ASM("primask");
183
-  __regPriMask = (priMask);
184
-}
185
-
186
-
187
-#if       (__CORTEX_M >= 0x03)
188
-
189
-/** \brief  Enable FIQ
190
-
191
-    This function enables FIQ interrupts by clearing the F-bit in the CPSR.
192
-    Can only be executed in Privileged modes.
193
- */
194
-#define __enable_fault_irq                __enable_fiq
195
-
196
-
197
-/** \brief  Disable FIQ
198
-
199
-    This function disables FIQ interrupts by setting the F-bit in the CPSR.
200
-    Can only be executed in Privileged modes.
201
- */
202
-#define __disable_fault_irq               __disable_fiq
203
-
204
-
205
-/** \brief  Get Base Priority
206
-
207
-    This function returns the current value of the Base Priority register.
208
-
209
-    \return               Base Priority register value
210
- */
211
-static __INLINE uint32_t  __get_BASEPRI(void)
212
-{
213
-  register uint32_t __regBasePri         __ASM("basepri");
214
-  return(__regBasePri);
215
-}
216
-
217
-
218
-/** \brief  Set Base Priority
219
-
220
-    This function assigns the given value to the Base Priority register.
221
-
222
-    \param [in]    basePri  Base Priority value to set
223
- */
224
-static __INLINE void __set_BASEPRI(uint32_t basePri)
225
-{
226
-  register uint32_t __regBasePri         __ASM("basepri");
227
-  __regBasePri = (basePri & 0xff);
228
-}
229
-
230
-
231
-/** \brief  Get Fault Mask
232
-
233
-    This function returns the current value of the Fault Mask register.
234
-
235
-    \return               Fault Mask register value
236
- */
237
-static __INLINE uint32_t __get_FAULTMASK(void)
238
-{
239
-  register uint32_t __regFaultMask       __ASM("faultmask");
240
-  return(__regFaultMask);
241
-}
242
-
243
-
244
-/** \brief  Set Fault Mask
245
-
246
-    This function assigns the given value to the Fault Mask register.
247
-
248
-    \param [in]    faultMask  Fault Mask value to set
249
- */
250
-static __INLINE void __set_FAULTMASK(uint32_t faultMask)
251
-{
252
-  register uint32_t __regFaultMask       __ASM("faultmask");
253
-  __regFaultMask = (faultMask & (uint32_t)1);
254
-}
255
-
256
-#endif /* (__CORTEX_M >= 0x03) */
257
-
258
-
259
-#if       (__CORTEX_M == 0x04)
260
-
261
-/** \brief  Get FPSCR
262
-
263
-    This function returns the current value of the Floating Point Status/Control register.
264
-
265
-    \return               Floating Point Status/Control register value
266
- */
267
-static __INLINE uint32_t __get_FPSCR(void)
268
-{
269
-#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
270
-  register uint32_t __regfpscr         __ASM("fpscr");
271
-  return(__regfpscr);
272
-#else
273
-   return(0);
274
-#endif
275
-}
276
-
277
-
278
-/** \brief  Set FPSCR
279
-
280
-    This function assigns the given value to the Floating Point Status/Control register.
281
-
282
-    \param [in]    fpscr  Floating Point Status/Control value to set
283
- */
284
-static __INLINE void __set_FPSCR(uint32_t fpscr)
285
-{
286
-#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
287
-  register uint32_t __regfpscr         __ASM("fpscr");
288
-  __regfpscr = (fpscr);
289
-#endif
290
-}
291
-
292
-#endif /* (__CORTEX_M == 0x04) */
293
-
294
-
295
-#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/
296
-/* IAR iccarm specific functions */
297
-
298
-#include <cmsis_iar.h>
299
-
300
-#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/
301
-/* GNU gcc specific functions */
302
-
303
-/** \brief  Enable IRQ Interrupts
304
-
305
-  This function enables IRQ interrupts by clearing the I-bit in the CPSR.
306
-  Can only be executed in Privileged modes.
307
- */
308
-__attribute__( ( always_inline ) ) static __INLINE void __enable_irq(void)
309
-{
310
-  __ASM volatile ("cpsie i");
311
-}
312
-
313
-
314
-/** \brief  Disable IRQ Interrupts
315
-
316
-  This function disables IRQ interrupts by setting the I-bit in the CPSR.
317
-  Can only be executed in Privileged modes.
318
- */
319
-__attribute__( ( always_inline ) ) static __INLINE void __disable_irq(void)
320
-{
321
-  __ASM volatile ("cpsid i");
322
-}
323
-
324
-
325
-/** \brief  Get Control Register
326
-
327
-    This function returns the content of the Control Register.
328
-
329
-    \return               Control Register value
330
- */
331
-__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_CONTROL(void)
332
-{
333
-  uint32_t result;
334
-
335
-  __ASM volatile ("MRS %0, control" : "=r" (result) );
336
-  return(result);
337
-}
338
-
339
-
340
-/** \brief  Set Control Register
341
-
342
-    This function writes the given value to the Control Register.
343
-
344
-    \param [in]    control  Control Register value to set
345
- */
346
-__attribute__( ( always_inline ) ) static __INLINE void __set_CONTROL(uint32_t control)
347
-{
348
-  __ASM volatile ("MSR control, %0" : : "r" (control) );
349
-}
350
-
351
-
352
-/** \brief  Get ISPR Register
353
-
354
-    This function returns the content of the ISPR Register.
355
-
356
-    \return               ISPR Register value
357
- */
358
-__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_IPSR(void)
359
-{
360
-  uint32_t result;
361
-
362
-  __ASM volatile ("MRS %0, ipsr" : "=r" (result) );
363
-  return(result);
364
-}
365
-
366
-
367
-/** \brief  Get APSR Register
368
-
369
-    This function returns the content of the APSR Register.
370
-
371
-    \return               APSR Register value
372
- */
373
-__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_APSR(void)
374
-{
375
-  uint32_t result;
376
-
377
-  __ASM volatile ("MRS %0, apsr" : "=r" (result) );
378
-  return(result);
379
-}
380
-
381
-
382
-/** \brief  Get xPSR Register
383
-
384
-    This function returns the content of the xPSR Register.
385
-
386
-    \return               xPSR Register value
387
- */
388
-__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_xPSR(void)
389
-{
390
-  uint32_t result;
391
-
392
-  __ASM volatile ("MRS %0, xpsr" : "=r" (result) );
393
-  return(result);
394
-}
395
-
396
-
397
-/** \brief  Get Process Stack Pointer
398
-
399
-    This function returns the current value of the Process Stack Pointer (PSP).
400
-
401
-    \return               PSP Register value
402
- */
403
-__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_PSP(void)
404
-{
405
-  register uint32_t result;
406
-
407
-  __ASM volatile ("MRS %0, psp\n"  : "=r" (result) );
408
-  return(result);
409
-}
410
-
411
-
412
-/** \brief  Set Process Stack Pointer
413
-
414
-    This function assigns the given value to the Process Stack Pointer (PSP).
415
-
416
-    \param [in]    topOfProcStack  Process Stack Pointer value to set
417
- */
418
-__attribute__( ( always_inline ) ) static __INLINE void __set_PSP(uint32_t topOfProcStack)
419
-{
420
-  __ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) );
421
-}
422
-
423
-
424
-/** \brief  Get Main Stack Pointer
425
-
426
-    This function returns the current value of the Main Stack Pointer (MSP).
427
-
428
-    \return               MSP Register value
429
- */
430
-__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_MSP(void)
431
-{
432
-  register uint32_t result;
433
-
434
-  __ASM volatile ("MRS %0, msp\n" : "=r" (result) );
435
-  return(result);
436
-}
437
-
438
-
439
-/** \brief  Set Main Stack Pointer
440
-
441
-    This function assigns the given value to the Main Stack Pointer (MSP).
442
-
443
-    \param [in]    topOfMainStack  Main Stack Pointer value to set
444
- */
445
-__attribute__( ( always_inline ) ) static __INLINE void __set_MSP(uint32_t topOfMainStack)
446
-{
447
-  __ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) );
448
-}
449
-
450
-
451
-/** \brief  Get Priority Mask
452
-
453
-    This function returns the current state of the priority mask bit from the Priority Mask Register.
454
-
455
-    \return               Priority Mask value
456
- */
457
-__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_PRIMASK(void)
458
-{
459
-  uint32_t result;
460
-
461
-  __ASM volatile ("MRS %0, primask" : "=r" (result) );
462
-  return(result);
463
-}
464
-
465
-
466
-/** \brief  Set Priority Mask
467
-
468
-    This function assigns the given value to the Priority Mask Register.
469
-
470
-    \param [in]    priMask  Priority Mask
471
- */
472
-__attribute__( ( always_inline ) ) static __INLINE void __set_PRIMASK(uint32_t priMask)
473
-{
474
-  __ASM volatile ("MSR primask, %0" : : "r" (priMask) );
475
-}
476
-
477
-
478
-#if       (__CORTEX_M >= 0x03)
479
-
480
-/** \brief  Enable FIQ
481
-
482
-    This function enables FIQ interrupts by clearing the F-bit in the CPSR.
483
-    Can only be executed in Privileged modes.
484
- */
485
-__attribute__( ( always_inline ) ) static __INLINE void __enable_fault_irq(void)
486
-{
487
-  __ASM volatile ("cpsie f");
488
-}
489
-
490
-
491
-/** \brief  Disable FIQ
492
-
493
-    This function disables FIQ interrupts by setting the F-bit in the CPSR.
494
-    Can only be executed in Privileged modes.
495
- */
496
-__attribute__( ( always_inline ) ) static __INLINE void __disable_fault_irq(void)
497
-{
498
-  __ASM volatile ("cpsid f");
499
-}
500
-
501
-
502
-/** \brief  Get Base Priority
503
-
504
-    This function returns the current value of the Base Priority register.
505
-
506
-    \return               Base Priority register value
507
- */
508
-__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_BASEPRI(void)
509
-{
510
-  uint32_t result;
511
-
512
-  __ASM volatile ("MRS %0, basepri_max" : "=r" (result) );
513
-  return(result);
514
-}
515
-
516
-
517
-/** \brief  Set Base Priority
518
-
519
-    This function assigns the given value to the Base Priority register.
520
-
521
-    \param [in]    basePri  Base Priority value to set
522
- */
523
-__attribute__( ( always_inline ) ) static __INLINE void __set_BASEPRI(uint32_t value)
524
-{
525
-  __ASM volatile ("MSR basepri, %0" : : "r" (value) );
526
-}
527
-
528
-
529
-/** \brief  Get Fault Mask
530
-
531
-    This function returns the current value of the Fault Mask register.
532
-
533
-    \return               Fault Mask register value
534
- */
535
-__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_FAULTMASK(void)
536
-{
537
-  uint32_t result;
538
-
539
-  __ASM volatile ("MRS %0, faultmask" : "=r" (result) );
540
-  return(result);
541
-}
542
-
543
-
544
-/** \brief  Set Fault Mask
545
-
546
-    This function assigns the given value to the Fault Mask register.
547
-
548
-    \param [in]    faultMask  Fault Mask value to set
549
- */
550
-__attribute__( ( always_inline ) ) static __INLINE void __set_FAULTMASK(uint32_t faultMask)
551
-{
552
-  __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) );
553
-}
554
-
555
-#endif /* (__CORTEX_M >= 0x03) */
556
-
557
-
558
-#if       (__CORTEX_M == 0x04)
559
-
560
-/** \brief  Get FPSCR
561
-
562
-    This function returns the current value of the Floating Point Status/Control register.
563
-
564
-    \return               Floating Point Status/Control register value
565
- */
566
-__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_FPSCR(void)
567
-{
568
-#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
569
-  uint32_t result;
570
-
571
-  __ASM volatile ("VMRS %0, fpscr" : "=r" (result) );
572
-  return(result);
573
-#else
574
-   return(0);
575
-#endif
576
-}
577
-
578
-
579
-/** \brief  Set FPSCR
580
-
581
-    This function assigns the given value to the Floating Point Status/Control register.
582
-
583
-    \param [in]    fpscr  Floating Point Status/Control value to set
584
- */
585
-__attribute__( ( always_inline ) ) static __INLINE void __set_FPSCR(uint32_t fpscr)
586
-{
587
-#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
588
-  __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) );
589
-#endif
590
-}
591
-
592
-#endif /* (__CORTEX_M == 0x04) */
593
-
594
-
595
-#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/
596
-/* TASKING carm specific functions */
597
-
598
-/*
599
- * The CMSIS functions have been implemented as intrinsics in the compiler.
600
- * Please use "carm -?i" to get an up to date list of all instrinsics,
601
- * Including the CMSIS ones.
602
- */
603
-
604
-#endif
605
-
606
-/*@} end of CMSIS_Core_RegAccFunctions */
607
-
608
-
609
-#endif /* __CORE_CMFUNC_H */

+ 0
- 586
frameworks/CMSIS/LPC1768/include/core_cmInstr.h Просмотреть файл

@@ -1,586 +0,0 @@
1
-/**************************************************************************//**
2
- * @file     core_cmInstr.h
3
- * @brief    CMSIS Cortex-M Core Instruction Access Header File
4
- * @version  V2.10
5
- * @date     19. July 2011
6
- *
7
- * @note
8
- * Copyright (C) 2009-2011 ARM Limited. All rights reserved.
9
- *
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.
14
- *
15
- * @par
16
- * THIS SOFTWARE IS PROVIDED "AS IS".  NO WARRANTIES, WHETHER EXPRESS, IMPLIED
17
- * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
18
- * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
19
- * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
20
- * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
21
- *
22
- ******************************************************************************/
23
-
24
-#ifndef __CORE_CMINSTR_H
25
-#define __CORE_CMINSTR_H
26
-
27
-
28
-/* ##########################  Core Instruction Access  ######################### */
29
-/** \ingroup CMSIS_Core
30
- 	\defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface
31
-  Access to dedicated instructions
32
-  @{
33
-*/
34
-
35
-#if   defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
36
-/* ARM armcc specific functions */
37
-
38
-#if (__ARMCC_VERSION < 400677)
39
-  #error "Please use ARM Compiler Toolchain V4.0.677 or later!"
40
-#endif
41
-
42
-
43
-/** \brief  No Operation
44
-
45
-    No Operation does nothing. This instruction can be used for code alignment purposes.
46
- */
47
-#define __NOP                             __nop
48
-
49
-
50
-/** \brief  Wait For Interrupt
51
-
52
-    Wait For Interrupt is a hint instruction that suspends execution
53
-    until one of a number of events occurs.
54
- */
55
-#define __WFI                             __wfi
56
-
57
-
58
-/** \brief  Wait For Event
59
-
60
-    Wait For Event is a hint instruction that permits the processor to enter
61
-    a low-power state until one of a number of events occurs.
62
- */
63
-#define __WFE                             __wfe
64
-
65
-
66
-/** \brief  Send Event
67
-
68
-    Send Event is a hint instruction. It causes an event to be signaled to the CPU.
69
- */
70
-#define __SEV                             __sev
71
-
72
-
73
-/** \brief  Instruction Synchronization Barrier
74
-
75
-    Instruction Synchronization Barrier flushes the pipeline in the processor,
76
-    so that all instructions following the ISB are fetched from cache or
77
-    memory, after the instruction has been completed.
78
- */
79
-#define __ISB()                           __isb(0xF)
80
-
81
-
82
-/** \brief  Data Synchronization Barrier
83
-
84
-    This function acts as a special kind of Data Memory Barrier.
85
-    It completes when all explicit memory accesses before this instruction complete.
86
- */
87
-#define __DSB()                           __dsb(0xF)
88
-
89
-
90
-/** \brief  Data Memory Barrier
91
-
92
-    This function ensures the apparent order of the explicit memory operations before
93
-    and after the instruction, without ensuring their completion.
94
- */
95
-#define __DMB()                           __dmb(0xF)
96
-
97
-
98
-/** \brief  Reverse byte order (32 bit)
99
-
100
-    This function reverses the byte order in integer value.
101
-
102
-    \param [in]    value  Value to reverse
103
-    \return               Reversed value
104
- */
105
-#define __REV                             __rev
106
-
107
-
108
-/** \brief  Reverse byte order (16 bit)
109
-
110
-    This function reverses the byte order in two unsigned short values.
111
-
112
-    \param [in]    value  Value to reverse
113
-    \return               Reversed value
114
- */
115
-static __INLINE __ASM uint32_t __REV16(uint32_t value)
116
-{
117
-  rev16 r0, r0
118
-  bx lr
119
-}
120
-
121
-
122
-/** \brief  Reverse byte order in signed short value
123
-
124
-    This function reverses the byte order in a signed short value with sign extension to integer.
125
-
126
-    \param [in]    value  Value to reverse
127
-    \return               Reversed value
128
- */
129
-static __INLINE __ASM int32_t __REVSH(int32_t value)
130
-{
131
-  revsh r0, r0
132
-  bx lr
133
-}
134
-
135
-
136
-#if       (__CORTEX_M >= 0x03)
137
-
138
-/** \brief  Reverse bit order of value
139
-
140
-    This function reverses the bit order of the given value.
141
-
142
-    \param [in]    value  Value to reverse
143
-    \return               Reversed value
144
- */
145
-#define __RBIT                            __rbit
146
-
147
-
148
-/** \brief  LDR Exclusive (8 bit)
149
-
150
-    This function performs a exclusive LDR command for 8 bit value.
151
-
152
-    \param [in]    ptr  Pointer to data
153
-    \return             value of type uint8_t at (*ptr)
154
- */
155
-#define __LDREXB(ptr)                     ((uint8_t ) __ldrex(ptr))
156
-
157
-
158
-/** \brief  LDR Exclusive (16 bit)
159
-
160
-    This function performs a exclusive LDR command for 16 bit values.
161
-
162
-    \param [in]    ptr  Pointer to data
163
-    \return        value of type uint16_t at (*ptr)
164
- */
165
-#define __LDREXH(ptr)                     ((uint16_t) __ldrex(ptr))
166
-
167
-
168
-/** \brief  LDR Exclusive (32 bit)
169
-
170
-    This function performs a exclusive LDR command for 32 bit values.
171
-
172
-    \param [in]    ptr  Pointer to data
173
-    \return        value of type uint32_t at (*ptr)
174
- */
175
-#define __LDREXW(ptr)                     ((uint32_t ) __ldrex(ptr))
176
-
177
-
178
-/** \brief  STR Exclusive (8 bit)
179
-
180
-    This function performs a exclusive STR command for 8 bit values.
181
-
182
-    \param [in]  value  Value to store
183
-    \param [in]    ptr  Pointer to location
184
-    \return          0  Function succeeded
185
-    \return          1  Function failed
186
- */
187
-#define __STREXB(value, ptr)              __strex(value, ptr)
188
-
189
-
190
-/** \brief  STR Exclusive (16 bit)
191
-
192
-    This function performs a exclusive STR command for 16 bit values.
193
-
194
-    \param [in]  value  Value to store
195
-    \param [in]    ptr  Pointer to location
196
-    \return          0  Function succeeded
197
-    \return          1  Function failed
198
- */
199
-#define __STREXH(value, ptr)              __strex(value, ptr)
200
-
201
-
202
-/** \brief  STR Exclusive (32 bit)
203
-
204
-    This function performs a exclusive STR command for 32 bit values.
205
-
206
-    \param [in]  value  Value to store
207
-    \param [in]    ptr  Pointer to location
208
-    \return          0  Function succeeded
209
-    \return          1  Function failed
210
- */
211
-#define __STREXW(value, ptr)              __strex(value, ptr)
212
-
213
-
214
-/** \brief  Remove the exclusive lock
215
-
216
-    This function removes the exclusive lock which is created by LDREX.
217
-
218
- */
219
-#define __CLREX                           __clrex
220
-
221
-
222
-/** \brief  Signed Saturate
223
-
224
-    This function saturates a signed value.
225
-
226
-    \param [in]  value  Value to be saturated
227
-    \param [in]    sat  Bit position to saturate to (1..32)
228
-    \return             Saturated value
229
- */
230
-#define __SSAT                            __ssat
231
-
232
-
233
-/** \brief  Unsigned Saturate
234
-
235
-    This function saturates an unsigned value.
236
-
237
-    \param [in]  value  Value to be saturated
238
-    \param [in]    sat  Bit position to saturate to (0..31)
239
-    \return             Saturated value
240
- */
241
-#define __USAT                            __usat
242
-
243
-
244
-/** \brief  Count leading zeros
245
-
246
-    This function counts the number of leading zeros of a data value.
247
-
248
-    \param [in]  value  Value to count the leading zeros
249
-    \return             number of leading zeros in value
250
- */
251
-#define __CLZ                             __clz
252
-
253
-#endif /* (__CORTEX_M >= 0x03) */
254
-
255
-
256
-
257
-#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/
258
-/* IAR iccarm specific functions */
259
-
260
-#include <cmsis_iar.h>
261
-
262
-
263
-#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/
264
-/* GNU gcc specific functions */
265
-
266
-/** \brief  No Operation
267
-
268
-    No Operation does nothing. This instruction can be used for code alignment purposes.
269
- */
270
-__attribute__( ( always_inline ) ) static __INLINE void __NOP(void)
271
-{
272
-  __ASM volatile ("nop");
273
-}
274
-
275
-
276
-/** \brief  Wait For Interrupt
277
-
278
-    Wait For Interrupt is a hint instruction that suspends execution
279
-    until one of a number of events occurs.
280
- */
281
-__attribute__( ( always_inline ) ) static __INLINE void __WFI(void)
282
-{
283
-  __ASM volatile ("wfi");
284
-}
285
-
286
-
287
-/** \brief  Wait For Event
288
-
289
-    Wait For Event is a hint instruction that permits the processor to enter
290
-    a low-power state until one of a number of events occurs.
291
- */
292
-__attribute__( ( always_inline ) ) static __INLINE void __WFE(void)
293
-{
294
-  __ASM volatile ("wfe");
295
-}
296
-
297
-
298
-/** \brief  Send Event
299
-
300
-    Send Event is a hint instruction. It causes an event to be signaled to the CPU.
301
- */
302
-__attribute__( ( always_inline ) ) static __INLINE void __SEV(void)
303
-{
304
-  __ASM volatile ("sev");
305
-}
306
-
307
-
308
-/** \brief  Instruction Synchronization Barrier
309
-
310
-    Instruction Synchronization Barrier flushes the pipeline in the processor,
311
-    so that all instructions following the ISB are fetched from cache or
312
-    memory, after the instruction has been completed.
313
- */
314
-__attribute__( ( always_inline ) ) static __INLINE void __ISB(void)
315
-{
316
-  __ASM volatile ("isb");
317
-}
318
-
319
-
320
-/** \brief  Data Synchronization Barrier
321
-
322
-    This function acts as a special kind of Data Memory Barrier.
323
-    It completes when all explicit memory accesses before this instruction complete.
324
- */
325
-__attribute__( ( always_inline ) ) static __INLINE void __DSB(void)
326
-{
327
-  __ASM volatile ("dsb");
328
-}
329
-
330
-
331
-/** \brief  Data Memory Barrier
332
-
333
-    This function ensures the apparent order of the explicit memory operations before
334
-    and after the instruction, without ensuring their completion.
335
- */
336
-__attribute__( ( always_inline ) ) static __INLINE void __DMB(void)
337
-{
338
-  __ASM volatile ("dmb");
339
-}
340
-
341
-
342
-/** \brief  Reverse byte order (32 bit)
343
-
344
-    This function reverses the byte order in integer value.
345
-
346
-    \param [in]    value  Value to reverse
347
-    \return               Reversed value
348
- */
349
-__attribute__( ( always_inline ) ) static __INLINE uint32_t __REV(uint32_t value)
350
-{
351
-  uint32_t result;
352
-
353
-  __ASM volatile ("rev %0, %1" : "=r" (result) : "r" (value) );
354
-  return(result);
355
-}
356
-
357
-
358
-/** \brief  Reverse byte order (16 bit)
359
-
360
-    This function reverses the byte order in two unsigned short values.
361
-
362
-    \param [in]    value  Value to reverse
363
-    \return               Reversed value
364
- */
365
-__attribute__( ( always_inline ) ) static __INLINE uint32_t __REV16(uint32_t value)
366
-{
367
-  uint32_t result;
368
-
369
-  __ASM volatile ("rev16 %0, %1" : "=r" (result) : "r" (value) );
370
-  return(result);
371
-}
372
-
373
-
374
-/** \brief  Reverse byte order in signed short value
375
-
376
-    This function reverses the byte order in a signed short value with sign extension to integer.
377
-
378
-    \param [in]    value  Value to reverse
379
-    \return               Reversed value
380
- */
381
-__attribute__( ( always_inline ) ) static __INLINE int32_t __REVSH(int32_t value)
382
-{
383
-  uint32_t result;
384
-
385
-  __ASM volatile ("revsh %0, %1" : "=r" (result) : "r" (value) );
386
-  return(result);
387
-}
388
-
389
-
390
-#if       (__CORTEX_M >= 0x03)
391
-
392
-/** \brief  Reverse bit order of value
393
-
394
-    This function reverses the bit order of the given value.
395
-
396
-    \param [in]    value  Value to reverse
397
-    \return               Reversed value
398
- */
399
-__attribute__( ( always_inline ) ) static __INLINE uint32_t __RBIT(uint32_t value)
400
-{
401
-  uint32_t result;
402
-
403
-   __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) );
404
-   return(result);
405
-}
406
-
407
-
408
-/** \brief  LDR Exclusive (8 bit)
409
-
410
-    This function performs a exclusive LDR command for 8 bit value.
411
-
412
-    \param [in]    ptr  Pointer to data
413
-    \return             value of type uint8_t at (*ptr)
414
- */
415
-__attribute__( ( always_inline ) ) static __INLINE uint8_t __LDREXB(volatile uint8_t *addr)
416
-{
417
-    uint8_t result;
418
-
419
-   __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) );
420
-   return(result);
421
-}
422
-
423
-
424
-/** \brief  LDR Exclusive (16 bit)
425
-
426
-    This function performs a exclusive LDR command for 16 bit values.
427
-
428
-    \param [in]    ptr  Pointer to data
429
-    \return        value of type uint16_t at (*ptr)
430
- */
431
-__attribute__( ( always_inline ) ) static __INLINE uint16_t __LDREXH(volatile uint16_t *addr)
432
-{
433
-    uint16_t result;
434
-
435
-   __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) );
436
-   return(result);
437
-}
438
-
439
-
440
-/** \brief  LDR Exclusive (32 bit)
441
-
442
-    This function performs a exclusive LDR command for 32 bit values.
443
-
444
-    \param [in]    ptr  Pointer to data
445
-    \return        value of type uint32_t at (*ptr)
446
- */
447
-__attribute__( ( always_inline ) ) static __INLINE uint32_t __LDREXW(volatile uint32_t *addr)
448
-{
449
-    uint32_t result;
450
-
451
-   __ASM volatile ("ldrex %0, [%1]" : "=r" (result) : "r" (addr) );
452
-   return(result);
453
-}
454
-
455
-
456
-/** \brief  STR Exclusive (8 bit)
457
-
458
-    This function performs a exclusive STR command for 8 bit values.
459
-
460
-    \param [in]  value  Value to store
461
-    \param [in]    ptr  Pointer to location
462
-    \return          0  Function succeeded
463
-    \return          1  Function failed
464
- */
465
-__attribute__( ( always_inline ) ) static __INLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr)
466
-{
467
-   uint32_t result;
468
-
469
-   __ASM volatile ("strexb %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) );
470
-   return(result);
471
-}
472
-
473
-
474
-/** \brief  STR Exclusive (16 bit)
475
-
476
-    This function performs a exclusive STR command for 16 bit values.
477
-
478
-    \param [in]  value  Value to store
479
-    \param [in]    ptr  Pointer to location
480
-    \return          0  Function succeeded
481
-    \return          1  Function failed
482
- */
483
-__attribute__( ( always_inline ) ) static __INLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr)
484
-{
485
-   uint32_t result;
486
-
487
-   __ASM volatile ("strexh %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) );
488
-   return(result);
489
-}
490
-
491
-
492
-/** \brief  STR Exclusive (32 bit)
493
-
494
-    This function performs a exclusive STR command for 32 bit values.
495
-
496
-    \param [in]  value  Value to store
497
-    \param [in]    ptr  Pointer to location
498
-    \return          0  Function succeeded
499
-    \return          1  Function failed
500
- */
501
-__attribute__( ( always_inline ) ) static __INLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr)
502
-{
503
-   uint32_t result;
504
-
505
-   __ASM volatile ("strex %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) );
506
-   return(result);
507
-}
508
-
509
-
510
-/** \brief  Remove the exclusive lock
511
-
512
-    This function removes the exclusive lock which is created by LDREX.
513
-
514
- */
515
-__attribute__( ( always_inline ) ) static __INLINE void __CLREX(void)
516
-{
517
-  __ASM volatile ("clrex");
518
-}
519
-
520
-
521
-/** \brief  Signed Saturate
522
-
523
-    This function saturates a signed value.
524
-
525
-    \param [in]  value  Value to be saturated
526
-    \param [in]    sat  Bit position to saturate to (1..32)
527
-    \return             Saturated value
528
- */
529
-#define __SSAT(ARG1,ARG2) \
530
-({                          \
531
-  uint32_t __RES, __ARG1 = (ARG1); \
532
-  __ASM ("ssat %0, %1, %2" : "=r" (__RES) :  "I" (ARG2), "r" (__ARG1) ); \
533
-  __RES; \
534
- })
535
-
536
-
537
-/** \brief  Unsigned Saturate
538
-
539
-    This function saturates an unsigned value.
540
-
541
-    \param [in]  value  Value to be saturated
542
-    \param [in]    sat  Bit position to saturate to (0..31)
543
-    \return             Saturated value
544
- */
545
-#define __USAT(ARG1,ARG2) \
546
-({                          \
547
-  uint32_t __RES, __ARG1 = (ARG1); \
548
-  __ASM ("usat %0, %1, %2" : "=r" (__RES) :  "I" (ARG2), "r" (__ARG1) ); \
549
-  __RES; \
550
- })
551
-
552
-
553
-/** \brief  Count leading zeros
554
-
555
-    This function counts the number of leading zeros of a data value.
556
-
557
-    \param [in]  value  Value to count the leading zeros
558
-    \return             number of leading zeros in value
559
- */
560
-__attribute__( ( always_inline ) ) static __INLINE uint8_t __CLZ(uint32_t value)
561
-{
562
-  uint8_t result;
563
-
564
-  __ASM volatile ("clz %0, %1" : "=r" (result) : "r" (value) );
565
-  return(result);
566
-}
567
-
568
-#endif /* (__CORTEX_M >= 0x03) */
569
-
570
-
571
-
572
-
573
-#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/
574
-/* TASKING carm specific functions */
575
-
576
-/*
577
- * The CMSIS functions have been implemented as intrinsics in the compiler.
578
- * Please use "carm -?i" to get an up to date list of all intrinsics,
579
- * Including the CMSIS ones.
580
- */
581
-
582
-#endif
583
-
584
-/*@}*/ /* end of group CMSIS_Core_InstructionInterface */
585
-
586
-#endif /* __CORE_CMINSTR_H */

+ 0
- 80
frameworks/CMSIS/LPC1768/include/debug_frmwrk.h Просмотреть файл

@@ -1,80 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		debug_frmwrk.h		2010-05-21
3
-*//**
4
-* @file		debug_frmwrk.h
5
-* @brief	Contains some utilities that used for debugging through UART
6
-* @version	2.0
7
-* @date		21. May. 2010
8
-* @author	NXP MCU SW Application Team
9
-*
10
-* Copyright(C) 2010, NXP Semiconductor
11
-* All rights reserved.
12
-*
13
-***********************************************************************
14
-* Software that is described herein is for illustrative purposes only
15
-* which provides customers with programming information regarding the
16
-* products. This software is supplied "AS IS" without any warranties.
17
-* NXP Semiconductors assumes no responsibility or liability for the
18
-* use of the software, conveys no license or title under any patent,
19
-* copyright, or mask work right to the product. NXP Semiconductors
20
-* reserves the right to make changes in the software without
21
-* notification. NXP Semiconductors also make no representation or
22
-* warranty that such application will be suitable for the specified
23
-* use without further testing or modification.
24
-* Permission to use, copy, modify, and distribute this software and its
25
-* documentation is hereby granted, under NXP Semiconductors'
26
-* relevant copyright in the software, without fee, provided that it
27
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
28
-* copyright, permission, and disclaimer notice must appear in all copies of
29
-* this code.
30
-**********************************************************************/
31
-#ifndef DEBUG_FRMWRK_H_
32
-#define DEBUG_FRMWRK_H_
33
-
34
-//#include <stdarg.h>
35
-#include "lpc17xx_uart.h"
36
-
37
-#define USED_UART_DEBUG_PORT	0
38
-
39
-#if (USED_UART_DEBUG_PORT==0)
40
-#define DEBUG_UART_PORT	LPC_UART0
41
-#elif (USED_UART_DEBUG_PORT==1)
42
-#define DEBUG_UART_PORT	LPC_UART1
43
-#endif
44
-
45
-#define _DBG(x)	 	_db_msg(DEBUG_UART_PORT, x)
46
-#define _DBG_(x)	_db_msg_(DEBUG_UART_PORT, x)
47
-#define _DBC(x)	 	_db_char(DEBUG_UART_PORT, x)
48
-#define _DBD(x)	 	_db_dec(DEBUG_UART_PORT, x)
49
-#define _DBD16(x)	 _db_dec_16(DEBUG_UART_PORT, x)
50
-#define _DBD32(x)	 _db_dec_32(DEBUG_UART_PORT, x)
51
-#define _DBH(x)	 	_db_hex(DEBUG_UART_PORT, x)
52
-#define _DBH16(x)	 _db_hex_16(DEBUG_UART_PORT, x)
53
-#define _DBH32(x)	 _db_hex_32(DEBUG_UART_PORT, x)
54
-#define _DG			_db_get_char(DEBUG_UART_PORT)
55
-//void  _printf (const  char *format, ...);
56
-
57
-extern void (*_db_msg)(LPC_UART_TypeDef *UARTx, const void *s);
58
-extern void (*_db_msg_)(LPC_UART_TypeDef *UARTx, const void *s);
59
-extern void (*_db_char)(LPC_UART_TypeDef *UARTx, uint8_t ch);
60
-extern void (*_db_dec)(LPC_UART_TypeDef *UARTx, uint8_t decn);
61
-extern void (*_db_dec_16)(LPC_UART_TypeDef *UARTx, uint16_t decn);
62
-extern void (*_db_dec_32)(LPC_UART_TypeDef *UARTx, uint32_t decn);
63
-extern void (*_db_hex)(LPC_UART_TypeDef *UARTx, uint8_t hexn);
64
-extern void (*_db_hex_16)(LPC_UART_TypeDef *UARTx, uint16_t hexn);
65
-extern void (*_db_hex_32)(LPC_UART_TypeDef *UARTx, uint32_t hexn);
66
-extern uint8_t (*_db_get_char)(LPC_UART_TypeDef *UARTx);
67
-
68
-void UARTPutChar (LPC_UART_TypeDef *UARTx, uint8_t ch);
69
-void UARTPuts(LPC_UART_TypeDef *UARTx, const void *str);
70
-void UARTPuts_(LPC_UART_TypeDef *UARTx, const void *str);
71
-void UARTPutDec(LPC_UART_TypeDef *UARTx, uint8_t decnum);
72
-void UARTPutDec16(LPC_UART_TypeDef *UARTx, uint16_t decnum);
73
-void UARTPutDec32(LPC_UART_TypeDef *UARTx, uint32_t decnum);
74
-void UARTPutHex (LPC_UART_TypeDef *UARTx, uint8_t hexnum);
75
-void UARTPutHex16 (LPC_UART_TypeDef *UARTx, uint16_t hexnum);
76
-void UARTPutHex32 (LPC_UART_TypeDef *UARTx, uint32_t hexnum);
77
-uint8_t UARTGetChar (LPC_UART_TypeDef *UARTx);
78
-void debug_frmwrk_init(void);
79
-
80
-#endif /* DEBUG_FRMWRK_H_ */

+ 0
- 302
frameworks/CMSIS/LPC1768/include/lpc17xx_adc.h Просмотреть файл

@@ -1,302 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_adc.h			2008-07-27
3
-*//**
4
-* @file		lpc17xx_adc.h
5
-* @brief	Contains the NXP ABL typedefs for C standard types.
6
-*     		It is intended to be used in ISO C conforming development
7
-*     		environments and checks for this insofar as it is possible
8
-*     		to do so.
9
-* @version	2.0
10
-* @date		27 Jul. 2008
11
-* @author	NXP MCU SW Application Team
12
-*
13
-* Copyright(C) 2008, NXP Semiconductor
14
-* All rights reserved.
15
-*
16
-***********************************************************************
17
-* Software that is described herein is for illustrative purposes only
18
-* which provides customers with programming information regarding the
19
-* products. This software is supplied "AS IS" without any warranties.
20
-* NXP Semiconductors assumes no responsibility or liability for the
21
-* use of the software, conveys no license or title under any patent,
22
-* copyright, or mask work right to the product. NXP Semiconductors
23
-* reserves the right to make changes in the software without
24
-* notification. NXP Semiconductors also make no representation or
25
-* warranty that such application will be suitable for the specified
26
-* use without further testing or modification.
27
-* Permission to use, copy, modify, and distribute this software and its
28
-* documentation is hereby granted, under NXP Semiconductors'
29
-* relevant copyright in the software, without fee, provided that it
30
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
31
-* copyright, permission, and disclaimer notice must appear in all copies of
32
-* this code.
33
-**********************************************************************/
34
-
35
-/* Peripheral group ----------------------------------------------------------- */
36
-/** @defgroup ADC ADC (Analog-to-Digital Converter)
37
- * @ingroup LPC1700CMSIS_FwLib_Drivers
38
- * @{
39
- */
40
-
41
-#ifndef LPC17XX_ADC_H_
42
-#define LPC17XX_ADC_H_
43
-
44
-/* Includes ------------------------------------------------------------------- */
45
-#include "LPC17xx.h"
46
-#include "lpc_types.h"
47
-
48
-
49
-#ifdef __cplusplus
50
-extern "C"
51
-{
52
-#endif
53
-
54
-/* Private macros ------------------------------------------------------------- */
55
-/** @defgroup ADC_Private_Macros ADC Private Macros
56
- * @{
57
- */
58
-
59
-/* -------------------------- BIT DEFINITIONS ----------------------------------- */
60
-/*********************************************************************//**
61
- * Macro defines for ADC  control register
62
- **********************************************************************/
63
-/**  Selects which of the AD0.0:7 pins is (are) to be sampled and converted */
64
-#define ADC_CR_CH_SEL(n)	((1UL << n))
65
-/**  The APB clock (PCLK) is divided by (this value plus one)
66
-* to produce the clock for the A/D */
67
-#define ADC_CR_CLKDIV(n)	((n<<8))
68
-/**  Repeated conversions A/D enable bit */
69
-#define ADC_CR_BURST		((1UL<<16))
70
-/**  ADC convert in power down mode */
71
-#define ADC_CR_PDN			((1UL<<21))
72
-/**  Start mask bits */
73
-#define ADC_CR_START_MASK	((7UL<<24))
74
-/**  Select Start Mode */
75
-#define ADC_CR_START_MODE_SEL(SEL)	((SEL<<24))
76
-/**  Start conversion now */
77
-#define ADC_CR_START_NOW	((1UL<<24))
78
-/**  Start conversion when the edge selected by bit 27 occurs on P2.10/EINT0 */
79
-#define ADC_CR_START_EINT0	((2UL<<24))
80
-/** Start conversion when the edge selected by bit 27 occurs on P1.27/CAP0.1 */
81
-#define ADC_CR_START_CAP01	((3UL<<24))
82
-/**  Start conversion when the edge selected by bit 27 occurs on MAT0.1 */
83
-#define ADC_CR_START_MAT01	((4UL<<24))
84
-/**  Start conversion when the edge selected by bit 27 occurs on MAT0.3 */
85
-#define ADC_CR_START_MAT03	((5UL<<24))
86
-/**  Start conversion when the edge selected by bit 27 occurs on MAT1.0 */
87
-#define ADC_CR_START_MAT10	((6UL<<24))
88
-/**  Start conversion when the edge selected by bit 27 occurs on MAT1.1 */
89
-#define ADC_CR_START_MAT11	((7UL<<24))
90
-/**  Start conversion on a falling edge on the selected CAP/MAT signal */
91
-#define ADC_CR_EDGE			((1UL<<27))
92
-
93
-/*********************************************************************//**
94
- * Macro defines for ADC Global Data register
95
- **********************************************************************/
96
-/** When DONE is 1, this field contains result value of ADC conversion */
97
-#define ADC_GDR_RESULT(n)		(((n>>4)&0xFFF))
98
-/** These bits contain the channel from which the LS bits were converted */
99
-#define ADC_GDR_CH(n)			(((n>>24)&0x7))
100
-/** This bit is 1 in burst mode if the results of one or
101
- * more conversions was (were) lost */
102
-#define ADC_GDR_OVERRUN_FLAG	((1UL<<30))
103
-/** This bit is set to 1 when an A/D conversion completes */
104
-#define ADC_GDR_DONE_FLAG		((1UL<<31))
105
-
106
-/** This bits is used to mask for Channel */
107
-#define ADC_GDR_CH_MASK		((7UL<<24))
108
-/*********************************************************************//**
109
- * Macro defines for ADC Interrupt register
110
- **********************************************************************/
111
-/** These bits allow control over which A/D channels generate
112
- * interrupts for conversion completion */
113
-#define ADC_INTEN_CH(n)			((1UL<<n))
114
-/** When 1, enables the global DONE flag in ADDR to generate an interrupt */
115
-#define ADC_INTEN_GLOBAL		((1UL<<8))
116
-
117
-/*********************************************************************//**
118
- * Macro defines for ADC Data register
119
- **********************************************************************/
120
-/** When DONE is 1, this field contains result value of ADC conversion */
121
-#define ADC_DR_RESULT(n)		(((n>>4)&0xFFF))
122
-/** These bits mirror the OVERRRUN status flags that appear in the
123
- * result register for each A/D channel */
124
-#define ADC_DR_OVERRUN_FLAG		((1UL<<30))
125
-/** This bit is set to 1 when an A/D conversion completes. It is cleared
126
- * when this register is read */
127
-#define ADC_DR_DONE_FLAG		((1UL<<31))
128
-
129
-/*********************************************************************//**
130
- * Macro defines for ADC Status register
131
-**********************************************************************/
132
-/** These bits mirror the DONE status flags that appear in the result
133
- * register for each A/D channel */
134
-#define ADC_STAT_CH_DONE_FLAG(n)		((n&0xFF))
135
-/** These bits mirror the OVERRRUN status flags that appear in the
136
- * result register for each A/D channel */
137
-#define ADC_STAT_CH_OVERRUN_FLAG(n)		(((n>>8)&0xFF))
138
-/** This bit is the A/D interrupt flag */
139
-#define ADC_STAT_INT_FLAG				((1UL<<16))
140
-
141
-/*********************************************************************//**
142
- * Macro defines for ADC Trim register
143
-**********************************************************************/
144
-/** Offset trim bits for ADC operation */
145
-#define ADC_ADCOFFS(n)		(((n&0xF)<<4))
146
-/** Written to boot code*/
147
-#define ADC_TRIM(n)		    (((n&0xF)<<8))
148
-
149
-/* ------------------- CHECK PARAM DEFINITIONS ------------------------- */
150
-/** Check ADC parameter */
151
-#define PARAM_ADCx(n)    (((uint32_t *)n)==((uint32_t *)LPC_ADC))
152
-
153
-/** Check ADC state parameter */
154
-#define PARAM_ADC_START_ON_EDGE_OPT(OPT)    ((OPT == ADC_START_ON_RISING)||(OPT == ADC_START_ON_FALLING))
155
-
156
-/** Check ADC state parameter */
157
-#define PARAM_ADC_DATA_STATUS(OPT)    ((OPT== ADC_DATA_BURST)||(OPT== ADC_DATA_DONE))
158
-
159
-/** Check ADC rate parameter */
160
-#define PARAM_ADC_RATE(rate)	((rate>0)&&(rate<=200000))
161
-
162
-/** Check ADC channel selection parameter */
163
-#define PARAM_ADC_CHANNEL_SELECTION(SEL)	((SEL == ADC_CHANNEL_0)||(ADC_CHANNEL_1)\
164
-||(SEL == ADC_CHANNEL_2)|(ADC_CHANNEL_3)\
165
-||(SEL == ADC_CHANNEL_4)||(ADC_CHANNEL_5)\
166
-||(SEL == ADC_CHANNEL_6)||(ADC_CHANNEL_7))
167
-
168
-/** Check ADC start option parameter */
169
-#define PARAM_ADC_START_OPT(OPT)    ((OPT == ADC_START_CONTINUOUS)||(OPT == ADC_START_NOW)\
170
-||(OPT == ADC_START_ON_EINT0)||(OPT == ADC_START_ON_CAP01)\
171
-||(OPT == ADC_START_ON_MAT01)||(OPT == ADC_START_ON_MAT03)\
172
-||(OPT == ADC_START_ON_MAT10)||(OPT == ADC_START_ON_MAT11))
173
-
174
-/** Check ADC interrupt type parameter */
175
-#define PARAM_ADC_TYPE_INT_OPT(OPT)    ((OPT == ADC_ADINTEN0)||(OPT == ADC_ADINTEN1)\
176
-||(OPT == ADC_ADINTEN2)||(OPT == ADC_ADINTEN3)\
177
-||(OPT == ADC_ADINTEN4)||(OPT == ADC_ADINTEN5)\
178
-||(OPT == ADC_ADINTEN6)||(OPT == ADC_ADINTEN7)\
179
-||(OPT == ADC_ADGINTEN))
180
-
181
-/**
182
- * @}
183
- */
184
-
185
-
186
-/* Public Types --------------------------------------------------------------- */
187
-/** @defgroup ADC_Public_Types ADC Public Types
188
- * @{
189
- */
190
-
191
-/*********************************************************************//**
192
- * @brief ADC enumeration
193
- **********************************************************************/
194
-/** @brief Channel Selection */
195
-typedef enum
196
-{
197
-	ADC_CHANNEL_0  = 0, /*!<  Channel 0 */
198
-	ADC_CHANNEL_1,		/*!<  Channel 1 */
199
-	ADC_CHANNEL_2,		/*!<  Channel 2 */
200
-	ADC_CHANNEL_3,		/*!<  Channel 3 */
201
-	ADC_CHANNEL_4,		/*!<  Channel 4 */
202
-	ADC_CHANNEL_5,		/*!<  Channel 5 */
203
-	ADC_CHANNEL_6,		/*!<  Channel 6 */
204
-	ADC_CHANNEL_7		/*!<  Channel 7 */
205
-}ADC_CHANNEL_SELECTION;
206
-
207
-/** @brief Type of start option */
208
-typedef enum
209
-{
210
-	ADC_START_CONTINUOUS =0,	/*!< Continuous mode */
211
-	ADC_START_NOW,				/*!< Start conversion now */
212
-	ADC_START_ON_EINT0,			/*!< Start conversion when the edge selected
213
-								 * by bit 27 occurs on P2.10/EINT0 */
214
-	ADC_START_ON_CAP01,			/*!< Start conversion when the edge selected
215
-								 * by bit 27 occurs on P1.27/CAP0.1 */
216
-	ADC_START_ON_MAT01,			/*!< Start conversion when the edge selected
217
-								 * by bit 27 occurs on MAT0.1 */
218
-	ADC_START_ON_MAT03,			/*!< Start conversion when the edge selected
219
-								 * by bit 27 occurs on MAT0.3 */
220
-	ADC_START_ON_MAT10,			/*!< Start conversion when the edge selected
221
-								  * by bit 27 occurs on MAT1.0 */
222
-	ADC_START_ON_MAT11			/*!< Start conversion when the edge selected
223
-								  * by bit 27 occurs on MAT1.1 */
224
-} ADC_START_OPT;
225
-
226
-
227
-/** @brief Type of edge when start conversion on the selected CAP/MAT signal */
228
-typedef enum
229
-{
230
-	ADC_START_ON_RISING = 0,	/*!< Start conversion on a rising edge
231
-								*on the selected CAP/MAT signal */
232
-	ADC_START_ON_FALLING		/*!< Start conversion on a falling edge
233
-								*on the selected CAP/MAT signal */
234
-} ADC_START_ON_EDGE_OPT;
235
-
236
-/** @brief* ADC type interrupt enum */
237
-typedef enum
238
-{
239
-	ADC_ADINTEN0 = 0,		/*!< Interrupt channel 0 */
240
-	ADC_ADINTEN1,			/*!< Interrupt channel 1 */
241
-	ADC_ADINTEN2,			/*!< Interrupt channel 2 */
242
-	ADC_ADINTEN3,			/*!< Interrupt channel 3 */
243
-	ADC_ADINTEN4,			/*!< Interrupt channel 4 */
244
-	ADC_ADINTEN5,			/*!< Interrupt channel 5 */
245
-	ADC_ADINTEN6,			/*!< Interrupt channel 6 */
246
-	ADC_ADINTEN7,			/*!< Interrupt channel 7 */
247
-	ADC_ADGINTEN			/*!< Individual channel/global flag done generate an interrupt */
248
-}ADC_TYPE_INT_OPT;
249
-
250
-/** @brief ADC Data  status */
251
-typedef enum
252
-{
253
-	ADC_DATA_BURST = 0,		/*Burst bit*/
254
-	ADC_DATA_DONE		 /*Done bit*/
255
-}ADC_DATA_STATUS;
256
-
257
-/**
258
- * @}
259
- */
260
-
261
-
262
-/* Public Functions ----------------------------------------------------------- */
263
-/** @defgroup ADC_Public_Functions ADC Public Functions
264
- * @{
265
- */
266
-/* Init/DeInit ADC peripheral ----------------*/
267
-void ADC_Init(LPC_ADC_TypeDef *ADCx, uint32_t rate);
268
-void ADC_DeInit(LPC_ADC_TypeDef *ADCx);
269
-
270
-/* Enable/Disable ADC functions --------------*/
271
-void ADC_BurstCmd(LPC_ADC_TypeDef *ADCx, FunctionalState NewState);
272
-void ADC_PowerdownCmd(LPC_ADC_TypeDef *ADCx, FunctionalState NewState);
273
-void ADC_StartCmd(LPC_ADC_TypeDef *ADCx, uint8_t start_mode);
274
-void ADC_ChannelCmd (LPC_ADC_TypeDef *ADCx, uint8_t Channel, FunctionalState NewState);
275
-
276
-/* Configure ADC functions -------------------*/
277
-void ADC_EdgeStartConfig(LPC_ADC_TypeDef *ADCx, uint8_t EdgeOption);
278
-void ADC_IntConfig (LPC_ADC_TypeDef *ADCx, ADC_TYPE_INT_OPT IntType, FunctionalState NewState);
279
-
280
-/* Get ADC information functions -------------------*/
281
-uint16_t ADC_ChannelGetData(LPC_ADC_TypeDef *ADCx, uint8_t channel);
282
-FlagStatus ADC_ChannelGetStatus(LPC_ADC_TypeDef *ADCx, uint8_t channel, uint32_t StatusType);
283
-uint32_t ADC_GlobalGetData(LPC_ADC_TypeDef *ADCx);
284
-FlagStatus	ADC_GlobalGetStatus(LPC_ADC_TypeDef *ADCx, uint32_t StatusType);
285
-
286
-/**
287
- * @}
288
- */
289
-
290
-
291
-#ifdef __cplusplus
292
-}
293
-#endif
294
-
295
-
296
-#endif /* LPC17XX_ADC_H_ */
297
-
298
-/**
299
- * @}
300
- */
301
-
302
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 872
frameworks/CMSIS/LPC1768/include/lpc17xx_can.h Просмотреть файл

@@ -1,872 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_can.h			2010-06-18
3
-*//**
4
-* @file		lpc17xx_can.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for CAN firmware library on LPC17xx
7
-* @version	3.0
8
-* @date		18. June. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @defgroup CAN CAN (Control Area Network)
35
- * @ingroup LPC1700CMSIS_FwLib_Drivers
36
- * @{
37
- */
38
-
39
-#ifndef LPC17XX_CAN_H_
40
-#define LPC17XX_CAN_H_
41
-
42
-/* Includes ------------------------------------------------------------------- */
43
-#include "LPC17xx.h"
44
-#include "lpc_types.h"
45
-
46
-#ifdef __cplusplus
47
-extern "C"
48
-{
49
-#endif
50
-
51
-/* Public Types --------------------------------------------------------------- */
52
-/** @defgroup CAN_Public_Macros CAN Public Macros
53
- * @{
54
- */
55
-#define MSG_ENABLE				((uint8_t)(0))
56
-#define MSG_DISABLE				((uint8_t)(1))
57
-#define CAN1_CTRL				((uint8_t)(0))
58
-#define CAN2_CTRL				((uint8_t)(1))
59
-#define PARAM_FULLCAN_IC(n)		((n==FULLCAN_IC0)||(n==FULLCAN_IC1))
60
-#define ID_11					1
61
-#define MAX_HW_FULLCAN_OBJ 		64
62
-#define MAX_SW_FULLCAN_OBJ 		32
63
-
64
-/**
65
- * @}
66
- */
67
-
68
-/* Private Macros ------------------------------------------------------------- */
69
-/** @defgroup CAN_Private_Macros CAN Private Macros
70
- * @{
71
- */
72
-
73
-/* --------------------- BIT DEFINITIONS -------------------------------------- */
74
-/*********************************************************************//**
75
- * Macro defines for CAN Mode Register
76
- **********************************************************************/
77
-/** CAN Reset mode */
78
-#define CAN_MOD_RM			((uint32_t)(1))
79
-/** CAN Listen Only Mode */
80
-#define CAN_MOD_LOM			((uint32_t)(1<<1))
81
-/** CAN Self Test mode */
82
-#define CAN_MOD_STM			((uint32_t)(1<<2))
83
-/** CAN Transmit Priority mode */
84
-#define CAN_MOD_TPM			((uint32_t)(1<<3))
85
-/** CAN Sleep mode */
86
-#define CAN_MOD_SM			((uint32_t)(1<<4))
87
-/** CAN Receive Polarity mode */
88
-#define CAN_MOD_RPM			((uint32_t)(1<<5))
89
-/** CAN Test mode */
90
-#define CAN_MOD_TM			((uint32_t)(1<<7))
91
-
92
-/*********************************************************************//**
93
- * Macro defines for CAN Command Register
94
- **********************************************************************/
95
-/** CAN Transmission Request */
96
-#define CAN_CMR_TR			((uint32_t)(1))
97
-/** CAN Abort Transmission */
98
-#define CAN_CMR_AT			((uint32_t)(1<<1))
99
-/** CAN Release Receive Buffer */
100
-#define CAN_CMR_RRB			((uint32_t)(1<<2))
101
-/** CAN Clear Data Overrun */
102
-#define CAN_CMR_CDO			((uint32_t)(1<<3))
103
-/** CAN Self Reception Request */
104
-#define CAN_CMR_SRR			((uint32_t)(1<<4))
105
-/** CAN Select Tx Buffer 1 */
106
-#define CAN_CMR_STB1		((uint32_t)(1<<5))
107
-/** CAN Select Tx Buffer 2 */
108
-#define CAN_CMR_STB2		((uint32_t)(1<<6))
109
-/** CAN Select Tx Buffer 3 */
110
-#define CAN_CMR_STB3		((uint32_t)(1<<7))
111
-
112
-/*********************************************************************//**
113
- * Macro defines for CAN Global Status Register
114
- **********************************************************************/
115
-/** CAN Receive Buffer Status */
116
-#define CAN_GSR_RBS			((uint32_t)(1))
117
-/** CAN Data Overrun Status */
118
-#define CAN_GSR_DOS			((uint32_t)(1<<1))
119
-/** CAN Transmit Buffer Status */
120
-#define CAN_GSR_TBS			((uint32_t)(1<<2))
121
-/** CAN Transmit Complete Status */
122
-#define CAN_GSR_TCS			((uint32_t)(1<<3))
123
-/** CAN Receive Status */
124
-#define CAN_GSR_RS			((uint32_t)(1<<4))
125
-/** CAN Transmit Status */
126
-#define CAN_GSR_TS			((uint32_t)(1<<5))
127
-/** CAN Error Status */
128
-#define CAN_GSR_ES			((uint32_t)(1<<6))
129
-/** CAN Bus Status */
130
-#define CAN_GSR_BS			((uint32_t)(1<<7))
131
-/** CAN Current value of the Rx Error Counter */
132
-#define CAN_GSR_RXERR(n)	((uint32_t)((n&0xFF)<<16))
133
-/** CAN Current value of the Tx Error Counter */
134
-#define CAN_GSR_TXERR(n)	((uint32_t)(n&0xFF)<<24))
135
-
136
-/*********************************************************************//**
137
- * Macro defines for CAN Interrupt and Capture Register
138
- **********************************************************************/
139
-/** CAN Receive Interrupt */
140
-#define CAN_ICR_RI			((uint32_t)(1))
141
-/** CAN Transmit Interrupt 1 */
142
-#define CAN_ICR_TI1			((uint32_t)(1<<1))
143
-/** CAN Error Warning Interrupt */
144
-#define CAN_ICR_EI			((uint32_t)(1<<2))
145
-/** CAN Data Overrun Interrupt */
146
-#define CAN_ICR_DOI			((uint32_t)(1<<3))
147
-/** CAN Wake-Up Interrupt */
148
-#define CAN_ICR_WUI			((uint32_t)(1<<4))
149
-/** CAN Error Passive Interrupt */
150
-#define CAN_ICR_EPI			((uint32_t)(1<<5))
151
-/** CAN Arbitration Lost Interrupt */
152
-#define CAN_ICR_ALI			((uint32_t)(1<<6))
153
-/** CAN Bus Error Interrupt */
154
-#define CAN_ICR_BEI			((uint32_t)(1<<7))
155
-/** CAN ID Ready Interrupt */
156
-#define CAN_ICR_IDI			((uint32_t)(1<<8))
157
-/** CAN Transmit Interrupt 2 */
158
-#define CAN_ICR_TI2			((uint32_t)(1<<9))
159
-/** CAN Transmit Interrupt 3 */
160
-#define CAN_ICR_TI3			((uint32_t)(1<<10))
161
-/** CAN Error Code Capture */
162
-#define CAN_ICR_ERRBIT(n)	((uint32_t)((n&0x1F)<<16))
163
-/** CAN Error Direction */
164
-#define CAN_ICR_ERRDIR		((uint32_t)(1<<21))
165
-/** CAN Error Capture */
166
-#define CAN_ICR_ERRC(n)		((uint32_t)((n&0x3)<<22))
167
-/** CAN Arbitration Lost Capture */
168
-#define CAN_ICR_ALCBIT(n)		((uint32_t)((n&0xFF)<<24))
169
-
170
-/*********************************************************************//**
171
- * Macro defines for CAN Interrupt Enable Register
172
- **********************************************************************/
173
-/** CAN Receive Interrupt Enable */
174
-#define CAN_IER_RIE			((uint32_t)(1))
175
-/** CAN Transmit Interrupt Enable for buffer 1 */
176
-#define CAN_IER_TIE1		((uint32_t)(1<<1))
177
-/** CAN Error Warning Interrupt Enable */
178
-#define CAN_IER_EIE			((uint32_t)(1<<2))
179
-/** CAN Data Overrun Interrupt Enable */
180
-#define CAN_IER_DOIE		((uint32_t)(1<<3))
181
-/** CAN Wake-Up Interrupt Enable */
182
-#define CAN_IER_WUIE		((uint32_t)(1<<4))
183
-/** CAN Error Passive Interrupt Enable */
184
-#define CAN_IER_EPIE		((uint32_t)(1<<5))
185
-/** CAN Arbitration Lost Interrupt Enable */
186
-#define CAN_IER_ALIE		((uint32_t)(1<<6))
187
-/** CAN Bus Error Interrupt Enable */
188
-#define CAN_IER_BEIE		((uint32_t)(1<<7))
189
-/** CAN ID Ready Interrupt Enable */
190
-#define CAN_IER_IDIE		((uint32_t)(1<<8))
191
-/** CAN Transmit Enable Interrupt for Buffer 2 */
192
-#define CAN_IER_TIE2		((uint32_t)(1<<9))
193
-/** CAN Transmit Enable Interrupt for Buffer 3 */
194
-#define CAN_IER_TIE3		((uint32_t)(1<<10))
195
-
196
-/*********************************************************************//**
197
- * Macro defines for CAN Bus Timing Register
198
- **********************************************************************/
199
-/** CAN Baudrate Prescaler */
200
-#define CAN_BTR_BRP(n)		((uint32_t)(n&0x3FF))
201
-/** CAN Synchronization Jump Width */
202
-#define CAN_BTR_SJM(n)		((uint32_t)((n&0x3)<<14))
203
-/** CAN Time Segment 1 */
204
-#define CAN_BTR_TESG1(n)	((uint32_t)(n&0xF)<<16))
205
-/** CAN Time Segment 2 */
206
-#define CAN_BTR_TESG2(n)	((uint32_t)(n&0xF)<<20))
207
-/** CAN Sampling */
208
-#define CAN_BTR_SAM(n)		((uint32_t)(1<<23))
209
-
210
-/*********************************************************************//**
211
- * Macro defines for CAN Error Warning Limit Register
212
- **********************************************************************/
213
-/** CAN Error Warning Limit */
214
-#define CAN_EWL_EWL(n)		((uint32_t)(n&0xFF))
215
-
216
-/*********************************************************************//**
217
- * Macro defines for CAN Status Register
218
- **********************************************************************/
219
-/** CAN Receive Buffer Status */
220
-#define CAN_SR_RBS		((uint32_t)(1))
221
-/** CAN Data Overrun Status */
222
-#define CAN_SR_DOS		((uint32_t)(1<<1))
223
-/** CAN Transmit Buffer Status 1 */
224
-#define CAN_SR_TBS1		((uint32_t)(1<<2))
225
-/** CAN Transmission Complete Status of Buffer 1 */
226
-#define CAN_SR_TCS1		((uint32_t)(1<<3))
227
-/** CAN Receive Status */
228
-#define CAN_SR_RS		((uint32_t)(1<<4))
229
-/** CAN Transmit Status 1 */
230
-#define CAN_SR_TS1		((uint32_t)(1<<5))
231
-/** CAN Error Status */
232
-#define CAN_SR_ES		((uint32_t)(1<<6))
233
-/** CAN Bus Status */
234
-#define CAN_SR_BS		((uint32_t)(1<<7))
235
-/** CAN Transmit Buffer Status 2 */
236
-#define CAN_SR_TBS2		((uint32_t)(1<<10))
237
-/** CAN Transmission Complete Status of Buffer 2 */
238
-#define CAN_SR_TCS2		((uint32_t)(1<<11))
239
-/** CAN Transmit Status 2 */
240
-#define CAN_SR_TS2		((uint32_t)(1<<13))
241
-/** CAN Transmit Buffer Status 2 */
242
-#define CAN_SR_TBS3		((uint32_t)(1<<18))
243
-/** CAN Transmission Complete Status of Buffer 2 */
244
-#define CAN_SR_TCS3		((uint32_t)(1<<19))
245
-/** CAN Transmit Status 2 */
246
-#define CAN_SR_TS3		((uint32_t)(1<<21))
247
-
248
-/*********************************************************************//**
249
- * Macro defines for CAN Receive Frame Status Register
250
- **********************************************************************/
251
-/** CAN ID Index */
252
-#define CAN_RFS_ID_INDEX(n)	((uint32_t)(n&0x3FF))
253
-/** CAN Bypass */
254
-#define CAN_RFS_BP			((uint32_t)(1<<10))
255
-/** CAN Data Length Code */
256
-#define CAN_RFS_DLC(n)		((uint32_t)((n&0xF)<<16)
257
-/** CAN Remote Transmission Request */
258
-#define CAN_RFS_RTR			((uint32_t)(1<<30))
259
-/** CAN control 11 bit or 29 bit Identifier */
260
-#define CAN_RFS_FF			((uint32_t)(1<<31))
261
-
262
-/*********************************************************************//**
263
- * Macro defines for CAN Receive Identifier Register
264
- **********************************************************************/
265
-/** CAN 11 bit Identifier */
266
-#define CAN_RID_ID_11(n)		((uint32_t)(n&0x7FF))
267
-/** CAN 29 bit Identifier */
268
-#define CAN_RID_ID_29(n)		((uint32_t)(n&0x1FFFFFFF))
269
-
270
-/*********************************************************************//**
271
- * Macro defines for CAN Receive Data A Register
272
- **********************************************************************/
273
-/** CAN Receive Data 1 */
274
-#define CAN_RDA_DATA1(n)		((uint32_t)(n&0xFF))
275
-/** CAN Receive Data 2 */
276
-#define CAN_RDA_DATA2(n)		((uint32_t)((n&0xFF)<<8))
277
-/** CAN Receive Data 3 */
278
-#define CAN_RDA_DATA3(n)		((uint32_t)((n&0xFF)<<16))
279
-/** CAN Receive Data 4 */
280
-#define CAN_RDA_DATA4(n)		((uint32_t)((n&0xFF)<<24))
281
-
282
-/*********************************************************************//**
283
- * Macro defines for CAN Receive Data B Register
284
- **********************************************************************/
285
-/** CAN Receive Data 5 */
286
-#define CAN_RDB_DATA5(n)		((uint32_t)(n&0xFF))
287
-/** CAN Receive Data 6 */
288
-#define CAN_RDB_DATA6(n)		((uint32_t)((n&0xFF)<<8))
289
-/** CAN Receive Data 7 */
290
-#define CAN_RDB_DATA7(n)		((uint32_t)((n&0xFF)<<16))
291
-/** CAN Receive Data 8 */
292
-#define CAN_RDB_DATA8(n)		((uint32_t)((n&0xFF)<<24))
293
-
294
-/*********************************************************************//**
295
- * Macro defines for CAN Transmit Frame Information Register
296
- **********************************************************************/
297
-/** CAN Priority */
298
-#define CAN_TFI_PRIO(n)			((uint32_t)(n&0xFF))
299
-/** CAN Data Length Code */
300
-#define CAN_TFI_DLC(n)			((uint32_t)((n&0xF)<<16))
301
-/** CAN Remote Frame Transmission */
302
-#define CAN_TFI_RTR				((uint32_t)(1<<30))
303
-/** CAN control 11-bit or 29-bit Identifier */
304
-#define CAN_TFI_FF				((uint32_t)(1<<31))
305
-
306
-/*********************************************************************//**
307
- * Macro defines for CAN Transmit Identifier Register
308
- **********************************************************************/
309
-/** CAN 11-bit Identifier */
310
-#define CAN_TID_ID11(n)			((uint32_t)(n&0x7FF))
311
-/** CAN 11-bit Identifier */
312
-#define CAN_TID_ID29(n)			((uint32_t)(n&0x1FFFFFFF))
313
-
314
-/*********************************************************************//**
315
- * Macro defines for CAN Transmit Data A Register
316
- **********************************************************************/
317
-/** CAN Transmit Data 1 */
318
-#define CAN_TDA_DATA1(n)		((uint32_t)(n&0xFF))
319
-/** CAN Transmit Data 2 */
320
-#define CAN_TDA_DATA2(n)		((uint32_t)((n&0xFF)<<8))
321
-/** CAN Transmit Data 3 */
322
-#define CAN_TDA_DATA3(n)		((uint32_t)((n&0xFF)<<16))
323
-/** CAN Transmit Data 4 */
324
-#define CAN_TDA_DATA4(n)		((uint32_t)((n&0xFF)<<24))
325
-
326
-/*********************************************************************//**
327
- * Macro defines for CAN Transmit Data B Register
328
- **********************************************************************/
329
-/** CAN Transmit Data 5 */
330
-#define CAN_TDA_DATA5(n)		((uint32_t)(n&0xFF))
331
-/** CAN Transmit Data 6 */
332
-#define CAN_TDA_DATA6(n)		((uint32_t)((n&0xFF)<<8))
333
-/** CAN Transmit Data 7 */
334
-#define CAN_TDA_DATA7(n)		((uint32_t)((n&0xFF)<<16))
335
-/** CAN Transmit Data 8 */
336
-#define CAN_TDA_DATA8(n)		((uint32_t)((n&0xFF)<<24))
337
-
338
-/*********************************************************************//**
339
- * Macro defines for CAN Sleep Clear Register
340
- **********************************************************************/
341
-/** CAN1 Sleep mode */
342
-#define CAN1SLEEPCLR			((uint32_t)(1<<1))
343
-/** CAN2 Sleep Mode */
344
-#define CAN2SLEEPCLR			((uint32_t)(1<<2))
345
-
346
-/*********************************************************************//**
347
- * Macro defines for CAN Wake up Flags Register
348
- **********************************************************************/
349
-/** CAN1 Sleep mode */
350
-#define CAN_WAKEFLAGES_CAN1WAKE		((uint32_t)(1<<1))
351
-/** CAN2 Sleep Mode */
352
-#define CAN_WAKEFLAGES_CAN2WAKE		((uint32_t)(1<<2))
353
-
354
-/*********************************************************************//**
355
- * Macro defines for Central transmit Status Register
356
- **********************************************************************/
357
-/** CAN Transmit 1 */
358
-#define CAN_TSR_TS1			((uint32_t)(1))
359
-/** CAN Transmit 2 */
360
-#define CAN_TSR_TS2			((uint32_t)(1<<1))
361
-/** CAN Transmit Buffer Status 1 */
362
-#define CAN_TSR_TBS1			((uint32_t)(1<<8))
363
-/** CAN Transmit Buffer Status 2 */
364
-#define CAN_TSR_TBS2			((uint32_t)(1<<9))
365
-/** CAN Transmission Complete Status 1 */
366
-#define CAN_TSR_TCS1			((uint32_t)(1<<16))
367
-/** CAN Transmission Complete Status 2 */
368
-#define CAN_TSR_TCS2			((uint32_t)(1<<17))
369
-
370
-/*********************************************************************//**
371
- * Macro defines for Central Receive Status Register
372
- **********************************************************************/
373
-/** CAN Receive Status 1 */
374
-#define CAN_RSR_RS1				((uint32_t)(1))
375
-/** CAN Receive Status 1 */
376
-#define CAN_RSR_RS2				((uint32_t)(1<<1))
377
-/** CAN Receive Buffer Status 1*/
378
-#define CAN_RSR_RB1				((uint32_t)(1<<8))
379
-/** CAN Receive Buffer Status 2*/
380
-#define CAN_RSR_RB2				((uint32_t)(1<<9))
381
-/** CAN Data Overrun Status 1 */
382
-#define CAN_RSR_DOS1			((uint32_t)(1<<16))
383
-/** CAN Data Overrun Status 1 */
384
-#define CAN_RSR_DOS2			((uint32_t)(1<<17))
385
-
386
-/*********************************************************************//**
387
- * Macro defines for Central Miscellaneous Status Register
388
- **********************************************************************/
389
-/** Same CAN Error Status in CAN1GSR */
390
-#define CAN_MSR_E1		((uint32_t)(1))
391
-/** Same CAN Error Status in CAN2GSR */
392
-#define CAN_MSR_E2		((uint32_t)(1<<1))
393
-/** Same CAN Bus Status in CAN1GSR */
394
-#define CAN_MSR_BS1		((uint32_t)(1<<8))
395
-/** Same CAN Bus Status in CAN2GSR */
396
-#define CAN_MSR_BS2		((uint32_t)(1<<9))
397
-
398
-/*********************************************************************//**
399
- * Macro defines for Acceptance Filter Mode Register
400
- **********************************************************************/
401
-/** CAN Acceptance Filter Off mode */
402
-#define CAN_AFMR_AccOff		((uint32_t)(1))
403
-/** CAN Acceptance File Bypass mode */
404
-#define CAN_AFMR_AccBP		((uint32_t)(1<<1))
405
-/** FullCAN Mode Enhancements */
406
-#define CAN_AFMR_eFCAN		((uint32_t)(1<<2))
407
-
408
-/*********************************************************************//**
409
- * Macro defines for Standard Frame Individual Start Address Register
410
- **********************************************************************/
411
-/** The start address of the table of individual Standard Identifier */
412
-#define CAN_STT_sa(n)		((uint32_t)((n&1FF)<<2))
413
-
414
-/*********************************************************************//**
415
- * Macro defines for Standard Frame Group Start Address Register
416
- **********************************************************************/
417
-/** The start address of the table of grouped Standard Identifier */
418
-#define CAN_SFF_GRP_sa(n)		((uint32_t)((n&3FF)<<2))
419
-
420
-/*********************************************************************//**
421
- * Macro defines for Extended Frame Start Address Register
422
- **********************************************************************/
423
-/** The start address of the table of individual Extended Identifier */
424
-#define CAN_EFF_sa(n)		((uint32_t)((n&1FF)<<2))
425
-
426
-/*********************************************************************//**
427
- * Macro defines for Extended Frame Group Start Address Register
428
- **********************************************************************/
429
-/** The start address of the table of grouped Extended Identifier */
430
-#define CAN_Eff_GRP_sa(n)		((uint32_t)((n&3FF)<<2))
431
-
432
-/*********************************************************************//**
433
- * Macro defines for End Of AF Table Register
434
- **********************************************************************/
435
-/** The End of Table of AF LookUp Table */
436
-#define CAN_EndofTable(n)		((uint32_t)((n&3FF)<<2))
437
-
438
-/*********************************************************************//**
439
- * Macro defines for LUT Error Address Register
440
- **********************************************************************/
441
-/** CAN Look-Up Table Error Address */
442
-#define CAN_LUTerrAd(n)		((uint32_t)((n&1FF)<<2))
443
-
444
-/*********************************************************************//**
445
- * Macro defines for LUT Error Register
446
- **********************************************************************/
447
-/** CAN Look-Up Table Error */
448
-#define CAN_LUTerr		((uint32_t)(1))
449
-
450
-/*********************************************************************//**
451
- * Macro defines for Global FullCANInterrupt Enable Register
452
- **********************************************************************/
453
-/** Global FullCANInterrupt Enable */
454
-#define CAN_FCANIE		((uint32_t)(1))
455
-
456
-/*********************************************************************//**
457
- * Macro defines for FullCAN Interrupt and Capture Register 0
458
- **********************************************************************/
459
-/** FullCAN Interrupt and Capture (0-31)*/
460
-#define CAN_FCANIC0_IntPnd(n)	((uint32_t)(1<<n))
461
-
462
-/*********************************************************************//**
463
- * Macro defines for FullCAN Interrupt and Capture Register 1
464
- **********************************************************************/
465
-/** FullCAN Interrupt and Capture (0-31)*/
466
-#define CAN_FCANIC1_IntPnd(n)	((uint32_t)(1<<(n-32)))
467
-
468
-
469
-/* ---------------- CHECK PARAMETER DEFINITIONS ---------------------------- */
470
-/** Macro to determine if it is valid CAN peripheral or not */
471
-#define PARAM_CANx(x)			((((uint32_t*)x)==((uint32_t *)LPC_CAN1)) \
472
-||(((uint32_t*)x)==((uint32_t *)LPC_CAN2)))
473
-
474
-/*	Macro to determine if it is valid CANAF or not*/
475
-#define PARAM_CANAFx(x)			(((uint32_t*)x)== ((uint32_t*)LPC_CANAF))
476
-
477
-/*	Macro to determine if it is valid CANAF RAM or not*/
478
-#define PARAM_CANAFRAMx(x)		(((uint32_t*)x)== (uint32_t*)LPC_CANAF_RAM)
479
-
480
-/*	Macro to determine if it is valid CANCR or not*/
481
-#define PARAM_CANCRx(x)			(((uint32_t*)x)==((uint32_t*)LPC_CANCR))
482
-
483
-/** Macro to check Data to send valid */
484
-#define PARAM_I2S_DATA(data) 	((data>=0)&&(data <= 0xFFFFFFFF))
485
-
486
-/** Macro to check frequency value */
487
-#define PRAM_I2S_FREQ(freq)		((freq>=16000)&&(freq <= 96000))
488
-
489
-/** Macro to check Frame Identifier */
490
-#define PARAM_ID_11(n)			((n>>11)==0) /*-- 11 bit --*/
491
-#define PARAM_ID_29(n)			((n>>29)==0) /*-- 29 bit --*/
492
-
493
-/** Macro to check DLC value */
494
-#define PARAM_DLC(n)			((n>>4)==0)  /*-- 4 bit --*/
495
-/** Macro to check ID format type */
496
-#define PARAM_ID_FORMAT(n)		((n==STD_ID_FORMAT)||(n==EXT_ID_FORMAT))
497
-
498
-/** Macro to check Group identifier */
499
-#define PARAM_GRP_ID(x, y)		((x<=y))
500
-
501
-/** Macro to check Frame type */
502
-#define PARAM_FRAME_TYPE(n)		((n==DATA_FRAME)||(n==REMOTE_FRAME))
503
-
504
-/** Macro to check Control/Central Status type parameter */
505
-#define PARAM_CTRL_STS_TYPE(n)	((n==CANCTRL_GLOBAL_STS)||(n==CANCTRL_INT_CAP) \
506
-||(n==CANCTRL_ERR_WRN)||(n==CANCTRL_STS))
507
-
508
-/** Macro to check CR status type */
509
-#define PARAM_CR_STS_TYPE(n)	((n==CANCR_TX_STS)||(n==CANCR_RX_STS) \
510
-||(n==CANCR_MS))
511
-/** Macro to check AF Mode type parameter */
512
-#define PARAM_AFMODE_TYPE(n)	((n==CAN_Normal)||(n==CAN_AccOff) \
513
-||(n==CAN_AccBP)||(n==CAN_eFCAN))
514
-
515
-/** Macro to check Operation Mode */
516
-#define PARAM_MODE_TYPE(n)		((n==CAN_OPERATING_MODE)||(n==CAN_RESET_MODE) \
517
-||(n==CAN_LISTENONLY_MODE)||(n==CAN_SELFTEST_MODE) \
518
-||(n==CAN_TXPRIORITY_MODE)||(n==CAN_SLEEP_MODE) \
519
-||(n==CAN_RXPOLARITY_MODE)||(n==CAN_TEST_MODE))
520
-
521
-/** Macro define for struct AF_Section parameter */
522
-#define PARAM_CTRL(n)	((n==CAN1_CTRL)|(n==CAN2_CTRL))
523
-
524
-/** Macro define for struct AF_Section parameter */
525
-#define PARAM_MSG_DISABLE(n)	((n==MSG_ENABLE)|(n==MSG_DISABLE))
526
-
527
-/**Macro to check Interrupt Type parameter */
528
-#define PARAM_INT_EN_TYPE(n)	((n==CANINT_RIE)||(n==CANINT_TIE1) \
529
-||(n==CANINT_EIE)||(n==CANINT_DOIE) \
530
-||(n==CANINT_WUIE)||(n==CANINT_EPIE) \
531
-||(n==CANINT_ALIE)||(n==CANINT_BEIE) \
532
-||(n==CANINT_IDIE)||(n==CANINT_TIE2) \
533
-||(n==CANINT_TIE3)||(n==CANINT_FCE))
534
-
535
-/** Macro to check AFLUT Entry type */
536
-#define PARAM_AFLUT_ENTRY_TYPE(n)	((n==FULLCAN_ENTRY)||(n==EXPLICIT_STANDARD_ENTRY)\
537
-||(n==GROUP_STANDARD_ENTRY)||(n==EXPLICIT_EXTEND_ENTRY)	\
538
-||(n==GROUP_EXTEND_ENTRY))
539
-
540
-/** Macro to check position */
541
-#define PARAM_POSITION(n)	(n<512)
542
-
543
-/**
544
- * @}
545
- */
546
-
547
-/* Public Types --------------------------------------------------------------- */
548
-/** @defgroup CAN_Public_Types CAN Public Types
549
- * @{
550
- */
551
-
552
-/** CAN configuration structure */
553
-/***********************************************************************
554
- * CAN device configuration commands (IOCTL commands and arguments)
555
- **********************************************************************/
556
-/**
557
- * @brief CAN ID format definition
558
- */
559
-typedef enum {
560
-	STD_ID_FORMAT = 0, 	/**< Use standard ID format (11 bit ID) */
561
-	EXT_ID_FORMAT = 1	/**< Use extended ID format (29 bit ID) */
562
-} CAN_ID_FORMAT_Type;
563
-
564
-/**
565
- * @brief AFLUT Entry type definition
566
- */
567
-typedef enum {
568
-	FULLCAN_ENTRY = 0,
569
-	EXPLICIT_STANDARD_ENTRY,
570
-	GROUP_STANDARD_ENTRY,
571
-	EXPLICIT_EXTEND_ENTRY,
572
-	GROUP_EXTEND_ENTRY
573
-} AFLUT_ENTRY_Type;
574
-
575
-/**
576
- * @brief Symbolic names for type of CAN message
577
- */
578
-typedef enum {
579
-	DATA_FRAME = 0, 	/**< Data frame */
580
-	REMOTE_FRAME = 1	/**< Remote frame */
581
-} CAN_FRAME_Type;
582
-
583
-/**
584
- * @brief CAN Control status definition
585
- */
586
-typedef enum {
587
-	CANCTRL_GLOBAL_STS = 0, /**< CAN Global Status */
588
-	CANCTRL_INT_CAP, 		/**< CAN Interrupt and Capture */
589
-	CANCTRL_ERR_WRN, 		/**< CAN Error Warning Limit */
590
-	CANCTRL_STS				/**< CAN Control Status */
591
-} CAN_CTRL_STS_Type;
592
-
593
-/**
594
- * @brief Central CAN status type definition
595
- */
596
-typedef enum {
597
-	CANCR_TX_STS = 0, 	/**< Central CAN Tx Status */
598
-	CANCR_RX_STS, 		/**< Central CAN Rx Status */
599
-	CANCR_MS			/**< Central CAN Miscellaneous Status */
600
-} CAN_CR_STS_Type;
601
-
602
-/**
603
- * @brief FullCAN Interrupt Capture type definition
604
- */
605
-typedef enum{
606
-	FULLCAN_IC0,	/**< FullCAN Interrupt and Capture 0 */
607
-	FULLCAN_IC1	/**< FullCAN Interrupt and Capture 1 */
608
-}FullCAN_IC_Type;
609
-
610
-/**
611
- * @brief CAN interrupt enable type definition
612
- */
613
-typedef enum {
614
-	CANINT_RIE = 0, 	/**< CAN Receiver Interrupt Enable */
615
-	CANINT_TIE1, 		/**< CAN Transmit Interrupt Enable */
616
-	CANINT_EIE, 		/**< CAN Error Warning Interrupt Enable */
617
-	CANINT_DOIE, 		/**< CAN Data Overrun Interrupt Enable */
618
-	CANINT_WUIE, 		/**< CAN Wake-Up Interrupt Enable */
619
-	CANINT_EPIE, 		/**< CAN Error Passive Interrupt Enable */
620
-	CANINT_ALIE, 		/**< CAN Arbitration Lost Interrupt Enable */
621
-	CANINT_BEIE, 		/**< CAN Bus Error Inter rupt Enable */
622
-	CANINT_IDIE, 		/**< CAN ID Ready Interrupt Enable */
623
-	CANINT_TIE2, 		/**< CAN Transmit Interrupt Enable for Buffer2 */
624
-	CANINT_TIE3, 		/**< CAN Transmit Interrupt Enable for Buffer3 */
625
-	CANINT_FCE			/**< FullCAN Interrupt Enable */
626
-} CAN_INT_EN_Type;
627
-
628
-/**
629
- * @brief Acceptance Filter Mode type definition
630
- */
631
-typedef enum {
632
-	CAN_Normal = 0, 	/**< Normal Mode */
633
-	CAN_AccOff, 		/**< Acceptance Filter Off Mode */
634
-	CAN_AccBP, 			/**< Acceptance Fileter Bypass Mode */
635
-	CAN_eFCAN			/**< FullCAN Mode Enhancement */
636
-} CAN_AFMODE_Type;
637
-
638
-/**
639
- * @brief CAN Mode Type definition
640
- */
641
-typedef enum {
642
-	CAN_OPERATING_MODE = 0, 	/**< Operating Mode */
643
-	CAN_RESET_MODE, 			/**< Reset Mode */
644
-	CAN_LISTENONLY_MODE, 		/**< Listen Only Mode */
645
-	CAN_SELFTEST_MODE, 			/**< Seft Test Mode */
646
-	CAN_TXPRIORITY_MODE, 		/**< Transmit Priority Mode */
647
-	CAN_SLEEP_MODE, 			/**< Sleep Mode */
648
-	CAN_RXPOLARITY_MODE, 		/**< Receive Polarity Mode */
649
-	CAN_TEST_MODE				/**< Test Mode */
650
-} CAN_MODE_Type;
651
-
652
-/**
653
- * @brief Error values that functions can return
654
- */
655
-typedef enum {
656
-	CAN_OK = 1, 				/**< No error */
657
-	CAN_OBJECTS_FULL_ERROR, 	/**< No more rx or tx objects available */
658
-	CAN_FULL_OBJ_NOT_RCV, 		/**< Full CAN object not received */
659
-	CAN_NO_RECEIVE_DATA, 		/**< No have receive data available */
660
-	CAN_AF_ENTRY_ERROR, 		/**< Entry load in AFLUT is unvalid */
661
-	CAN_CONFLICT_ID_ERROR, 		/**< Conflict ID occur */
662
-	CAN_ENTRY_NOT_EXIT_ERROR	/**< Entry remove outo AFLUT is not exit */
663
-} CAN_ERROR;
664
-
665
-/**
666
- * @brief Pin Configuration structure
667
- */
668
-typedef struct {
669
-	uint8_t RD; 			/**< Serial Inputs, from CAN transceivers, should be:
670
-							 ** For CAN1:
671
-							 - CAN_RD1_P0_0: RD pin is on P0.0
672
-							 - CAN_RD1_P0_21 : RD pin is on P0.21
673
-							 ** For CAN2:
674
-							 - CAN_RD2_P0_4: RD pin is on P0.4
675
-							 - CAN_RD2_P2_7: RD pin is on P2.7
676
-							 */
677
-	uint8_t TD;				/**< Serial Outputs, To CAN transceivers, should be:
678
-							 ** For CAN1:
679
-							 - CAN_TD1_P0_1: TD pin is on P0.1
680
-							 - CAN_TD1_P0_22: TD pin is on P0.22
681
-							 ** For CAN2:
682
-							 - CAN_TD2_P0_5: TD pin is on P0.5
683
-							 - CAN_TD2_P2_8: TD pin is on P2.8
684
-							 */
685
-} CAN_PinCFG_Type;
686
-
687
-/**
688
- * @brief CAN message object structure
689
- */
690
-typedef struct {
691
-	uint32_t id; 			/**< 29 bit identifier, it depend on "format" value
692
-								 - if format = STD_ID_FORMAT, id should be 11 bit identifier
693
-								 - if format = EXT_ID_FORMAT, id should be 29 bit identifier
694
-							 */
695
-	uint8_t dataA[4]; 		/**< Data field A */
696
-	uint8_t dataB[4]; 		/**< Data field B */
697
-	uint8_t len; 			/**< Length of data field in bytes, should be:
698
-								 - 0000b-0111b: 0-7 bytes
699
-								 - 1xxxb: 8 bytes
700
-							*/
701
-	uint8_t format; 		/**< Identifier Format, should be:
702
-								 - STD_ID_FORMAT: Standard ID - 11 bit format
703
-								 - EXT_ID_FORMAT: Extended ID - 29 bit format
704
-							*/
705
-	uint8_t type; 			/**< Remote Frame transmission, should be:
706
-								 - DATA_FRAME: the number of data bytes called out by the DLC
707
-								 field are send from the CANxTDA and CANxTDB registers
708
-								 - REMOTE_FRAME: Remote Frame is sent
709
-							*/
710
-} CAN_MSG_Type;
711
-
712
-/**
713
- * @brief FullCAN Entry structure
714
- */
715
-typedef struct {
716
-	uint8_t controller;		/**< CAN Controller, should be:
717
-								 - CAN1_CTRL: CAN1 Controller
718
-								 - CAN2_CTRL: CAN2 Controller
719
-							*/
720
-	uint8_t disable;		/**< Disable bit, should be:
721
-								 - MSG_ENABLE: disable bit = 0
722
-								 - MSG_DISABLE: disable bit = 1
723
-							*/
724
-	uint16_t id_11;			/**< Standard ID, should be 11-bit value */
725
-} FullCAN_Entry;
726
-
727
-/**
728
- * @brief Standard ID Frame Format Entry structure
729
- */
730
-typedef struct {
731
-	uint8_t controller; 	/**< CAN Controller, should be:
732
-								 - CAN1_CTRL: CAN1 Controller
733
-								 - CAN2_CTRL: CAN2 Controller
734
-							*/
735
-	uint8_t disable; 		/**< Disable bit, should be:
736
-								 - MSG_ENABLE: disable bit = 0
737
-								 - MSG_DISABLE: disable bit = 1
738
-							*/
739
-	uint16_t id_11; 		/**< Standard ID, should be 11-bit value */
740
-} SFF_Entry;
741
-
742
-/**
743
- * @brief Group of Standard ID Frame Format Entry structure
744
- */
745
-typedef struct {
746
-	uint8_t controller1; 	/**< First CAN Controller, should be:
747
-								 - CAN1_CTRL: CAN1 Controller
748
-								 - CAN2_CTRL: CAN2 Controller
749
-							*/
750
-	uint8_t disable1; 		/**< First Disable bit, should be:
751
-								 - MSG_ENABLE: disable bit = 0)
752
-								 - MSG_DISABLE: disable bit = 1
753
-							*/
754
-	uint16_t lowerID; 		/**< ID lower bound, should be 11-bit value */
755
-	uint8_t controller2; 	/**< Second CAN Controller, should be:
756
-								 - CAN1_CTRL: CAN1 Controller
757
-								 - CAN2_CTRL: CAN2 Controller
758
-							*/
759
-	uint8_t disable2; 		/**< Second Disable bit, should be:
760
-								 - MSG_ENABLE: disable bit = 0
761
-								 - MSG_DISABLE: disable bit = 1
762
-							*/
763
-	uint16_t upperID; 		/**< ID upper bound, should be 11-bit value and
764
-								 equal or greater than lowerID
765
-							*/
766
-} SFF_GPR_Entry;
767
-
768
-/**
769
- * @brief Extended ID Frame Format Entry structure
770
- */
771
-typedef struct {
772
-	uint8_t controller; 	/**< CAN Controller, should be:
773
-								 - CAN1_CTRL: CAN1 Controller
774
-								 - CAN2_CTRL: CAN2 Controller
775
-							*/
776
-	uint32_t ID_29; 		/**< Extend ID, shoud be 29-bit value */
777
-} EFF_Entry;
778
-
779
-
780
-/**
781
- * @brief Group of Extended ID Frame Format Entry structure
782
- */
783
-typedef struct {
784
-	uint8_t controller1; 	/**< First CAN Controller, should be:
785
-								 - CAN1_CTRL: CAN1 Controller
786
-								 - CAN2_CTRL: CAN2 Controller
787
-							*/
788
-	uint8_t controller2; 	/**< Second Disable bit, should be:
789
-								 - MSG_ENABLE: disable bit = 0(default)
790
-								 - MSG_DISABLE: disable bit = 1
791
-							*/
792
-	uint32_t lowerEID; 		/**< Extended ID lower bound, should be 29-bit value */
793
-	uint32_t upperEID; 		/**< Extended ID upper bound, should be 29-bit value */
794
-} EFF_GPR_Entry;
795
-
796
-
797
-/**
798
- * @brief Acceptance Filter Section Table structure
799
- */
800
-typedef struct {
801
-	FullCAN_Entry* FullCAN_Sec; 	/**< The pointer point to FullCAN_Entry */
802
-	uint8_t FC_NumEntry;			/**< FullCAN Entry Number */
803
-	SFF_Entry* SFF_Sec; 			/**< The pointer point to SFF_Entry */
804
-	uint8_t SFF_NumEntry;			/**< Standard ID Entry Number */
805
-	SFF_GPR_Entry* SFF_GPR_Sec; 	/**< The pointer point to SFF_GPR_Entry */
806
-	uint8_t SFF_GPR_NumEntry;		/**< Group Standard ID Entry Number */
807
-	EFF_Entry* EFF_Sec; 			/**< The pointer point to EFF_Entry */
808
-	uint8_t EFF_NumEntry;			/**< Extended ID Entry Number */
809
-	EFF_GPR_Entry* EFF_GPR_Sec; 	/**< The pointer point to EFF_GPR_Entry */
810
-	uint8_t EFF_GPR_NumEntry;		/**< Group Extended ID Entry Number */
811
-} AF_SectionDef;
812
-
813
-/**
814
- * @}
815
- */
816
-
817
-
818
-/* Public Functions ----------------------------------------------------------- */
819
-/** @defgroup CAN_Public_Functions CAN Public Functions
820
- * @{
821
- */
822
-
823
-/* Init/DeInit CAN peripheral -----------*/
824
-void CAN_Init(LPC_CAN_TypeDef *CANx, uint32_t baudrate);
825
-void CAN_DeInit(LPC_CAN_TypeDef *CANx);
826
-
827
-/* CAN messages functions ---------------*/
828
-Status CAN_SendMsg(LPC_CAN_TypeDef *CANx, CAN_MSG_Type *CAN_Msg);
829
-Status CAN_ReceiveMsg(LPC_CAN_TypeDef *CANx, CAN_MSG_Type *CAN_Msg);
830
-CAN_ERROR FCAN_ReadObj(LPC_CANAF_TypeDef* CANAFx, CAN_MSG_Type *CAN_Msg);
831
-
832
-/* CAN configure functions ---------------*/
833
-void CAN_ModeConfig(LPC_CAN_TypeDef* CANx, CAN_MODE_Type mode,
834
-		FunctionalState NewState);
835
-void CAN_SetAFMode(LPC_CANAF_TypeDef* CANAFx, CAN_AFMODE_Type AFmode);
836
-void CAN_SetCommand(LPC_CAN_TypeDef* CANx, uint32_t CMRType);
837
-
838
-/* AFLUT functions ---------------------- */
839
-CAN_ERROR CAN_SetupAFLUT(LPC_CANAF_TypeDef* CANAFx, AF_SectionDef* AFSection);
840
-CAN_ERROR CAN_LoadFullCANEntry(LPC_CAN_TypeDef* CANx, uint16_t ID);
841
-CAN_ERROR CAN_LoadExplicitEntry(LPC_CAN_TypeDef* CANx, uint32_t ID,
842
-		CAN_ID_FORMAT_Type format);
843
-CAN_ERROR CAN_LoadGroupEntry(LPC_CAN_TypeDef* CANx, uint32_t lowerID,
844
-		uint32_t upperID, CAN_ID_FORMAT_Type format);
845
-CAN_ERROR CAN_RemoveEntry(AFLUT_ENTRY_Type EntryType, uint16_t position);
846
-
847
-/* CAN interrupt functions -----------------*/
848
-void CAN_IRQCmd(LPC_CAN_TypeDef* CANx, CAN_INT_EN_Type arg, FunctionalState NewState);
849
-uint32_t CAN_IntGetStatus(LPC_CAN_TypeDef* CANx);
850
-
851
-/* CAN get status functions ----------------*/
852
-IntStatus CAN_FullCANIntGetStatus (LPC_CANAF_TypeDef* CANAFx);
853
-uint32_t CAN_FullCANPendGetStatus (LPC_CANAF_TypeDef* CANAFx, FullCAN_IC_Type type);
854
-uint32_t CAN_GetCTRLStatus(LPC_CAN_TypeDef* CANx, CAN_CTRL_STS_Type arg);
855
-uint32_t CAN_GetCRStatus(LPC_CANCR_TypeDef* CANCRx, CAN_CR_STS_Type arg);
856
-
857
-/**
858
- * @}
859
- */
860
-
861
-
862
-#ifdef __cplusplus
863
-}
864
-#endif
865
-
866
-#endif /* LPC17XX_CAN_H_ */
867
-
868
-/**
869
- * @}
870
- */
871
-
872
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 406
frameworks/CMSIS/LPC1768/include/lpc17xx_clkpwr.h Просмотреть файл

@@ -1,406 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_clkpwr.h			2010-05-21
3
-*//**
4
-* @file		lpc17xx_clkpwr.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for Clock and Power Control firmware library on LPC17xx
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @defgroup CLKPWR CLKPWR (Clock Power)
35
- * @ingroup LPC1700CMSIS_FwLib_Drivers
36
- * @{
37
- */
38
-
39
-#ifndef LPC17XX_CLKPWR_H_
40
-#define LPC17XX_CLKPWR_H_
41
-
42
-/* Includes ------------------------------------------------------------------- */
43
-#include "LPC17xx.h"
44
-#include "lpc_types.h"
45
-
46
-#ifdef __cplusplus
47
-extern "C"
48
-{
49
-#endif
50
-
51
-/* Public Macros -------------------------------------------------------------- */
52
-/** @defgroup CLKPWR_Public_Macros CLKPWR Public Macros
53
- * @{
54
- */
55
-
56
-/**********************************************************************
57
- * Peripheral Clock Selection Definitions
58
- **********************************************************************/
59
-/** Peripheral clock divider bit position for WDT */
60
-#define	CLKPWR_PCLKSEL_WDT  		((uint32_t)(0))
61
-/** Peripheral clock divider bit position for TIMER0 */
62
-#define	CLKPWR_PCLKSEL_TIMER0  		((uint32_t)(2))
63
-/** Peripheral clock divider bit position for TIMER1 */
64
-#define	CLKPWR_PCLKSEL_TIMER1  		((uint32_t)(4))
65
-/** Peripheral clock divider bit position for UART0 */
66
-#define	CLKPWR_PCLKSEL_UART0  		((uint32_t)(6))
67
-/** Peripheral clock divider bit position for UART1 */
68
-#define	CLKPWR_PCLKSEL_UART1  		((uint32_t)(8))
69
-/** Peripheral clock divider bit position for PWM1 */
70
-#define	CLKPWR_PCLKSEL_PWM1  		((uint32_t)(12))
71
-/** Peripheral clock divider bit position for I2C0 */
72
-#define	CLKPWR_PCLKSEL_I2C0  		((uint32_t)(14))
73
-/** Peripheral clock divider bit position for SPI */
74
-#define	CLKPWR_PCLKSEL_SPI  		((uint32_t)(16))
75
-/** Peripheral clock divider bit position for SSP1 */
76
-#define	CLKPWR_PCLKSEL_SSP1  		((uint32_t)(20))
77
-/** Peripheral clock divider bit position for DAC */
78
-#define	CLKPWR_PCLKSEL_DAC  		((uint32_t)(22))
79
-/** Peripheral clock divider bit position for ADC */
80
-#define	CLKPWR_PCLKSEL_ADC  		((uint32_t)(24))
81
-/** Peripheral clock divider bit position for CAN1 */
82
-#define	CLKPWR_PCLKSEL_CAN1 		((uint32_t)(26))
83
-/** Peripheral clock divider bit position for CAN2 */
84
-#define	CLKPWR_PCLKSEL_CAN2 		((uint32_t)(28))
85
-/** Peripheral clock divider bit position for ACF */
86
-#define	CLKPWR_PCLKSEL_ACF  		((uint32_t)(30))
87
-/** Peripheral clock divider bit position for QEI */
88
-#define	CLKPWR_PCLKSEL_QEI  		((uint32_t)(32))
89
-/** Peripheral clock divider bit position for PCB */
90
-#define	CLKPWR_PCLKSEL_PCB  		((uint32_t)(36))
91
-/** Peripheral clock divider bit position for  I2C1 */
92
-#define	CLKPWR_PCLKSEL_I2C1  		((uint32_t)(38))
93
-/** Peripheral clock divider bit position for SSP0 */
94
-#define	CLKPWR_PCLKSEL_SSP0  		((uint32_t)(42))
95
-/** Peripheral clock divider bit position for TIMER2 */
96
-#define	CLKPWR_PCLKSEL_TIMER2  		((uint32_t)(44))
97
-/** Peripheral clock divider bit position for  TIMER3 */
98
-#define	CLKPWR_PCLKSEL_TIMER3  		((uint32_t)(46))
99
-/** Peripheral clock divider bit position for UART2 */
100
-#define	CLKPWR_PCLKSEL_UART2  		((uint32_t)(48))
101
-/** Peripheral clock divider bit position for UART3 */
102
-#define	CLKPWR_PCLKSEL_UART3  		((uint32_t)(50))
103
-/** Peripheral clock divider bit position for I2C2 */
104
-#define	CLKPWR_PCLKSEL_I2C2  		((uint32_t)(52))
105
-/** Peripheral clock divider bit position for I2S */
106
-#define	CLKPWR_PCLKSEL_I2S  		((uint32_t)(54))
107
-/** Peripheral clock divider bit position for RIT */
108
-#define	CLKPWR_PCLKSEL_RIT  		((uint32_t)(58))
109
-/** Peripheral clock divider bit position for SYSCON */
110
-#define	CLKPWR_PCLKSEL_SYSCON  		((uint32_t)(60))
111
-/** Peripheral clock divider bit position for MC */
112
-#define	CLKPWR_PCLKSEL_MC  			((uint32_t)(62))
113
-
114
-/** Macro for Peripheral Clock Selection register bit values
115
- * Note: When CCLK_DIV_8, Peripheral�s clock is selected to
116
- * PCLK_xyz = CCLK/8 except for CAN1, CAN2, and CAN filtering
117
- * when �11�selects PCLK_xyz = CCLK/6 */
118
-/* Peripheral clock divider is set to 4 from CCLK */
119
-#define	CLKPWR_PCLKSEL_CCLK_DIV_4  ((uint32_t)(0))
120
-/** Peripheral clock divider is the same with CCLK */
121
-#define	CLKPWR_PCLKSEL_CCLK_DIV_1  ((uint32_t)(1))
122
-/** Peripheral clock divider is set to 2 from CCLK */
123
-#define	CLKPWR_PCLKSEL_CCLK_DIV_2  ((uint32_t)(2))
124
-
125
-
126
-/********************************************************************
127
-* Power Control for Peripherals Definitions
128
-**********************************************************************/
129
-/** Timer/Counter 0 power/clock control bit */
130
-#define	 CLKPWR_PCONP_PCTIM0	((uint32_t)(1<<1))
131
-/* Timer/Counter 1 power/clock control bit */
132
-#define	 CLKPWR_PCONP_PCTIM1	((uint32_t)(1<<2))
133
-/** UART0 power/clock control bit */
134
-#define	 CLKPWR_PCONP_PCUART0  	((uint32_t)(1<<3))
135
-/** UART1 power/clock control bit */
136
-#define	 CLKPWR_PCONP_PCUART1  	((uint32_t)(1<<4))
137
-/** PWM1 power/clock control bit */
138
-#define	 CLKPWR_PCONP_PCPWM1	((uint32_t)(1<<6))
139
-/** The I2C0 interface power/clock control bit */
140
-#define	 CLKPWR_PCONP_PCI2C0	((uint32_t)(1<<7))
141
-/** The SPI interface power/clock control bit */
142
-#define	 CLKPWR_PCONP_PCSPI  	((uint32_t)(1<<8))
143
-/** The RTC power/clock control bit */
144
-#define	 CLKPWR_PCONP_PCRTC  	((uint32_t)(1<<9))
145
-/** The SSP1 interface power/clock control bit */
146
-#define	 CLKPWR_PCONP_PCSSP1	((uint32_t)(1<<10))
147
-/** A/D converter 0 (ADC0) power/clock control bit */
148
-#define	 CLKPWR_PCONP_PCAD  	((uint32_t)(1<<12))
149
-/** CAN Controller 1 power/clock control bit */
150
-#define	 CLKPWR_PCONP_PCAN1  	((uint32_t)(1<<13))
151
-/** CAN Controller 2 power/clock control bit */
152
-#define	 CLKPWR_PCONP_PCAN2 	((uint32_t)(1<<14))
153
-/** GPIO power/clock control bit */
154
-#define	CLKPWR_PCONP_PCGPIO 	((uint32_t)(1<<15))
155
-/** Repetitive Interrupt Timer power/clock control bit */
156
-#define	CLKPWR_PCONP_PCRIT 		((uint32_t)(1<<16))
157
-/** Motor Control PWM */
158
-#define CLKPWR_PCONP_PCMC 		((uint32_t)(1<<17))
159
-/** Quadrature Encoder Interface power/clock control bit */
160
-#define CLKPWR_PCONP_PCQEI 		((uint32_t)(1<<18))
161
-/** The I2C1 interface power/clock control bit */
162
-#define	 CLKPWR_PCONP_PCI2C1  	((uint32_t)(1<<19))
163
-/** The SSP0 interface power/clock control bit */
164
-#define	 CLKPWR_PCONP_PCSSP0	((uint32_t)(1<<21))
165
-/** Timer 2 power/clock control bit */
166
-#define	 CLKPWR_PCONP_PCTIM2	((uint32_t)(1<<22))
167
-/** Timer 3 power/clock control bit */
168
-#define	 CLKPWR_PCONP_PCTIM3	((uint32_t)(1<<23))
169
-/** UART 2 power/clock control bit */
170
-#define	 CLKPWR_PCONP_PCUART2  	((uint32_t)(1<<24))
171
-/** UART 3 power/clock control bit */
172
-#define	 CLKPWR_PCONP_PCUART3  	((uint32_t)(1<<25))
173
-/** I2C interface 2 power/clock control bit */
174
-#define	 CLKPWR_PCONP_PCI2C2	((uint32_t)(1<<26))
175
-/** I2S interface power/clock control bit*/
176
-#define	 CLKPWR_PCONP_PCI2S  	((uint32_t)(1<<27))
177
-/** GP DMA function power/clock control bit*/
178
-#define	 CLKPWR_PCONP_PCGPDMA  	((uint32_t)(1<<29))
179
-/** Ethernet block power/clock control bit*/
180
-#define	 CLKPWR_PCONP_PCENET	((uint32_t)(1<<30))
181
-/** USB interface power/clock control bit*/
182
-#define	 CLKPWR_PCONP_PCUSB  	((uint32_t)(1<<31))
183
-
184
-
185
-/**
186
- * @}
187
- */
188
-/* Private Macros ------------------------------------------------------------- */
189
-/** @defgroup CLKPWR_Private_Macros CLKPWR Private Macros
190
- * @{
191
- */
192
-
193
-/* --------------------- BIT DEFINITIONS -------------------------------------- */
194
-/*********************************************************************//**
195
- * Macro defines for Clock Source Select Register
196
- **********************************************************************/
197
-/** Internal RC oscillator */
198
-#define CLKPWR_CLKSRCSEL_CLKSRC_IRC			((uint32_t)(0x00))
199
-/** Main oscillator */
200
-#define CLKPWR_CLKSRCSEL_CLKSRC_MAINOSC		((uint32_t)(0x01))
201
-/** RTC oscillator */
202
-#define CLKPWR_CLKSRCSEL_CLKSRC_RTC			((uint32_t)(0x02))
203
-/** Clock source selection bit mask */
204
-#define CLKPWR_CLKSRCSEL_BITMASK			((uint32_t)(0x03))
205
-
206
-/*********************************************************************//**
207
- * Macro defines for Clock Output Configuration Register
208
- **********************************************************************/
209
-/* Clock Output Configuration register definition */
210
-/** Selects the CPU clock as the CLKOUT source */
211
-#define CLKPWR_CLKOUTCFG_CLKOUTSEL_CPU		((uint32_t)(0x00))
212
-/** Selects the main oscillator as the CLKOUT source */
213
-#define CLKPWR_CLKOUTCFG_CLKOUTSEL_MAINOSC	((uint32_t)(0x01))
214
-/** Selects the Internal RC oscillator as the CLKOUT source */
215
-#define CLKPWR_CLKOUTCFG_CLKOUTSEL_RC		((uint32_t)(0x02))
216
-/** Selects the USB clock as the CLKOUT source */
217
-#define CLKPWR_CLKOUTCFG_CLKOUTSEL_USB		((uint32_t)(0x03))
218
-/** Selects the RTC oscillator as the CLKOUT source */
219
-#define CLKPWR_CLKOUTCFG_CLKOUTSEL_RTC		((uint32_t)(0x04))
220
-/** Integer value to divide the output clock by, minus one */
221
-#define CLKPWR_CLKOUTCFG_CLKOUTDIV(n)		((uint32_t)((n&0x0F)<<4))
222
-/** CLKOUT enable control */
223
-#define CLKPWR_CLKOUTCFG_CLKOUT_EN			((uint32_t)(1<<8))
224
-/** CLKOUT activity indication */
225
-#define CLKPWR_CLKOUTCFG_CLKOUT_ACT			((uint32_t)(1<<9))
226
-/** Clock source selection bit mask */
227
-#define CLKPWR_CLKOUTCFG_BITMASK			((uint32_t)(0x3FF))
228
-
229
-/*********************************************************************//**
230
- * Macro defines for PPL0 Control Register
231
- **********************************************************************/
232
-/** PLL 0 control enable */
233
-#define CLKPWR_PLL0CON_ENABLE		((uint32_t)(0x01))
234
-/** PLL 0 control connect */
235
-#define CLKPWR_PLL0CON_CONNECT		((uint32_t)(0x02))
236
-/** PLL 0 control bit mask */
237
-#define CLKPWR_PLL0CON_BITMASK		((uint32_t)(0x03))
238
-
239
-/*********************************************************************//**
240
- * Macro defines for PPL0 Configuration Register
241
- **********************************************************************/
242
-/** PLL 0 Configuration MSEL field */
243
-#define CLKPWR_PLL0CFG_MSEL(n)		((uint32_t)(n&0x7FFF))
244
-/** PLL 0 Configuration NSEL field */
245
-#define CLKPWR_PLL0CFG_NSEL(n)		((uint32_t)((n<<16)&0xFF0000))
246
-/** PLL 0 Configuration bit mask */
247
-#define CLKPWR_PLL0CFG_BITMASK		((uint32_t)(0xFF7FFF))
248
-
249
-
250
-/*********************************************************************//**
251
- * Macro defines for PPL0 Status Register
252
- **********************************************************************/
253
-/** PLL 0 MSEL value */
254
-#define CLKPWR_PLL0STAT_MSEL(n)		((uint32_t)(n&0x7FFF))
255
-/** PLL NSEL get value  */
256
-#define CLKPWR_PLL0STAT_NSEL(n)		((uint32_t)((n>>16)&0xFF))
257
-/** PLL status enable bit */
258
-#define CLKPWR_PLL0STAT_PLLE		((uint32_t)(1<<24))
259
-/** PLL status Connect bit */
260
-#define CLKPWR_PLL0STAT_PLLC		((uint32_t)(1<<25))
261
-/** PLL status lock */
262
-#define CLKPWR_PLL0STAT_PLOCK		((uint32_t)(1<<26))
263
-
264
-/*********************************************************************//**
265
- * Macro defines for PPL0 Feed Register
266
- **********************************************************************/
267
-/** PLL0 Feed bit mask */
268
-#define CLKPWR_PLL0FEED_BITMASK			((uint32_t)0xFF)
269
-
270
-/*********************************************************************//**
271
- * Macro defines for PLL1 Control Register
272
- **********************************************************************/
273
-/** USB PLL control enable */
274
-#define CLKPWR_PLL1CON_ENABLE		((uint32_t)(0x01))
275
-/** USB PLL control connect */
276
-#define CLKPWR_PLL1CON_CONNECT		((uint32_t)(0x02))
277
-/** USB PLL control bit mask */
278
-#define CLKPWR_PLL1CON_BITMASK		((uint32_t)(0x03))
279
-
280
-/*********************************************************************//**
281
- * Macro defines for PLL1 Configuration Register
282
- **********************************************************************/
283
-/** USB PLL MSEL set value */
284
-#define CLKPWR_PLL1CFG_MSEL(n)		((uint32_t)(n&0x1F))
285
-/** USB PLL PSEL set value */
286
-#define CLKPWR_PLL1CFG_PSEL(n)		((uint32_t)((n&0x03)<<5))
287
-/** USB PLL configuration bit mask */
288
-#define CLKPWR_PLL1CFG_BITMASK		((uint32_t)(0x7F))
289
-
290
-/*********************************************************************//**
291
- * Macro defines for PLL1 Status Register
292
- **********************************************************************/
293
-/** USB PLL MSEL get value  */
294
-#define CLKPWR_PLL1STAT_MSEL(n)		((uint32_t)(n&0x1F))
295
-/** USB PLL PSEL get value  */
296
-#define CLKPWR_PLL1STAT_PSEL(n)		((uint32_t)((n>>5)&0x03))
297
-/** USB PLL status enable bit */
298
-#define CLKPWR_PLL1STAT_PLLE		((uint32_t)(1<<8))
299
-/** USB PLL status Connect bit */
300
-#define CLKPWR_PLL1STAT_PLLC		((uint32_t)(1<<9))
301
-/** USB PLL status lock */
302
-#define CLKPWR_PLL1STAT_PLOCK		((uint32_t)(1<<10))
303
-
304
-/*********************************************************************//**
305
- * Macro defines for PLL1 Feed Register
306
- **********************************************************************/
307
-/** PLL1 Feed bit mask */
308
-#define CLKPWR_PLL1FEED_BITMASK		((uint32_t)0xFF)
309
-
310
-/*********************************************************************//**
311
- * Macro defines for CPU Clock Configuration Register
312
- **********************************************************************/
313
-/** CPU Clock configuration bit mask */
314
-#define CLKPWR_CCLKCFG_BITMASK		((uint32_t)(0xFF))
315
-
316
-/*********************************************************************//**
317
- * Macro defines for USB Clock Configuration Register
318
- **********************************************************************/
319
-/** USB Clock Configuration bit mask */
320
-#define CLKPWR_USBCLKCFG_BITMASK	((uint32_t)(0x0F))
321
-
322
-/*********************************************************************//**
323
- * Macro defines for IRC Trim Register
324
- **********************************************************************/
325
-/** IRC Trim bit mask */
326
-#define CLKPWR_IRCTRIM_BITMASK		((uint32_t)(0x0F))
327
-
328
-/*********************************************************************//**
329
- * Macro defines for Peripheral Clock Selection Register 0 and 1
330
- **********************************************************************/
331
-/** Peripheral Clock Selection 0 mask bit */
332
-#define CLKPWR_PCLKSEL0_BITMASK		((uint32_t)(0xFFF3F3FF))
333
-/** Peripheral Clock Selection 1 mask bit */
334
-#define CLKPWR_PCLKSEL1_BITMASK		((uint32_t)(0xFCF3F0F3))
335
-/** Macro to set peripheral clock of each type
336
- * p: position of two bits that hold divider of peripheral clock
337
- * n: value of divider of peripheral clock  to be set */
338
-#define CLKPWR_PCLKSEL_SET(p,n)		_SBF(p,n)
339
-/** Macro to mask peripheral clock of each type */
340
-#define CLKPWR_PCLKSEL_BITMASK(p)	_SBF(p,0x03)
341
-/** Macro to get peripheral clock of each type */
342
-#define CLKPWR_PCLKSEL_GET(p, n)	((uint32_t)((n>>p)&0x03))
343
-
344
-/*********************************************************************//**
345
- * Macro defines for Power Mode Control Register
346
- **********************************************************************/
347
-/** Power mode control bit 0 */
348
-#define CLKPWR_PCON_PM0			((uint32_t)(1<<0))
349
-/** Power mode control bit 1 */
350
-#define CLKPWR_PCON_PM1			((uint32_t)(1<<1))
351
-/** Brown-Out Reduced Power Mode */
352
-#define CLKPWR_PCON_BODPDM		((uint32_t)(1<<2))
353
-/** Brown-Out Global Disable */
354
-#define CLKPWR_PCON_BOGD		((uint32_t)(1<<3))
355
-/** Brown Out Reset Disable */
356
-#define CLKPWR_PCON_BORD		((uint32_t)(1<<4))
357
-/** Sleep Mode entry flag */
358
-#define CLKPWR_PCON_SMFLAG		((uint32_t)(1<<8))
359
-/** Deep Sleep entry flag */
360
-#define CLKPWR_PCON_DSFLAG		((uint32_t)(1<<9))
361
-/** Power-down entry flag */
362
-#define CLKPWR_PCON_PDFLAG		((uint32_t)(1<<10))
363
-/** Deep Power-down entry flag */
364
-#define CLKPWR_PCON_DPDFLAG		((uint32_t)(1<<11))
365
-
366
-/*********************************************************************//**
367
- * Macro defines for Power Control for Peripheral Register
368
- **********************************************************************/
369
-/** Power Control for Peripherals bit mask */
370
-#define CLKPWR_PCONP_BITMASK	0xEFEFF7DE
371
-
372
-/**
373
- * @}
374
- */
375
-
376
-
377
-/* Public Functions ----------------------------------------------------------- */
378
-/** @defgroup CLKPWR_Public_Functions CLKPWR Public Functions
379
- * @{
380
- */
381
-
382
-void CLKPWR_SetPCLKDiv (uint32_t ClkType, uint32_t DivVal);
383
-uint32_t CLKPWR_GetPCLKSEL (uint32_t ClkType);
384
-uint32_t CLKPWR_GetPCLK (uint32_t ClkType);
385
-void CLKPWR_ConfigPPWR (uint32_t PPType, FunctionalState NewState);
386
-void CLKPWR_Sleep(void);
387
-void CLKPWR_DeepSleep(void);
388
-void CLKPWR_PowerDown(void);
389
-void CLKPWR_DeepPowerDown(void);
390
-
391
-/**
392
- * @}
393
- */
394
-
395
-
396
-#ifdef __cplusplus
397
-}
398
-#endif
399
-
400
-#endif /* LPC17XX_CLKPWR_H_ */
401
-
402
-/**
403
- * @}
404
- */
405
-
406
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 154
frameworks/CMSIS/LPC1768/include/lpc17xx_dac.h Просмотреть файл

@@ -1,154 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_dac.h				2010-05-21
3
-*//**
4
-* @file		lpc17xx_dac.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for Clock and Power Control firmware library on LPC17xx
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @defgroup DAC DAC (Digital-to-Analog Controller)
35
- * @ingroup LPC1700CMSIS_FwLib_Drivers
36
- * @{
37
- */
38
-
39
-#ifndef LPC17XX_DAC_H_
40
-#define LPC17XX_DAC_H_
41
-
42
-/* Includes ------------------------------------------------------------------- */
43
-#include "LPC17xx.h"
44
-#include "lpc_types.h"
45
-
46
-
47
-#ifdef __cplusplus
48
-extern "C"
49
-{
50
-#endif
51
-
52
-/* Public Macros -------------------------------------------------------------- */
53
-/** @defgroup DAC_Private_Macros DAC Private Macros
54
- * @{
55
- */
56
-
57
-/** After the selected settling time after this field is written with a
58
-new VALUE, the voltage on the AOUT pin (with respect to VSSA)
59
-is VALUE/1024 × VREF */
60
-#define DAC_VALUE(n) 		((uint32_t)((n&0x3FF)<<6))
61
-/** If this bit = 0: The settling time of the DAC is 1 microsecond max,
62
- * and the maximum current is 700 microAmpere
63
- * If this bit = 1: The settling time of the DAC is 2.5 microsecond
64
- * and the maximum current is 350 microAmpere */
65
-#define DAC_BIAS_EN			((uint32_t)(1<<16))
66
-/** Value to reload interrupt DMA counter */
67
-#define DAC_CCNT_VALUE(n)  ((uint32_t)(n&0xffff))
68
-
69
-/** DCAR double buffering */
70
-#define DAC_DBLBUF_ENA		((uint32_t)(1<<1))
71
-/** DCAR Time out count enable */
72
-#define DAC_CNT_ENA			((uint32_t)(1<<2))
73
-/** DCAR DMA access */
74
-#define DAC_DMA_ENA			((uint32_t)(1<<3))
75
-/** DCAR DACCTRL mask bit */
76
-#define DAC_DACCTRL_MASK	((uint32_t)(0x0F))
77
-
78
-/** Macro to determine if it is valid DAC peripheral */
79
-#define PARAM_DACx(n)	(((uint32_t *)n)==((uint32_t *)LPC_DAC))
80
-
81
-/** Macro to check DAC current optional parameter */
82
-#define	PARAM_DAC_CURRENT_OPT(OPTION) ((OPTION == DAC_MAX_CURRENT_700uA)\
83
-||(OPTION == DAC_MAX_CURRENT_350uA))
84
-/**
85
- * @}
86
- */
87
-/* Public Types --------------------------------------------------------------- */
88
-/** @defgroup DAC_Public_Types DAC Public Types
89
- * @{
90
- */
91
-
92
-/**
93
- * @brief Current option in DAC configuration option */
94
-typedef enum
95
-{
96
-	DAC_MAX_CURRENT_700uA = 0, 	/*!< The settling time of the DAC is 1 us max,
97
-								and the maximum	current is 700 uA */
98
-	DAC_MAX_CURRENT_350uA		/*!< The settling time of the DAC is 2.5 us
99
-								and the maximum current is 350 uA */
100
-} DAC_CURRENT_OPT;
101
-
102
-/**
103
- * @brief Configuration for DAC converter control register */
104
-typedef struct
105
-{
106
-
107
-	uint8_t  DBLBUF_ENA; 	/**<
108
-	                         -0: Disable DACR double buffering
109
-	                         -1: when bit CNT_ENA, enable DACR double buffering feature
110
-							 */
111
-	uint8_t  CNT_ENA;		/*!<
112
-	                         -0: Time out counter is disable
113
-	                         -1: Time out conter is enable
114
-							 */
115
-	uint8_t  DMA_ENA;		/*!<
116
-		                         -0: DMA access is disable
117
-		                         -1: DMA burst request
118
-							*/
119
-	uint8_t RESERVED;
120
-
121
-} DAC_CONVERTER_CFG_Type;
122
-
123
-/**
124
- * @}
125
- */
126
-
127
-/* Public Functions ----------------------------------------------------------- */
128
-/** @defgroup DAC_Public_Functions DAC Public Functions
129
- * @{
130
- */
131
-
132
-void 	DAC_Init(LPC_DAC_TypeDef *DACx);
133
-void    DAC_UpdateValue (LPC_DAC_TypeDef *DACx, uint32_t dac_value);
134
-void    DAC_SetBias (LPC_DAC_TypeDef *DACx,uint32_t bias);
135
-void    DAC_ConfigDAConverterControl (LPC_DAC_TypeDef *DACx,DAC_CONVERTER_CFG_Type *DAC_ConverterConfigStruct);
136
-void 	DAC_SetDMATimeOut(LPC_DAC_TypeDef *DACx,uint32_t time_out);
137
-
138
-/**
139
- * @}
140
- */
141
-
142
-#ifdef __cplusplus
143
-}
144
-#endif
145
-
146
-
147
-#endif /* LPC17XX_DAC_H_ */
148
-
149
-/**
150
- * @}
151
- */
152
-
153
-/* --------------------------------- End Of File ------------------------------ */
154
-

+ 0
- 711
frameworks/CMSIS/LPC1768/include/lpc17xx_emac.h Просмотреть файл

@@ -1,711 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_emac.h				2010-05-21
3
-*//**
4
-* @file		lpc17xx_emac.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for Ethernet MAC firmware library on LPC17xx
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @defgroup EMAC EMAC (Ethernet Media Access Controller)
35
- * @ingroup LPC1700CMSIS_FwLib_Drivers
36
- * @{
37
- */
38
-
39
-#ifndef LPC17XX_EMAC_H_
40
-#define LPC17XX_EMAC_H_
41
-
42
-/* Includes ------------------------------------------------------------------- */
43
-#include "LPC17xx.h"
44
-#include "lpc_types.h"
45
-
46
-
47
-#ifdef __cplusplus
48
-extern "C"
49
-{
50
-#endif
51
-
52
-#define MCB_LPC_1768
53
-//#define IAR_LPC_1768
54
-
55
-/* Public Macros -------------------------------------------------------------- */
56
-/** @defgroup EMAC_Public_Macros EMAC Public Macros
57
- * @{
58
- */
59
-
60
-
61
-/* EMAC PHY status type definitions */
62
-#define EMAC_PHY_STAT_LINK			(0)		/**< Link Status */
63
-#define EMAC_PHY_STAT_SPEED			(1)		/**< Speed Status */
64
-#define EMAC_PHY_STAT_DUP			(2)		/**< Duplex Status */
65
-
66
-/* EMAC PHY device Speed definitions */
67
-#define EMAC_MODE_AUTO				(0)		/**< Auto-negotiation mode */
68
-#define EMAC_MODE_10M_FULL			(1)		/**< 10Mbps FullDuplex mode */
69
-#define EMAC_MODE_10M_HALF			(2)		/**< 10Mbps HalfDuplex mode */
70
-#define EMAC_MODE_100M_FULL			(3)		/**< 100Mbps FullDuplex mode */
71
-#define EMAC_MODE_100M_HALF			(4)		/**< 100Mbps HalfDuplex mode */
72
-
73
-/**
74
- * @}
75
- */
76
-/* Private Macros ------------------------------------------------------------- */
77
-/** @defgroup EMAC_Private_Macros EMAC Private Macros
78
- * @{
79
- */
80
-
81
-
82
-/* EMAC Memory Buffer configuration for 16K Ethernet RAM */
83
-#define EMAC_NUM_RX_FRAG         4           /**< Num.of RX Fragments 4*1536= 6.0kB */
84
-#define EMAC_NUM_TX_FRAG         3           /**< Num.of TX Fragments 3*1536= 4.6kB */
85
-#define EMAC_ETH_MAX_FLEN        1536        /**< Max. Ethernet Frame Size          */
86
-#define EMAC_TX_FRAME_TOUT       0x00100000  /**< Frame Transmit timeout count      */
87
-
88
-/* --------------------- BIT DEFINITIONS -------------------------------------- */
89
-/*********************************************************************//**
90
- * Macro defines for MAC Configuration Register 1
91
- **********************************************************************/
92
-#define EMAC_MAC1_REC_EN         0x00000001  /**< Receive Enable                    */
93
-#define EMAC_MAC1_PASS_ALL       0x00000002  /**< Pass All Receive Frames           */
94
-#define EMAC_MAC1_RX_FLOWC       0x00000004  /**< RX Flow Control                   */
95
-#define EMAC_MAC1_TX_FLOWC       0x00000008  /**< TX Flow Control                   */
96
-#define EMAC_MAC1_LOOPB          0x00000010  /**< Loop Back Mode                    */
97
-#define EMAC_MAC1_RES_TX         0x00000100  /**< Reset TX Logic                    */
98
-#define EMAC_MAC1_RES_MCS_TX     0x00000200  /**< Reset MAC TX Control Sublayer     */
99
-#define EMAC_MAC1_RES_RX         0x00000400  /**< Reset RX Logic                    */
100
-#define EMAC_MAC1_RES_MCS_RX     0x00000800  /**< Reset MAC RX Control Sublayer     */
101
-#define EMAC_MAC1_SIM_RES        0x00004000  /**< Simulation Reset                  */
102
-#define EMAC_MAC1_SOFT_RES       0x00008000  /**< Soft Reset MAC                    */
103
-
104
-/*********************************************************************//**
105
- * Macro defines for MAC Configuration Register 2
106
- **********************************************************************/
107
-#define EMAC_MAC2_FULL_DUP       0x00000001  /**< Full-Duplex Mode                  */
108
-#define EMAC_MAC2_FRM_LEN_CHK    0x00000002  /**< Frame Length Checking             */
109
-#define EMAC_MAC2_HUGE_FRM_EN    0x00000004  /**< Huge Frame Enable                 */
110
-#define EMAC_MAC2_DLY_CRC        0x00000008  /**< Delayed CRC Mode                  */
111
-#define EMAC_MAC2_CRC_EN         0x00000010  /**< Append CRC to every Frame         */
112
-#define EMAC_MAC2_PAD_EN         0x00000020  /**< Pad all Short Frames              */
113
-#define EMAC_MAC2_VLAN_PAD_EN    0x00000040  /**< VLAN Pad Enable                   */
114
-#define EMAC_MAC2_ADET_PAD_EN    0x00000080  /**< Auto Detect Pad Enable            */
115
-#define EMAC_MAC2_PPREAM_ENF     0x00000100  /**< Pure Preamble Enforcement         */
116
-#define EMAC_MAC2_LPREAM_ENF     0x00000200  /**< Long Preamble Enforcement         */
117
-#define EMAC_MAC2_NO_BACKOFF     0x00001000  /**< No Backoff Algorithm              */
118
-#define EMAC_MAC2_BACK_PRESSURE  0x00002000  /**< Backoff Presurre / No Backoff     */
119
-#define EMAC_MAC2_EXCESS_DEF     0x00004000  /**< Excess Defer                      */
120
-
121
-/*********************************************************************//**
122
- * Macro defines for Back-to-Back Inter-Packet-Gap Register
123
- **********************************************************************/
124
-/** Programmable field representing the nibble time offset of the minimum possible period
125
- * between the end of any transmitted packet to the beginning of the next */
126
-#define EMAC_IPGT_BBIPG(n)		(n&0x7F)
127
-/** Recommended value for Full Duplex of Programmable field representing the nibble time
128
- * offset of the minimum possible period between the end of any transmitted packet to the
129
- * beginning of the next */
130
-#define EMAC_IPGT_FULL_DUP		(EMAC_IPGT_BBIPG(0x15))
131
-/** Recommended value for Half Duplex of Programmable field representing the nibble time
132
- * offset of the minimum possible period between the end of any transmitted packet to the
133
- * beginning of the next */
134
-#define EMAC_IPGT_HALF_DUP      (EMAC_IPGT_BBIPG(0x12))
135
-
136
-/*********************************************************************//**
137
- * Macro defines for Non Back-to-Back Inter-Packet-Gap Register
138
- **********************************************************************/
139
-/** Programmable field representing the Non-Back-to-Back Inter-Packet-Gap */
140
-#define EMAC_IPGR_NBBIPG_P2(n)	(n&0x7F)
141
-/** Recommended value for Programmable field representing the Non-Back-to-Back Inter-Packet-Gap Part 1 */
142
-#define EMAC_IPGR_P2_DEF		(EMAC_IPGR_NBBIPG_P2(0x12))
143
-/** Programmable field representing the optional carrierSense window referenced in
144
- * IEEE 802.3/4.2.3.2.1 'Carrier Deference' */
145
-#define EMAC_IPGR_NBBIPG_P1(n)	((n&0x7F)<<8)
146
-/** Recommended value for Programmable field representing the Non-Back-to-Back Inter-Packet-Gap Part 2 */
147
-#define EMAC_IPGR_P1_DEF        EMAC_IPGR_NBBIPG_P1(0x0C)
148
-
149
-/*********************************************************************//**
150
- * Macro defines for Collision Window/Retry Register
151
- **********************************************************************/
152
-/** Programmable field specifying the number of retransmission attempts following a collision before
153
- * aborting the packet due to excessive collisions */
154
-#define EMAC_CLRT_MAX_RETX(n)	(n&0x0F)
155
-/** Programmable field representing the slot time or collision window during which collisions occur
156
- * in properly configured networks */
157
-#define EMAC_CLRT_COLL(n)		((n&0x3F)<<8)
158
-/** Default value for Collision Window / Retry register */
159
-#define EMAC_CLRT_DEF           ((EMAC_CLRT_MAX_RETX(0x0F))|(EMAC_CLRT_COLL(0x37)))
160
-
161
-/*********************************************************************//**
162
- * Macro defines for Maximum Frame Register
163
- **********************************************************************/
164
-/** Represents a maximum receive frame of 1536 octets */
165
-#define EMAC_MAXF_MAXFRMLEN(n)	(n&0xFFFF)
166
-
167
-/*********************************************************************//**
168
- * Macro defines for PHY Support Register
169
- **********************************************************************/
170
-#define EMAC_SUPP_SPEED			0x00000100  	/**< Reduced MII Logic Current Speed   */
171
-//#define EMAC_SUPP_RES_RMII      0x00000800  	/**< Reset Reduced MII Logic           */
172
-
173
-/*********************************************************************//**
174
- * Macro defines for Test Register
175
- **********************************************************************/
176
-#define EMAC_TEST_SHCUT_PQUANTA  0x00000001  	/**< Shortcut Pause Quanta             */
177
-#define EMAC_TEST_TST_PAUSE      0x00000002  	/**< Test Pause                        */
178
-#define EMAC_TEST_TST_BACKP      0x00000004  	/**< Test Back Pressure                */
179
-
180
-/*********************************************************************//**
181
- * Macro defines for MII Management Configuration Register
182
- **********************************************************************/
183
-#define EMAC_MCFG_SCAN_INC       0x00000001  	/**< Scan Increment PHY Address        */
184
-#define EMAC_MCFG_SUPP_PREAM     0x00000002  	/**< Suppress Preamble                 */
185
-#define EMAC_MCFG_CLK_SEL(n)     ((n&0x0F)<<2)  /**< Clock Select Field                 */
186
-#define EMAC_MCFG_RES_MII        0x00008000  	/**< Reset MII Management Hardware     */
187
-#define EMAC_MCFG_MII_MAXCLK	 2500000UL		/**< MII Clock max */
188
-
189
-/*********************************************************************//**
190
- * Macro defines for MII Management Command Register
191
- **********************************************************************/
192
-#define EMAC_MCMD_READ           0x00000001  	/**< MII Read                          */
193
-#define EMAC_MCMD_SCAN           0x00000002  	/**< MII Scan continuously             */
194
-
195
-#define EMAC_MII_WR_TOUT         0x00050000  	/**< MII Write timeout count           */
196
-#define EMAC_MII_RD_TOUT         0x00050000  	/**< MII Read timeout count            */
197
-
198
-/*********************************************************************//**
199
- * Macro defines for MII Management Address Register
200
- **********************************************************************/
201
-#define EMAC_MADR_REG_ADR(n)     (n&0x1F)  		/**< MII Register Address field         */
202
-#define EMAC_MADR_PHY_ADR(n)     ((n&0x1F)<<8)  /**< PHY Address Field                  */
203
-
204
-/*********************************************************************//**
205
- * Macro defines for MII Management Write Data Register
206
- **********************************************************************/
207
-#define EMAC_MWTD_DATA(n)		(n&0xFFFF)		/**< Data field for MMI Management Write Data register */
208
-
209
-/*********************************************************************//**
210
- * Macro defines for MII Management Read Data Register
211
- **********************************************************************/
212
-#define EMAC_MRDD_DATA(n)		(n&0xFFFF)		/**< Data field for MMI Management Read Data register */
213
-
214
-/*********************************************************************//**
215
- * Macro defines for MII Management Indicators Register
216
- **********************************************************************/
217
-#define EMAC_MIND_BUSY           0x00000001  	/**< MII is Busy                       */
218
-#define EMAC_MIND_SCAN           0x00000002  	/**< MII Scanning in Progress          */
219
-#define EMAC_MIND_NOT_VAL        0x00000004  	/**< MII Read Data not valid           */
220
-#define EMAC_MIND_MII_LINK_FAIL  0x00000008  	/**< MII Link Failed                   */
221
-
222
-/* Station Address 0 Register */
223
-/* Station Address 1 Register */
224
-/* Station Address 2 Register */
225
-
226
-
227
-/* Control register definitions --------------------------------------------------------------------------- */
228
-/*********************************************************************//**
229
- * Macro defines for Command Register
230
- **********************************************************************/
231
-#define EMAC_CR_RX_EN            0x00000001  	/**< Enable Receive                    */
232
-#define EMAC_CR_TX_EN            0x00000002  	/**< Enable Transmit                   */
233
-#define EMAC_CR_REG_RES          0x00000008  	/**< Reset Host Registers              */
234
-#define EMAC_CR_TX_RES           0x00000010  	/**< Reset Transmit Datapath           */
235
-#define EMAC_CR_RX_RES           0x00000020  	/**< Reset Receive Datapath            */
236
-#define EMAC_CR_PASS_RUNT_FRM    0x00000040  	/**< Pass Runt Frames                  */
237
-#define EMAC_CR_PASS_RX_FILT     0x00000080  	/**< Pass RX Filter                    */
238
-#define EMAC_CR_TX_FLOW_CTRL     0x00000100  	/**< TX Flow Control                   */
239
-#define EMAC_CR_RMII             0x00000200  	/**< Reduced MII Interface             */
240
-#define EMAC_CR_FULL_DUP         0x00000400  	/**< Full Duplex                       */
241
-
242
-/*********************************************************************//**
243
- * Macro defines for Status Register
244
- **********************************************************************/
245
-#define EMAC_SR_RX_EN            0x00000001  	/**< Enable Receive                    */
246
-#define EMAC_SR_TX_EN            0x00000002  	/**< Enable Transmit                   */
247
-
248
-/*********************************************************************//**
249
- * Macro defines for Transmit Status Vector 0 Register
250
- **********************************************************************/
251
-#define EMAC_TSV0_CRC_ERR        0x00000001  /**< CRC error                         */
252
-#define EMAC_TSV0_LEN_CHKERR     0x00000002  /**< Length Check Error                */
253
-#define EMAC_TSV0_LEN_OUTRNG     0x00000004  /**< Length Out of Range               */
254
-#define EMAC_TSV0_DONE           0x00000008  /**< Tramsmission Completed            */
255
-#define EMAC_TSV0_MCAST          0x00000010  /**< Multicast Destination             */
256
-#define EMAC_TSV0_BCAST          0x00000020  /**< Broadcast Destination             */
257
-#define EMAC_TSV0_PKT_DEFER      0x00000040  /**< Packet Deferred                   */
258
-#define EMAC_TSV0_EXC_DEFER      0x00000080  /**< Excessive Packet Deferral         */
259
-#define EMAC_TSV0_EXC_COLL       0x00000100  /**< Excessive Collision               */
260
-#define EMAC_TSV0_LATE_COLL      0x00000200  /**< Late Collision Occured            */
261
-#define EMAC_TSV0_GIANT          0x00000400  /**< Giant Frame                       */
262
-#define EMAC_TSV0_UNDERRUN       0x00000800  /**< Buffer Underrun                   */
263
-#define EMAC_TSV0_BYTES          0x0FFFF000  /**< Total Bytes Transferred           */
264
-#define EMAC_TSV0_CTRL_FRAME     0x10000000  /**< Control Frame                     */
265
-#define EMAC_TSV0_PAUSE          0x20000000  /**< Pause Frame                       */
266
-#define EMAC_TSV0_BACK_PRESS     0x40000000  /**< Backpressure Method Applied       */
267
-#define EMAC_TSV0_VLAN           0x80000000  /**< VLAN Frame                        */
268
-
269
-/*********************************************************************//**
270
- * Macro defines for Transmit Status Vector 1 Register
271
- **********************************************************************/
272
-#define EMAC_TSV1_BYTE_CNT       0x0000FFFF  /**< Transmit Byte Count               */
273
-#define EMAC_TSV1_COLL_CNT       0x000F0000  /**< Transmit Collision Count          */
274
-
275
-/*********************************************************************//**
276
- * Macro defines for Receive Status Vector Register
277
- **********************************************************************/
278
-#define EMAC_RSV_BYTE_CNT        0x0000FFFF  /**< Receive Byte Count                */
279
-#define EMAC_RSV_PKT_IGNORED     0x00010000  /**< Packet Previously Ignored         */
280
-#define EMAC_RSV_RXDV_SEEN       0x00020000  /**< RXDV Event Previously Seen        */
281
-#define EMAC_RSV_CARR_SEEN       0x00040000  /**< Carrier Event Previously Seen     */
282
-#define EMAC_RSV_REC_CODEV       0x00080000  /**< Receive Code Violation            */
283
-#define EMAC_RSV_CRC_ERR         0x00100000  /**< CRC Error                         */
284
-#define EMAC_RSV_LEN_CHKERR      0x00200000  /**< Length Check Error                */
285
-#define EMAC_RSV_LEN_OUTRNG      0x00400000  /**< Length Out of Range               */
286
-#define EMAC_RSV_REC_OK          0x00800000  /**< Frame Received OK                 */
287
-#define EMAC_RSV_MCAST           0x01000000  /**< Multicast Frame                   */
288
-#define EMAC_RSV_BCAST           0x02000000  /**< Broadcast Frame                   */
289
-#define EMAC_RSV_DRIB_NIBB       0x04000000  /**< Dribble Nibble                    */
290
-#define EMAC_RSV_CTRL_FRAME      0x08000000  /**< Control Frame                     */
291
-#define EMAC_RSV_PAUSE           0x10000000  /**< Pause Frame                       */
292
-#define EMAC_RSV_UNSUPP_OPC      0x20000000  /**< Unsupported Opcode                */
293
-#define EMAC_RSV_VLAN            0x40000000  /**< VLAN Frame                        */
294
-
295
-/*********************************************************************//**
296
- * Macro defines for Flow Control Counter Register
297
- **********************************************************************/
298
-#define EMAC_FCC_MIRR_CNT(n)        	(n&0xFFFF)  		/**< Mirror Counter                    */
299
-#define EMAC_FCC_PAUSE_TIM(n)       	((n&0xFFFF)<<16)  	/**< Pause Timer                       */
300
-
301
-/*********************************************************************//**
302
- * Macro defines for Flow Control Status Register
303
- **********************************************************************/
304
-#define EMAC_FCS_MIRR_CNT(n)        	(n&0xFFFF)  		/**< Mirror Counter Current            */
305
-
306
-
307
-/* Receive filter register definitions -------------------------------------------------------- */
308
-/*********************************************************************//**
309
- * Macro defines for Receive Filter Control Register
310
- **********************************************************************/
311
-#define EMAC_RFC_UCAST_EN        0x00000001  /**< Accept Unicast Frames Enable      */
312
-#define EMAC_RFC_BCAST_EN        0x00000002  /**< Accept Broadcast Frames Enable    */
313
-#define EMAC_RFC_MCAST_EN        0x00000004  /**< Accept Multicast Frames Enable    */
314
-#define EMAC_RFC_UCAST_HASH_EN   0x00000008  /**< Accept Unicast Hash Filter Frames */
315
-#define EMAC_RFC_MCAST_HASH_EN   0x00000010  /**< Accept Multicast Hash Filter Fram.*/
316
-#define EMAC_RFC_PERFECT_EN      0x00000020  /**< Accept Perfect Match Enable       */
317
-#define EMAC_RFC_MAGP_WOL_EN     0x00001000  /**< Magic Packet Filter WoL Enable    */
318
-#define EMAC_RFC_PFILT_WOL_EN    0x00002000  /**< Perfect Filter WoL Enable         */
319
-
320
-/*********************************************************************//**
321
- * Macro defines for Receive Filter WoL Status/Clear Registers
322
- **********************************************************************/
323
-#define EMAC_WOL_UCAST           0x00000001  /**< Unicast Frame caused WoL          */
324
-#define EMAC_WOL_BCAST           0x00000002  /**< Broadcast Frame caused WoL        */
325
-#define EMAC_WOL_MCAST           0x00000004  /**< Multicast Frame caused WoL        */
326
-#define EMAC_WOL_UCAST_HASH      0x00000008  /**< Unicast Hash Filter Frame WoL     */
327
-#define EMAC_WOL_MCAST_HASH      0x00000010  /**< Multicast Hash Filter Frame WoL   */
328
-#define EMAC_WOL_PERFECT         0x00000020  /**< Perfect Filter WoL                */
329
-#define EMAC_WOL_RX_FILTER       0x00000080  /**< RX Filter caused WoL              */
330
-#define EMAC_WOL_MAG_PACKET      0x00000100  /**< Magic Packet Filter caused WoL    */
331
-#define EMAC_WOL_BITMASK		 0x01BF		/**< Receive Filter WoL Status/Clear bitmasl value */
332
-
333
-
334
-/* Module control register definitions ---------------------------------------------------- */
335
-/*********************************************************************//**
336
- * Macro defines for Interrupt Status/Enable/Clear/Set Registers
337
- **********************************************************************/
338
-#define EMAC_INT_RX_OVERRUN      0x00000001  /**< Overrun Error in RX Queue         */
339
-#define EMAC_INT_RX_ERR          0x00000002  /**< Receive Error                     */
340
-#define EMAC_INT_RX_FIN          0x00000004  /**< RX Finished Process Descriptors   */
341
-#define EMAC_INT_RX_DONE         0x00000008  /**< Receive Done                      */
342
-#define EMAC_INT_TX_UNDERRUN     0x00000010  /**< Transmit Underrun                 */
343
-#define EMAC_INT_TX_ERR          0x00000020  /**< Transmit Error                    */
344
-#define EMAC_INT_TX_FIN          0x00000040  /**< TX Finished Process Descriptors   */
345
-#define EMAC_INT_TX_DONE         0x00000080  /**< Transmit Done                     */
346
-#define EMAC_INT_SOFT_INT        0x00001000  /**< Software Triggered Interrupt      */
347
-#define EMAC_INT_WAKEUP          0x00002000  /**< Wakeup Event Interrupt            */
348
-
349
-/*********************************************************************//**
350
- * Macro defines for Power Down Register
351
- **********************************************************************/
352
-#define EMAC_PD_POWER_DOWN       0x80000000  /**< Power Down MAC                    */
353
-
354
-/* Descriptor and status formats ---------------------------------------------------- */
355
-/*********************************************************************//**
356
- * Macro defines for RX Descriptor Control Word
357
- **********************************************************************/
358
-#define EMAC_RCTRL_SIZE(n)       (n&0x7FF)  	/**< Buffer size field                  */
359
-#define EMAC_RCTRL_INT           0x80000000  	/**< Generate RxDone Interrupt         */
360
-
361
-/*********************************************************************//**
362
- * Macro defines for RX Status Hash CRC Word
363
- **********************************************************************/
364
-#define EMAC_RHASH_SA            0x000001FF  	/**< Hash CRC for Source Address       */
365
-#define EMAC_RHASH_DA            0x001FF000  	/**< Hash CRC for Destination Address  */
366
-
367
-/*********************************************************************//**
368
- * Macro defines for RX Status Information Word
369
- **********************************************************************/
370
-#define EMAC_RINFO_SIZE          0x000007FF  /**< Data size in bytes                */
371
-#define EMAC_RINFO_CTRL_FRAME    0x00040000  /**< Control Frame                     */
372
-#define EMAC_RINFO_VLAN          0x00080000  /**< VLAN Frame                        */
373
-#define EMAC_RINFO_FAIL_FILT     0x00100000  /**< RX Filter Failed                  */
374
-#define EMAC_RINFO_MCAST         0x00200000  /**< Multicast Frame                   */
375
-#define EMAC_RINFO_BCAST         0x00400000  /**< Broadcast Frame                   */
376
-#define EMAC_RINFO_CRC_ERR       0x00800000  /**< CRC Error in Frame                */
377
-#define EMAC_RINFO_SYM_ERR       0x01000000  /**< Symbol Error from PHY             */
378
-#define EMAC_RINFO_LEN_ERR       0x02000000  /**< Length Error                      */
379
-#define EMAC_RINFO_RANGE_ERR     0x04000000  /**< Range Error (exceeded max. size)  */
380
-#define EMAC_RINFO_ALIGN_ERR     0x08000000  /**< Alignment Error                   */
381
-#define EMAC_RINFO_OVERRUN       0x10000000  /**< Receive overrun                   */
382
-#define EMAC_RINFO_NO_DESCR      0x20000000  /**< No new Descriptor available       */
383
-#define EMAC_RINFO_LAST_FLAG     0x40000000  /**< Last Fragment in Frame            */
384
-#define EMAC_RINFO_ERR           0x80000000  /**< Error Occured (OR of all errors)  */
385
-#define EMAC_RINFO_ERR_MASK     (EMAC_RINFO_FAIL_FILT | EMAC_RINFO_CRC_ERR   | EMAC_RINFO_SYM_ERR | \
386
-EMAC_RINFO_LEN_ERR   | EMAC_RINFO_ALIGN_ERR | EMAC_RINFO_OVERRUN)
387
-
388
-/*********************************************************************//**
389
- * Macro defines for TX Descriptor Control Word
390
- **********************************************************************/
391
-#define EMAC_TCTRL_SIZE          0x000007FF  /**< Size of data buffer in bytes      */
392
-#define EMAC_TCTRL_OVERRIDE      0x04000000  /**< Override Default MAC Registers    */
393
-#define EMAC_TCTRL_HUGE          0x08000000  /**< Enable Huge Frame                 */
394
-#define EMAC_TCTRL_PAD           0x10000000  /**< Pad short Frames to 64 bytes      */
395
-#define EMAC_TCTRL_CRC           0x20000000  /**< Append a hardware CRC to Frame    */
396
-#define EMAC_TCTRL_LAST          0x40000000  /**< Last Descriptor for TX Frame      */
397
-#define EMAC_TCTRL_INT           0x80000000  /**< Generate TxDone Interrupt         */
398
-
399
-/*********************************************************************//**
400
- * Macro defines for TX Status Information Word
401
- **********************************************************************/
402
-#define EMAC_TINFO_COL_CNT       0x01E00000  /**< Collision Count                   */
403
-#define EMAC_TINFO_DEFER         0x02000000  /**< Packet Deferred (not an error)    */
404
-#define EMAC_TINFO_EXCESS_DEF    0x04000000  /**< Excessive Deferral                */
405
-#define EMAC_TINFO_EXCESS_COL    0x08000000  /**< Excessive Collision               */
406
-#define EMAC_TINFO_LATE_COL      0x10000000  /**< Late Collision Occured            */
407
-#define EMAC_TINFO_UNDERRUN      0x20000000  /**< Transmit Underrun                 */
408
-#define EMAC_TINFO_NO_DESCR      0x40000000  /**< No new Descriptor available       */
409
-#define EMAC_TINFO_ERR           0x80000000  /**< Error Occured (OR of all errors)  */
410
-
411
-#ifdef MCB_LPC_1768
412
-/* DP83848C PHY definition ------------------------------------------------------------ */
413
-
414
-/** PHY device reset time out definition */
415
-#define EMAC_PHY_RESP_TOUT		0x100000UL
416
-
417
-/* ENET Device Revision ID */
418
-#define EMAC_OLD_EMAC_MODULE_ID  0x39022000  /**< Rev. ID for first rev '-'         */
419
-
420
-/*********************************************************************//**
421
- * Macro defines for DP83848C PHY Registers
422
- **********************************************************************/
423
-#define EMAC_PHY_REG_BMCR        0x00        /**< Basic Mode Control Register       */
424
-#define EMAC_PHY_REG_BMSR        0x01        /**< Basic Mode Status Register        */
425
-#define EMAC_PHY_REG_IDR1        0x02        /**< PHY Identifier 1                  */
426
-#define EMAC_PHY_REG_IDR2        0x03        /**< PHY Identifier 2                  */
427
-#define EMAC_PHY_REG_ANAR        0x04        /**< Auto-Negotiation Advertisement    */
428
-#define EMAC_PHY_REG_ANLPAR      0x05        /**< Auto-Neg. Link Partner Abitily    */
429
-#define EMAC_PHY_REG_ANER        0x06        /**< Auto-Neg. Expansion Register      */
430
-#define EMAC_PHY_REG_ANNPTR      0x07        /**< Auto-Neg. Next Page TX            */
431
-#define EMAC_PHY_REG_LPNPA		 0x08
432
-
433
-/*********************************************************************//**
434
- * Macro defines for PHY Extended Registers
435
- **********************************************************************/
436
-#define EMAC_PHY_REG_STS         0x10        /**< Status Register                   */
437
-#define EMAC_PHY_REG_MICR        0x11        /**< MII Interrupt Control Register    */
438
-#define EMAC_PHY_REG_MISR        0x12        /**< MII Interrupt Status Register     */
439
-#define EMAC_PHY_REG_FCSCR       0x14        /**< False Carrier Sense Counter       */
440
-#define EMAC_PHY_REG_RECR        0x15        /**< Receive Error Counter             */
441
-#define EMAC_PHY_REG_PCSR        0x16        /**< PCS Sublayer Config. and Status   */
442
-#define EMAC_PHY_REG_RBR         0x17        /**< RMII and Bypass Register          */
443
-#define EMAC_PHY_REG_LEDCR       0x18        /**< LED Direct Control Register       */
444
-#define EMAC_PHY_REG_PHYCR       0x19        /**< PHY Control Register              */
445
-#define EMAC_PHY_REG_10BTSCR     0x1A        /**< 10Base-T Status/Control Register  */
446
-#define EMAC_PHY_REG_CDCTRL1     0x1B        /**< CD Test Control and BIST Extens.  */
447
-#define EMAC_PHY_REG_EDCR        0x1D        /**< Energy Detect Control Register    */
448
-
449
-/*********************************************************************//**
450
- * Macro defines for PHY Basic Mode Control Register
451
- **********************************************************************/
452
-#define EMAC_PHY_BMCR_RESET     			(1<<15)		/**< Reset bit */
453
-#define EMAC_PHY_BMCR_LOOPBACK      		(1<<14)		/**< Loop back */
454
-#define EMAC_PHY_BMCR_SPEED_SEL     		(1<<13)		/**< Speed selection */
455
-#define EMAC_PHY_BMCR_AN					(1<<12)		/**< Auto Negotiation */
456
-#define EMAC_PHY_BMCR_POWERDOWN				(1<<11)		/**< Power down mode */
457
-#define EMAC_PHY_BMCR_ISOLATE				(1<<10)		/**< Isolate */
458
-#define EMAC_PHY_BMCR_RE_AN					(1<<9)		/**< Restart auto negotiation */
459
-#define EMAC_PHY_BMCR_DUPLEX				(1<<8)		/**< Duplex mode */
460
-
461
-/*********************************************************************//**
462
- * Macro defines for PHY Basic Mode Status Status Register
463
- **********************************************************************/
464
-#define EMAC_PHY_BMSR_100BE_T4        	   	(1<<15)		/**< 100 base T4 */
465
-#define EMAC_PHY_BMSR_100TX_FULL			(1<<14)		/**< 100 base full duplex */
466
-#define EMAC_PHY_BMSR_100TX_HALF			(1<<13)		/**< 100 base half duplex */
467
-#define EMAC_PHY_BMSR_10BE_FULL				(1<<12)		/**< 10 base T full duplex */
468
-#define EMAC_PHY_BMSR_10BE_HALF				(1<<11)		/**< 10 base T half duplex */
469
-#define EMAC_PHY_BMSR_NOPREAM				(1<<6)		/**< MF Preamable Supress */
470
-#define EMAC_PHY_BMSR_AUTO_DONE				(1<<5)		/**< Auto negotiation complete */
471
-#define EMAC_PHY_BMSR_REMOTE_FAULT			(1<<4)		/**< Remote fault */
472
-#define EMAC_PHY_BMSR_NO_AUTO				(1<<3)		/**< Auto Negotiation ability */
473
-#define EMAC_PHY_BMSR_LINK_ESTABLISHED		(1<<2)		/**< Link status */
474
-
475
-/*********************************************************************//**
476
- * Macro defines for PHY Status Register
477
- **********************************************************************/
478
-#define EMAC_PHY_SR_REMOTE_FAULT   			(1<<6)		/**< Remote Fault */
479
-#define EMAC_PHY_SR_JABBER					(1<<5)		/**< Jabber detect */
480
-#define EMAC_PHY_SR_AUTO_DONE				(1<<4)		/**< Auto Negotiation complete */
481
-#define EMAC_PHY_SR_LOOPBACK				(1<<3)		/**< Loop back status */
482
-#define EMAC_PHY_SR_DUP						(1<<2)		/**< Duplex status */
483
-#define EMAC_PHY_SR_SPEED					(1<<1)		/**< Speed status */
484
-#define EMAC_PHY_SR_LINK					(1<<0)		/**< Link Status */
485
-
486
-#define EMAC_PHY_FULLD_100M      0x2100      /**< Full Duplex 100Mbit               */
487
-#define EMAC_PHY_HALFD_100M      0x2000      /**< Half Duplex 100Mbit               */
488
-#define EMAC_PHY_FULLD_10M       0x0100      /**< Full Duplex 10Mbit                */
489
-#define EMAC_PHY_HALFD_10M       0x0000      /**< Half Duplex 10MBit                */
490
-#define EMAC_PHY_AUTO_NEG        0x3000      /**< Select Auto Negotiation           */
491
-
492
-#define EMAC_DEF_ADR    0x0100      /**< Default PHY device address        */
493
-#define EMAC_DP83848C_ID         0x20005C90  /**< PHY Identifier                    */
494
-
495
-#define EMAC_PHY_SR_100_SPEED		((1<<14)|(1<<13))
496
-#define EMAC_PHY_SR_FULL_DUP		((1<<14)|(1<<12))
497
-#define EMAC_PHY_BMSR_LINK_STATUS			(1<<2)		/**< Link status */
498
-
499
-#elif defined(IAR_LPC_1768)
500
-/* KSZ8721BL PHY definition ------------------------------------------------------------ */
501
-/** PHY device reset time out definition */
502
-#define EMAC_PHY_RESP_TOUT		0x100000UL
503
-
504
-/* ENET Device Revision ID */
505
-#define EMAC_OLD_EMAC_MODULE_ID  0x39022000  /**< Rev. ID for first rev '-'         */
506
-
507
-/*********************************************************************//**
508
- * Macro defines for KSZ8721BL PHY Registers
509
- **********************************************************************/
510
-#define EMAC_PHY_REG_BMCR        0x00        /**< Basic Mode Control Register       */
511
-#define EMAC_PHY_REG_BMSR        0x01        /**< Basic Mode Status Register        */
512
-#define EMAC_PHY_REG_IDR1        0x02        /**< PHY Identifier 1                  */
513
-#define EMAC_PHY_REG_IDR2        0x03        /**< PHY Identifier 2                  */
514
-#define EMAC_PHY_REG_ANAR        0x04        /**< Auto-Negotiation Advertisement    */
515
-#define EMAC_PHY_REG_ANLPAR      0x05        /**< Auto-Neg. Link Partner Abitily    */
516
-#define EMAC_PHY_REG_ANER        0x06        /**< Auto-Neg. Expansion Register      */
517
-#define EMAC_PHY_REG_ANNPTR      0x07        /**< Auto-Neg. Next Page TX            */
518
-#define EMAC_PHY_REG_LPNPA		 0x08		 /**< Link Partner Next Page Ability    */
519
-#define EMAC_PHY_REG_REC		 0x15		 /**< RXError Counter Register			*/
520
-#define EMAC_PHY_REG_ISC		 0x1b		 /**< Interrupt Control/Status Register */
521
-#define EMAC_PHY_REG_100BASE	 0x1f		 /**< 100BASE-TX PHY Control Register   */
522
-
523
-/*********************************************************************//**
524
- * Macro defines for PHY Basic Mode Control Register
525
- **********************************************************************/
526
-#define EMAC_PHY_BMCR_RESET     			(1<<15)		/**< Reset bit */
527
-#define EMAC_PHY_BMCR_LOOPBACK      		(1<<14)		/**< Loop back */
528
-#define EMAC_PHY_BMCR_SPEED_SEL     		(1<<13)		/**< Speed selection */
529
-#define EMAC_PHY_BMCR_AN					(1<<12)		/**< Auto Negotiation */
530
-#define EMAC_PHY_BMCR_POWERDOWN				(1<<11)		/**< Power down mode */
531
-#define EMAC_PHY_BMCR_ISOLATE				(1<<10)		/**< Isolate */
532
-#define EMAC_PHY_BMCR_RE_AN					(1<<9)		/**< Restart auto negotiation */
533
-#define EMAC_PHY_BMCR_DUPLEX				(1<<8)		/**< Duplex mode */
534
-#define EMAC_PHY_BMCR_COLLISION				(1<<7)		/**< Collision test */
535
-#define EMAC_PHY_BMCR_TXDIS					(1<<0)		/**< Disable transmit */
536
-
537
-/*********************************************************************//**
538
- * Macro defines for PHY Basic Mode Status Register
539
- **********************************************************************/
540
-#define EMAC_PHY_BMSR_100BE_T4        	   	(1<<15)		/**< 100 base T4 */
541
-#define EMAC_PHY_BMSR_100TX_FULL			(1<<14)		/**< 100 base full duplex */
542
-#define EMAC_PHY_BMSR_100TX_HALF			(1<<13)		/**< 100 base half duplex */
543
-#define EMAC_PHY_BMSR_10BE_FULL				(1<<12)		/**< 10 base T full duplex */
544
-#define EMAC_PHY_BMSR_10BE_HALF				(1<<11)		/**< 10 base T half duplex */
545
-#define EMAC_PHY_BMSR_NOPREAM				(1<<6)		/**< MF Preamable Supress */
546
-#define EMAC_PHY_BMSR_AUTO_DONE				(1<<5)		/**< Auto negotiation complete */
547
-#define EMAC_PHY_BMSR_REMOTE_FAULT			(1<<4)		/**< Remote fault */
548
-#define EMAC_PHY_BMSR_NO_AUTO				(1<<3)		/**< Auto Negotiation ability */
549
-#define EMAC_PHY_BMSR_LINK_STATUS			(1<<2)		/**< Link status */
550
-#define EMAC_PHY_BMSR_JABBER_DETECT			(1<<1)		/**< Jabber detect */
551
-#define EMAC_PHY_BMSR_EXTEND				(1<<0)		/**< Extended support */
552
-
553
-/*********************************************************************//**
554
- * Macro defines for PHY Identifier
555
- **********************************************************************/
556
-/* PHY Identifier 1 bitmap definitions */
557
-#define EMAC_PHY_IDR1(n)		(n & 0xFFFF)		/**< PHY ID1 Number */
558
-
559
-/* PHY Identifier 2 bitmap definitions */
560
-#define EMAC_PHY_IDR2(n)		(n & 0xFFFF)		/**< PHY ID2 Number */
561
-
562
-/*********************************************************************//**
563
- * Macro defines for Auto-Negotiation Advertisement
564
- **********************************************************************/
565
-#define EMAC_PHY_AN_NEXTPAGE					(1<<15)		/**<  Next page capable */
566
-#define EMAC_PHY_AN_REMOTE_FAULT				(1<<13)		/**< Remote Fault support */
567
-#define EMAC_PHY_AN_PAUSE						(1<<10)		/**< Pause support */
568
-#define EMAC_PHY_AN_100BASE_T4					(1<<9)		/**< T4 capable */
569
-#define EMAC_PHY_AN_100BASE_TX_FD				(1<<8)		/**< TX with Full-duplex capable */
570
-#define EMAC_PHY_AN_100BASE_TX					(1<<7)		/**< TX capable */
571
-#define EMAC_PHY_AN_10BASE_T_FD					(1<<6)		/**< 10Mbps with full-duplex capable */
572
-#define EMAC_PHY_AN_10BASE_T					(1<<5)		/**< 10Mbps capable */
573
-#define EMAC_PHY_AN_FIELD(n)					(n & 0x1F)  /**< Selector Field */
574
-
575
-#define EMAC_PHY_FULLD_100M      0x2100      /**< Full Duplex 100Mbit               */
576
-#define EMAC_PHY_HALFD_100M      0x2000      /**< Half Duplex 100Mbit               */
577
-#define EMAC_PHY_FULLD_10M       0x0100      /**< Full Duplex 10Mbit                */
578
-#define EMAC_PHY_HALFD_10M       0x0000      /**< Half Duplex 10MBit                */
579
-#define EMAC_PHY_AUTO_NEG        0x3000      /**< Select Auto Negotiation           */
580
-
581
-#define EMAC_PHY_SR_100_SPEED		((1<<14)|(1<<13))
582
-#define EMAC_PHY_SR_FULL_DUP		((1<<14)|(1<<12))
583
-
584
-#define EMAC_DEF_ADR    (0x01<<8)		/**< Default PHY device address        */
585
-#define EMAC_KSZ8721BL_ID 	((0x22 << 16) | 0x1619 ) /**< PHY Identifier */
586
-#endif
587
-
588
-/**
589
- * @}
590
- */
591
-
592
-
593
-/* Public Types --------------------------------------------------------------- */
594
-/** @defgroup EMAC_Public_Types EMAC Public Types
595
- * @{
596
- */
597
-
598
-/* Descriptor and status formats ---------------------------------------------- */
599
-
600
-/**
601
- * @brief RX Descriptor structure type definition
602
- */
603
-typedef struct {
604
-	uint32_t Packet;	/**< Receive Packet Descriptor */
605
-	uint32_t Ctrl;		/**< Receive Control Descriptor */
606
-} RX_Desc;
607
-
608
-/**
609
- * @brief RX Status structure type definition
610
- */
611
-typedef struct {
612
-	uint32_t Info;		/**< Receive Information Status */
613
-	uint32_t HashCRC;	/**< Receive Hash CRC Status */
614
-} RX_Stat;
615
-
616
-/**
617
- * @brief TX Descriptor structure type definition
618
- */
619
-typedef struct {
620
-	uint32_t Packet;	/**< Transmit Packet Descriptor */
621
-	uint32_t Ctrl;		/**< Transmit Control Descriptor */
622
-} TX_Desc;
623
-
624
-/**
625
- * @brief TX Status structure type definition
626
- */
627
-typedef struct {
628
-   uint32_t Info;		/**< Transmit Information Status */
629
-} TX_Stat;
630
-
631
-
632
-/**
633
- * @brief TX Data Buffer structure definition
634
- */
635
-typedef struct {
636
-	uint32_t ulDataLen;			/**< Data length */
637
-	uint32_t *pbDataBuf;		/**< A word-align data pointer to data buffer */
638
-} EMAC_PACKETBUF_Type;
639
-
640
-/**
641
- * @brief EMAC configuration structure definition
642
- */
643
-typedef struct {
644
-	uint32_t	Mode;						/**< Supported EMAC PHY device speed, should be one of the following:
645
-											- EMAC_MODE_AUTO
646
-											- EMAC_MODE_10M_FULL
647
-											- EMAC_MODE_10M_HALF
648
-											- EMAC_MODE_100M_FULL
649
-											- EMAC_MODE_100M_HALF
650
-											*/
651
-	uint8_t 	*pbEMAC_Addr;				/**< Pointer to EMAC Station address that contains 6-bytes
652
-											of MAC address, it must be sorted in order (bEMAC_Addr[0]..[5])
653
-											*/
654
-} EMAC_CFG_Type;
655
-
656
-
657
-/**
658
- * @}
659
- */
660
-
661
-
662
-/* Public Functions ----------------------------------------------------------- */
663
-/** @defgroup EMAC_Public_Functions EMAC Public Functions
664
- * @{
665
- */
666
-/* Init/DeInit EMAC peripheral */
667
-Status EMAC_Init(EMAC_CFG_Type *EMAC_ConfigStruct);
668
-void EMAC_DeInit(void);
669
-
670
-/* PHY functions --------------*/
671
-int32_t EMAC_CheckPHYStatus(uint32_t ulPHYState);
672
-int32_t EMAC_SetPHYMode(uint32_t ulPHYMode);
673
-int32_t EMAC_UpdatePHYStatus(void);
674
-
675
-/* Filter functions ----------*/
676
-void EMAC_SetHashFilter(uint8_t dstMAC_addr[], FunctionalState NewState);
677
-void EMAC_SetFilterMode(uint32_t ulFilterMode, FunctionalState NewState);
678
-
679
-/* EMAC Packet Buffer functions */
680
-void EMAC_WritePacketBuffer(EMAC_PACKETBUF_Type *pDataStruct);
681
-void EMAC_ReadPacketBuffer(EMAC_PACKETBUF_Type *pDataStruct);
682
-
683
-/* EMAC Interrupt functions -------*/
684
-void EMAC_IntCmd(uint32_t ulIntType, FunctionalState NewState);
685
-IntStatus EMAC_IntGetStatus(uint32_t ulIntType);
686
-
687
-/* EMAC Index functions -----------*/
688
-Bool EMAC_CheckReceiveIndex(void);
689
-Bool EMAC_CheckTransmitIndex(void);
690
-void EMAC_UpdateRxConsumeIndex(void);
691
-void EMAC_UpdateTxProduceIndex(void);
692
-
693
-FlagStatus EMAC_CheckReceiveDataStatus(uint32_t ulRxStatType);
694
-uint32_t EMAC_GetReceiveDataSize(void);
695
-FlagStatus EMAC_GetWoLStatus(uint32_t ulWoLMode);
696
-
697
-/**
698
- * @}
699
- */
700
-
701
-#ifdef __cplusplus
702
-}
703
-#endif
704
-
705
-#endif /* LPC17XX_EMAC_H_ */
706
-
707
-/**
708
- * @}
709
- */
710
-
711
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 155
frameworks/CMSIS/LPC1768/include/lpc17xx_exti.h Просмотреть файл

@@ -1,155 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_exti.h				2010-05-21
3
-*//**
4
-* @file		lpc17xx_exti.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for External interrupt firmware library on LPC17xx
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @defgroup EXTI EXTI (External Interrupt)
35
- * @ingroup LPC1700CMSIS_FwLib_Drivers
36
- * @{
37
- */
38
-
39
-#ifndef LPC17XX_EXTI_H_
40
-#define LPC17XX_EXTI_H_
41
-
42
-/* Includes ------------------------------------------------------------------- */
43
-#include "LPC17xx.h"
44
-#include "lpc_types.h"
45
-
46
-
47
-#ifdef __cplusplus
48
-extern "C"
49
-{
50
-#endif
51
-
52
-
53
-/* Private Macros ------------------------------------------------------------- */
54
-/** @defgroup EXTI_Private_Macros EXTI Private Macros
55
- * @{
56
- */
57
-/*********************************************************************//**
58
- * Macro defines for EXTI  control register
59
- **********************************************************************/
60
-#define EXTI_EINT0_BIT_MARK 	0x01
61
-#define EXTI_EINT1_BIT_MARK 	0x02
62
-#define EXTI_EINT2_BIT_MARK 	0x04
63
-#define EXTI_EINT3_BIT_MARK 	0x08
64
-
65
-/**
66
- * @}
67
- */
68
-
69
-/* Private Macros ------------------------------------------------------------- */
70
-/** @defgroup EXTI_Public_Types EXTI Public Types
71
- * @{
72
- */
73
-
74
-/**
75
- * @brief EXTI external interrupt line option
76
- */
77
-typedef enum
78
-{
79
-	EXTI_EINT0, /*!<  External interrupt 0, P2.10 */
80
-	EXTI_EINT1, /*!<  External interrupt 0, P2.11 */
81
-	EXTI_EINT2, /*!<  External interrupt 0, P2.12 */
82
-	EXTI_EINT3 	/*!<  External interrupt 0, P2.13 */
83
-} EXTI_LINE_ENUM;
84
-
85
-/**
86
- * @brief EXTI mode option
87
- */
88
-typedef enum
89
-{
90
-	EXTI_MODE_LEVEL_SENSITIVE, 	/*!< Level sensitivity is selected */
91
-	EXTI_MODE_EDGE_SENSITIVE  	/*!< Edge sensitivity is selected */
92
-} EXTI_MODE_ENUM;
93
-
94
-/**
95
- * @brief EXTI polarity option
96
- */
97
-typedef enum
98
-{
99
-	EXTI_POLARITY_LOW_ACTIVE_OR_FALLING_EDGE,	/*!< Low active or falling edge sensitive
100
-												depending on pin mode */
101
-	EXTI_POLARITY_HIGH_ACTIVE_OR_RISING_EDGE	/*!< High active or rising edge sensitive
102
-												depending on pin mode */
103
-} EXTI_POLARITY_ENUM;
104
-
105
-/**
106
- * @brief EXTI Initialize structure
107
- */
108
-typedef struct
109
-{
110
-	EXTI_LINE_ENUM EXTI_Line; /*!<Select external interrupt pin (EINT0, EINT1, EINT 2, EINT3) */
111
-
112
-	EXTI_MODE_ENUM EXTI_Mode; /*!< Choose between Level-sensitivity or Edge sensitivity */
113
-
114
-	EXTI_POLARITY_ENUM EXTI_polarity; /*!< 	If EXTI mode is level-sensitive: this element use to select low or high active level
115
-											if EXTI mode is polarity-sensitive: this element use to select falling or rising edge */
116
-
117
-}EXTI_InitTypeDef;
118
-
119
-
120
-/**
121
- * @}
122
- */
123
-
124
-
125
-/* Public Functions ----------------------------------------------------------- */
126
-/** @defgroup EXTI_Public_Functions EXTI Public Functions
127
- * @{
128
- */
129
-
130
-void EXTI_Init(void);
131
-void EXTI_DeInit(void);
132
-
133
-void EXTI_Config(EXTI_InitTypeDef *EXTICfg);
134
-void EXTI_SetMode(EXTI_LINE_ENUM EXTILine, EXTI_MODE_ENUM mode);
135
-void EXTI_SetPolarity(EXTI_LINE_ENUM EXTILine, EXTI_POLARITY_ENUM polarity);
136
-void EXTI_ClearEXTIFlag(EXTI_LINE_ENUM EXTILine);
137
-
138
-
139
-/**
140
- * @}
141
- */
142
-
143
-
144
-#ifdef __cplusplus
145
-}
146
-#endif
147
-
148
-
149
-#endif /* LPC17XX_EXTI_H_ */
150
-
151
-/**
152
- * @}
153
- */
154
-
155
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 429
frameworks/CMSIS/LPC1768/include/lpc17xx_gpdma.h Просмотреть файл

@@ -1,429 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_gpdma.h				2010-05-21
3
-*//**
4
-* @file		lpc17xx_gpdma.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for GPDMA firmware library on LPC17xx
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @defgroup GPDMA GPDMA (General Purpose Direct Memory Access)
35
- * @ingroup LPC1700CMSIS_FwLib_Drivers
36
- * @{
37
- */
38
-
39
-#ifndef LPC17XX_GPDMA_H_
40
-#define LPC17XX_GPDMA_H_
41
-
42
-/* Includes ------------------------------------------------------------------- */
43
-#include "LPC17xx.h"
44
-#include "lpc_types.h"
45
-
46
-
47
-#ifdef __cplusplus
48
-extern "C"
49
-{
50
-#endif
51
-
52
-/* Public Macros -------------------------------------------------------------- */
53
-/** @defgroup GPDMA_Public_Macros GPDMA Public Macros
54
- * @{
55
- */
56
-
57
-/** DMA Connection number definitions */
58
-#define GPDMA_CONN_SSP0_Tx 			((0UL)) 		/**< SSP0 Tx */
59
-#define GPDMA_CONN_SSP0_Rx 			((1UL)) 		/**< SSP0 Rx */
60
-#define GPDMA_CONN_SSP1_Tx 			((2UL)) 		/**< SSP1 Tx */
61
-#define GPDMA_CONN_SSP1_Rx 			((3UL)) 		/**< SSP1 Rx */
62
-#define GPDMA_CONN_ADC 				((4UL)) 		/**< ADC */
63
-#define GPDMA_CONN_I2S_Channel_0 	((5UL)) 		/**< I2S channel 0 */
64
-#define GPDMA_CONN_I2S_Channel_1 	((6UL)) 		/**< I2S channel 1 */
65
-#define GPDMA_CONN_DAC 				((7UL)) 		/**< DAC */
66
-#define GPDMA_CONN_UART0_Tx			((8UL)) 		/**< UART0 Tx */
67
-#define GPDMA_CONN_UART0_Rx			((9UL)) 		/**< UART0 Rx */
68
-#define GPDMA_CONN_UART1_Tx			((10UL)) 		/**< UART1 Tx */
69
-#define GPDMA_CONN_UART1_Rx			((11UL)) 		/**< UART1 Rx */
70
-#define GPDMA_CONN_UART2_Tx			((12UL)) 		/**< UART2 Tx */
71
-#define GPDMA_CONN_UART2_Rx			((13UL)) 		/**< UART2 Rx */
72
-#define GPDMA_CONN_UART3_Tx			((14UL)) 		/**< UART3 Tx */
73
-#define GPDMA_CONN_UART3_Rx			((15UL)) 		/**< UART3 Rx */
74
-#define GPDMA_CONN_MAT0_0 			((16UL)) 		/**< MAT0.0 */
75
-#define GPDMA_CONN_MAT0_1 			((17UL)) 		/**< MAT0.1 */
76
-#define GPDMA_CONN_MAT1_0 			((18UL)) 		/**< MAT1.0 */
77
-#define GPDMA_CONN_MAT1_1   		((19UL)) 		/**< MAT1.1 */
78
-#define GPDMA_CONN_MAT2_0   		((20UL)) 		/**< MAT2.0 */
79
-#define GPDMA_CONN_MAT2_1   		((21UL)) 		/**< MAT2.1 */
80
-#define GPDMA_CONN_MAT3_0 			((22UL)) 		/**< MAT3.0 */
81
-#define GPDMA_CONN_MAT3_1   		((23UL)) 		/**< MAT3.1 */
82
-
83
-/** GPDMA Transfer type definitions */
84
-#define GPDMA_TRANSFERTYPE_M2M 		((0UL)) 	/**< Memory to memory - DMA control */
85
-#define GPDMA_TRANSFERTYPE_M2P 		((1UL)) 	/**< Memory to peripheral - DMA control */
86
-#define GPDMA_TRANSFERTYPE_P2M 		((2UL)) 	/**< Peripheral to memory - DMA control */
87
-#define GPDMA_TRANSFERTYPE_P2P 		((3UL)) 	/**< Source peripheral to destination peripheral - DMA control */
88
-
89
-/** Burst size in Source and Destination definitions */
90
-#define GPDMA_BSIZE_1 	((0UL)) /**< Burst size = 1 */
91
-#define GPDMA_BSIZE_4 	((1UL)) /**< Burst size = 4 */
92
-#define GPDMA_BSIZE_8 	((2UL)) /**< Burst size = 8 */
93
-#define GPDMA_BSIZE_16 	((3UL)) /**< Burst size = 16 */
94
-#define GPDMA_BSIZE_32 	((4UL)) /**< Burst size = 32 */
95
-#define GPDMA_BSIZE_64 	((5UL)) /**< Burst size = 64 */
96
-#define GPDMA_BSIZE_128 ((6UL)) /**< Burst size = 128 */
97
-#define GPDMA_BSIZE_256 ((7UL)) /**< Burst size = 256 */
98
-
99
-/** Width in Source transfer width and Destination transfer width definitions */
100
-#define GPDMA_WIDTH_BYTE 		((0UL)) /**< Width = 1 byte */
101
-#define GPDMA_WIDTH_HALFWORD 	((1UL)) /**< Width = 2 bytes */
102
-#define GPDMA_WIDTH_WORD 		((2UL)) /**< Width = 4 bytes */
103
-
104
-/** DMA Request Select Mode definitions */
105
-#define GPDMA_REQSEL_UART 	((0UL)) /**< UART TX/RX is selected */
106
-#define GPDMA_REQSEL_TIMER 	((1UL)) /**< Timer match is selected */
107
-
108
-/**
109
- * @}
110
- */
111
-
112
-
113
-/* Private Macros ------------------------------------------------------------- */
114
-/** @defgroup GPDMA_Private_Macros GPDMA Private Macros
115
- * @{
116
- */
117
-
118
-/* --------------------- BIT DEFINITIONS -------------------------------------- */
119
-/*********************************************************************//**
120
- * Macro defines for DMA Interrupt Status register
121
- **********************************************************************/
122
-#define GPDMA_DMACIntStat_Ch(n)			(((1UL<<n)&0xFF))
123
-#define GPDMA_DMACIntStat_BITMASK		((0xFF))
124
-
125
-/*********************************************************************//**
126
- * Macro defines for DMA Interrupt Terminal Count Request Status register
127
- **********************************************************************/
128
-#define GPDMA_DMACIntTCStat_Ch(n)		(((1UL<<n)&0xFF))
129
-#define GPDMA_DMACIntTCStat_BITMASK		((0xFF))
130
-
131
-/*********************************************************************//**
132
- * Macro defines for DMA Interrupt Terminal Count Request Clear register
133
- **********************************************************************/
134
-#define GPDMA_DMACIntTCClear_Ch(n)		(((1UL<<n)&0xFF))
135
-#define GPDMA_DMACIntTCClear_BITMASK	((0xFF))
136
-
137
-/*********************************************************************//**
138
- * Macro defines for DMA Interrupt Error Status register
139
- **********************************************************************/
140
-#define GPDMA_DMACIntErrStat_Ch(n)		(((1UL<<n)&0xFF))
141
-#define GPDMA_DMACIntErrStat_BITMASK	((0xFF))
142
-
143
-/*********************************************************************//**
144
- * Macro defines for DMA Interrupt Error Clear register
145
- **********************************************************************/
146
-#define GPDMA_DMACIntErrClr_Ch(n)		(((1UL<<n)&0xFF))
147
-#define GPDMA_DMACIntErrClr_BITMASK		((0xFF))
148
-
149
-/*********************************************************************//**
150
- * Macro defines for DMA Raw Interrupt Terminal Count Status register
151
- **********************************************************************/
152
-#define GPDMA_DMACRawIntTCStat_Ch(n)	(((1UL<<n)&0xFF))
153
-#define GPDMA_DMACRawIntTCStat_BITMASK	((0xFF))
154
-
155
-/*********************************************************************//**
156
- * Macro defines for DMA Raw Error Interrupt Status register
157
- **********************************************************************/
158
-#define GPDMA_DMACRawIntErrStat_Ch(n)	(((1UL<<n)&0xFF))
159
-#define GPDMA_DMACRawIntErrStat_BITMASK	((0xFF))
160
-
161
-/*********************************************************************//**
162
- * Macro defines for DMA Enabled Channel register
163
- **********************************************************************/
164
-#define GPDMA_DMACEnbldChns_Ch(n)		(((1UL<<n)&0xFF))
165
-#define GPDMA_DMACEnbldChns_BITMASK		((0xFF))
166
-
167
-/*********************************************************************//**
168
- * Macro defines for DMA Software Burst Request register
169
- **********************************************************************/
170
-#define	GPDMA_DMACSoftBReq_Src(n)		(((1UL<<n)&0xFFFF))
171
-#define GPDMA_DMACSoftBReq_BITMASK		((0xFFFF))
172
-
173
-/*********************************************************************//**
174
- * Macro defines for DMA Software Single Request register
175
- **********************************************************************/
176
-#define GPDMA_DMACSoftSReq_Src(n) 		(((1UL<<n)&0xFFFF))
177
-#define GPDMA_DMACSoftSReq_BITMASK		((0xFFFF))
178
-
179
-/*********************************************************************//**
180
- * Macro defines for DMA Software Last Burst Request register
181
- **********************************************************************/
182
-#define GPDMA_DMACSoftLBReq_Src(n)		(((1UL<<n)&0xFFFF))
183
-#define GPDMA_DMACSoftLBReq_BITMASK		((0xFFFF))
184
-
185
-/*********************************************************************//**
186
- * Macro defines for DMA Software Last Single Request register
187
- **********************************************************************/
188
-#define GPDMA_DMACSoftLSReq_Src(n) 		(((1UL<<n)&0xFFFF))
189
-#define GPDMA_DMACSoftLSReq_BITMASK		((0xFFFF))
190
-
191
-/*********************************************************************//**
192
- * Macro defines for DMA Configuration register
193
- **********************************************************************/
194
-#define GPDMA_DMACConfig_E				((0x01))	 /**< DMA Controller enable*/
195
-#define GPDMA_DMACConfig_M				((0x02))	 /**< AHB Master endianness configuration*/
196
-#define GPDMA_DMACConfig_BITMASK		((0x03))
197
-
198
-/*********************************************************************//**
199
- * Macro defines for DMA Synchronization register
200
- **********************************************************************/
201
-#define GPDMA_DMACSync_Src(n)			(((1UL<<n)&0xFFFF))
202
-#define GPDMA_DMACSync_BITMASK			((0xFFFF))
203
-
204
-/*********************************************************************//**
205
- * Macro defines for DMA Request Select register
206
- **********************************************************************/
207
-#define GPDMA_DMAReqSel_Input(n)		(((1UL<<(n-8))&0xFF))
208
-#define GPDMA_DMAReqSel_BITMASK			((0xFF))
209
-
210
-/*********************************************************************//**
211
- * Macro defines for DMA Channel Linked List Item registers
212
- **********************************************************************/
213
-/** DMA Channel Linked List Item registers bit mask*/
214
-#define GPDMA_DMACCxLLI_BITMASK 		((0xFFFFFFFC))
215
-
216
-/*********************************************************************//**
217
- * Macro defines for DMA channel control registers
218
- **********************************************************************/
219
-#define GPDMA_DMACCxControl_TransferSize(n) (((n&0xFFF)<<0)) 	/**< Transfer size*/
220
-#define GPDMA_DMACCxControl_SBSize(n)		(((n&0x07)<<12)) 	/**< Source burst size*/
221
-#define GPDMA_DMACCxControl_DBSize(n)		(((n&0x07)<<15)) 	/**< Destination burst size*/
222
-#define GPDMA_DMACCxControl_SWidth(n)		(((n&0x07)<<18)) 	/**< Source transfer width*/
223
-#define GPDMA_DMACCxControl_DWidth(n)		(((n&0x07)<<21)) 	/**< Destination transfer width*/
224
-#define GPDMA_DMACCxControl_SI				((1UL<<26)) 		/**< Source increment*/
225
-#define GPDMA_DMACCxControl_DI				((1UL<<27)) 		/**< Destination increment*/
226
-#define GPDMA_DMACCxControl_Prot1			((1UL<<28)) 		/**< Indicates that the access is in user mode or privileged mode*/
227
-#define GPDMA_DMACCxControl_Prot2			((1UL<<29)) 		/**< Indicates that the access is bufferable or not bufferable*/
228
-#define GPDMA_DMACCxControl_Prot3			((1UL<<30)) 		/**< Indicates that the access is cacheable or not cacheable*/
229
-#define GPDMA_DMACCxControl_I				((1UL<<31)) 		/**< Terminal count interrupt enable bit */
230
-/** DMA channel control registers bit mask */
231
-#define GPDMA_DMACCxControl_BITMASK			((0xFCFFFFFF))
232
-
233
-/*********************************************************************//**
234
- * Macro defines for DMA Channel Configuration registers
235
- **********************************************************************/
236
-#define GPDMA_DMACCxConfig_E 					((1UL<<0))			/**< DMA control enable*/
237
-#define GPDMA_DMACCxConfig_SrcPeripheral(n) 	(((n&0x1F)<<1)) 	/**< Source peripheral*/
238
-#define GPDMA_DMACCxConfig_DestPeripheral(n) 	(((n&0x1F)<<6)) 	/**< Destination peripheral*/
239
-#define GPDMA_DMACCxConfig_TransferType(n) 		(((n&0x7)<<11)) 	/**< This value indicates the type of transfer*/
240
-#define GPDMA_DMACCxConfig_IE 					((1UL<<14))			/**< Interrupt error mask*/
241
-#define GPDMA_DMACCxConfig_ITC 					((1UL<<15)) 		/**< Terminal count interrupt mask*/
242
-#define GPDMA_DMACCxConfig_L 					((1UL<<16)) 		/**< Lock*/
243
-#define GPDMA_DMACCxConfig_A 					((1UL<<17)) 		/**< Active*/
244
-#define GPDMA_DMACCxConfig_H 					((1UL<<18)) 		/**< Halt*/
245
-/** DMA Channel Configuration registers bit mask */
246
-#define GPDMA_DMACCxConfig_BITMASK				((0x7FFFF))
247
-
248
-/* ---------------- CHECK PARAMETER DEFINITIONS ---------------------------- */
249
-/* Macros check GPDMA channel */
250
-#define PARAM_GPDMA_CHANNEL(n)	(n<=7)
251
-
252
-/* Macros check GPDMA connection type */
253
-#define PARAM_GPDMA_CONN(n)		((n==GPDMA_CONN_SSP0_Tx) || (n==GPDMA_CONN_SSP0_Rx) \
254
-|| (n==GPDMA_CONN_SSP1_Tx) || (n==GPDMA_CONN_SSP1_Rx) \
255
-|| (n==GPDMA_CONN_ADC) || (n==GPDMA_CONN_I2S_Channel_0) \
256
-|| (n==GPDMA_CONN_I2S_Channel_1) || (n==GPDMA_CONN_DAC) \
257
-|| (n==GPDMA_CONN_UART0_Tx) || (n==GPDMA_CONN_UART0_Rx) \
258
-|| (n==GPDMA_CONN_UART1_Tx) || (n==GPDMA_CONN_UART1_Rx) \
259
-|| (n==GPDMA_CONN_UART2_Tx) || (n==GPDMA_CONN_UART2_Rx) \
260
-|| (n==GPDMA_CONN_UART3_Tx) || (n==GPDMA_CONN_UART3_Rx) \
261
-|| (n==GPDMA_CONN_MAT0_0) || (n==GPDMA_CONN_MAT0_1) \
262
-|| (n==GPDMA_CONN_MAT1_0) || (n==GPDMA_CONN_MAT1_1) \
263
-|| (n==GPDMA_CONN_MAT2_0) || (n==GPDMA_CONN_MAT2_1) \
264
-|| (n==GPDMA_CONN_MAT3_0) || (n==GPDMA_CONN_MAT3_1))
265
-
266
-/* Macros check GPDMA burst size type */
267
-#define PARAM_GPDMA_BSIZE(n)	((n==GPDMA_BSIZE_1) || (n==GPDMA_BSIZE_4) \
268
-|| (n==GPDMA_BSIZE_8) || (n==GPDMA_BSIZE_16) \
269
-|| (n==GPDMA_BSIZE_32) || (n==GPDMA_BSIZE_64) \
270
-|| (n==GPDMA_BSIZE_128) || (n==GPDMA_BSIZE_256))
271
-
272
-/* Macros check GPDMA width type */
273
-#define PARAM_GPDMA_WIDTH(n) ((n==GPDMA_WIDTH_BYTE) || (n==GPDMA_WIDTH_HALFWORD) \
274
-|| (n==GPDMA_WIDTH_WORD))
275
-
276
-/* Macros check GPDMA status type */
277
-#define PARAM_GPDMA_STAT(n)	((n==GPDMA_STAT_INT) || (n==GPDMA_STAT_INTTC) \
278
-|| (n==GPDMA_STAT_INTERR) || (n==GPDMA_STAT_RAWINTTC) \
279
-|| (n==GPDMA_STAT_RAWINTERR) || (n==GPDMA_STAT_ENABLED_CH))
280
-
281
-/* Macros check GPDMA transfer type */
282
-#define PARAM_GPDMA_TRANSFERTYPE(n) ((n==GPDMA_TRANSFERTYPE_M2M)||(n==GPDMA_TRANSFERTYPE_M2P) \
283
-||(n==GPDMA_TRANSFERTYPE_P2M)||(n==GPDMA_TRANSFERTYPE_P2P))
284
-
285
-/* Macros check GPDMA state clear type */
286
-#define PARAM_GPDMA_STATCLR(n)	((n==GPDMA_STATCLR_INTTC) || (n==GPDMA_STATCLR_INTERR))
287
-
288
-/* Macros check GPDMA request select type */
289
-#define PARAM_GPDMA_REQSEL(n)	((n==GPDMA_REQSEL_UART) || (n==GPDMA_REQSEL_TIMER))
290
-/**
291
- * @}
292
- */
293
-
294
-
295
-/* Public Types --------------------------------------------------------------- */
296
-/** @defgroup GPDMA_Public_Types GPDMA Public Types
297
- * @{
298
- */
299
-
300
-/**
301
- * @brief GPDMA Status enumeration
302
- */
303
-typedef enum {
304
-	GPDMA_STAT_INT,			/**< GPDMA Interrupt Status */
305
-	GPDMA_STAT_INTTC,		/**< GPDMA Interrupt Terminal Count Request Status */
306
-	GPDMA_STAT_INTERR,		/**< GPDMA Interrupt Error Status */
307
-	GPDMA_STAT_RAWINTTC,	/**< GPDMA Raw Interrupt Terminal Count Status */
308
-	GPDMA_STAT_RAWINTERR,	/**< GPDMA Raw Error Interrupt Status */
309
-	GPDMA_STAT_ENABLED_CH	/**< GPDMA Enabled Channel Status */
310
-} GPDMA_Status_Type;
311
-
312
-/**
313
- * @brief GPDMA Interrupt clear status enumeration
314
- */
315
-typedef enum{
316
-	GPDMA_STATCLR_INTTC,	/**< GPDMA Interrupt Terminal Count Request Clear */
317
-	GPDMA_STATCLR_INTERR	/**< GPDMA Interrupt Error Clear */
318
-}GPDMA_StateClear_Type;
319
-
320
-/**
321
- * @brief GPDMA Channel configuration structure type definition
322
- */
323
-typedef struct {
324
-	uint32_t ChannelNum; 	/**< DMA channel number, should be in
325
-								range from 0 to 7.
326
-								Note: DMA channel 0 has the highest priority
327
-								and DMA channel 7 the lowest priority.
328
-								*/
329
-	uint32_t TransferSize;	/**< Length/Size of transfer */
330
-	uint32_t TransferWidth;	/**< Transfer width - used for TransferType is GPDMA_TRANSFERTYPE_M2M only */
331
-	uint32_t SrcMemAddr;	/**< Physical Source Address, used in case TransferType is chosen as
332
-								 GPDMA_TRANSFERTYPE_M2M or GPDMA_TRANSFERTYPE_M2P */
333
-	uint32_t DstMemAddr;	/**< Physical Destination Address, used in case TransferType is chosen as
334
-								 GPDMA_TRANSFERTYPE_M2M or GPDMA_TRANSFERTYPE_P2M */
335
-	uint32_t TransferType;	/**< Transfer Type, should be one of the following:
336
-							- GPDMA_TRANSFERTYPE_M2M: Memory to memory - DMA control
337
-							- GPDMA_TRANSFERTYPE_M2P: Memory to peripheral - DMA control
338
-							- GPDMA_TRANSFERTYPE_P2M: Peripheral to memory - DMA control
339
-							- GPDMA_TRANSFERTYPE_P2P: Source peripheral to destination peripheral - DMA control
340
-							*/
341
-	uint32_t SrcConn;		/**< Peripheral Source Connection type, used in case TransferType is chosen as
342
-							GPDMA_TRANSFERTYPE_P2M or GPDMA_TRANSFERTYPE_P2P, should be one of
343
-							following:
344
-							 - GPDMA_CONN_SSP0_Tx: SSP0, Tx
345
-							 - GPDMA_CONN_SSP0_Rx: SSP0, Rx
346
-							 - GPDMA_CONN_SSP1_Tx: SSP1, Tx
347
-							 - GPDMA_CONN_SSP1_Rx: SSP1, Rx
348
-							 - GPDMA_CONN_ADC: ADC
349
-							 - GPDMA_CONN_I2S_Channel_0: I2S Channel 0
350
-							 - GPDMA_CONN_I2S_Channel_1: I2S Channel 1
351
-							 - GPDMA_CONN_DAC: DAC
352
-							 - GPDMA_CONN_UART0_Tx_MAT0_0: UART0 Tx / MAT0.0
353
-							 - GPDMA_CONN_UART0_Rx_MAT0_1: UART0 Rx / MAT0.1
354
-							 - GPDMA_CONN_UART1_Tx_MAT1_0: UART1 Tx / MAT1.0
355
-							 - GPDMA_CONN_UART1_Rx_MAT1_1: UART1 Rx / MAT1.1
356
-							 - GPDMA_CONN_UART2_Tx_MAT2_0: UART2 Tx / MAT2.0
357
-							 - GPDMA_CONN_UART2_Rx_MAT2_1: UART2 Rx / MAT2.1
358
-							 - GPDMA_CONN_UART3_Tx_MAT3_0: UART3 Tx / MAT3.0
359
-							 - GPDMA_CONN_UART3_Rx_MAT3_1: UART3 Rx / MAT3.1
360
-							 */
361
-	uint32_t DstConn;		/**< Peripheral Destination Connection type, used in case TransferType is chosen as
362
-							GPDMA_TRANSFERTYPE_M2P or GPDMA_TRANSFERTYPE_P2P, should be one of
363
-							following:
364
-							 - GPDMA_CONN_SSP0_Tx: SSP0, Tx
365
-							 - GPDMA_CONN_SSP0_Rx: SSP0, Rx
366
-							 - GPDMA_CONN_SSP1_Tx: SSP1, Tx
367
-							 - GPDMA_CONN_SSP1_Rx: SSP1, Rx
368
-							 - GPDMA_CONN_ADC: ADC
369
-							 - GPDMA_CONN_I2S_Channel_0: I2S Channel 0
370
-							 - GPDMA_CONN_I2S_Channel_1: I2S Channel 1
371
-							 - GPDMA_CONN_DAC: DAC
372
-							 - GPDMA_CONN_UART0_Tx_MAT0_0: UART0 Tx / MAT0.0
373
-							 - GPDMA_CONN_UART0_Rx_MAT0_1: UART0 Rx / MAT0.1
374
-							 - GPDMA_CONN_UART1_Tx_MAT1_0: UART1 Tx / MAT1.0
375
-							 - GPDMA_CONN_UART1_Rx_MAT1_1: UART1 Rx / MAT1.1
376
-							 - GPDMA_CONN_UART2_Tx_MAT2_0: UART2 Tx / MAT2.0
377
-							 - GPDMA_CONN_UART2_Rx_MAT2_1: UART2 Rx / MAT2.1
378
-							 - GPDMA_CONN_UART3_Tx_MAT3_0: UART3 Tx / MAT3.0
379
-							 - GPDMA_CONN_UART3_Rx_MAT3_1: UART3 Rx / MAT3.1
380
-							 */
381
-	uint32_t DMALLI;		/**< Linker List Item structure data address
382
-							if there's no Linker List, set as '0'
383
-							*/
384
-} GPDMA_Channel_CFG_Type;
385
-
386
-/**
387
- * @brief GPDMA Linker List Item structure type definition
388
- */
389
-typedef struct {
390
-	uint32_t SrcAddr;	/**< Source Address */
391
-	uint32_t DstAddr;	/**< Destination address */
392
-	uint32_t NextLLI;	/**< Next LLI address, otherwise set to '0' */
393
-	uint32_t Control;	/**< GPDMA Control of this LLI */
394
-} GPDMA_LLI_Type;
395
-
396
-
397
-/**
398
- * @}
399
- */
400
-
401
-/* Public Functions ----------------------------------------------------------- */
402
-/** @defgroup GPDMA_Public_Functions GPDMA Public Functions
403
- * @{
404
- */
405
-
406
-void GPDMA_Init(void);
407
-//Status GPDMA_Setup(GPDMA_Channel_CFG_Type *GPDMAChannelConfig, fnGPDMACbs_Type *pfnGPDMACbs);
408
-Status GPDMA_Setup(GPDMA_Channel_CFG_Type *GPDMAChannelConfig);
409
-IntStatus GPDMA_IntGetStatus(GPDMA_Status_Type type, uint8_t channel);
410
-void GPDMA_ClearIntPending(GPDMA_StateClear_Type type, uint8_t channel);
411
-void GPDMA_ChannelCmd(uint8_t channelNum, FunctionalState NewState);
412
-//void GPDMA_IntHandler(void);
413
-
414
-/**
415
- * @}
416
- */
417
-
418
-
419
-#ifdef __cplusplus
420
-}
421
-#endif
422
-
423
-#endif /* LPC17XX_GPDMA_H_ */
424
-
425
-/**
426
- * @}
427
- */
428
-
429
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 177
frameworks/CMSIS/LPC1768/include/lpc17xx_gpio.h Просмотреть файл

@@ -1,177 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_gpio.h				2010-06-18
3
-*//**
4
-* @file		lpc17xx_gpio.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for GPDMA firmware library on LPC17xx
7
-* @version	3.0
8
-* @date		18. June. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @defgroup GPIO GPIO (General Purpose Input/Output)
35
- * @ingroup LPC1700CMSIS_FwLib_Drivers
36
- * @{
37
- */
38
-
39
-#ifndef LPC17XX_GPIO_H_
40
-#define LPC17XX_GPIO_H_
41
-
42
-/* Includes ------------------------------------------------------------------- */
43
-#include "LPC17xx.h"
44
-#include "lpc_types.h"
45
-
46
-
47
-#ifdef __cplusplus
48
-extern "C"
49
-{
50
-#endif
51
-
52
-/* Public Macros -------------------------------------------------------------- */
53
-/** @defgroup GPIO_Public_Macros GPIO Public Macros
54
- * @{
55
- */
56
-
57
-/** Fast GPIO port 0 byte accessible definition */
58
-#define GPIO0_Byte	((GPIO_Byte_TypeDef *)(LPC_GPIO0_BASE))
59
-/** Fast GPIO port 1 byte accessible definition */
60
-#define GPIO1_Byte	((GPIO_Byte_TypeDef *)(LPC_GPIO1_BASE))
61
-/** Fast GPIO port 2 byte accessible definition */
62
-#define GPIO2_Byte	((GPIO_Byte_TypeDef *)(LPC_GPIO2_BASE))
63
-/** Fast GPIO port 3 byte accessible definition */
64
-#define GPIO3_Byte	((GPIO_Byte_TypeDef *)(LPC_GPIO3_BASE))
65
-/** Fast GPIO port 4 byte accessible definition */
66
-#define GPIO4_Byte	((GPIO_Byte_TypeDef *)(LPC_GPIO4_BASE))
67
-
68
-
69
-/** Fast GPIO port 0 half-word accessible definition */
70
-#define GPIO0_HalfWord	((GPIO_HalfWord_TypeDef *)(LPC_GPIO0_BASE))
71
-/** Fast GPIO port 1 half-word accessible definition */
72
-#define GPIO1_HalfWord	((GPIO_HalfWord_TypeDef *)(LPC_GPIO1_BASE))
73
-/** Fast GPIO port 2 half-word accessible definition */
74
-#define GPIO2_HalfWord	((GPIO_HalfWord_TypeDef *)(LPC_GPIO2_BASE))
75
-/** Fast GPIO port 3 half-word accessible definition */
76
-#define GPIO3_HalfWord	((GPIO_HalfWord_TypeDef *)(LPC_GPIO3_BASE))
77
-/** Fast GPIO port 4 half-word accessible definition */
78
-#define GPIO4_HalfWord	((GPIO_HalfWord_TypeDef *)(LPC_GPIO4_BASE))
79
-
80
-/**
81
- * @}
82
- */
83
-
84
-/* Public Types --------------------------------------------------------------- */
85
-/** @defgroup GPIO_Public_Types GPIO Public Types
86
- * @{
87
- */
88
-
89
-/**
90
- * @brief Fast GPIO port byte type definition
91
- */
92
-typedef struct {
93
-	__IO uint8_t FIODIR[4];		/**< FIO direction register in byte-align */
94
-	   uint32_t RESERVED0[3];	/**< Reserved */
95
-	__IO uint8_t FIOMASK[4];	/**< FIO mask register in byte-align */
96
-	__IO uint8_t FIOPIN[4];		/**< FIO pin register in byte align */
97
-	__IO uint8_t FIOSET[4];		/**< FIO set register in byte-align */
98
-	__O  uint8_t FIOCLR[4];		/**< FIO clear register in byte-align */
99
-} GPIO_Byte_TypeDef;
100
-
101
-
102
-/**
103
- * @brief Fast GPIO port half-word type definition
104
- */
105
-typedef struct {
106
-	__IO uint16_t FIODIRL;		/**< FIO direction register lower halfword part */
107
-	__IO uint16_t FIODIRU;		/**< FIO direction register upper halfword part */
108
-	   uint32_t RESERVED0[3];	/**< Reserved */
109
-	__IO uint16_t FIOMASKL;		/**< FIO mask register lower halfword part */
110
-	__IO uint16_t FIOMASKU;		/**< FIO mask register upper halfword part */
111
-	__IO uint16_t FIOPINL;		/**< FIO pin register lower halfword part */
112
-	__IO uint16_t FIOPINU;		/**< FIO pin register upper halfword part */
113
-	__IO uint16_t FIOSETL;		/**< FIO set register lower halfword part */
114
-	__IO uint16_t FIOSETU;		/**< FIO set register upper halfword part */
115
-	__O  uint16_t FIOCLRL;		/**< FIO clear register lower halfword part */
116
-	__O  uint16_t FIOCLRU;		/**< FIO clear register upper halfword part */
117
-} GPIO_HalfWord_TypeDef;
118
-
119
-/**
120
- * @}
121
- */
122
-
123
-
124
-/* Public Functions ----------------------------------------------------------- */
125
-/** @defgroup GPIO_Public_Functions GPIO Public Functions
126
- * @{
127
- */
128
-
129
-/* GPIO style ------------------------------- */
130
-void GPIO_SetDir(uint8_t portNum, uint32_t bitValue, uint8_t dir);
131
-void GPIO_SetValue(uint8_t portNum, uint32_t bitValue);
132
-void GPIO_ClearValue(uint8_t portNum, uint32_t bitValue);
133
-uint32_t GPIO_ReadValue(uint8_t portNum);
134
-void GPIO_IntCmd(uint8_t portNum, uint32_t bitValue, uint8_t edgeState);
135
-FunctionalState GPIO_GetIntStatus(uint8_t portNum, uint32_t pinNum, uint8_t edgeState);
136
-void GPIO_ClearInt(uint8_t portNum, uint32_t bitValue);
137
-
138
-/* FIO (word-accessible) style ------------------------------- */
139
-void FIO_SetDir(uint8_t portNum, uint32_t bitValue, uint8_t dir);
140
-void FIO_SetValue(uint8_t portNum, uint32_t bitValue);
141
-void FIO_ClearValue(uint8_t portNum, uint32_t bitValue);
142
-uint32_t FIO_ReadValue(uint8_t portNum);
143
-void FIO_SetMask(uint8_t portNum, uint32_t bitValue, uint8_t maskValue);
144
-void FIO_IntCmd(uint8_t portNum, uint32_t bitValue, uint8_t edgeState);
145
-FunctionalState FIO_GetIntStatus(uint8_t portNum, uint32_t pinNum, uint8_t edgeState);
146
-void FIO_ClearInt(uint8_t portNum, uint32_t pinNum);
147
-
148
-/* FIO (halfword-accessible) style ------------------------------- */
149
-void FIO_HalfWordSetDir(uint8_t portNum, uint8_t halfwordNum, uint16_t bitValue, uint8_t dir);
150
-void FIO_HalfWordSetMask(uint8_t portNum, uint8_t halfwordNum, uint16_t bitValue, uint8_t maskValue);
151
-void FIO_HalfWordSetValue(uint8_t portNum, uint8_t halfwordNum, uint16_t bitValue);
152
-void FIO_HalfWordClearValue(uint8_t portNum, uint8_t halfwordNum, uint16_t bitValue);
153
-uint16_t FIO_HalfWordReadValue(uint8_t portNum, uint8_t halfwordNum);
154
-
155
-/* FIO (byte-accessible) style ------------------------------- */
156
-void FIO_ByteSetDir(uint8_t portNum, uint8_t byteNum, uint8_t bitValue, uint8_t dir);
157
-void FIO_ByteSetMask(uint8_t portNum, uint8_t byteNum, uint8_t bitValue, uint8_t maskValue);
158
-void FIO_ByteSetValue(uint8_t portNum, uint8_t byteNum, uint8_t bitValue);
159
-void FIO_ByteClearValue(uint8_t portNum, uint8_t byteNum, uint8_t bitValue);
160
-uint8_t FIO_ByteReadValue(uint8_t portNum, uint8_t byteNum);
161
-
162
-/**
163
- * @}
164
- */
165
-
166
-
167
-#ifdef __cplusplus
168
-}
169
-#endif
170
-
171
-#endif /* LPC17XX_GPIO_H_ */
172
-
173
-/**
174
- * @}
175
- */
176
-
177
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 434
frameworks/CMSIS/LPC1768/include/lpc17xx_i2c.h Просмотреть файл

@@ -1,434 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_i2c.h				2010-05-21
3
-*//**
4
-* @file		lpc17xx_i2c.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for I2C firmware library on LPC17xx
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @defgroup I2C I2C (Inter-IC Control bus)
35
- * @ingroup LPC1700CMSIS_FwLib_Drivers
36
- * @{
37
- */
38
-
39
-#ifndef LPC17XX_I2C_H_
40
-#define LPC17XX_I2C_H_
41
-
42
-/* Includes ------------------------------------------------------------------- */
43
-#include "LPC17xx.h"
44
-#include "lpc_types.h"
45
-
46
-
47
-#ifdef __cplusplus
48
-extern "C"
49
-{
50
-#endif
51
-
52
-
53
-/* Private Macros ------------------------------------------------------------- */
54
-/** @defgroup I2C_Private_Macros I2C Private Macros
55
- * @{
56
- */
57
-
58
-/* --------------------- BIT DEFINITIONS -------------------------------------- */
59
-/*******************************************************************//**
60
- * I2C Control Set register description
61
- *********************************************************************/
62
-#define I2C_I2CONSET_AA				((0x04)) /*!< Assert acknowledge flag */
63
-#define I2C_I2CONSET_SI				((0x08)) /*!< I2C interrupt flag */
64
-#define I2C_I2CONSET_STO			((0x10)) /*!< STOP flag */
65
-#define I2C_I2CONSET_STA			((0x20)) /*!< START flag */
66
-#define I2C_I2CONSET_I2EN			((0x40)) /*!< I2C interface enable */
67
-
68
-/*******************************************************************//**
69
- * I2C Control Clear register description
70
- *********************************************************************/
71
-/** Assert acknowledge Clear bit */
72
-#define I2C_I2CONCLR_AAC			((1<<2))
73
-/** I2C interrupt Clear bit */
74
-#define I2C_I2CONCLR_SIC			((1<<3))
75
-/** I2C STOP Clear bit */
76
-#define I2C_I2CONCLR_STOC			((1<<4))
77
-/** START flag Clear bit */
78
-#define I2C_I2CONCLR_STAC			((1<<5))
79
-/** I2C interface Disable bit */
80
-#define I2C_I2CONCLR_I2ENC			((1<<6))
81
-
82
-/********************************************************************//**
83
- * I2C Status Code definition (I2C Status register)
84
- *********************************************************************/
85
-/* Return Code in I2C status register */
86
-#define I2C_STAT_CODE_BITMASK		((0xF8))
87
-
88
-/* I2C return status code definitions ----------------------------- */
89
-
90
-/** No relevant information */
91
-#define I2C_I2STAT_NO_INF						((0xF8))
92
-
93
-/** Bus Error */
94
-#define I2C_I2STAT_BUS_ERROR					((0x00))
95
-
96
-/* Master transmit mode -------------------------------------------- */
97
-/** A start condition has been transmitted */
98
-#define I2C_I2STAT_M_TX_START					((0x08))
99
-
100
-/** A repeat start condition has been transmitted */
101
-#define I2C_I2STAT_M_TX_RESTART					((0x10))
102
-
103
-/** SLA+W has been transmitted, ACK has been received */
104
-#define I2C_I2STAT_M_TX_SLAW_ACK				((0x18))
105
-
106
-/** SLA+W has been transmitted, NACK has been received */
107
-#define I2C_I2STAT_M_TX_SLAW_NACK				((0x20))
108
-
109
-/** Data has been transmitted, ACK has been received */
110
-#define I2C_I2STAT_M_TX_DAT_ACK					((0x28))
111
-
112
-/** Data has been transmitted, NACK has been received */
113
-#define I2C_I2STAT_M_TX_DAT_NACK				((0x30))
114
-
115
-/** Arbitration lost in SLA+R/W or Data bytes */
116
-#define I2C_I2STAT_M_TX_ARB_LOST				((0x38))
117
-
118
-/* Master receive mode -------------------------------------------- */
119
-/** A start condition has been transmitted */
120
-#define I2C_I2STAT_M_RX_START					((0x08))
121
-
122
-/** A repeat start condition has been transmitted */
123
-#define I2C_I2STAT_M_RX_RESTART					((0x10))
124
-
125
-/** Arbitration lost */
126
-#define I2C_I2STAT_M_RX_ARB_LOST				((0x38))
127
-
128
-/** SLA+R has been transmitted, ACK has been received */
129
-#define I2C_I2STAT_M_RX_SLAR_ACK				((0x40))
130
-
131
-/** SLA+R has been transmitted, NACK has been received */
132
-#define I2C_I2STAT_M_RX_SLAR_NACK				((0x48))
133
-
134
-/** Data has been received, ACK has been returned */
135
-#define I2C_I2STAT_M_RX_DAT_ACK					((0x50))
136
-
137
-/** Data has been received, NACK has been return */
138
-#define I2C_I2STAT_M_RX_DAT_NACK				((0x58))
139
-
140
-/* Slave receive mode -------------------------------------------- */
141
-/** Own slave address has been received, ACK has been returned */
142
-#define I2C_I2STAT_S_RX_SLAW_ACK				((0x60))
143
-
144
-/** Arbitration lost in SLA+R/W as master */
145
-#define I2C_I2STAT_S_RX_ARB_LOST_M_SLA			((0x68))
146
-
147
-/** General call address has been received, ACK has been returned */
148
-#define I2C_I2STAT_S_RX_GENCALL_ACK				((0x70))
149
-
150
-/** Arbitration lost in SLA+R/W (GENERAL CALL) as master */
151
-#define I2C_I2STAT_S_RX_ARB_LOST_M_GENCALL		((0x78))
152
-
153
-/** Previously addressed with own SLV address;
154
- * Data has been received, ACK has been return */
155
-#define I2C_I2STAT_S_RX_PRE_SLA_DAT_ACK			((0x80))
156
-
157
-/** Previously addressed with own SLA;
158
- * Data has been received and NOT ACK has been return */
159
-#define I2C_I2STAT_S_RX_PRE_SLA_DAT_NACK		((0x88))
160
-
161
-/** Previously addressed with General Call;
162
- * Data has been received and ACK has been return */
163
-#define I2C_I2STAT_S_RX_PRE_GENCALL_DAT_ACK		((0x90))
164
-
165
-/** Previously addressed with General Call;
166
- * Data has been received and NOT ACK has been return */
167
-#define I2C_I2STAT_S_RX_PRE_GENCALL_DAT_NACK	((0x98))
168
-
169
-/** A STOP condition or repeated START condition has
170
- * been received while still addressed as SLV/REC
171
- * (Slave Receive) or SLV/TRX (Slave Transmit) */
172
-#define I2C_I2STAT_S_RX_STA_STO_SLVREC_SLVTRX	((0xA0))
173
-
174
-/** Slave transmit mode */
175
-/** Own SLA+R has been received, ACK has been returned */
176
-#define I2C_I2STAT_S_TX_SLAR_ACK				((0xA8))
177
-
178
-/** Arbitration lost in SLA+R/W as master */
179
-#define I2C_I2STAT_S_TX_ARB_LOST_M_SLA			((0xB0))
180
-
181
-/** Data has been transmitted, ACK has been received */
182
-#define I2C_I2STAT_S_TX_DAT_ACK					((0xB8))
183
-
184
-/** Data has been transmitted, NACK has been received */
185
-#define I2C_I2STAT_S_TX_DAT_NACK				((0xC0))
186
-
187
-/** Last data byte in I2DAT has been transmitted (AA = 0);
188
- ACK has been received */
189
-#define I2C_I2STAT_S_TX_LAST_DAT_ACK			((0xC8))
190
-
191
-/** Time out in case of using I2C slave mode */
192
-#define I2C_SLAVE_TIME_OUT						0x10000UL
193
-
194
-/********************************************************************//**
195
- * I2C Data register definition
196
- *********************************************************************/
197
-/** Mask for I2DAT register*/
198
-#define I2C_I2DAT_BITMASK			((0xFF))
199
-
200
-/** Idle data value will be send out in slave mode in case of the actual
201
- * expecting data requested from the master is greater than its sending data
202
- * length that can be supported */
203
-#define I2C_I2DAT_IDLE_CHAR			(0xFF)
204
-
205
-/********************************************************************//**
206
- * I2C Monitor mode control register description
207
- *********************************************************************/
208
-#define I2C_I2MMCTRL_MM_ENA			((1<<0))		/**< Monitor mode enable */
209
-#define I2C_I2MMCTRL_ENA_SCL		((1<<1))		/**< SCL output enable */
210
-#define I2C_I2MMCTRL_MATCH_ALL		((1<<2))		/**< Select interrupt register match */
211
-#define I2C_I2MMCTRL_BITMASK		((0x07))		/**< Mask for I2MMCTRL register */
212
-
213
-/********************************************************************//**
214
- * I2C Data buffer register description
215
- *********************************************************************/
216
-/** I2C Data buffer register bit mask */
217
-#define I2DATA_BUFFER_BITMASK		((0xFF))
218
-
219
-/********************************************************************//**
220
- * I2C Slave Address registers definition
221
- *********************************************************************/
222
-/** General Call enable bit */
223
-#define I2C_I2ADR_GC				((1<<0))
224
-
225
-/** I2C Slave Address registers bit mask */
226
-#define I2C_I2ADR_BITMASK			((0xFF))
227
-
228
-/********************************************************************//**
229
- * I2C Mask Register definition
230
- *********************************************************************/
231
-/** I2C Mask Register mask field */
232
-#define I2C_I2MASK_MASK(n)			((n&0xFE))
233
-
234
-/********************************************************************//**
235
- * I2C SCL HIGH duty cycle Register definition
236
- *********************************************************************/
237
-/** I2C SCL HIGH duty cycle Register bit mask */
238
-#define I2C_I2SCLH_BITMASK			((0xFFFF))
239
-
240
-/********************************************************************//**
241
- * I2C SCL LOW duty cycle Register definition
242
- *********************************************************************/
243
-/** I2C SCL LOW duty cycle Register bit mask */
244
-#define I2C_I2SCLL_BITMASK			((0xFFFF))
245
-
246
-
247
-/* I2C status values */
248
-#define I2C_SETUP_STATUS_ARBF   (1<<8)	/**< Arbitration false */
249
-#define I2C_SETUP_STATUS_NOACKF (1<<9)	/**< No ACK returned */
250
-#define I2C_SETUP_STATUS_DONE   (1<<10)	/**< Status DONE */
251
-
252
-/*********************************************************************//**
253
- * I2C monitor control configuration defines
254
- **********************************************************************/
255
-#define I2C_MONITOR_CFG_SCL_OUTPUT	I2C_I2MMCTRL_ENA_SCL		/**< SCL output enable */
256
-#define I2C_MONITOR_CFG_MATCHALL	I2C_I2MMCTRL_MATCH_ALL		/**< Select interrupt register match */
257
-
258
-/* ---------------- CHECK PARAMETER DEFINITIONS ---------------------------- */
259
-/* Macros check I2C slave address */
260
-#define PARAM_I2C_SLAVEADDR_CH(n)	(n<=3)
261
-
262
-/** Macro to determine if it is valid SSP port number */
263
-#define PARAM_I2Cx(n)	((((uint32_t *)n)==((uint32_t *)LPC_I2C0)) \
264
-|| (((uint32_t *)n)==((uint32_t *)LPC_I2C1)) \
265
-|| (((uint32_t *)n)==((uint32_t *)LPC_I2C2)))
266
-
267
-/* Macros check I2C monitor configuration type */
268
-#define PARAM_I2C_MONITOR_CFG(n) ((n==I2C_MONITOR_CFG_SCL_OUTPUT) || (I2C_MONITOR_CFG_MATCHALL))
269
-
270
-/* I2C state handle return values */
271
-#define I2C_OK					0x00
272
-#define I2C_BYTE_SENT				0x01
273
-#define I2C_BYTE_RECV				0x02
274
-#define I2C_LAST_BYTE_RECV		0x04
275
-#define I2C_SEND_END				0x08
276
-#define I2C_RECV_END 				0x10
277
-#define I2C_STA_STO_RECV			0x20
278
-
279
-#define I2C_ERR				        (0x10000000)
280
-#define I2C_NAK_RECV				(0x10000000 |0x01)
281
-
282
-#define I2C_CheckError(ErrorCode)	(ErrorCode & 0x10000000)
283
-
284
-/**
285
- * @}
286
- */
287
-
288
-
289
-
290
-/* Public Types --------------------------------------------------------------- */
291
-/** @defgroup I2C_Public_Types I2C Public Types
292
- * @{
293
- */
294
-
295
-typedef enum
296
-{
297
-	I2C_0 = 0,
298
-	I2C_1,
299
-	I2C_2
300
-} en_I2C_unitId;
301
-
302
-typedef enum
303
-{
304
-	I2C_MASTER_MODE,
305
-	I2C_SLAVE_MODE,
306
-	I2C_GENERAL_MODE,
307
-} en_I2C_Mode;
308
-/**
309
- * @brief I2C Own slave address setting structure
310
- */
311
-typedef struct {
312
-	uint8_t SlaveAddrChannel;	/**< Slave Address channel in I2C control,
313
-								should be in range from 0..3
314
-								*/
315
-	uint8_t SlaveAddr_7bit;		/**< Value of 7-bit slave address */
316
-	uint8_t GeneralCallState;	/**< Enable/Disable General Call Functionality
317
-								when I2C control being in Slave mode, should be:
318
-								- ENABLE: Enable General Call function.
319
-								- DISABLE: Disable General Call function.
320
-								*/
321
-	uint8_t SlaveAddrMaskValue;	/**< Any bit in this 8-bit value (bit 7:1)
322
-								which is set to '1' will cause an automatic compare on
323
-								the corresponding bit of the received address when it
324
-								is compared to the SlaveAddr_7bit value associated with this
325
-								mask register. In other words, bits in SlaveAddr_7bit value
326
-								which are masked are not taken into account in determining
327
-								an address match
328
-								*/
329
-} I2C_OWNSLAVEADDR_CFG_Type;
330
-
331
-
332
-/**
333
- * @brief Master transfer setup data structure definitions
334
- */
335
-typedef struct
336
-{
337
-  uint32_t          sl_addr7bit;				/**< Slave address in 7bit mode */
338
-  __IO uint8_t*     tx_data;					/**< Pointer to Transmit data - NULL if data transmit
339
-													  is not used */
340
-  uint32_t          tx_length;					/**< Transmit data length - 0 if data transmit
341
-													  is not used*/
342
-  __IO uint32_t     tx_count;					/**< Current Transmit data counter */
343
-  __IO uint8_t*     rx_data;					/**< Pointer to Receive data - NULL if data receive
344
-													  is not used */
345
-  uint32_t          rx_length;					/**< Receive data length - 0 if data receive is
346
-													   not used */
347
-  __IO uint32_t     rx_count;					/**< Current Receive data counter */
348
-  uint32_t          retransmissions_max;		/**< Max Re-Transmission value */
349
-  uint32_t          retransmissions_count;		/**< Current Re-Transmission counter */
350
-  __IO uint32_t     status;						/**< Current status of I2C activity */
351
-  void 				(*callback)(void);			/**< Pointer to Call back function when transmission complete
352
-													used in interrupt transfer mode */
353
-} I2C_M_SETUP_Type;
354
-
355
-
356
-/**
357
- * @brief Slave transfer setup data structure definitions
358
- */
359
-typedef struct
360
-{
361
-  __IO uint8_t*         tx_data;
362
-  uint32_t              tx_length;
363
-  __IO uint32_t         tx_count;
364
-  __IO uint8_t*         rx_data;
365
-  uint32_t              rx_length;
366
-  __IO uint32_t         rx_count;
367
-  __IO uint32_t         status;
368
-  void 				(*callback)(void);
369
-} I2C_S_SETUP_Type;
370
-
371
-/**
372
- * @brief Transfer option type definitions
373
- */
374
-typedef enum {
375
-	I2C_TRANSFER_POLLING = 0,		/**< Transfer in polling mode */
376
-	I2C_TRANSFER_INTERRUPT			/**< Transfer in interrupt mode */
377
-} I2C_TRANSFER_OPT_Type;
378
-
379
-
380
-/**
381
- * @}
382
- */
383
-
384
-
385
-/* Public Functions ----------------------------------------------------------- */
386
-/** @defgroup I2C_Public_Functions I2C Public Functions
387
- * @{
388
- */
389
-
390
-/* I2C Init/DeInit functions ---------- */
391
-void I2C_Init(LPC_I2C_TypeDef *I2Cx, uint32_t clockrate);
392
-void I2C_DeInit(LPC_I2C_TypeDef* I2Cx);
393
-void I2C_Cmd(LPC_I2C_TypeDef* I2Cx, en_I2C_Mode Mode, FunctionalState NewState);
394
-
395
-/* I2C transfer data functions -------- */
396
-Status I2C_MasterTransferData(LPC_I2C_TypeDef *I2Cx, \
397
-		I2C_M_SETUP_Type *TransferCfg, I2C_TRANSFER_OPT_Type Opt);
398
-Status I2C_SlaveTransferData(LPC_I2C_TypeDef *I2Cx, \
399
-		I2C_S_SETUP_Type *TransferCfg, I2C_TRANSFER_OPT_Type Opt);
400
-uint32_t I2C_MasterTransferComplete(LPC_I2C_TypeDef *I2Cx);
401
-uint32_t I2C_SlaveTransferComplete(LPC_I2C_TypeDef *I2Cx);
402
-
403
-
404
-void I2C_SetOwnSlaveAddr(LPC_I2C_TypeDef *I2Cx, I2C_OWNSLAVEADDR_CFG_Type *OwnSlaveAddrConfigStruct);
405
-uint8_t I2C_GetLastStatusCode(LPC_I2C_TypeDef* I2Cx);
406
-
407
-/* I2C Monitor functions ---------------*/
408
-void I2C_MonitorModeConfig(LPC_I2C_TypeDef *I2Cx, uint32_t MonitorCfgType, FunctionalState NewState);
409
-void I2C_MonitorModeCmd(LPC_I2C_TypeDef *I2Cx, FunctionalState NewState);
410
-uint8_t I2C_MonitorGetDatabuffer(LPC_I2C_TypeDef *I2Cx);
411
-BOOL_8 I2C_MonitorHandler(LPC_I2C_TypeDef *I2Cx, uint8_t *buffer, uint32_t size);
412
-
413
-/* I2C Interrupt handler functions ------*/
414
-void I2C_IntCmd (LPC_I2C_TypeDef *I2Cx, Bool NewState);
415
-void I2C_MasterHandler (LPC_I2C_TypeDef *I2Cx);
416
-void I2C_SlaveHandler (LPC_I2C_TypeDef *I2Cx);
417
-
418
-
419
-/**
420
- * @}
421
- */
422
-
423
-
424
-#ifdef __cplusplus
425
-}
426
-#endif
427
-
428
-#endif /* LPC17XX_I2C_H_ */
429
-
430
-/**
431
- * @}
432
- */
433
-
434
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 384
frameworks/CMSIS/LPC1768/include/lpc17xx_i2s.h Просмотреть файл

@@ -1,384 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_i2s.h				2011-06-06
3
-*//**
4
-* @file		lpc17xx_i2s.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for I2S firmware library on LPC17xx
7
-* @version	3.1
8
-* @date		06. June. 2011
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2011, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @defgroup I2S I2S (Inter-IC Sound bus)
35
- * @ingroup LPC1700CMSIS_FwLib_Drivers
36
- * @{
37
- */
38
-
39
-#ifndef LPC17XX_I2S_H_
40
-#define LPC17XX_I2S_H_
41
-
42
-/* Includes ------------------------------------------------------------------- */
43
-#include "LPC17xx.h"
44
-#include "lpc_types.h"
45
-
46
-
47
-#ifdef __cplusplus
48
-extern "C"
49
-{
50
-#endif
51
-
52
-/* Public Macros -------------------------------------------------------------- */
53
-/** @defgroup I2S_Public_Macros I2S Public Macros
54
- * @{
55
- */
56
-
57
-/*********************************************************************//**
58
- * I2S configuration parameter defines
59
- **********************************************************************/
60
-/** I2S Wordwidth bit */
61
-#define I2S_WORDWIDTH_8		((uint32_t)(0))
62
-#define I2S_WORDWIDTH_16	((uint32_t)(1))
63
-#define I2S_WORDWIDTH_32	((uint32_t)(3))
64
-/** I2S Channel bit */
65
-#define I2S_STEREO			((uint32_t)(0))
66
-#define I2S_MONO			((uint32_t)(1))
67
-/** I2S Master/Slave mode bit */
68
-#define I2S_MASTER_MODE		((uint8_t)(0))
69
-#define I2S_SLAVE_MODE		((uint8_t)(1))
70
-/** I2S Stop bit */
71
-#define I2S_STOP_ENABLE		((uint8_t)(1))
72
-#define I2S_STOP_DISABLE	((uint8_t)(0))
73
-/** I2S Reset bit */
74
-#define I2S_RESET_ENABLE	((uint8_t)(1))
75
-#define I2S_RESET_DISABLE	((uint8_t)(0))
76
-/** I2S Mute bit */
77
-#define I2S_MUTE_ENABLE		((uint8_t)(1))
78
-#define I2S_MUTE_DISABLE	((uint8_t)(0))
79
-/** I2S Transmit/Receive bit */
80
-#define I2S_TX_MODE			((uint8_t)(0))
81
-#define I2S_RX_MODE			((uint8_t)(1))
82
-/** I2S Clock Select bit */
83
-#define I2S_CLKSEL_FRDCLK	((uint8_t)(0))
84
-#define I2S_CLKSEL_MCLK		((uint8_t)(2))
85
-/** I2S 4-pin Mode bit */
86
-#define I2S_4PIN_ENABLE 	((uint8_t)(1))
87
-#define I2S_4PIN_DISABLE 	((uint8_t)(0))
88
-/** I2S MCLK Enable bit */
89
-#define I2S_MCLK_ENABLE		((uint8_t)(1))
90
-#define I2S_MCLK_DISABLE	((uint8_t)(0))
91
-/** I2S select DMA bit */
92
-#define I2S_DMA_1			((uint8_t)(0))
93
-#define I2S_DMA_2			((uint8_t)(1))
94
-
95
-/**
96
- * @}
97
- */
98
-
99
-/* Private Macros ------------------------------------------------------------- */
100
-/** @defgroup I2S_Private_Macros I2S Private Macros
101
- * @{
102
- */
103
-
104
-/*********************************************************************//**
105
- * Macro defines for DAO-Digital Audio Output register
106
- **********************************************************************/
107
-/** I2S wordwide - the number of bytes in data*/
108
-#define I2S_DAO_WORDWIDTH_8		((uint32_t)(0))		/** 8 bit	*/
109
-#define I2S_DAO_WORDWIDTH_16	((uint32_t)(1))		/** 16 bit	*/
110
-#define I2S_DAO_WORDWIDTH_32	((uint32_t)(3))		/** 32 bit	*/
111
-/** I2S control mono or stereo format */
112
-#define I2S_DAO_MONO			((uint32_t)(1<<2))
113
-/** I2S control stop mode */
114
-#define I2S_DAO_STOP			((uint32_t)(1<<3))
115
-/** I2S control reset mode */
116
-#define I2S_DAO_RESET			((uint32_t)(1<<4))
117
-/** I2S control master/slave mode */
118
-#define I2S_DAO_SLAVE			((uint32_t)(1<<5))
119
-/** I2S word select half period minus one */
120
-#define I2S_DAO_WS_HALFPERIOD(n)	((uint32_t)(n<<6))
121
-/** I2S control mute mode */
122
-#define I2S_DAO_MUTE			((uint32_t)(1<<15))
123
-
124
-/*********************************************************************//**
125
- * Macro defines for DAI-Digital Audio Input register
126
-**********************************************************************/
127
-/** I2S wordwide - the number of bytes in data*/
128
-#define I2S_DAI_WORDWIDTH_8		((uint32_t)(0))		/** 8 bit	*/
129
-#define I2S_DAI_WORDWIDTH_16	((uint32_t)(1))		/** 16 bit	*/
130
-#define I2S_DAI_WORDWIDTH_32	((uint32_t)(3))		/** 32 bit	*/
131
-/** I2S control mono or stereo format */
132
-#define I2S_DAI_MONO			((uint32_t)(1<<2))
133
-/** I2S control stop mode */
134
-#define I2S_DAI_STOP			((uint32_t)(1<<3))
135
-/** I2S control reset mode */
136
-#define I2S_DAI_RESET			((uint32_t)(1<<4))
137
-/** I2S control master/slave mode */
138
-#define I2S_DAI_SLAVE			((uint32_t)(1<<5))
139
-/** I2S word select half period minus one (9 bits)*/
140
-#define I2S_DAI_WS_HALFPERIOD(n)	((uint32_t)((n&0x1FF)<<6))
141
-/** I2S control mute mode */
142
-#define I2S_DAI_MUTE			((uint32_t)(1<<15))
143
-
144
-/*********************************************************************//**
145
- * Macro defines for STAT register (Status Feedback register)
146
-**********************************************************************/
147
-/** I2S Status Receive or Transmit Interrupt */
148
-#define I2S_STATE_IRQ		((uint32_t)(1))
149
-/** I2S Status Receive or Transmit DMA1 */
150
-#define I2S_STATE_DMA1		((uint32_t)(1<<1))
151
-/** I2S Status Receive or Transmit DMA2 */
152
-#define I2S_STATE_DMA2		((uint32_t)(1<<2))
153
-/** I2S Status Current level of the Receive FIFO (5 bits)*/
154
-#define I2S_STATE_RX_LEVEL(n)	((uint32_t)((n&1F)<<8))
155
-/** I2S Status Current level of the Transmit FIFO (5 bits)*/
156
-#define I2S_STATE_TX_LEVEL(n)	((uint32_t)((n&1F)<<16))
157
-
158
-/*********************************************************************//**
159
- * Macro defines for DMA1 register (DMA1 Configuration register)
160
-**********************************************************************/
161
-/** I2S control DMA1 for I2S receive */
162
-#define I2S_DMA1_RX_ENABLE		((uint32_t)(1))
163
-/** I2S control DMA1 for I2S transmit */
164
-#define I2S_DMA1_TX_ENABLE		((uint32_t)(1<<1))
165
-/** I2S set FIFO level that trigger a receive DMA request on DMA1 */
166
-#define I2S_DMA1_RX_DEPTH(n)	((uint32_t)((n&0x1F)<<8))
167
-/** I2S set FIFO level that trigger a transmit DMA request on DMA1 */
168
-#define I2S_DMA1_TX_DEPTH(n)	((uint32_t)((n&0x1F)<<16))
169
-
170
-/*********************************************************************//**
171
- * Macro defines for DMA2 register (DMA2 Configuration register)
172
-**********************************************************************/
173
-/** I2S control DMA2 for I2S receive */
174
-#define I2S_DMA2_RX_ENABLE		((uint32_t)(1))
175
-/** I2S control DMA1 for I2S transmit */
176
-#define I2S_DMA2_TX_ENABLE		((uint32_t)(1<<1))
177
-/** I2S set FIFO level that trigger a receive DMA request on DMA1 */
178
-#define I2S_DMA2_RX_DEPTH(n)	((uint32_t)((n&0x1F)<<8))
179
-/** I2S set FIFO level that trigger a transmit DMA request on DMA1 */
180
-#define I2S_DMA2_TX_DEPTH(n)	((uint32_t)((n&0x1F)<<16))
181
-
182
-/*********************************************************************//**
183
-* Macro defines for IRQ register (Interrupt Request Control register)
184
-**********************************************************************/
185
-/** I2S control I2S receive interrupt */
186
-#define I2S_IRQ_RX_ENABLE		((uint32_t)(1))
187
-/** I2S control I2S transmit interrupt */
188
-#define I2S_IRQ_TX_ENABLE		((uint32_t)(1<<1))
189
-/** I2S set the FIFO level on which to create an irq request */
190
-#define I2S_IRQ_RX_DEPTH(n)		((uint32_t)((n&0x1F)<<8))
191
-/** I2S set the FIFO level on which to create an irq request */
192
-#define I2S_IRQ_TX_DEPTH(n)		((uint32_t)((n&0x1F)<<16))
193
-
194
-/********************************************************************************//**
195
- * Macro defines for TXRATE/RXRATE register (Transmit/Receive Clock Rate register)
196
-*********************************************************************************/
197
-/** I2S Transmit MCLK rate denominator */
198
-#define I2S_TXRATE_Y_DIVIDER(n)	((uint32_t)(n&0xFF))
199
-/** I2S Transmit MCLK rate denominator */
200
-#define I2S_TXRATE_X_DIVIDER(n)	((uint32_t)((n&0xFF)<<8))
201
-/** I2S Receive MCLK rate denominator */
202
-#define I2S_RXRATE_Y_DIVIDER(n)	((uint32_t)(n&0xFF))
203
-/** I2S Receive MCLK rate denominator */
204
-#define I2S_RXRATE_X_DIVIDER(n)	((uint32_t)((n&0xFF)<<8))
205
-
206
-/*************************************************************************************//**
207
- * Macro defines for TXBITRATE & RXBITRATE register (Transmit/Receive Bit Rate register)
208
-**************************************************************************************/
209
-#define I2S_TXBITRATE(n)	((uint32_t)(n&0x3F))
210
-#define I2S_RXBITRATE(n)	((uint32_t)(n&0x3F))
211
-
212
-/**********************************************************************************//**
213
- * Macro defines for TXMODE/RXMODE register (Transmit/Receive Mode Control register)
214
-************************************************************************************/
215
-/** I2S Transmit select clock source (2 bits)*/
216
-#define I2S_TXMODE_CLKSEL(n)	((uint32_t)(n&0x03))
217
-/** I2S Transmit control 4-pin mode */
218
-#define I2S_TXMODE_4PIN_ENABLE	((uint32_t)(1<<2))
219
-/** I2S Transmit control the TX_MCLK output */
220
-#define I2S_TXMODE_MCENA		((uint32_t)(1<<3))
221
-/** I2S Receive select clock source */
222
-#define I2S_RXMODE_CLKSEL(n)	((uint32_t)(n&0x03))
223
-/** I2S Receive control 4-pin mode */
224
-#define I2S_RXMODE_4PIN_ENABLE	((uint32_t)(1<<2))
225
-/** I2S Receive control the TX_MCLK output */
226
-#define I2S_RXMODE_MCENA		((uint32_t)(1<<3))
227
-
228
-
229
-/* ---------------- CHECK PARAMETER DEFINITIONS ---------------------------- */
230
-/** Macro to determine if it is valid I2S peripheral */
231
-#define PARAM_I2Sx(n)	(((uint32_t *)n)==((uint32_t *)LPC_I2S))
232
-/** Macro to check Data to send valid */
233
-#define PRAM_I2S_FREQ(freq)		((freq>=16000)&&(freq <= 96000))
234
-/* Macro check I2S word width type */
235
-#define PARAM_I2S_WORDWIDTH(n)	((n==I2S_WORDWIDTH_8)||(n==I2S_WORDWIDTH_16)\
236
-||(n==I2S_WORDWIDTH_32))
237
-/* Macro check I2S channel type */
238
-#define PARAM_I2S_CHANNEL(n)	((n==I2S_STEREO)||(n==I2S_MONO))
239
-/* Macro check I2S master/slave mode */
240
-#define PARAM_I2S_WS_SEL(n)		((n==I2S_MASTER_MODE)||(n==I2S_SLAVE_MODE))
241
-/* Macro check I2S stop mode */
242
-#define PARAM_I2S_STOP(n)	((n==I2S_STOP_ENABLE)||(n==I2S_STOP_DISABLE))
243
-/* Macro check I2S reset mode */
244
-#define PARAM_I2S_RESET(n)	((n==I2S_RESET_ENABLE)||(n==I2S_RESET_DISABLE))
245
-/* Macro check I2S reset mode */
246
-#define PARAM_I2S_MUTE(n)	((n==I2S_MUTE_ENABLE)||(n==I2S_MUTE_DISABLE))
247
-/* Macro check I2S transmit/receive mode */
248
-#define PARAM_I2S_TRX(n) 		((n==I2S_TX_MODE)||(n==I2S_RX_MODE))
249
-/* Macro check I2S clock select mode */
250
-#define PARAM_I2S_CLKSEL(n)		((n==I2S_CLKSEL_FRDCLK)||(n==I2S_CLKSEL_MCLK))
251
-/* Macro check I2S 4-pin mode */
252
-#define PARAM_I2S_4PIN(n)	((n==I2S_4PIN_ENABLE)||(n==I2S_4PIN_DISABLE))
253
-/* Macro check I2S MCLK mode */
254
-#define PARAM_I2S_MCLK(n)	((n==I2S_MCLK_ENABLE)||(n==I2S_MCLK_DISABLE))
255
-/* Macro check I2S DMA mode */
256
-#define PARAM_I2S_DMA(n)		((n==I2S_DMA_1)||(n==I2S_DMA_2))
257
-/* Macro check I2S DMA depth value */
258
-#define PARAM_I2S_DMA_DEPTH(n)	(n<=31)
259
-/* Macro check I2S irq level value */
260
-#define PARAM_I2S_IRQ_LEVEL(n)	(n<=31)
261
-/* Macro check I2S half-period value */
262
-#define PARAM_I2S_HALFPERIOD(n)	(n<512)
263
-/* Macro check I2S bit-rate value */
264
-#define PARAM_I2S_BITRATE(n)	(n<=63)
265
-/**
266
- * @}
267
- */
268
-
269
-
270
-
271
-/* Public Types --------------------------------------------------------------- */
272
-/** @defgroup I2S_Public_Types I2S Public Types
273
- * @{
274
- */
275
-
276
-/**
277
- * @brief I2S configuration structure definition
278
- */
279
-typedef struct {
280
-	uint8_t wordwidth;		/** the number of bytes in data as follow:
281
-							-I2S_WORDWIDTH_8: 8 bit data
282
-							-I2S_WORDWIDTH_16: 16 bit data
283
-							-I2S_WORDWIDTH_32: 32 bit data */
284
-	uint8_t	mono; 			/** Set mono/stereo mode, should be:
285
-							- I2S_STEREO: stereo mode
286
-							- I2S_MONO: mono mode */
287
-	uint8_t stop;			/** Disables accesses on FIFOs, should be:
288
-							- I2S_STOP_ENABLE: enable stop mode
289
-							- I2S_STOP_DISABLE: disable stop mode */
290
-	uint8_t reset;			/** Asynchronously reset tje transmit channel and FIFO, should be:
291
-							- I2S_RESET_ENABLE: enable reset mode
292
-							- I2S_RESET_DISABLE: disable reset mode */
293
-	uint8_t ws_sel;			/** Set Master/Slave mode, should be:
294
-							- I2S_MASTER_MODE: I2S master mode
295
-							- I2S_SLAVE_MODE: I2S slave mode */
296
-	uint8_t mute;			/** MUTE mode: when true, the transmit channel sends only zeroes, shoule be:
297
-							- I2S_MUTE_ENABLE: enable mute mode
298
-							- I2S_MUTE_DISABLE: disable mute mode */
299
-	uint8_t Reserved0[2];
300
-} I2S_CFG_Type;
301
-
302
-/**
303
- * @brief I2S DMA configuration structure definition
304
- */
305
-typedef struct {
306
-	uint8_t DMAIndex;		/** Select DMA1 or DMA2, should be:
307
-							- I2S_DMA_1: DMA1
308
-							- I2S_DMA_2: DMA2 */
309
-	uint8_t depth;			/** FIFO level that triggers a DMA request */
310
-	uint8_t Reserved0[2];
311
-}I2S_DMAConf_Type;
312
-
313
-/**
314
- * @brief I2S mode configuration structure definition
315
- */
316
-typedef struct{
317
-	uint8_t clksel;			/** Clock source selection, should be:
318
-							- I2S_CLKSEL_FRDCLK: Select the fractional rate divider clock output
319
-							- I2S_CLKSEL_MCLK: Select the MCLK signal as the clock source */
320
-	uint8_t fpin;			/** Select four pin mode, should be:
321
-							- I2S_4PIN_ENABLE: 4-pin enable
322
-							- I2S_4PIN_DISABLE: 4-pin disable */
323
-	uint8_t mcena;			/** Select MCLK mode, should be:
324
-							- I2S_MCLK_ENABLE: MCLK enable for output
325
-							- I2S_MCLK_DISABLE: MCLK disable for output */
326
-	uint8_t Reserved;
327
-}I2S_MODEConf_Type;
328
-
329
-
330
-/**
331
- * @}
332
- */
333
-
334
-
335
-/* Public Functions ----------------------------------------------------------- */
336
-/** @defgroup I2S_Public_Functions I2S Public Functions
337
- * @{
338
- */
339
-/* I2S Init/DeInit functions ---------*/
340
-void I2S_Init(LPC_I2S_TypeDef *I2Sx);
341
-void I2S_DeInit(LPC_I2S_TypeDef *I2Sx);
342
-
343
-/* I2S configuration functions --------*/
344
-void I2S_Config(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode, I2S_CFG_Type* ConfigStruct);
345
-Status I2S_FreqConfig(LPC_I2S_TypeDef *I2Sx, uint32_t Freq, uint8_t TRMode);
346
-void I2S_SetBitRate(LPC_I2S_TypeDef *I2Sx, uint8_t bitrate, uint8_t TRMode);
347
-void I2S_ModeConfig(LPC_I2S_TypeDef *I2Sx, I2S_MODEConf_Type* ModeConfig, uint8_t TRMode);
348
-uint8_t I2S_GetLevel(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode);
349
-
350
-/* I2S operate functions -------------*/
351
-void I2S_Send(LPC_I2S_TypeDef *I2Sx, uint32_t BufferData);
352
-uint32_t I2S_Receive(LPC_I2S_TypeDef* I2Sx);
353
-void I2S_Start(LPC_I2S_TypeDef *I2Sx);
354
-void I2S_Pause(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode);
355
-void I2S_Mute(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode);
356
-void I2S_Stop(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode);
357
-
358
-/* I2S DMA functions ----------------*/
359
-void I2S_DMAConfig(LPC_I2S_TypeDef *I2Sx, I2S_DMAConf_Type* DMAConfig, uint8_t TRMode);
360
-void I2S_DMACmd(LPC_I2S_TypeDef *I2Sx, uint8_t DMAIndex,uint8_t TRMode, FunctionalState NewState);
361
-
362
-/* I2S IRQ functions ----------------*/
363
-void I2S_IRQCmd(LPC_I2S_TypeDef *I2Sx,uint8_t TRMode, FunctionalState NewState);
364
-void I2S_IRQConfig(LPC_I2S_TypeDef *I2Sx, uint8_t TRMode, uint8_t level);
365
-FunctionalState I2S_GetIRQStatus(LPC_I2S_TypeDef *I2Sx,uint8_t TRMode);
366
-uint8_t I2S_GetIRQDepth(LPC_I2S_TypeDef *I2Sx,uint8_t TRMode);
367
-
368
-/**
369
- * @}
370
- */
371
-
372
-
373
-#ifdef __cplusplus
374
-}
375
-#endif
376
-
377
-
378
-#endif /* LPC17XX_SSP_H_ */
379
-
380
-/**
381
- * @}
382
- */
383
-
384
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 153
frameworks/CMSIS/LPC1768/include/lpc17xx_iap.h Просмотреть файл

@@ -1,153 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_iap.h			2012-04-18
3
-*//**
4
-* @file		lpc17xx_iap.h
5
-* @brief	Contains all functions support for IAP
6
-*			on lpc17xx
7
-* @version	1.0
8
-* @date		18. April. 2012
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2011, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-#ifndef _LPC17xx_IAP_H
34
-#define _LPC17xx_IAP_H
35
-#include "lpc_types.h"
36
-
37
-/** @defgroup IAP  	IAP (In Application Programming)
38
- * @ingroup LPC1700CMSIS_FwLib_Drivers
39
- * @{
40
- */
41
-
42
-/** @defgroup IAP_Public_Macros IAP Public Macros
43
- * @{
44
- */
45
-
46
-/** IAP entry location */
47
-#define IAP_LOCATION              (0x1FFF1FF1UL)
48
-
49
-/**
50
- * @}
51
- */
52
-
53
-/** @defgroup IAP_Public_Types IAP Public Types
54
- * @{
55
- */
56
-
57
-/**
58
- * @brief IAP command code definitions
59
- */
60
-typedef enum
61
-{
62
-    IAP_PREPARE = 50,       // Prepare sector(s) for write operation
63
-    IAP_COPY_RAM2FLASH = 51,     // Copy RAM to Flash
64
-    IAP_ERASE = 52,              // Erase sector(s)
65
-    IAP_BLANK_CHECK = 53,        // Blank check sector(s)
66
-    IAP_READ_PART_ID = 54,       // Read chip part ID
67
-    IAP_READ_BOOT_VER = 55,      // Read chip boot code version
68
-    IAP_COMPARE = 56,            // Compare memory areas
69
-    IAP_REINVOKE_ISP = 57,       // Reinvoke ISP
70
-    IAP_READ_SERIAL_NUMBER = 58, // Read serial number
71
-}  IAP_COMMAND_CODE;
72
-
73
-/**
74
- * @brief IAP status code definitions
75
- */
76
-typedef enum
77
-{
78
-    CMD_SUCCESS,	             // Command is executed successfully.
79
-    INVALID_COMMAND,             // Invalid command.
80
-    SRC_ADDR_ERROR,              // Source address is not on a word boundary.
81
-    DST_ADDR_ERROR,              // Destination address is not on a correct boundary.
82
-    SRC_ADDR_NOT_MAPPED,         // Source address is not mapped in the memory map.
83
-    DST_ADDR_NOT_MAPPED,         // Destination address is not mapped in the memory map.
84
-    COUNT_ERROR,	               // Byte count is not multiple of 4 or is not a permitted value.
85
-    INVALID_SECTOR,	           // Sector number is invalid.
86
-    SECTOR_NOT_BLANK,	           // Sector is not blank.
87
-    SECTOR_NOT_PREPARED_FOR_WRITE_OPERATION,	// Command to prepare sector for write operation was not executed.
88
-    COMPARE_ERROR,               // Source and destination data is not same.
89
-    BUSY,		                   // Flash programming hardware interface is busy.
90
-} IAP_STATUS_CODE;
91
-
92
-/**
93
- * @brief IAP write length definitions
94
- */
95
-typedef enum {
96
-  IAP_WRITE_256  = 256,
97
-  IAP_WRITE_512  = 512,
98
-  IAP_WRITE_1024 = 1024,
99
-  IAP_WRITE_4096 = 4096,
100
-} IAP_WRITE_SIZE;
101
-
102
-/**
103
- * @brief IAP command structure
104
- */
105
-typedef struct {
106
-    uint32_t cmd;   // Command
107
-    uint32_t param[4];      // Parameters
108
-    uint32_t status;        // status code
109
-    uint32_t result[4];     // Result
110
-} IAP_COMMAND_Type;
111
-
112
-/**
113
- * @}
114
- */
115
-
116
-/* Public Functions ----------------------------------------------------------- */
117
-/** @defgroup IAP_Public_Functions IAP Public Functions
118
- * @{
119
- */
120
-
121
-/**  Get sector number of an address */
122
-uint32_t GetSecNum (uint32_t adr);
123
-/**  Prepare sector(s) for write operation */
124
-IAP_STATUS_CODE PrepareSector(uint32_t start_sec, uint32_t end_sec);
125
-/**  Copy RAM to Flash */
126
-IAP_STATUS_CODE CopyRAM2Flash(uint8_t * dest, uint8_t* source, IAP_WRITE_SIZE size);
127
-/**  Prepare sector(s) for write operation */
128
-IAP_STATUS_CODE EraseSector(uint32_t start_sec, uint32_t end_sec);
129
-/**  Blank check sectors */
130
-IAP_STATUS_CODE BlankCheckSector(uint32_t start_sec, uint32_t end_sec,
131
-                                 uint32_t *first_nblank_loc,
132
-								 uint32_t *first_nblank_val);
133
-/**  Read part identification number */
134
-IAP_STATUS_CODE ReadPartID(uint32_t *partID);
135
-/**  Read boot code version */
136
-IAP_STATUS_CODE ReadBootCodeVer(uint8_t *major, uint8_t* minor);
137
-/**  Read Device serial number */
138
-IAP_STATUS_CODE ReadDeviceSerialNum(uint32_t *uid);
139
-/**  Compare memory */
140
-IAP_STATUS_CODE Compare(uint8_t *addr1, uint8_t *addr2, uint32_t size);
141
-/**  Invoke ISP */
142
-void InvokeISP(void);
143
-
144
-/**
145
- * @}
146
- */
147
-
148
-/**
149
- * @}
150
- */
151
-
152
-#endif /*_LPC17xx_IAP_H*/
153
-

+ 0
- 181
frameworks/CMSIS/LPC1768/include/lpc17xx_libcfg_default.h Просмотреть файл

@@ -1,181 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_libcfg_default.h				2010-05-21
3
-*//**
4
-* @file		lpc17xx_libcfg_default.h
5
-* @brief	Default Library configuration header file
6
-* @version	2.0
7
-* @date		21. May. 2010
8
-* @author	NXP MCU SW Application Team
9
-*
10
-* Copyright(C) 2010, NXP Semiconductor
11
-* All rights reserved.
12
-*
13
-***********************************************************************
14
-* Software that is described herein is for illustrative purposes only
15
-* which provides customers with programming information regarding the
16
-* products. This software is supplied "AS IS" without any warranties.
17
-* NXP Semiconductors assumes no responsibility or liability for the
18
-* use of the software, conveys no license or title under any patent,
19
-* copyright, or mask work right to the product. NXP Semiconductors
20
-* reserves the right to make changes in the software without
21
-* notification. NXP Semiconductors also make no representation or
22
-* warranty that such application will be suitable for the specified
23
-* use without further testing or modification.
24
-* Permission to use, copy, modify, and distribute this software and its
25
-* documentation is hereby granted, under NXP Semiconductors'
26
-* relevant copyright in the software, without fee, provided that it
27
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
28
-* copyright, permission, and disclaimer notice must appear in all copies of
29
-* this code.
30
-**********************************************************************/
31
-
32
-/* Library Configuration group ----------------------------------------------------------- */
33
-/** @defgroup LIBCFG_DEFAULT LIBCFG_DEFAULT (Default Library Configuration)
34
- * @ingroup LPC1700CMSIS_FwLib_Drivers
35
- * @{
36
- */
37
-
38
-#ifndef LPC17XX_LIBCFG_DEFAULT_H_
39
-#define LPC17XX_LIBCFG_DEFAULT_H_
40
-
41
-/* Includes ------------------------------------------------------------------- */
42
-#include "lpc_types.h"
43
-
44
-
45
-/* Public Macros -------------------------------------------------------------- */
46
-/** @defgroup LIBCFG_DEFAULT_Public_Macros LIBCFG_DEFAULT Public Macros
47
- * @{
48
- */
49
-
50
-/************************** DEBUG MODE DEFINITIONS *********************************/
51
-/* Un-comment the line below to compile the library in DEBUG mode, this will expanse
52
-   the "CHECK_PARAM" macro in the FW library code */
53
-//#define DEBUG
54
-
55
-
56
-/******************* PERIPHERAL FW LIBRARY CONFIGURATION DEFINITIONS ***********************/
57
-/* Comment the line below to disable the specific peripheral inclusion */
58
-
59
-/* DEBUG_FRAMWORK ------------------------------ */
60
-#define _DBGFWK
61
-
62
-/* GPIO ------------------------------- */
63
-#define _GPIO
64
-
65
-/* EXTI ------------------------------- */
66
-#define _EXTI
67
-
68
-/* UART ------------------------------- */
69
-#define _UART
70
-#define _UART0
71
-#define _UART1
72
-#define _UART2
73
-#define _UART3
74
-
75
-/* SPI ------------------------------- */
76
-#define _SPI
77
-
78
-/* SYSTICK --------------------------- */
79
-#define _SYSTICK
80
-
81
-/* SSP ------------------------------- */
82
-#define _SSP
83
-#define _SSP0
84
-#define _SSP1
85
-
86
-
87
-/* I2C ------------------------------- */
88
-#define _I2C
89
-#define _I2C0
90
-#define _I2C1
91
-#define _I2C2
92
-
93
-/* TIMER ------------------------------- */
94
-#define _TIM
95
-
96
-/* WDT ------------------------------- */
97
-#define _WDT
98
-
99
-
100
-/* GPDMA ------------------------------- */
101
-#define _GPDMA
102
-
103
-
104
-/* DAC ------------------------------- */
105
-#define _DAC
106
-
107
-/* DAC ------------------------------- */
108
-#define _ADC
109
-
110
-
111
-/* PWM ------------------------------- */
112
-#define _PWM
113
-#define _PWM1
114
-
115
-/* RTC ------------------------------- */
116
-#define _RTC
117
-
118
-/* I2S ------------------------------- */
119
-#define _I2S
120
-
121
-/* USB device ------------------------------- */
122
-#define _USBDEV
123
-#define _USB_DMA
124
-
125
-/* QEI ------------------------------- */
126
-#define _QEI
127
-
128
-/* MCPWM ------------------------------- */
129
-#define _MCPWM
130
-
131
-/* CAN--------------------------------*/
132
-#define _CAN
133
-
134
-/* RIT ------------------------------- */
135
-#define _RIT
136
-
137
-/* EMAC ------------------------------ */
138
-#define _EMAC
139
-
140
-/************************** GLOBAL/PUBLIC MACRO DEFINITIONS *********************************/
141
-
142
-#ifdef  DEBUG
143
-/*******************************************************************************
144
-* @brief		The CHECK_PARAM macro is used for function's parameters check.
145
-* 				It is used only if the library is compiled in DEBUG mode.
146
-* @param[in]	expr - If expr is false, it calls check_failed() function
147
-*                    	which reports the name of the source file and the source
148
-*                    	line number of the call that failed.
149
-*                    - If expr is true, it returns no value.
150
-* @return		None
151
-*******************************************************************************/
152
-#define CHECK_PARAM(expr) ((expr) ? (void)0 : check_failed((uint8_t *)__FILE__, __LINE__))
153
-#else
154
-#define CHECK_PARAM(expr)
155
-#endif /* DEBUG */
156
-
157
-/**
158
- * @}
159
- */
160
-
161
-
162
-/* Public Functions ----------------------------------------------------------- */
163
-/** @defgroup LIBCFG_DEFAULT_Public_Functions LIBCFG_DEFAULT Public Functions
164
- * @{
165
- */
166
-
167
-#ifdef  DEBUG
168
-void check_failed(uint8_t *file, uint32_t line);
169
-#endif
170
-
171
-/**
172
- * @}
173
- */
174
-
175
-#endif /* LPC17XX_LIBCFG_DEFAULT_H_ */
176
-
177
-/**
178
- * @}
179
- */
180
-
181
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 329
frameworks/CMSIS/LPC1768/include/lpc17xx_mcpwm.h Просмотреть файл

@@ -1,329 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_mcpwm.h				2010-05-21
3
-*//**
4
-* @file		lpc17xx_mcpwm.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for Motor Control PWM firmware library on LPC17xx
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @defgroup MCPWM MCPWM (Motor Control PWM)
35
- * @ingroup LPC1700CMSIS_FwLib_Drivers
36
- * @{
37
- */
38
-
39
-#ifndef LPC17XX_MCPWM_H_
40
-#define LPC17XX_MCPWM_H_
41
-
42
-/* Includes ------------------------------------------------------------------- */
43
-#include "LPC17xx.h"
44
-#include "lpc_types.h"
45
-
46
-
47
-#ifdef __cplusplus
48
-extern "C"
49
-{
50
-#endif
51
-
52
-/* Public Macros -------------------------------------------------------------- */
53
-/** @defgroup MCPWM_Public_Macros MCPWM Public Macros
54
- * @{
55
- */
56
-
57
-
58
-/** Edge aligned mode for channel in MCPWM */
59
-#define MCPWM_CHANNEL_EDGE_MODE			((uint32_t)(0))
60
-/** Center aligned mode for channel in MCPWM */
61
-#define MCPWM_CHANNEL_CENTER_MODE		((uint32_t)(1))
62
-
63
-/** Polarity of the MCOA and MCOB pins: Passive state is LOW, active state is HIGH */
64
-#define MCPWM_CHANNEL_PASSIVE_LO		((uint32_t)(0))
65
-/** Polarity of the MCOA and MCOB pins: Passive state is HIGH, active state is LOW */
66
-#define MCPWM_CHANNEL_PASSIVE_HI		((uint32_t)(1))
67
-
68
-/* Output Patent in 3-phase DC mode, the internal MCOA0 signal is routed to any or all of
69
- * the six output pins under the control of the bits in this register */
70
-#define MCPWM_PATENT_A0		((uint32_t)(1<<0))	/**< MCOA0 tracks internal MCOA0 */
71
-#define MCPWM_PATENT_B0		((uint32_t)(1<<1))	/**< MCOB0 tracks internal MCOA0 */
72
-#define MCPWM_PATENT_A1		((uint32_t)(1<<2))	/**< MCOA1 tracks internal MCOA0 */
73
-#define MCPWM_PATENT_B1		((uint32_t)(1<<3))	/**< MCOB1 tracks internal MCOA0 */
74
-#define MCPWM_PATENT_A2		((uint32_t)(1<<4))	/**< MCOA2 tracks internal MCOA0 */
75
-#define MCPWM_PATENT_B2		((uint32_t)(1<<5))	/**< MCOB2 tracks internal MCOA0 */
76
-
77
-/* Interrupt type in MCPWM */
78
-/** Limit interrupt for channel (0) */
79
-#define MCPWM_INTFLAG_LIM0	MCPWM_INT_ILIM(0)
80
-/** Match interrupt for channel (0) */
81
-#define MCPWM_INTFLAG_MAT0	MCPWM_INT_IMAT(0)
82
-/** Capture interrupt for channel (0) */
83
-#define MCPWM_INTFLAG_CAP0	MCPWM_INT_ICAP(0)
84
-
85
-/** Limit interrupt for channel (1) */
86
-#define MCPWM_INTFLAG_LIM1	MCPWM_INT_ILIM(1)
87
-/** Match interrupt for channel (1) */
88
-#define MCPWM_INTFLAG_MAT1	MCPWM_INT_IMAT(1)
89
-/** Capture interrupt for channel (1) */
90
-#define MCPWM_INTFLAG_CAP1	MCPWM_INT_ICAP(1)
91
-
92
-/** Limit interrupt for channel (2) */
93
-#define MCPWM_INTFLAG_LIM2	MCPWM_INT_ILIM(2)
94
-/** Match interrupt for channel (2) */
95
-#define MCPWM_INTFLAG_MAT2	MCPWM_INT_IMAT(2)
96
-/** Capture interrupt for channel (2) */
97
-#define MCPWM_INTFLAG_CAP2	MCPWM_INT_ICAP(2)
98
-
99
-/** Fast abort interrupt */
100
-#define MCPWM_INTFLAG_ABORT	MCPWM_INT_ABORT
101
-
102
-/**
103
- * @}
104
- */
105
-
106
-/* Private Macros ------------------------------------------------------------- */
107
-/** @defgroup MCPWM_Private_Macros MCPWM Private Macros
108
- * @{
109
- */
110
-
111
-/*********************************************************************//**
112
- * Macro defines for MCPWM Control register
113
- **********************************************************************/
114
-/* MCPWM Control register, these macro definitions below can be applied for these
115
- * register type:
116
- * - MCPWM Control read address
117
- * - MCPWM Control set address
118
- * - MCPWM Control clear address
119
- */
120
-#define MCPWM_CON_RUN(n)		((n<=2) ? ((uint32_t)(1<<((n*8)+0))) : (0))		/**< Stops/starts timer channel n */
121
-#define MCPWM_CON_CENTER(n)		((n<=2) ? ((uint32_t)(1<<((n*8)+1))) : (0))		/**< Edge/center aligned operation for channel n */
122
-#define MCPWM_CON_POLAR(n)		((n<=2) ? ((uint32_t)(1<<((n*8)+2))) : (0))		/**< Select polarity of the MCOAn and MCOBn pin */
123
-#define MCPWM_CON_DTE(n)		((n<=2) ? ((uint32_t)(1<<((n*8)+3))) : (0))		/**< Control the dead-time feature for channel n */
124
-#define MCPWM_CON_DISUP(n)		((n<=2) ? ((uint32_t)(1<<((n*8)+4))) : (0))		/**< Enable/Disable update of functional register for channel n */
125
-#define MCPWM_CON_INVBDC		((uint32_t)(1<<29))								/**< Control the polarity for all 3 channels */
126
-#define MCPWM_CON_ACMODE		((uint32_t)(1<<30))								/**< 3-phase AC mode select */
127
-#define MCPWM_CON_DCMODE		((uint32_t)(0x80000000))						/**< 3-phase DC mode select */
128
-
129
-/*********************************************************************//**
130
- * Macro defines for MCPWM Capture Control register
131
- **********************************************************************/
132
-/* Capture Control register, these macro definitions below can be applied for these
133
- * register type:
134
- * - MCPWM Capture Control read address
135
- * - MCPWM Capture Control set address
136
- * - MCPWM Capture control clear address
137
- */
138
-/** Enables/Disable channel (cap) capture event on a rising edge on MCI(mci) */
139
-#define MCPWM_CAPCON_CAPMCI_RE(cap,mci)	(((cap<=2)&&(mci<=2)) ? ((uint32_t)(1<<((cap*6)+(mci*2)+0))) : (0))
140
-/** Enables/Disable channel (cap) capture event on a falling edge on MCI(mci) */
141
-#define MCPWM_CAPCON_CAPMCI_FE(cap,mci)	(((cap<=2)&&(mci<=2)) ? ((uint32_t)(1<<((cap*6)+(mci*2)+1))) : (0))
142
-/** TC(n) is reset by channel (n) capture event */
143
-#define MCPWM_CAPCON_RT(n)				((n<=2) ? ((uint32_t)(1<<(18+(n)))) : (0))
144
-/** Hardware noise filter: channel (n) capture events are delayed */
145
-#define MCPWM_CAPCON_HNFCAP(n)			((n<=2) ? ((uint32_t)(1<<(21+(n)))) : (0))
146
-
147
-/*********************************************************************//**
148
- * Macro defines for MCPWM Interrupt register
149
- **********************************************************************/
150
-/* Interrupt registers, these macro definitions below can be applied for these
151
- * register type:
152
- * - MCPWM Interrupt Enable read address
153
- * - MCPWM Interrupt Enable set address
154
- * - MCPWM Interrupt Enable clear address
155
- * - MCPWM Interrupt Flags read address
156
- * - MCPWM Interrupt Flags set address
157
- * - MCPWM Interrupt Flags clear address
158
- */
159
-/** Limit interrupt for channel (n) */
160
-#define MCPWM_INT_ILIM(n)	(((n>=0)&&(n<=2)) ? ((uint32_t)(1<<((n*4)+0))) : (0))
161
-/** Match interrupt for channel (n) */
162
-#define MCPWM_INT_IMAT(n)	(((n>=0)&&(n<=2)) ? ((uint32_t)(1<<((n*4)+1))) : (0))
163
-/** Capture interrupt for channel (n) */
164
-#define MCPWM_INT_ICAP(n)	(((n>=0)&&(n<=2)) ? ((uint32_t)(1<<((n*4)+2))) : (0))
165
-/** Fast abort interrupt */
166
-#define MCPWM_INT_ABORT		((uint32_t)(1<<15))
167
-
168
-/*********************************************************************//**
169
- * Macro defines for MCPWM Count Control register
170
- **********************************************************************/
171
-/* MCPWM Count Control register, these macro definitions below can be applied for these
172
- * register type:
173
- * - MCPWM Count Control read address
174
- * - MCPWM Count Control set address
175
- * - MCPWM Count Control clear address
176
- */
177
-/** Counter(tc) advances on a rising edge on MCI(mci) pin */
178
-#define MCPWM_CNTCON_TCMCI_RE(tc,mci)	(((tc<=2)&&(mci<=2)) ? ((uint32_t)(1<<((6*tc)+(2*mci)+0))) : (0))
179
-/** Counter(cnt) advances on a falling edge on MCI(mci) pin */
180
-#define MCPWM_CNTCON_TCMCI_FE(tc,mci)	(((tc<=2)&&(mci<=2)) ? ((uint32_t)(1<<((6*tc)+(2*mci)+1))) : (0))
181
-/** Channel (n) is in counter mode */
182
-#define MCPWM_CNTCON_CNTR(n)			((n<=2) ? ((uint32_t)(1<<(29+n))) : (0))
183
-
184
-/*********************************************************************//**
185
- * Macro defines for MCPWM Dead-time register
186
- **********************************************************************/
187
-/** Dead time value x for channel n */
188
-#define MCPWM_DT(n,x)		((n<=2) ? ((uint32_t)((x&0x3FF)<<(n*10))) : (0))
189
-
190
-/*********************************************************************//**
191
- * Macro defines for MCPWM Communication Pattern register
192
- **********************************************************************/
193
-#define MCPWM_CP_A0		((uint32_t)(1<<0))	/**< MCOA0 tracks internal MCOA0 */
194
-#define MCPWM_CP_B0		((uint32_t)(1<<1))	/**< MCOB0 tracks internal MCOA0 */
195
-#define MCPWM_CP_A1		((uint32_t)(1<<2))	/**< MCOA1 tracks internal MCOA0 */
196
-#define MCPWM_CP_B1		((uint32_t)(1<<3))	/**< MCOB1 tracks internal MCOA0 */
197
-#define MCPWM_CP_A2		((uint32_t)(1<<4))	/**< MCOA2 tracks internal MCOA0 */
198
-#define MCPWM_CP_B2		((uint32_t)(1<<5))	/**< MCOB2 tracks internal MCOA0 */
199
-
200
-/*********************************************************************//**
201
- * Macro defines for MCPWM Capture clear address register
202
- **********************************************************************/
203
-/** Clear the MCCAP (n) register */
204
-#define MCPWM_CAPCLR_CAP(n)		((n<=2) ? ((uint32_t)(1<<n)) : (0))
205
-
206
-
207
-/**
208
- * @}
209
- */
210
-
211
-
212
-/* Public Types --------------------------------------------------------------- */
213
-/** @defgroup MCPWM_Public_Types MCPWM Public Types
214
- * @{
215
- */
216
-
217
-/**
218
- * @brief Motor Control PWM Channel Configuration structure type definition
219
- */
220
-typedef struct {
221
-	uint32_t channelType;					/**< Edge/center aligned mode for this channel,
222
-												should be:
223
-												- MCPWM_CHANNEL_EDGE_MODE: Channel is in Edge mode
224
-												- MCPWM_CHANNEL_CENTER_MODE: Channel is in Center mode
225
-												*/
226
-	uint32_t channelPolarity;				/**< Polarity of the MCOA and MCOB pins, should be:
227
-												- MCPWM_CHANNEL_PASSIVE_LO: Passive state is LOW, active state is HIGH
228
-												- MCPWM_CHANNEL_PASSIVE_HI: Passive state is HIGH, active state is LOW
229
-												*/
230
-	uint32_t channelDeadtimeEnable;			/**< Enable/Disable DeadTime function for channel, should be:
231
-												- ENABLE.
232
-												- DISABLE.
233
-												*/
234
-	uint32_t channelDeadtimeValue;			/**< DeadTime value, should be less than 0x3FF */
235
-	uint32_t channelUpdateEnable;			/**< Enable/Disable updates of functional registers,
236
-												 should be:
237
-												- ENABLE.
238
-												- DISABLE.
239
-												*/
240
-	uint32_t channelTimercounterValue;		/**< MCPWM Timer Counter value */
241
-	uint32_t channelPeriodValue;			/**< MCPWM Period value */
242
-	uint32_t channelPulsewidthValue;		/**< MCPWM Pulse Width value */
243
-} MCPWM_CHANNEL_CFG_Type;
244
-
245
-/**
246
- * @brief MCPWM Capture Configuration type definition
247
- */
248
-typedef struct {
249
-	uint32_t captureChannel;		/**< Capture Channel Number, should be in range from 0 to 2 */
250
-	uint32_t captureRising;			/**< Enable/Disable Capture on Rising Edge event, should be:
251
-										- ENABLE.
252
-										- DISABLE.
253
-										*/
254
-	uint32_t captureFalling;		/**< Enable/Disable Capture on Falling Edge event, should be:
255
-										- ENABLE.
256
-										- DISABLE.
257
-										*/
258
-	uint32_t timerReset;			/**< Enable/Disable Timer reset function an capture, should be:
259
-										- ENABLE.
260
-										- DISABLE.
261
-										*/
262
-	uint32_t hnfEnable;				/**< Enable/Disable Hardware noise filter function, should be:
263
-										- ENABLE.
264
-										- DISABLE.
265
-										*/
266
-} MCPWM_CAPTURE_CFG_Type;
267
-
268
-
269
-/**
270
- * @brief MCPWM Count Control Configuration type definition
271
- */
272
-typedef struct {
273
-	uint32_t counterChannel;		/**< Counter Channel Number, should be in range from 0 to 2 */
274
-	uint32_t countRising;			/**< Enable/Disable Capture on Rising Edge event, should be:
275
-										- ENABLE.
276
-										- DISABLE.
277
-										*/
278
-	uint32_t countFalling;		/**< Enable/Disable Capture on Falling Edge event, should be:
279
-										- ENABLE.
280
-										- DISABLE.
281
-										*/
282
-} MCPWM_COUNT_CFG_Type;
283
-
284
-/**
285
- * @}
286
- */
287
-
288
-
289
-/* Public Functions ----------------------------------------------------------- */
290
-/** @defgroup MCPWM_Public_Functions MCPWM Public Functions
291
- * @{
292
- */
293
-
294
-void MCPWM_Init(LPC_MCPWM_TypeDef *MCPWMx);
295
-void MCPWM_ConfigChannel(LPC_MCPWM_TypeDef *MCPWMx, uint32_t channelNum,
296
-						MCPWM_CHANNEL_CFG_Type * channelSetup);
297
-void MCPWM_WriteToShadow(LPC_MCPWM_TypeDef *MCPWMx, uint32_t channelNum,
298
-						MCPWM_CHANNEL_CFG_Type *channelSetup);
299
-void MCPWM_ConfigCapture(LPC_MCPWM_TypeDef *MCPWMx, uint32_t channelNum,
300
-						MCPWM_CAPTURE_CFG_Type *captureConfig);
301
-void MCPWM_ClearCapture(LPC_MCPWM_TypeDef *MCPWMx, uint32_t captureChannel);
302
-uint32_t MCPWM_GetCapture(LPC_MCPWM_TypeDef *MCPWMx, uint32_t captureChannel);
303
-void MCPWM_CountConfig(LPC_MCPWM_TypeDef *MCPWMx, uint32_t channelNum,
304
-					uint32_t countMode, MCPWM_COUNT_CFG_Type *countConfig);
305
-void MCPWM_Start(LPC_MCPWM_TypeDef *MCPWMx,uint32_t channel0, uint32_t channel1, uint32_t channel2);
306
-void MCPWM_Stop(LPC_MCPWM_TypeDef *MCPWMx,uint32_t channel0, uint32_t channel1, uint32_t channel2);
307
-void MCPWM_ACMode(LPC_MCPWM_TypeDef *MCPWMx,uint32_t acMode);
308
-void MCPWM_DCMode(LPC_MCPWM_TypeDef *MCPWMx, uint32_t dcMode,
309
-					uint32_t outputInvered, uint32_t outputPattern);
310
-void MCPWM_IntConfig(LPC_MCPWM_TypeDef *MCPWMx, uint32_t ulIntType, FunctionalState NewState);
311
-void MCPWM_IntSet(LPC_MCPWM_TypeDef *MCPWMx, uint32_t ulIntType);
312
-void MCPWM_IntClear(LPC_MCPWM_TypeDef *MCPWMx, uint32_t ulIntType);
313
-FlagStatus MCPWM_GetIntStatus(LPC_MCPWM_TypeDef *MCPWMx, uint32_t ulIntType);
314
-
315
-/**
316
- * @}
317
- */
318
-
319
-#ifdef __cplusplus
320
-}
321
-#endif
322
-
323
-#endif /* LPC17XX_MCPWM_H_ */
324
-
325
-/**
326
- * @}
327
- */
328
-
329
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 76
frameworks/CMSIS/LPC1768/include/lpc17xx_nvic.h Просмотреть файл

@@ -1,76 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_nvic.h				2010-05-21
3
-*//**
4
-* @file		lpc17xx_nvic.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for Nesting Vectored Interrupt firmware library
7
-* 			on LPC17xx
8
-* @version	2.0
9
-* @date		21. May. 2010
10
-* @author	NXP MCU SW Application Team
11
-*
12
-* Copyright(C) 2010, NXP Semiconductor
13
-* All rights reserved.
14
-*
15
-***********************************************************************
16
-* Software that is described herein is for illustrative purposes only
17
-* which provides customers with programming information regarding the
18
-* products. This software is supplied "AS IS" without any warranties.
19
-* NXP Semiconductors assumes no responsibility or liability for the
20
-* use of the software, conveys no license or title under any patent,
21
-* copyright, or mask work right to the product. NXP Semiconductors
22
-* reserves the right to make changes in the software without
23
-* notification. NXP Semiconductors also make no representation or
24
-* warranty that such application will be suitable for the specified
25
-* use without further testing or modification.
26
-* Permission to use, copy, modify, and distribute this software and its
27
-* documentation is hereby granted, under NXP Semiconductors'
28
-* relevant copyright in the software, without fee, provided that it
29
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
30
-* copyright, permission, and disclaimer notice must appear in all copies of
31
-* this code.
32
-**********************************************************************/
33
-
34
-/* Peripheral group ----------------------------------------------------------- */
35
-/** @defgroup NVIC NVIC (Nested Vectored Interrupt Controller)
36
- * @ingroup LPC1700CMSIS_FwLib_Drivers
37
- * @{
38
- */
39
-
40
-#ifndef LPC17XX_NVIC_H_
41
-#define LPC17XX_NVIC_H_
42
-
43
-/* Includes ------------------------------------------------------------------- */
44
-#include "LPC17xx.h"
45
-#include "lpc_types.h"
46
-
47
-#ifdef __cplusplus
48
-extern "C"
49
-{
50
-#endif
51
-
52
-
53
-/* Public Functions ----------------------------------------------------------- */
54
-/** @defgroup NVIC_Public_Functions NVIC Public Functions
55
- * @{
56
- */
57
-
58
-void NVIC_DeInit(void);
59
-void NVIC_SCBDeInit(void);
60
-void NVIC_SetVTOR(uint32_t offset);
61
-
62
-/**
63
- * @}
64
- */
65
-
66
-#ifdef __cplusplus
67
-}
68
-#endif
69
-
70
-#endif /* LPC17XX_NVIC_H_ */
71
-
72
-/**
73
- * @}
74
- */
75
-
76
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 203
frameworks/CMSIS/LPC1768/include/lpc17xx_pinsel.h Просмотреть файл

@@ -1,203 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_pinsel.h				2010-05-21
3
-*//**
4
-* @file		lpc17xx_pinsel.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for Pin connect block firmware library on LPC17xx
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @defgroup PINSEL PINSEL (Pin Selection)
35
- * @ingroup LPC1700CMSIS_FwLib_Drivers
36
- * @{
37
- */
38
-
39
-#ifndef LPC17XX_PINSEL_H_
40
-#define LPC17XX_PINSEL_H_
41
-
42
-/* Includes ------------------------------------------------------------------- */
43
-#include "LPC17xx.h"
44
-#include "lpc_types.h"
45
-
46
-#ifdef __cplusplus
47
-extern "C"
48
-{
49
-#endif
50
-
51
-/* Public Macros -------------------------------------------------------------- */
52
-/** @defgroup PINSEL_Public_Macros PINSEL Public Macros
53
- * @{
54
- */
55
-
56
-/*********************************************************************//**
57
- *!< Macros define for PORT Selection
58
- ***********************************************************************/
59
-#define PINSEL_PORT_0 	((0))	/**< PORT 0*/
60
-#define PINSEL_PORT_1 	((1))	/**< PORT 1*/
61
-#define PINSEL_PORT_2 	((2))	/**< PORT 2*/
62
-#define PINSEL_PORT_3 	((3))	/**< PORT 3*/
63
-#define PINSEL_PORT_4 	((4))	/**< PORT 4*/
64
-
65
-/***********************************************************************
66
- * Macros define for Pin Function selection
67
- **********************************************************************/
68
-#define PINSEL_FUNC_0	((0))	/**< default function*/
69
-#define PINSEL_FUNC_1	((1))	/**< first alternate function*/
70
-#define PINSEL_FUNC_2	((2))	/**< second alternate function*/
71
-#define PINSEL_FUNC_3	((3))	/**< third or reserved alternate function*/
72
-
73
-/***********************************************************************
74
- * Macros define for Pin Number of Port
75
- **********************************************************************/
76
-#define PINSEL_PIN_0 	((0)) 	/**< Pin 0 */
77
-#define PINSEL_PIN_1 	((1)) 	/**< Pin 1 */
78
-#define PINSEL_PIN_2 	((2)) 	/**< Pin 2 */
79
-#define PINSEL_PIN_3 	((3)) 	/**< Pin 3 */
80
-#define PINSEL_PIN_4 	((4)) 	/**< Pin 4 */
81
-#define PINSEL_PIN_5 	((5)) 	/**< Pin 5 */
82
-#define PINSEL_PIN_6 	((6)) 	/**< Pin 6 */
83
-#define PINSEL_PIN_7 	((7)) 	/**< Pin 7 */
84
-#define PINSEL_PIN_8 	((8)) 	/**< Pin 8 */
85
-#define PINSEL_PIN_9 	((9)) 	/**< Pin 9 */
86
-#define PINSEL_PIN_10 	((10)) 	/**< Pin 10 */
87
-#define PINSEL_PIN_11 	((11)) 	/**< Pin 11 */
88
-#define PINSEL_PIN_12 	((12)) 	/**< Pin 12 */
89
-#define PINSEL_PIN_13 	((13)) 	/**< Pin 13 */
90
-#define PINSEL_PIN_14 	((14)) 	/**< Pin 14 */
91
-#define PINSEL_PIN_15 	((15)) 	/**< Pin 15 */
92
-#define PINSEL_PIN_16 	((16)) 	/**< Pin 16 */
93
-#define PINSEL_PIN_17 	((17)) 	/**< Pin 17 */
94
-#define PINSEL_PIN_18 	((18)) 	/**< Pin 18 */
95
-#define PINSEL_PIN_19 	((19)) 	/**< Pin 19 */
96
-#define PINSEL_PIN_20 	((20)) 	/**< Pin 20 */
97
-#define PINSEL_PIN_21 	((21)) 	/**< Pin 21 */
98
-#define PINSEL_PIN_22 	((22)) 	/**< Pin 22 */
99
-#define PINSEL_PIN_23 	((23)) 	/**< Pin 23 */
100
-#define PINSEL_PIN_24 	((24)) 	/**< Pin 24 */
101
-#define PINSEL_PIN_25 	((25)) 	/**< Pin 25 */
102
-#define PINSEL_PIN_26 	((26)) 	/**< Pin 26 */
103
-#define PINSEL_PIN_27 	((27)) 	/**< Pin 27 */
104
-#define PINSEL_PIN_28 	((28)) 	/**< Pin 28 */
105
-#define PINSEL_PIN_29 	((29)) 	/**< Pin 29 */
106
-#define PINSEL_PIN_30 	((30)) 	/**< Pin 30 */
107
-#define PINSEL_PIN_31 	((31)) 	/**< Pin 31 */
108
-
109
-/***********************************************************************
110
- * Macros define for Pin mode
111
- **********************************************************************/
112
-#define PINSEL_PINMODE_PULLUP		((0))	/**< Internal pull-up resistor*/
113
-#define PINSEL_PINMODE_TRISTATE 	((2))	/**< Tri-state */
114
-#define PINSEL_PINMODE_PULLDOWN 	((3)) 	/**< Internal pull-down resistor */
115
-
116
-/***********************************************************************
117
- * Macros define for Pin mode (normal/open drain)
118
- **********************************************************************/
119
-#define	PINSEL_PINMODE_NORMAL		((0))	/**< Pin is in the normal (not open drain) mode.*/
120
-#define	PINSEL_PINMODE_OPENDRAIN	((1)) 	/**< Pin is in the open drain mode */
121
-
122
-/***********************************************************************
123
- * Macros define for I2C mode
124
- ***********************************************************************/
125
-#define	PINSEL_I2C_Normal_Mode		((0))	/**< The standard drive mode */
126
-#define	PINSEL_I2C_Fast_Mode		((1)) 	/**<  Fast Mode Plus drive mode */
127
-
128
-/**
129
- * @}
130
- */
131
-
132
-/* Private Macros ------------------------------------------------------------- */
133
-/** @defgroup PINSEL_Private_Macros PINSEL Private Macros
134
- * @{
135
- */
136
-
137
-/* Pin selection define */
138
-/* I2C Pin Configuration register bit description */
139
-#define PINSEL_I2CPADCFG_SDADRV0 	_BIT(0) /**< Drive mode control for the SDA0 pin, P0.27 */
140
-#define PINSEL_I2CPADCFG_SDAI2C0	_BIT(1) /**< I2C mode control for the SDA0 pin, P0.27 */
141
-#define PINSEL_I2CPADCFG_SCLDRV0	_BIT(2) /**< Drive mode control for the SCL0 pin, P0.28 */
142
-#define PINSEL_I2CPADCFG_SCLI2C0	_BIT(3) /**< I2C mode control for the SCL0 pin, P0.28 */
143
-
144
-/**
145
- * @}
146
- */
147
-
148
-
149
-/* Public Types --------------------------------------------------------------- */
150
-/** @defgroup PINSEL_Public_Types PINSEL Public Types
151
- * @{
152
- */
153
-
154
-/** @brief Pin configuration structure */
155
-typedef struct
156
-{
157
-	uint8_t Portnum;	/**< Port Number, should be PINSEL_PORT_x,
158
-						where x should be in range from 0 to 4 */
159
-	uint8_t Pinnum;		/**< Pin Number, should be PINSEL_PIN_x,
160
-						where x should be in range from 0 to 31 */
161
-	uint8_t Funcnum;	/**< Function Number, should be PINSEL_FUNC_x,
162
-						where x should be in range from 0 to 3 */
163
-	uint8_t Pinmode;	/**< Pin Mode, should be:
164
-						- PINSEL_PINMODE_PULLUP: Internal pull-up resistor
165
-						- PINSEL_PINMODE_TRISTATE: Tri-state
166
-						- PINSEL_PINMODE_PULLDOWN: Internal pull-down resistor */
167
-	uint8_t OpenDrain;	/**< OpenDrain mode, should be:
168
-						- PINSEL_PINMODE_NORMAL: Pin is in the normal (not open drain) mode
169
-						- PINSEL_PINMODE_OPENDRAIN: Pin is in the open drain mode */
170
-} PINSEL_CFG_Type;
171
-
172
-/**
173
- * @}
174
- */
175
-
176
-
177
-/* Public Functions ----------------------------------------------------------- */
178
-/** @defgroup PINSEL_Public_Functions PINSEL Public Functions
179
- * @{
180
- */
181
-
182
-void PINSEL_ConfigPin(PINSEL_CFG_Type *PinCfg);
183
-void PINSEL_ConfigTraceFunc (FunctionalState NewState);
184
-void PINSEL_SetI2C0Pins(uint8_t i2cPinMode, FunctionalState filterSlewRateEnable);
185
-
186
-
187
-/**
188
- * @}
189
- */
190
-
191
-
192
-#ifdef __cplusplus
193
-}
194
-#endif
195
-
196
-#endif /* LPC17XX_PINSEL_H_ */
197
-
198
-/**
199
- * @}
200
- */
201
-
202
-/* --------------------------------- End Of File ------------------------------ */
203
-

+ 0
- 348
frameworks/CMSIS/LPC1768/include/lpc17xx_pwm.h Просмотреть файл

@@ -1,348 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_pwm.h				2011-03-31
3
-*//**
4
-* @file		lpc17xx_pwm.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for PWM firmware library on LPC17xx
7
-* @version	2.1
8
-* @date		31. Mar. 2011
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2011, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @defgroup PWM PWM (Pulse Width Modulator)
35
- * @ingroup LPC1700CMSIS_FwLib_Drivers
36
- * @{
37
- */
38
-
39
-#ifndef LPC17XX_PWM_H_
40
-#define LPC17XX_PWM_H_
41
-
42
-/* Includes ------------------------------------------------------------------- */
43
-#include "LPC17xx.h"
44
-#include "lpc_types.h"
45
-
46
-
47
-#ifdef __cplusplus
48
-extern "C"
49
-{
50
-#endif
51
-
52
-
53
-/* Private Macros ------------------------------------------------------------- */
54
-/** @defgroup PWM_Private_Macros PWM Private Macros
55
- * @{
56
- */
57
-
58
-/* --------------------- BIT DEFINITIONS -------------------------------------- */
59
-/**********************************************************************
60
-* IR register definitions
61
-**********************************************************************/
62
-/** Interrupt flag for PWM match channel for 6 channel */
63
-#define PWM_IR_PWMMRn(n)    	((uint32_t)((n<4)?(1<<n):(1<<(n+4))))
64
-/** Interrupt flag for capture input */
65
-#define PWM_IR_PWMCAPn(n)		((uint32_t)(1<<(n+4)))
66
-/**  IR register mask */
67
-#define PWM_IR_BITMASK			((uint32_t)(0x0000073F))
68
-
69
-/**********************************************************************
70
-* TCR register definitions
71
-**********************************************************************/
72
-/** TCR register mask */
73
-#define PWM_TCR_BITMASK				((uint32_t)(0x0000000B))
74
-#define PWM_TCR_COUNTER_ENABLE      ((uint32_t)(1<<0)) /*!< PWM Counter Enable */
75
-#define PWM_TCR_COUNTER_RESET       ((uint32_t)(1<<1)) /*!< PWM Counter Reset */
76
-#define PWM_TCR_PWM_ENABLE          ((uint32_t)(1<<3)) /*!< PWM Enable */
77
-
78
-/**********************************************************************
79
-* CTCR register definitions
80
-**********************************************************************/
81
-/** CTCR register mask */
82
-#define PWM_CTCR_BITMASK			((uint32_t)(0x0000000F))
83
-/** PWM Counter-Timer Mode */
84
-#define PWM_CTCR_MODE(n)        	((uint32_t)(n&0x03))
85
-/** PWM Capture input select */
86
-#define PWM_CTCR_SELECT_INPUT(n)	((uint32_t)((n&0x03)<<2))
87
-
88
-/**********************************************************************
89
-* MCR register definitions
90
-**********************************************************************/
91
-/** MCR register mask */
92
-#define PWM_MCR_BITMASK				((uint32_t)(0x001FFFFF))
93
-/** generate a PWM interrupt when a MATCHn occurs */
94
-#define PWM_MCR_INT_ON_MATCH(n)     ((uint32_t)(1<<(((n&0x7)<<1)+(n&0x07))))
95
-/** reset the PWM when a MATCHn occurs */
96
-#define PWM_MCR_RESET_ON_MATCH(n)   ((uint32_t)(1<<(((n&0x7)<<1)+(n&0x07)+1)))
97
-/** stop the PWM when a MATCHn occurs */
98
-#define PWM_MCR_STOP_ON_MATCH(n)    ((uint32_t)(1<<(((n&0x7)<<1)+(n&0x07)+2)))
99
-
100
-/**********************************************************************
101
-* CCR register definitions
102
-**********************************************************************/
103
-/** CCR register mask */
104
-#define PWM_CCR_BITMASK				((uint32_t)(0x0000003F))
105
-/** PCAPn is rising edge sensitive */
106
-#define PWM_CCR_CAP_RISING(n) 	 	((uint32_t)(1<<(((n&0x2)<<1)+(n&0x1))))
107
-/** PCAPn is falling edge sensitive */
108
-#define PWM_CCR_CAP_FALLING(n) 		((uint32_t)(1<<(((n&0x2)<<1)+(n&0x1)+1)))
109
-/** PWM interrupt is generated on a PCAP event */
110
-#define PWM_CCR_INT_ON_CAP(n)  		((uint32_t)(1<<(((n&0x2)<<1)+(n&0x1)+2)))
111
-
112
-/**********************************************************************
113
-* PCR register definitions
114
-**********************************************************************/
115
-/** PCR register mask */
116
-#define PWM_PCR_BITMASK			(uint32_t)0x00007E7C
117
-/** PWM output n is a single edge controlled output */
118
-#define PWM_PCR_PWMSELn(n)   	((uint32_t)(((n&0x7)<2) ? 0 : (1<<n)))
119
-/** enable PWM output n */
120
-#define PWM_PCR_PWMENAn(n)   	((uint32_t)(((n&0x7)<1) ? 0 : (1<<(n+8))))
121
-
122
-/**********************************************************************
123
-* LER register definitions
124
-**********************************************************************/
125
-/** LER register mask*/
126
-#define PWM_LER_BITMASK				((uint32_t)(0x0000007F))
127
-/** PWM MATCHn register update control */
128
-#define PWM_LER_EN_MATCHn_LATCH(n)   ((uint32_t)((n<7) ? (1<<n) : 0))
129
-
130
-/* ---------------- CHECK PARAMETER DEFINITIONS ---------------------------- */
131
-/** Macro to determine if it is valid PWM peripheral or not */
132
-#define PARAM_PWMx(n)	(((uint32_t *)n)==((uint32_t *)LPC_PWM1))
133
-
134
-/** Macro check PWM1 match channel value */
135
-#define PARAM_PWM1_MATCH_CHANNEL(n)		(n<=6)
136
-
137
-/** Macro check PWM1 channel value */
138
-#define PARAM_PWM1_CHANNEL(n)			((n>=1) && (n<=6))
139
-
140
-/** Macro check PWM1 edge channel mode */
141
-#define PARAM_PWM1_EDGE_MODE_CHANNEL(n)			((n>=2) && (n<=6))
142
-
143
-/** Macro check PWM1 capture channel mode */
144
-#define PARAM_PWM1_CAPTURE_CHANNEL(n)	((n==0) || (n==1))
145
-
146
-/** Macro check PWM1 interrupt status type */
147
-#define PARAM_PWM_INTSTAT(n)	((n==PWM_INTSTAT_MR0) || (n==PWM_INTSTAT_MR1) || (n==PWM_INTSTAT_MR2) \
148
-|| (n==PWM_INTSTAT_MR3) || (n==PWM_INTSTAT_MR4) || (n==PWM_INTSTAT_MR5) \
149
-|| (n==PWM_INTSTAT_MR6) || (n==PWM_INTSTAT_CAP0) || (n==PWM_INTSTAT_CAP1))
150
-/**
151
- * @}
152
- */
153
-
154
-
155
-/* Public Types --------------------------------------------------------------- */
156
-/** @defgroup PWM_Public_Types PWM Public Types
157
- * @{
158
- */
159
-
160
-/** @brief Configuration structure in PWM TIMER mode */
161
-typedef struct {
162
-
163
-	uint8_t PrescaleOption;		/**< Prescale option, should be:
164
-								- PWM_TIMER_PRESCALE_TICKVAL: Prescale in absolute value
165
-								- PWM_TIMER_PRESCALE_USVAL: Prescale in microsecond value
166
-								*/
167
-	uint8_t Reserved[3];
168
-	uint32_t PrescaleValue;		/**< Prescale value, 32-bit long, should be matched
169
-								with PrescaleOption
170
-								*/
171
-} PWM_TIMERCFG_Type;
172
-
173
-/** @brief Configuration structure in PWM COUNTER mode */
174
-typedef struct {
175
-
176
-	uint8_t CounterOption;		/**< Counter Option, should be:
177
-								- PWM_COUNTER_RISING: Rising Edge
178
-								- PWM_COUNTER_FALLING: Falling Edge
179
-								- PWM_COUNTER_ANY: Both rising and falling mode
180
-								*/
181
-	uint8_t CountInputSelect;	/**< Counter input select, should be:
182
-								- PWM_COUNTER_PCAP1_0: PWM Counter input selected is PCAP1.0 pin
183
-								- PWM_COUNTER_PCAP1_1: PWM Counter input selected is PCAP1.1 pin
184
-								*/
185
-	uint8_t Reserved[2];
186
-} PWM_COUNTERCFG_Type;
187
-
188
-/** @brief PWM Match channel configuration structure */
189
-typedef struct {
190
-	uint8_t MatchChannel;	/**< Match channel, should be in range
191
-							from 0..6 */
192
-	uint8_t IntOnMatch;		/**< Interrupt On match, should be:
193
-							- ENABLE: Enable this function.
194
-							- DISABLE: Disable this function.
195
-							*/
196
-	uint8_t StopOnMatch;	/**< Stop On match, should be:
197
-							- ENABLE: Enable this function.
198
-							- DISABLE: Disable this function.
199
-							*/
200
-	uint8_t ResetOnMatch;	/**< Reset On match, should be:
201
-							- ENABLE: Enable this function.
202
-							- DISABLE: Disable this function.
203
-							*/
204
-} PWM_MATCHCFG_Type;
205
-
206
-
207
-/** @brief PWM Capture Input configuration structure */
208
-typedef struct {
209
-	uint8_t CaptureChannel;	/**< Capture channel, should be in range
210
-							from 0..1 */
211
-	uint8_t RisingEdge;		/**< caption rising edge, should be:
212
-							- ENABLE: Enable rising edge.
213
-							- DISABLE: Disable this function.
214
-							*/
215
-	uint8_t FallingEdge;		/**< caption falling edge, should be:
216
-							- ENABLE: Enable falling edge.
217
-							- DISABLE: Disable this function.
218
-								*/
219
-	uint8_t IntOnCaption;	/**< Interrupt On caption, should be:
220
-							- ENABLE: Enable interrupt function.
221
-							- DISABLE: Disable this function.
222
-							*/
223
-} PWM_CAPTURECFG_Type;
224
-
225
-/* Timer/Counter in PWM configuration type definition -----------------------------------*/
226
-
227
-/** @brief PMW TC mode select option */
228
-typedef enum {
229
-	PWM_MODE_TIMER = 0,		/*!< PWM using Timer mode */
230
-	PWM_MODE_COUNTER		/*!< PWM using Counter mode */
231
-} PWM_TC_MODE_OPT;
232
-
233
-#define PARAM_PWM_TC_MODE(n) ((n==PWM_MODE_TIMER) || (n==PWM_MODE_COUNTER))
234
-
235
-
236
-/** @brief PWM Timer/Counter prescale option */
237
-typedef enum
238
-{
239
-	PWM_TIMER_PRESCALE_TICKVAL = 0,			/*!< Prescale in absolute value */
240
-	PWM_TIMER_PRESCALE_USVAL				/*!< Prescale in microsecond value */
241
-} PWM_TIMER_PRESCALE_OPT;
242
-
243
-#define PARAM_PWM_TIMER_PRESCALE(n) ((n==PWM_TIMER_PRESCALE_TICKVAL) || (n==PWM_TIMER_PRESCALE_USVAL))
244
-
245
-
246
-/** @brief PWM Input Select in counter mode */
247
-typedef enum {
248
-	PWM_COUNTER_PCAP1_0 = 0,		/*!< PWM Counter input selected is PCAP1.0 pin */
249
-	PWM_COUNTER_PCAP1_1			/*!< PWM counter input selected is CAP1.1 pin */
250
-} PWM_COUNTER_INPUTSEL_OPT;
251
-
252
-#define PARAM_PWM_COUNTER_INPUTSEL(n) ((n==PWM_COUNTER_PCAP1_0) || (n==PWM_COUNTER_PCAP1_1))
253
-
254
-/** @brief PWM Input Edge Option in counter mode */
255
-typedef enum {
256
-    PWM_COUNTER_RISING = 1,		/*!< Rising edge mode */
257
-    PWM_COUNTER_FALLING = 2,	/*!< Falling edge mode */
258
-    PWM_COUNTER_ANY = 3			/*!< Both rising and falling mode */
259
-} PWM_COUNTER_EDGE_OPT;
260
-
261
-#define PARAM_PWM_COUNTER_EDGE(n)	((n==PWM_COUNTER_RISING) || (n==PWM_COUNTER_FALLING) \
262
-|| (n==PWM_COUNTER_ANY))
263
-
264
-
265
-/* PWM configuration type definition ----------------------------------------------------- */
266
-/** @brief PWM operating mode options */
267
-typedef enum {
268
-    PWM_CHANNEL_SINGLE_EDGE,	/*!< PWM Channel Single edge mode */
269
-    PWM_CHANNEL_DUAL_EDGE		/*!< PWM Channel Dual edge mode */
270
-} PWM_CHANNEL_EDGE_OPT;
271
-
272
-#define PARAM_PWM_CHANNEL_EDGE(n)	((n==PWM_CHANNEL_SINGLE_EDGE) || (n==PWM_CHANNEL_DUAL_EDGE))
273
-
274
-
275
-/** @brief PWM update type */
276
-typedef enum {
277
-	PWM_MATCH_UPDATE_NOW = 0,			/**< PWM Match Channel Update Now */
278
-	PWM_MATCH_UPDATE_NEXT_RST			/**< PWM Match Channel Update on next
279
-											PWM Counter resetting */
280
-} PWM_MATCH_UPDATE_OPT;
281
-
282
-#define PARAM_PWM_MATCH_UPDATE(n)	((n==PWM_MATCH_UPDATE_NOW) || (n==PWM_MATCH_UPDATE_NEXT_RST))
283
-
284
-
285
-/** @brief PWM interrupt status type definition ----------------------------------------------------- */
286
-/** @brief PWM Interrupt status type */
287
-typedef enum
288
-{
289
-	PWM_INTSTAT_MR0 = PWM_IR_PWMMRn(0), 	/**< Interrupt flag for PWM match channel 0 */
290
-	PWM_INTSTAT_MR1 = PWM_IR_PWMMRn(1),		/**< Interrupt flag for PWM match channel 1 */
291
-	PWM_INTSTAT_MR2 = PWM_IR_PWMMRn(2),		/**< Interrupt flag for PWM match channel 2 */
292
-	PWM_INTSTAT_MR3 = PWM_IR_PWMMRn(3),		/**< Interrupt flag for PWM match channel 3 */
293
-	PWM_INTSTAT_CAP0 = PWM_IR_PWMCAPn(0),	/**< Interrupt flag for capture input 0 */
294
-	PWM_INTSTAT_CAP1 = PWM_IR_PWMCAPn(1),	/**< Interrupt flag for capture input 1 */
295
-	PWM_INTSTAT_MR4 = PWM_IR_PWMMRn(4),		/**< Interrupt flag for PWM match channel 4 */
296
-	PWM_INTSTAT_MR6 = PWM_IR_PWMMRn(5),		/**< Interrupt flag for PWM match channel 5 */
297
-	PWM_INTSTAT_MR5 = PWM_IR_PWMMRn(6)		/**< Interrupt flag for PWM match channel 6 */
298
-}PWM_INTSTAT_TYPE;
299
-
300
-/** @brief Match update structure */
301
-typedef struct
302
-{
303
-	uint32_t Matchvalue;
304
-	FlagStatus Status;
305
-}PWM_Match_T;
306
-
307
-/**
308
- * @}
309
- */
310
-
311
-
312
-/* Public Functions ----------------------------------------------------------- */
313
-/** @defgroup PWM_Public_Functions PWM Public Functions
314
- * @{
315
- */
316
-
317
-void PWM_PinConfig(LPC_PWM_TypeDef *PWMx, uint8_t PWM_Channel, uint8_t PinselOption);
318
-IntStatus PWM_GetIntStatus(LPC_PWM_TypeDef *PWMx, uint32_t IntFlag);
319
-void PWM_ClearIntPending(LPC_PWM_TypeDef *PWMx, uint32_t IntFlag);
320
-void PWM_ConfigStructInit(uint8_t PWMTimerCounterMode, void *PWM_InitStruct);
321
-void PWM_Init(LPC_PWM_TypeDef *PWMx, uint32_t PWMTimerCounterMode, void *PWM_ConfigStruct);
322
-void PWM_DeInit (LPC_PWM_TypeDef *PWMx);
323
-void PWM_Cmd(LPC_PWM_TypeDef *PWMx, FunctionalState NewState);
324
-void PWM_CounterCmd(LPC_PWM_TypeDef *PWMx, FunctionalState NewState);
325
-void PWM_ResetCounter(LPC_PWM_TypeDef *PWMx);
326
-void PWM_ConfigMatch(LPC_PWM_TypeDef *PWMx, PWM_MATCHCFG_Type *PWM_MatchConfigStruct);
327
-void PWM_ConfigCapture(LPC_PWM_TypeDef *PWMx, PWM_CAPTURECFG_Type *PWM_CaptureConfigStruct);
328
-uint32_t PWM_GetCaptureValue(LPC_PWM_TypeDef *PWMx, uint8_t CaptureChannel);
329
-void PWM_MatchUpdate(LPC_PWM_TypeDef *PWMx, uint8_t MatchChannel, \
330
-					uint32_t MatchValue, uint8_t UpdateType);
331
-void PWM_ChannelConfig(LPC_PWM_TypeDef *PWMx, uint8_t PWMChannel, uint8_t ModeOption);
332
-void PWM_ChannelCmd(LPC_PWM_TypeDef *PWMx, uint8_t PWMChannel, FunctionalState NewState);
333
-
334
-/**
335
- * @}
336
- */
337
-
338
-#ifdef __cplusplus
339
-}
340
-#endif
341
-
342
-#endif /* LPC17XX_PWM_H_ */
343
-
344
-/**
345
- * @}
346
- */
347
-
348
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 424
frameworks/CMSIS/LPC1768/include/lpc17xx_qei.h Просмотреть файл

@@ -1,424 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_qei.h				2010-05-21
3
-*//**
4
-* @file		lpc17xx_qei.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for QEI firmware library on LPC17xx
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @defgroup QEI QEI (Quadrature Encoder Interface)
35
- * @ingroup LPC1700CMSIS_FwLib_Drivers
36
- * @{
37
- */
38
-
39
-#ifndef LPC17XX_QEI_H_
40
-#define LPC17XX_QEI_H_
41
-
42
-/* Includes ------------------------------------------------------------------- */
43
-#include "LPC17xx.h"
44
-#include "lpc_types.h"
45
-
46
-
47
-#ifdef __cplusplus
48
-extern "C"
49
-{
50
-#endif
51
-
52
-/* Public Macros -------------------------------------------------------------- */
53
-/** @defgroup QEI_Public_Macros QEI Public Macros
54
- * @{
55
- */
56
-
57
-/* QEI Reset types */
58
-#define QEI_RESET_POS			QEI_CON_RESP		/**< Reset position counter */
59
-#define QEI_RESET_POSOnIDX		QEI_CON_RESPI		/**< Reset Posistion Counter on Index */
60
-#define QEI_RESET_VEL			QEI_CON_RESV		/**< Reset Velocity */
61
-#define QEI_RESET_IDX			QEI_CON_RESI		/**< Reset Index Counter */
62
-
63
-/* QEI Direction Invert Type Option */
64
-#define QEI_DIRINV_NONE		((uint32_t)(0))		/**< Direction is not inverted */
65
-#define QEI_DIRINV_CMPL		((uint32_t)(1))		/**< Direction is complemented */
66
-
67
-/* QEI Signal Mode Option */
68
-#define QEI_SIGNALMODE_QUAD		((uint32_t)(0))		/**< Signal operation: Quadrature phase mode */
69
-#define QEI_SIGNALMODE_CLKDIR	((uint32_t)(1))		/**< Signal operation: Clock/Direction mode */
70
-
71
-/* QEI Capture Mode Option */
72
-#define QEI_CAPMODE_2X			((uint32_t)(0))		/**< Capture mode: Only Phase-A edges are counted (2X) */
73
-#define QEI_CAPMODE_4X			((uint32_t)(1))		/**< Capture mode: BOTH PhA and PhB edges are counted (4X)*/
74
-
75
-/* QEI Invert Index Signal Option */
76
-#define QEI_INVINX_NONE			((uint32_t)(0))		/**< Invert Index signal option: None */
77
-#define QEI_INVINX_EN			((uint32_t)(1))		/**< Invert Index signal option: Enable */
78
-
79
-/* QEI timer reload option */
80
-#define QEI_TIMERRELOAD_TICKVAL	((uint8_t)(0))	/**< Reload value in absolute value */
81
-#define QEI_TIMERRELOAD_USVAL	((uint8_t)(1))	/**< Reload value in microsecond value */
82
-
83
-/* QEI Flag Status type */
84
-#define QEI_STATUS_DIR			((uint32_t)(1<<0))	/**< Direction status */
85
-
86
-/* QEI Compare Position channel option */
87
-#define QEI_COMPPOS_CH_0			((uint8_t)(0))		/**< QEI compare position channel 0 */
88
-#define QEI_COMPPOS_CH_1			((uint8_t)(1))		/**< QEI compare position channel 1 */
89
-#define QEI_COMPPOS_CH_2			((uint8_t)(2))		/**< QEI compare position channel 2 */
90
-
91
-/* QEI interrupt flag type */
92
-#define QEI_INTFLAG_INX_Int			((uint32_t)(1<<0))	/**< index pulse was detected interrupt */
93
-#define QEI_INTFLAG_TIM_Int			((uint32_t)(1<<1))	/**< Velocity timer over flow interrupt */
94
-#define QEI_INTFLAG_VELC_Int		((uint32_t)(1<<2))	/**< Capture velocity is less than compare interrupt */
95
-#define QEI_INTFLAG_DIR_Int			((uint32_t)(1<<3))	/**< Change of direction interrupt */
96
-#define QEI_INTFLAG_ERR_Int			((uint32_t)(1<<4))	/**< An encoder phase error interrupt */
97
-#define QEI_INTFLAG_ENCLK_Int		((uint32_t)(1<<5))	/**< An encoder clock pulse was detected interrupt */
98
-#define QEI_INTFLAG_POS0_Int		((uint32_t)(1<<6))	/**< position 0 compare value is equal to the
99
-														current position interrupt */
100
-#define QEI_INTFLAG_POS1_Int		((uint32_t)(1<<7))	/**< position 1 compare value is equal to the
101
-														current position interrupt */
102
-#define QEI_INTFLAG_POS2_Int		((uint32_t)(1<<8))	/**< position 2 compare value is equal to the
103
-														current position interrupt */
104
-#define QEI_INTFLAG_REV_Int			((uint32_t)(1<<9))	/**< Index compare value is equal to the current
105
-														index count interrupt */
106
-#define QEI_INTFLAG_POS0REV_Int		((uint32_t)(1<<10))	/**< Combined position 0 and revolution count interrupt */
107
-#define QEI_INTFLAG_POS1REV_Int		((uint32_t)(1<<11))	/**< Combined position 1 and revolution count interrupt */
108
-#define QEI_INTFLAG_POS2REV_Int		((uint32_t)(1<<12))	/**< Combined position 2 and revolution count interrupt */
109
-
110
-/**
111
- * @}
112
- */
113
-
114
-
115
-/* Private Macros ------------------------------------------------------------- */
116
-/** @defgroup QEI_Private_Macros QEI Private Macros
117
- * @{
118
- */
119
-
120
-/* --------------------- BIT DEFINITIONS -------------------------------------- */
121
-/* Quadrature Encoder Interface Control Register Definition --------------------- */
122
-/*********************************************************************//**
123
- * Macro defines for QEI Control register
124
- **********************************************************************/
125
-#define QEI_CON_RESP		((uint32_t)(1<<0))		/**< Reset position counter */
126
-#define QEI_CON_RESPI		((uint32_t)(1<<1))		/**< Reset Posistion Counter on Index */
127
-#define QEI_CON_RESV		((uint32_t)(1<<2))		/**< Reset Velocity */
128
-#define QEI_CON_RESI		((uint32_t)(1<<3))		/**< Reset Index Counter */
129
-#define QEI_CON_BITMASK		((uint32_t)(0x0F))		/**< QEI Control register bit-mask */
130
-
131
-/*********************************************************************//**
132
- * Macro defines for QEI Configuration register
133
- **********************************************************************/
134
-#define QEI_CONF_DIRINV		((uint32_t)(1<<0))		/**< Direction Invert */
135
-#define QEI_CONF_SIGMODE	((uint32_t)(1<<1))		/**< Signal mode */
136
-#define QEI_CONF_CAPMODE	((uint32_t)(1<<2))		/**< Capture mode */
137
-#define QEI_CONF_INVINX		((uint32_t)(1<<3))		/**< Invert index */
138
-#define QEI_CONF_BITMASK	((uint32_t)(0x0F))		/**< QEI Configuration register bit-mask */
139
-
140
-/*********************************************************************//**
141
- * Macro defines for QEI Status register
142
- **********************************************************************/
143
-#define QEI_STAT_DIR		((uint32_t)(1<<0))		/**< Direction bit */
144
-#define QEI_STAT_BITMASK	((uint32_t)(1<<0))		/**< QEI status register bit-mask */
145
-
146
-/* Quadrature Encoder Interface Interrupt registers definitions --------------------- */
147
-/*********************************************************************//**
148
- * Macro defines for QEI Interrupt Status register
149
- **********************************************************************/
150
-#define QEI_INTSTAT_INX_Int			((uint32_t)(1<<0))	/**< Indicates that an index pulse was detected */
151
-#define QEI_INTSTAT_TIM_Int			((uint32_t)(1<<1))	/**< Indicates that a velocity timer overflow occurred */
152
-#define QEI_INTSTAT_VELC_Int		((uint32_t)(1<<2))	/**< Indicates that capture velocity is less than compare velocity */
153
-#define QEI_INTSTAT_DIR_Int			((uint32_t)(1<<3))	/**< Indicates that a change of direction was detected */
154
-#define QEI_INTSTAT_ERR_Int			((uint32_t)(1<<4))	/**< Indicates that an encoder phase error was detected */
155
-#define QEI_INTSTAT_ENCLK_Int		((uint32_t)(1<<5))	/**< Indicates that and encoder clock pulse was detected */
156
-#define QEI_INTSTAT_POS0_Int		((uint32_t)(1<<6))	/**< Indicates that the position 0 compare value is equal to the
157
-														current position */
158
-#define QEI_INTSTAT_POS1_Int		((uint32_t)(1<<7))	/**< Indicates that the position 1compare value is equal to the
159
-														current position */
160
-#define QEI_INTSTAT_POS2_Int		((uint32_t)(1<<8))	/**< Indicates that the position 2 compare value is equal to the
161
-														current position */
162
-#define QEI_INTSTAT_REV_Int			((uint32_t)(1<<9))	/**< Indicates that the index compare value is equal to the current
163
-														index count */
164
-#define QEI_INTSTAT_POS0REV_Int		((uint32_t)(1<<10))	/**< Combined position 0 and revolution count interrupt. Set when
165
-														both the POS0_Int bit is set and the REV_Int is set */
166
-#define QEI_INTSTAT_POS1REV_Int		((uint32_t)(1<<11))	/**< Combined position 1 and revolution count interrupt. Set when
167
-														both the POS1_Int bit is set and the REV_Int is set */
168
-#define QEI_INTSTAT_POS2REV_Int		((uint32_t)(1<<12))	/**< Combined position 2 and revolution count interrupt. Set when
169
-														both the POS2_Int bit is set and the REV_Int is set */
170
-#define QEI_INTSTAT_BITMASK			((uint32_t)(0x1FFF))	/**< QEI Interrupt Status register bit-mask */
171
-
172
-/*********************************************************************//**
173
- * Macro defines for QEI Interrupt Set register
174
- **********************************************************************/
175
-#define QEI_INTSET_INX_Int			((uint32_t)(1<<0))	/**< Set Bit Indicates that an index pulse was detected */
176
-#define QEI_INTSET_TIM_Int			((uint32_t)(1<<1))	/**< Set Bit Indicates that a velocity timer overflow occurred */
177
-#define QEI_INTSET_VELC_Int			((uint32_t)(1<<2))	/**< Set Bit Indicates that capture velocity is less than compare velocity */
178
-#define QEI_INTSET_DIR_Int			((uint32_t)(1<<3))	/**< Set Bit Indicates that a change of direction was detected */
179
-#define QEI_INTSET_ERR_Int			((uint32_t)(1<<4))	/**< Set Bit Indicates that an encoder phase error was detected */
180
-#define QEI_INTSET_ENCLK_Int		((uint32_t)(1<<5))	/**< Set Bit Indicates that and encoder clock pulse was detected */
181
-#define QEI_INTSET_POS0_Int			((uint32_t)(1<<6))	/**< Set Bit Indicates that the position 0 compare value is equal to the
182
-														current position */
183
-#define QEI_INTSET_POS1_Int			((uint32_t)(1<<7))	/**< Set Bit Indicates that the position 1compare value is equal to the
184
-														current position */
185
-#define QEI_INTSET_POS2_Int			((uint32_t)(1<<8))	/**< Set Bit Indicates that the position 2 compare value is equal to the
186
-														current position */
187
-#define QEI_INTSET_REV_Int			((uint32_t)(1<<9))	/**< Set Bit Indicates that the index compare value is equal to the current
188
-														index count */
189
-#define QEI_INTSET_POS0REV_Int		((uint32_t)(1<<10))	/**< Set Bit that combined position 0 and revolution count interrupt */
190
-#define QEI_INTSET_POS1REV_Int		((uint32_t)(1<<11))	/**< Set Bit that Combined position 1 and revolution count interrupt */
191
-#define QEI_INTSET_POS2REV_Int		((uint32_t)(1<<12))	/**< Set Bit that Combined position 2 and revolution count interrupt */
192
-#define QEI_INTSET_BITMASK			((uint32_t)(0x1FFF))	/**< QEI Interrupt Set register bit-mask */
193
-
194
-/*********************************************************************//**
195
- * Macro defines for QEI Interrupt Clear register
196
- **********************************************************************/
197
-#define QEI_INTCLR_INX_Int			((uint32_t)(1<<0))	/**< Clear Bit Indicates that an index pulse was detected */
198
-#define QEI_INTCLR_TIM_Int			((uint32_t)(1<<1))	/**< Clear Bit Indicates that a velocity timer overflow occurred */
199
-#define QEI_INTCLR_VELC_Int			((uint32_t)(1<<2))	/**< Clear Bit Indicates that capture velocity is less than compare velocity */
200
-#define QEI_INTCLR_DIR_Int			((uint32_t)(1<<3))	/**< Clear Bit Indicates that a change of direction was detected */
201
-#define QEI_INTCLR_ERR_Int			((uint32_t)(1<<4))	/**< Clear Bit Indicates that an encoder phase error was detected */
202
-#define QEI_INTCLR_ENCLK_Int		((uint32_t)(1<<5))	/**< Clear Bit Indicates that and encoder clock pulse was detected */
203
-#define QEI_INTCLR_POS0_Int			((uint32_t)(1<<6))	/**< Clear Bit Indicates that the position 0 compare value is equal to the
204
-														current position */
205
-#define QEI_INTCLR_POS1_Int			((uint32_t)(1<<7))	/**< Clear Bit Indicates that the position 1compare value is equal to the
206
-														current position */
207
-#define QEI_INTCLR_POS2_Int			((uint32_t)(1<<8))	/**< Clear Bit Indicates that the position 2 compare value is equal to the
208
-														current position */
209
-#define QEI_INTCLR_REV_Int			((uint32_t)(1<<9))	/**< Clear Bit Indicates that the index compare value is equal to the current
210
-														index count */
211
-#define QEI_INTCLR_POS0REV_Int		((uint32_t)(1<<10))	/**< Clear Bit that combined position 0 and revolution count interrupt */
212
-#define QEI_INTCLR_POS1REV_Int		((uint32_t)(1<<11))	/**< Clear Bit that Combined position 1 and revolution count interrupt */
213
-#define QEI_INTCLR_POS2REV_Int		((uint32_t)(1<<12))	/**< Clear Bit that Combined position 2 and revolution count interrupt */
214
-#define QEI_INTCLR_BITMASK			((uint32_t)(0x1FFF))	/**< QEI Interrupt Clear register bit-mask */
215
-
216
-/*********************************************************************//**
217
- * Macro defines for QEI Interrupt Enable register
218
- **********************************************************************/
219
-#define QEI_INTEN_INX_Int			((uint32_t)(1<<0))	/**< Enabled Interrupt Bit Indicates that an index pulse was detected */
220
-#define QEI_INTEN_TIM_Int			((uint32_t)(1<<1))	/**< Enabled Interrupt Bit Indicates that a velocity timer overflow occurred */
221
-#define QEI_INTEN_VELC_Int			((uint32_t)(1<<2))	/**< Enabled Interrupt Bit Indicates that capture velocity is less than compare velocity */
222
-#define QEI_INTEN_DIR_Int			((uint32_t)(1<<3))	/**< Enabled Interrupt Bit Indicates that a change of direction was detected */
223
-#define QEI_INTEN_ERR_Int			((uint32_t)(1<<4))	/**< Enabled Interrupt Bit Indicates that an encoder phase error was detected */
224
-#define QEI_INTEN_ENCLK_Int			((uint32_t)(1<<5))	/**< Enabled Interrupt Bit Indicates that and encoder clock pulse was detected */
225
-#define QEI_INTEN_POS0_Int			((uint32_t)(1<<6))	/**< Enabled Interrupt Bit Indicates that the position 0 compare value is equal to the
226
-														current position */
227
-#define QEI_INTEN_POS1_Int			((uint32_t)(1<<7))	/**< Enabled Interrupt Bit Indicates that the position 1compare value is equal to the
228
-														current position */
229
-#define QEI_INTEN_POS2_Int			((uint32_t)(1<<8))	/**< Enabled Interrupt Bit Indicates that the position 2 compare value is equal to the
230
-														current position */
231
-#define QEI_INTEN_REV_Int			((uint32_t)(1<<9))	/**< Enabled Interrupt Bit Indicates that the index compare value is equal to the current
232
-														index count */
233
-#define QEI_INTEN_POS0REV_Int		((uint32_t)(1<<10))	/**< Enabled Interrupt Bit that combined position 0 and revolution count interrupt */
234
-#define QEI_INTEN_POS1REV_Int		((uint32_t)(1<<11))	/**< Enabled Interrupt Bit that Combined position 1 and revolution count interrupt */
235
-#define QEI_INTEN_POS2REV_Int		((uint32_t)(1<<12))	/**< Enabled Interrupt Bit that Combined position 2 and revolution count interrupt */
236
-#define QEI_INTEN_BITMASK			((uint32_t)(0x1FFF))	/**< QEI Interrupt Enable register bit-mask */
237
-
238
-/*********************************************************************//**
239
- * Macro defines for QEI Interrupt Enable Set register
240
- **********************************************************************/
241
-#define QEI_IESET_INX_Int			((uint32_t)(1<<0))	/**< Set Enable Interrupt Bit Indicates that an index pulse was detected */
242
-#define QEI_IESET_TIM_Int			((uint32_t)(1<<1))	/**< Set Enable Interrupt Bit Indicates that a velocity timer overflow occurred */
243
-#define QEI_IESET_VELC_Int			((uint32_t)(1<<2))	/**< Set Enable Interrupt Bit Indicates that capture velocity is less than compare velocity */
244
-#define QEI_IESET_DIR_Int			((uint32_t)(1<<3))	/**< Set Enable Interrupt Bit Indicates that a change of direction was detected */
245
-#define QEI_IESET_ERR_Int			((uint32_t)(1<<4))	/**< Set Enable Interrupt Bit Indicates that an encoder phase error was detected */
246
-#define QEI_IESET_ENCLK_Int			((uint32_t)(1<<5))	/**< Set Enable Interrupt Bit Indicates that and encoder clock pulse was detected */
247
-#define QEI_IESET_POS0_Int			((uint32_t)(1<<6))	/**< Set Enable Interrupt Bit Indicates that the position 0 compare value is equal to the
248
-														current position */
249
-#define QEI_IESET_POS1_Int			((uint32_t)(1<<7))	/**< Set Enable Interrupt Bit Indicates that the position 1compare value is equal to the
250
-														current position */
251
-#define QEI_IESET_POS2_Int			((uint32_t)(1<<8))	/**< Set Enable Interrupt Bit Indicates that the position 2 compare value is equal to the
252
-														current position */
253
-#define QEI_IESET_REV_Int			((uint32_t)(1<<9))	/**< Set Enable Interrupt Bit Indicates that the index compare value is equal to the current
254
-														index count */
255
-#define QEI_IESET_POS0REV_Int		((uint32_t)(1<<10))	/**< Set Enable Interrupt Bit that combined position 0 and revolution count interrupt */
256
-#define QEI_IESET_POS1REV_Int		((uint32_t)(1<<11))	/**< Set Enable Interrupt Bit that Combined position 1 and revolution count interrupt */
257
-#define QEI_IESET_POS2REV_Int		((uint32_t)(1<<12))	/**< Set Enable Interrupt Bit that Combined position 2 and revolution count interrupt */
258
-#define QEI_IESET_BITMASK			((uint32_t)(0x1FFF))	/**< QEI Interrupt Enable Set register bit-mask */
259
-
260
-/*********************************************************************//**
261
- * Macro defines for QEI Interrupt Enable Clear register
262
- **********************************************************************/
263
-#define QEI_IECLR_INX_Int			((uint32_t)(1<<0))	/**< Clear Enabled Interrupt Bit Indicates that an index pulse was detected */
264
-#define QEI_IECLR_TIM_Int			((uint32_t)(1<<1))	/**< Clear Enabled Interrupt Bit Indicates that a velocity timer overflow occurred */
265
-#define QEI_IECLR_VELC_Int			((uint32_t)(1<<2))	/**< Clear Enabled Interrupt Bit Indicates that capture velocity is less than compare velocity */
266
-#define QEI_IECLR_DIR_Int			((uint32_t)(1<<3))	/**< Clear Enabled Interrupt Bit Indicates that a change of direction was detected */
267
-#define QEI_IECLR_ERR_Int			((uint32_t)(1<<4))	/**< Clear Enabled Interrupt Bit Indicates that an encoder phase error was detected */
268
-#define QEI_IECLR_ENCLK_Int			((uint32_t)(1<<5))	/**< Clear Enabled Interrupt Bit Indicates that and encoder clock pulse was detected */
269
-#define QEI_IECLR_POS0_Int			((uint32_t)(1<<6))	/**< Clear Enabled Interrupt Bit Indicates that the position 0 compare value is equal to the
270
-														current position */
271
-#define QEI_IECLR_POS1_Int			((uint32_t)(1<<7))	/**< Clear Enabled Interrupt Bit Indicates that the position 1compare value is equal to the
272
-														current position */
273
-#define QEI_IECLR_POS2_Int			((uint32_t)(1<<8))	/**< Clear Enabled Interrupt Bit Indicates that the position 2 compare value is equal to the
274
-														current position */
275
-#define QEI_IECLR_REV_Int			((uint32_t)(1<<9))	/**< Clear Enabled Interrupt Bit Indicates that the index compare value is equal to the current
276
-														index count */
277
-#define QEI_IECLR_POS0REV_Int		((uint32_t)(1<<10))	/**< Clear Enabled Interrupt Bit that combined position 0 and revolution count interrupt */
278
-#define QEI_IECLR_POS1REV_Int		((uint32_t)(1<<11))	/**< Clear Enabled Interrupt Bit that Combined position 1 and revolution count interrupt */
279
-#define QEI_IECLR_POS2REV_Int		((uint32_t)(1<<12))	/**< Clear Enabled Interrupt Bit that Combined position 2 and revolution count interrupt */
280
-#define QEI_IECLR_BITMASK			((uint32_t)(0x1FFF))	/**< QEI Interrupt Enable Clear register bit-mask */
281
-
282
-
283
-/* ---------------- CHECK PARAMETER DEFINITIONS ---------------------------- */
284
-/* Macro check QEI peripheral */
285
-#define PARAM_QEIx(n)	((n==LPC_QEI))
286
-
287
-/* Macro check QEI reset type */
288
-#define PARAM_QEI_RESET(n)	((n==QEI_CON_RESP) \
289
-|| (n==QEI_RESET_POSOnIDX) \
290
-|| (n==QEI_RESET_VEL) \
291
-|| (n==QEI_RESET_IDX))
292
-
293
-/* Macro check QEI Direction invert mode */
294
-#define PARAM_QEI_DIRINV(n)	((n==QEI_DIRINV_NONE) || (n==QEI_DIRINV_CMPL))
295
-
296
-/* Macro check QEI signal mode */
297
-#define PARAM_QEI_SIGNALMODE(n)	((n==QEI_SIGNALMODE_QUAD) || (n==QEI_SIGNALMODE_CLKDIR))
298
-
299
-/* Macro check QEI Capture mode */
300
-#define PARAM_QEI_CAPMODE(n)	((n==QEI_CAPMODE_2X) || (n==QEI_CAPMODE_4X))
301
-
302
-/* Macro check QEI Invert index mode */
303
-#define PARAM_QEI_INVINX(n)		((n==QEI_INVINX_NONE) || (n==QEI_INVINX_EN))
304
-
305
-/* Macro check QEI Direction invert mode */
306
-#define PARAM_QEI_TIMERRELOAD(n)	((n==QEI_TIMERRELOAD_TICKVAL) || (n==QEI_TIMERRELOAD_USVAL))
307
-
308
-/* Macro check QEI status type */
309
-#define PARAM_QEI_STATUS(n)		((n==QEI_STATUS_DIR))
310
-
311
-/* Macro check QEI combine position type */
312
-#define PARAM_QEI_COMPPOS_CH(n)		((n==QEI_COMPPOS_CH_0) || (n==QEI_COMPPOS_CH_1) || (n==QEI_COMPPOS_CH_2))
313
-
314
-/* Macro check QEI interrupt flag type */
315
-#define PARAM_QEI_INTFLAG(n)	((n==QEI_INTFLAG_INX_Int) \
316
-|| (n==QEI_INTFLAG_TIM_Int) \
317
-|| (n==QEI_INTFLAG_VELC_Int) \
318
-|| (n==QEI_INTFLAG_DIR_Int) \
319
-|| (n==QEI_INTFLAG_ERR_Int) \
320
-|| (n==QEI_INTFLAG_ENCLK_Int) \
321
-|| (n==QEI_INTFLAG_POS0_Int) \
322
-|| (n==QEI_INTFLAG_POS1_Int) \
323
-|| (n==QEI_INTFLAG_POS2_Int) \
324
-|| (n==QEI_INTFLAG_REV_Int) \
325
-|| (n==QEI_INTFLAG_POS0REV_Int) \
326
-|| (n==QEI_INTFLAG_POS1REV_Int) \
327
-|| (n==QEI_INTFLAG_POS2REV_Int))
328
-/**
329
- * @}
330
- */
331
-
332
-/* Public Types --------------------------------------------------------------- */
333
-/** @defgroup QEI_Public_Types QEI Public Types
334
- * @{
335
- */
336
-
337
-/**
338
- * @brief QEI Configuration structure type definition
339
- */
340
-typedef struct {
341
-	uint32_t DirectionInvert	:1; 	/**< Direction invert option:
342
-										- QEI_DIRINV_NONE: QEI Direction is normal
343
-										- QEI_DIRINV_CMPL: QEI Direction is complemented
344
-										*/
345
-	uint32_t SignalMode			:1; 	/**< Signal mode Option:
346
-										- QEI_SIGNALMODE_QUAD: Signal is in Quadrature phase mode
347
-										- QEI_SIGNALMODE_CLKDIR: Signal is in Clock/Direction mode
348
-										*/
349
-	uint32_t CaptureMode		:1;		/**< Capture Mode Option:
350
-										- QEI_CAPMODE_2X: Only Phase-A edges are counted (2X)
351
-										- QEI_CAPMODE_4X: BOTH Phase-A and Phase-B edges are counted (4X)
352
-										*/
353
-	uint32_t InvertIndex		:1; 	/**< Invert Index Option:
354
-										- QEI_INVINX_NONE: the sense of the index input is normal
355
-										- QEI_INVINX_EN: inverts the sense of the index input
356
-										*/
357
-} QEI_CFG_Type;
358
-
359
-/**
360
- * @brief Timer Reload Configuration structure type definition
361
- */
362
-typedef struct {
363
-
364
-	uint8_t ReloadOption;		/**< Velocity Timer Reload Option, should be:
365
-								- QEI_TIMERRELOAD_TICKVAL: Reload value in absolute value
366
-								- QEI_TIMERRELOAD_USVAL: Reload value in microsecond value
367
-								*/
368
-	uint8_t Reserved[3];
369
-	uint32_t ReloadValue;		/**< Velocity Timer Reload Value, 32-bit long, should be matched
370
-								with Velocity Timer Reload Option
371
-								*/
372
-} QEI_RELOADCFG_Type;
373
-
374
-/**
375
- * @}
376
- */
377
-
378
-
379
-
380
-
381
-
382
-/* Public Functions ----------------------------------------------------------- */
383
-/** @defgroup QEI_Public_Functions QEI Public Functions
384
- * @{
385
- */
386
-
387
-void QEI_Reset(LPC_QEI_TypeDef *QEIx, uint32_t ulResetType);
388
-void QEI_Init(LPC_QEI_TypeDef *QEIx, QEI_CFG_Type *QEI_ConfigStruct);
389
-void QEI_ConfigStructInit(QEI_CFG_Type *QIE_InitStruct);
390
-void QEI_DeInit(LPC_QEI_TypeDef *QEIx);
391
-FlagStatus QEI_GetStatus(LPC_QEI_TypeDef *QEIx, uint32_t ulFlagType);
392
-uint32_t QEI_GetPosition(LPC_QEI_TypeDef *QEIx);
393
-void QEI_SetMaxPosition(LPC_QEI_TypeDef *QEIx, uint32_t ulMaxPos);
394
-void QEI_SetPositionComp(LPC_QEI_TypeDef *QEIx, uint8_t bPosCompCh, uint32_t ulPosComp);
395
-uint32_t QEI_GetIndex(LPC_QEI_TypeDef *QEIx);
396
-void QEI_SetIndexComp(LPC_QEI_TypeDef *QEIx, uint32_t ulIndexComp);
397
-void QEI_SetTimerReload(LPC_QEI_TypeDef *QEIx, QEI_RELOADCFG_Type *QEIReloadStruct);
398
-uint32_t QEI_GetTimer(LPC_QEI_TypeDef *QEIx);
399
-uint32_t QEI_GetVelocity(LPC_QEI_TypeDef *QEIx);
400
-uint32_t QEI_GetVelocityCap(LPC_QEI_TypeDef *QEIx);
401
-void QEI_SetVelocityComp(LPC_QEI_TypeDef *QEIx, uint32_t ulVelComp);
402
-void QEI_SetDigiFilter(LPC_QEI_TypeDef *QEIx, uint32_t ulSamplingPulse);
403
-FlagStatus QEI_GetIntStatus(LPC_QEI_TypeDef *QEIx, uint32_t ulIntType);
404
-void QEI_IntCmd(LPC_QEI_TypeDef *QEIx, uint32_t ulIntType, FunctionalState NewState);
405
-void QEI_IntSet(LPC_QEI_TypeDef *QEIx, uint32_t ulIntType);
406
-void QEI_IntClear(LPC_QEI_TypeDef *QEIx, uint32_t ulIntType);
407
-uint32_t QEI_CalculateRPM(LPC_QEI_TypeDef *QEIx, uint32_t ulVelCapValue, uint32_t ulPPR);
408
-
409
-
410
-/**
411
- * @}
412
- */
413
-
414
-#ifdef __cplusplus
415
-}
416
-#endif
417
-
418
-#endif /* LPC17XX_QEI_H_ */
419
-
420
-/**
421
- * @}
422
- */
423
-
424
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 112
frameworks/CMSIS/LPC1768/include/lpc17xx_rit.h Просмотреть файл

@@ -1,112 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_rit.h				2010-05-21
3
-*//**
4
-* @file		lpc17xx_rit.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for RIT firmware library on LPC17xx
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @defgroup RIT RIT (Repetitive Interrupt Timer)
35
- * @ingroup LPC1700CMSIS_FwLib_Drivers
36
- * @{
37
- */
38
-
39
-#ifndef LPC17XX_RIT_H_
40
-#define LPC17XX_RIT_H_
41
-
42
-/* Includes ------------------------------------------------------------------- */
43
-#include "LPC17xx.h"
44
-#include "lpc_types.h"
45
-
46
-
47
-#ifdef __cplusplus
48
-extern "C"
49
-{
50
-#endif
51
-
52
-
53
-/* Private Macros ------------------------------------------------------------- */
54
-/** @defgroup RIT_Private_Macros RIT Private Macros
55
- * @{
56
- */
57
-
58
-/* --------------------- BIT DEFINITIONS -------------------------------------- */
59
-/*********************************************************************//**
60
- * Macro defines for RIT control register
61
- **********************************************************************/
62
-/**	Set interrupt flag when the counter value equals the masked compare value */
63
-#define RIT_CTRL_INTEN	((uint32_t) (1))
64
-/** Set timer enable clear to 0 when the counter value equals the masked compare value  */
65
-#define RIT_CTRL_ENCLR 	((uint32_t) _BIT(1))
66
-/** Set timer enable on debug */
67
-#define RIT_CTRL_ENBR	((uint32_t) _BIT(2))
68
-/** Set timer enable */
69
-#define RIT_CTRL_TEN	((uint32_t) _BIT(3))
70
-
71
-/** Macro to determine if it is valid RIT peripheral */
72
-#define PARAM_RITx(n)	(((uint32_t *)n)==((uint32_t *)LPC_RIT))
73
-/**
74
- * @}
75
- */
76
-
77
-
78
-
79
-/* Public Functions ----------------------------------------------------------- */
80
-/** @defgroup RIT_Public_Functions RIT Public Functions
81
- * @{
82
- */
83
-/* RIT Init/DeInit functions */
84
-void RIT_Init(LPC_RIT_TypeDef *RITx);
85
-void RIT_DeInit(LPC_RIT_TypeDef *RITx);
86
-
87
-/* RIT config timer functions */
88
-void RIT_TimerConfig(LPC_RIT_TypeDef *RITx, uint32_t time_interval);
89
-
90
-/* Enable/Disable RIT functions */
91
-void RIT_TimerClearCmd(LPC_RIT_TypeDef *RITx, FunctionalState NewState);
92
-void RIT_Cmd(LPC_RIT_TypeDef *RITx, FunctionalState NewState);
93
-void RIT_TimerDebugCmd(LPC_RIT_TypeDef *RITx, FunctionalState NewState);
94
-
95
-/* RIT Interrupt functions */
96
-IntStatus RIT_GetIntStatus(LPC_RIT_TypeDef *RITx);
97
-
98
-/**
99
- * @}
100
- */
101
-
102
-#ifdef __cplusplus
103
-}
104
-#endif
105
-
106
-#endif /* LPC17XX_RIT_H_ */
107
-
108
-/**
109
- * @}
110
- */
111
-
112
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 314
frameworks/CMSIS/LPC1768/include/lpc17xx_rtc.h Просмотреть файл

@@ -1,314 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_rtc.h				2010-05-21
3
-*//**
4
-* @file		lpc17xx_rtc.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for RTC firmware library on LPC17xx
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @defgroup RTC RTC (Real Time Clock)
35
- * @ingroup LPC1700CMSIS_FwLib_Drivers
36
- * @{
37
- */
38
-
39
-#ifndef LPC17XX_RTC_H_
40
-#define LPC17XX_RTC_H_
41
-
42
-/* Includes ------------------------------------------------------------------- */
43
-#include "LPC17xx.h"
44
-#include "lpc_types.h"
45
-
46
-
47
-#ifdef __cplusplus
48
-extern "C"
49
-{
50
-#endif
51
-
52
-
53
-/* Private Macros ------------------------------------------------------------- */
54
-/** @defgroup RTC_Private_Macros RTC Private Macros
55
- * @{
56
- */
57
-
58
-/* ----------------------- BIT DEFINITIONS ----------------------------------- */
59
-/* Miscellaneous register group --------------------------------------------- */
60
-/**********************************************************************
61
-* ILR register definitions
62
-**********************************************************************/
63
-/** ILR register mask */
64
-#define RTC_ILR_BITMASK			((0x00000003))
65
-/** Bit inform the source interrupt is counter increment*/
66
-#define RTC_IRL_RTCCIF			((1<<0))
67
-/** Bit inform the source interrupt is alarm match*/
68
-#define RTC_IRL_RTCALF			((1<<1))
69
-
70
-/**********************************************************************
71
-* CCR register definitions
72
-**********************************************************************/
73
-/** CCR register mask */
74
-#define RTC_CCR_BITMASK			((0x00000013))
75
-/** Clock enable */
76
-#define RTC_CCR_CLKEN			((1<<0))
77
-/** Clock reset */
78
-#define RTC_CCR_CTCRST			((1<<1))
79
-/** Calibration counter enable */
80
-#define RTC_CCR_CCALEN			((1<<4))
81
-
82
-/**********************************************************************
83
-* CIIR register definitions
84
-**********************************************************************/
85
-/** Counter Increment Interrupt bit for second */
86
-#define RTC_CIIR_IMSEC			((1<<0))
87
-/** Counter Increment Interrupt bit for minute */
88
-#define RTC_CIIR_IMMIN			((1<<1))
89
-/** Counter Increment Interrupt bit for hour */
90
-#define RTC_CIIR_IMHOUR			((1<<2))
91
-/** Counter Increment Interrupt bit for day of month */
92
-#define RTC_CIIR_IMDOM			((1<<3))
93
-/** Counter Increment Interrupt bit for day of week */
94
-#define RTC_CIIR_IMDOW			((1<<4))
95
-/** Counter Increment Interrupt bit for day of year */
96
-#define RTC_CIIR_IMDOY			((1<<5))
97
-/** Counter Increment Interrupt bit for month */
98
-#define RTC_CIIR_IMMON			((1<<6))
99
-/** Counter Increment Interrupt bit for year */
100
-#define RTC_CIIR_IMYEAR			((1<<7))
101
-/** CIIR bit mask */
102
-#define RTC_CIIR_BITMASK		((0xFF))
103
-
104
-/**********************************************************************
105
-* AMR register definitions
106
-**********************************************************************/
107
-/** Counter Increment Select Mask bit for second */
108
-#define RTC_AMR_AMRSEC			((1<<0))
109
-/** Counter Increment Select Mask bit for minute */
110
-#define RTC_AMR_AMRMIN			((1<<1))
111
-/** Counter Increment Select Mask bit for hour */
112
-#define RTC_AMR_AMRHOUR			((1<<2))
113
-/** Counter Increment Select Mask bit for day of month */
114
-#define RTC_AMR_AMRDOM			((1<<3))
115
-/** Counter Increment Select Mask bit for day of week */
116
-#define RTC_AMR_AMRDOW			((1<<4))
117
-/** Counter Increment Select Mask bit for day of year */
118
-#define RTC_AMR_AMRDOY			((1<<5))
119
-/** Counter Increment Select Mask bit for month */
120
-#define RTC_AMR_AMRMON			((1<<6))
121
-/** Counter Increment Select Mask bit for year */
122
-#define RTC_AMR_AMRYEAR			((1<<7))
123
-/** AMR bit mask */
124
-#define RTC_AMR_BITMASK			((0xFF))
125
-
126
-/**********************************************************************
127
-* RTC_AUX register definitions
128
-**********************************************************************/
129
-/** RTC Oscillator Fail detect flag */
130
-#define RTC_AUX_RTC_OSCF		((1<<4))
131
-
132
-/**********************************************************************
133
-* RTC_AUXEN register definitions
134
-**********************************************************************/
135
-/** Oscillator Fail Detect interrupt enable*/
136
-#define RTC_AUXEN_RTC_OSCFEN	((1<<4))
137
-
138
-/* Consolidated time register group ----------------------------------- */
139
-/**********************************************************************
140
-* Consolidated Time Register 0 definitions
141
-**********************************************************************/
142
-#define RTC_CTIME0_SECONDS_MASK		((0x3F))
143
-#define RTC_CTIME0_MINUTES_MASK		((0x3F00))
144
-#define RTC_CTIME0_HOURS_MASK		((0x1F0000))
145
-#define RTC_CTIME0_DOW_MASK			((0x7000000))
146
-
147
-/**********************************************************************
148
-* Consolidated Time Register 1 definitions
149
-**********************************************************************/
150
-#define RTC_CTIME1_DOM_MASK			((0x1F))
151
-#define RTC_CTIME1_MONTH_MASK		((0xF00))
152
-#define RTC_CTIME1_YEAR_MASK		((0xFFF0000))
153
-
154
-/**********************************************************************
155
-* Consolidated Time Register 2 definitions
156
-**********************************************************************/
157
-#define RTC_CTIME2_DOY_MASK			((0xFFF))
158
-
159
-/**********************************************************************
160
-* Time Counter Group and Alarm register group
161
-**********************************************************************/
162
-/** SEC register mask */
163
-#define RTC_SEC_MASK			(0x0000003F)
164
-/** MIN register mask */
165
-#define RTC_MIN_MASK			(0x0000003F)
166
-/** HOUR register mask */
167
-#define RTC_HOUR_MASK			(0x0000001F)
168
-/** DOM register mask */
169
-#define RTC_DOM_MASK			(0x0000001F)
170
-/** DOW register mask */
171
-#define RTC_DOW_MASK			(0x00000007)
172
-/** DOY register mask */
173
-#define RTC_DOY_MASK			(0x000001FF)
174
-/** MONTH register mask */
175
-#define RTC_MONTH_MASK			(0x0000000F)
176
-/** YEAR register mask */
177
-#define RTC_YEAR_MASK			(0x00000FFF)
178
-
179
-#define RTC_SECOND_MAX		59 /*!< Maximum value of second */
180
-#define RTC_MINUTE_MAX		59 /*!< Maximum value of minute*/
181
-#define RTC_HOUR_MAX		23 /*!< Maximum value of hour*/
182
-#define RTC_MONTH_MIN		1 /*!< Minimum value of month*/
183
-#define RTC_MONTH_MAX		12 /*!< Maximum value of month*/
184
-#define RTC_DAYOFMONTH_MIN 	1 /*!< Minimum value of day of month*/
185
-#define RTC_DAYOFMONTH_MAX 	31 /*!< Maximum value of day of month*/
186
-#define RTC_DAYOFWEEK_MAX	6 /*!< Maximum value of day of week*/
187
-#define RTC_DAYOFYEAR_MIN	1 /*!< Minimum value of day of year*/
188
-#define RTC_DAYOFYEAR_MAX	366 /*!< Maximum value of day of year*/
189
-#define RTC_YEAR_MAX		4095 /*!< Maximum value of year*/
190
-
191
-/**********************************************************************
192
-* Calibration register
193
-**********************************************************************/
194
-/* Calibration register */
195
-/** Calibration value */
196
-#define RTC_CALIBRATION_CALVAL_MASK		((0x1FFFF))
197
-/** Calibration direction */
198
-#define RTC_CALIBRATION_LIBDIR			((1<<17))
199
-/** Calibration max value */
200
-#define RTC_CALIBRATION_MAX				((0x20000))
201
-/** Calibration definitions */
202
-#define RTC_CALIB_DIR_FORWARD			((uint8_t)(0))
203
-#define RTC_CALIB_DIR_BACKWARD			((uint8_t)(1))
204
-
205
-
206
-/* ---------------- CHECK PARAMETER DEFINITIONS ---------------------------- */
207
-/** Macro to determine if it is valid RTC peripheral */
208
-#define PARAM_RTCx(x)	(((uint32_t *)x)==((uint32_t *)LPC_RTC))
209
-
210
-/* Macro check RTC interrupt type */
211
-#define PARAM_RTC_INT(n)	((n==RTC_INT_COUNTER_INCREASE) || (n==RTC_INT_ALARM))
212
-
213
-/* Macro check RTC time type */
214
-#define PARAM_RTC_TIMETYPE(n)	((n==RTC_TIMETYPE_SECOND) || (n==RTC_TIMETYPE_MINUTE) \
215
-|| (n==RTC_TIMETYPE_HOUR) || (n==RTC_TIMETYPE_DAYOFWEEK) \
216
-|| (n==RTC_TIMETYPE_DAYOFMONTH) || (n==RTC_TIMETYPE_DAYOFYEAR) \
217
-|| (n==RTC_TIMETYPE_MONTH) || (n==RTC_TIMETYPE_YEAR))
218
-
219
-/* Macro check RTC calibration type */
220
-#define PARAM_RTC_CALIB_DIR(n)	((n==RTC_CALIB_DIR_FORWARD) || (n==RTC_CALIB_DIR_BACKWARD))
221
-
222
-/* Macro check RTC GPREG type */
223
-#define PARAM_RTC_GPREG_CH(n)	(n<=4)
224
-
225
-/**
226
- * @}
227
- */
228
-
229
-
230
-/* Public Types --------------------------------------------------------------- */
231
-/** @defgroup RTC_Public_Types RTC Public Types
232
- * @{
233
- */
234
-
235
-/** @brief Time structure definitions for easy manipulate the data */
236
-typedef struct {
237
-	uint32_t SEC; 		/*!< Seconds Register */
238
-	uint32_t MIN; 		/*!< Minutes Register */
239
-	uint32_t HOUR; 		/*!< Hours Register */
240
-	uint32_t DOM;		/*!< Day of Month Register */
241
-	uint32_t DOW; 		/*!< Day of Week Register */
242
-	uint32_t DOY; 		/*!< Day of Year Register */
243
-	uint32_t MONTH; 	/*!< Months Register */
244
-	uint32_t YEAR; 		/*!< Years Register */
245
-} RTC_TIME_Type;
246
-
247
-/** @brief RTC interrupt source */
248
-typedef enum {
249
-	RTC_INT_COUNTER_INCREASE = RTC_IRL_RTCCIF, 	/*!<  Counter Increment Interrupt */
250
-	RTC_INT_ALARM = RTC_IRL_RTCALF 				/*!< The alarm interrupt */
251
-} RTC_INT_OPT;
252
-
253
-
254
-/** @brief RTC time type option */
255
-typedef enum {
256
-	RTC_TIMETYPE_SECOND = 0, 		/*!< Second */
257
-	RTC_TIMETYPE_MINUTE = 1, 		/*!< Month */
258
-	RTC_TIMETYPE_HOUR = 2, 			/*!< Hour */
259
-	RTC_TIMETYPE_DAYOFWEEK = 3, 	/*!< Day of week */
260
-	RTC_TIMETYPE_DAYOFMONTH = 4, 	/*!< Day of month */
261
-	RTC_TIMETYPE_DAYOFYEAR = 5, 	/*!< Day of year */
262
-	RTC_TIMETYPE_MONTH = 6, 		/*!< Month */
263
-	RTC_TIMETYPE_YEAR = 7 			/*!< Year */
264
-} RTC_TIMETYPE_Num;
265
-
266
-/**
267
- * @}
268
- */
269
-
270
-
271
-
272
-/* Public Functions ----------------------------------------------------------- */
273
-/** @defgroup RTC_Public_Functions RTC Public Functions
274
- * @{
275
- */
276
-
277
-void RTC_Init (LPC_RTC_TypeDef *RTCx);
278
-void RTC_DeInit(LPC_RTC_TypeDef *RTCx);
279
-void RTC_ResetClockTickCounter(LPC_RTC_TypeDef *RTCx);
280
-void RTC_Cmd (LPC_RTC_TypeDef *RTCx, FunctionalState NewState);
281
-void RTC_CntIncrIntConfig (LPC_RTC_TypeDef *RTCx, uint32_t CntIncrIntType, \
282
-								FunctionalState NewState);
283
-void RTC_AlarmIntConfig (LPC_RTC_TypeDef *RTCx, uint32_t AlarmTimeType, \
284
-								FunctionalState NewState);
285
-void RTC_SetTime (LPC_RTC_TypeDef *RTCx, uint32_t Timetype, uint32_t TimeValue);
286
-uint32_t RTC_GetTime(LPC_RTC_TypeDef *RTCx, uint32_t Timetype);
287
-void RTC_SetFullTime (LPC_RTC_TypeDef *RTCx, RTC_TIME_Type *pFullTime);
288
-void RTC_GetFullTime (LPC_RTC_TypeDef *RTCx, RTC_TIME_Type *pFullTime);
289
-void RTC_SetAlarmTime (LPC_RTC_TypeDef *RTCx, uint32_t Timetype, uint32_t ALValue);
290
-uint32_t RTC_GetAlarmTime (LPC_RTC_TypeDef *RTCx, uint32_t Timetype);
291
-void RTC_SetFullAlarmTime (LPC_RTC_TypeDef *RTCx, RTC_TIME_Type *pFullTime);
292
-void RTC_GetFullAlarmTime (LPC_RTC_TypeDef *RTCx, RTC_TIME_Type *pFullTime);
293
-IntStatus RTC_GetIntPending (LPC_RTC_TypeDef *RTCx, uint32_t IntType);
294
-void RTC_ClearIntPending (LPC_RTC_TypeDef *RTCx, uint32_t IntType);
295
-void RTC_CalibCounterCmd(LPC_RTC_TypeDef *RTCx, FunctionalState NewState);
296
-void RTC_CalibConfig(LPC_RTC_TypeDef *RTCx, uint32_t CalibValue, uint8_t CalibDir);
297
-void RTC_WriteGPREG (LPC_RTC_TypeDef *RTCx, uint8_t Channel, uint32_t Value);
298
-uint32_t RTC_ReadGPREG (LPC_RTC_TypeDef *RTCx, uint8_t Channel);
299
-
300
-/**
301
- * @}
302
- */
303
-
304
-#ifdef __cplusplus
305
-}
306
-#endif
307
-
308
-#endif /* LPC17XX_RTC_H_ */
309
-
310
-/**
311
- * @}
312
- */
313
-
314
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 328
frameworks/CMSIS/LPC1768/include/lpc17xx_spi.h Просмотреть файл

@@ -1,328 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_spi.h				2010-05-21
3
-*//**
4
-* @file		lpc17xx_spi.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for SPI firmware library on LPC17xx
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @defgroup SPI SPI (Serial Peripheral Interface)
35
- * @ingroup LPC1700CMSIS_FwLib_Drivers
36
- * @{
37
- */
38
-
39
-#ifndef LPC17XX_SPI_H_
40
-#define LPC17XX_SPI_H_
41
-
42
-/* Includes ------------------------------------------------------------------- */
43
-#include "LPC17xx.h"
44
-#include "lpc_types.h"
45
-
46
-
47
-#ifdef __cplusplus
48
-extern "C"
49
-{
50
-#endif
51
-
52
-/* Public Macros -------------------------------------------------------------- */
53
-/** @defgroup SPI_Public_Macros SPI Public Macros
54
- * @{
55
- */
56
-
57
-/*********************************************************************//**
58
- * SPI configuration parameter defines
59
- **********************************************************************/
60
-/** Clock phase control bit */
61
-#define SPI_CPHA_FIRST			((uint32_t)(0))
62
-#define SPI_CPHA_SECOND			((uint32_t)(1<<3))
63
-
64
-/** Clock polarity control bit */
65
-#define SPI_CPOL_HI				((uint32_t)(0))
66
-#define SPI_CPOL_LO				((uint32_t)(1<<4))
67
-
68
-/** SPI master mode enable */
69
-#define SPI_SLAVE_MODE			((uint32_t)(0))
70
-#define SPI_MASTER_MODE			((uint32_t)(1<<5))
71
-
72
-/** LSB enable bit */
73
-#define SPI_DATA_MSB_FIRST		((uint32_t)(0))
74
-#define SPI_DATA_LSB_FIRST		((uint32_t)(1<<6))
75
-
76
-/** SPI data bit number defines */
77
-#define SPI_DATABIT_16		SPI_SPCR_BITS(0)		/*!< Databit number = 16 */
78
-#define SPI_DATABIT_8		SPI_SPCR_BITS(0x08) 	/*!< Databit number = 8 */
79
-#define SPI_DATABIT_9		SPI_SPCR_BITS(0x09) 	/*!< Databit number = 9 */
80
-#define SPI_DATABIT_10		SPI_SPCR_BITS(0x0A) 	/*!< Databit number = 10 */
81
-#define SPI_DATABIT_11		SPI_SPCR_BITS(0x0B) 	/*!< Databit number = 11 */
82
-#define SPI_DATABIT_12		SPI_SPCR_BITS(0x0C) 	/*!< Databit number = 12 */
83
-#define SPI_DATABIT_13		SPI_SPCR_BITS(0x0D) 	/*!< Databit number = 13 */
84
-#define SPI_DATABIT_14		SPI_SPCR_BITS(0x0E) 	/*!< Databit number = 14 */
85
-#define SPI_DATABIT_15		SPI_SPCR_BITS(0x0F) 	/*!< Databit number = 15 */
86
-
87
-/*********************************************************************//**
88
- * SPI Status Flag defines
89
- **********************************************************************/
90
-/** Slave abort */
91
-#define SPI_STAT_ABRT		SPI_SPSR_ABRT
92
-/** Mode fault */
93
-#define SPI_STAT_MODF		SPI_SPSR_MODF
94
-/** Read overrun */
95
-#define SPI_STAT_ROVR		SPI_SPSR_ROVR
96
-/** Write collision */
97
-#define SPI_STAT_WCOL		SPI_SPSR_WCOL
98
-/** SPI transfer complete flag */
99
-#define SPI_STAT_SPIF		SPI_SPSR_SPIF
100
-
101
-/* SPI Status Implementation definitions */
102
-#define SPI_STAT_DONE		(1UL<<8)		/**< Done */
103
-#define SPI_STAT_ERROR		(1UL<<9)		/**< Error */
104
-
105
-/**
106
- * @}
107
- */
108
-
109
-
110
-/* Private Macros ------------------------------------------------------------- */
111
-/** @defgroup SPI_Private_Macros SPI Private Macros
112
- * @{
113
- */
114
-
115
-/* --------------------- BIT DEFINITIONS -------------------------------------- */
116
-/*********************************************************************//**
117
- * Macro defines for SPI Control Register
118
- **********************************************************************/
119
-/** Bit enable, the SPI controller sends and receives the number
120
- * of bits selected by bits 11:8 */
121
-#define SPI_SPCR_BIT_EN			((uint32_t)(1<<2))
122
-/** Clock phase control bit */
123
-#define SPI_SPCR_CPHA_SECOND	((uint32_t)(1<<3))
124
-/** Clock polarity control bit */
125
-#define SPI_SPCR_CPOL_LOW 		((uint32_t)(1<<4))
126
-/** SPI master mode enable */
127
-#define SPI_SPCR_MSTR		 	((uint32_t)(1<<5))
128
-/** LSB enable bit */
129
-#define SPI_SPCR_LSBF			((uint32_t)(1<<6))
130
-/** SPI interrupt enable bit */
131
-#define SPI_SPCR_SPIE			((uint32_t)(1<<7))
132
-/**  When bit 2 of this register is 1, this field controls the
133
-number of bits per transfer */
134
-#define SPI_SPCR_BITS(n)		((n==0) ? ((uint32_t)0) : ((uint32_t)((n&0x0F)<<8)))
135
-/** SPI Control bit mask */
136
-#define SPI_SPCR_BITMASK		((uint32_t)(0xFFC))
137
-
138
-/*********************************************************************//**
139
- * Macro defines for  SPI Status Register
140
- **********************************************************************/
141
-/** Slave abort */
142
-#define SPI_SPSR_ABRT		((uint32_t)(1<<3))
143
-/** Mode fault */
144
-#define SPI_SPSR_MODF		((uint32_t)(1<<4))
145
-/** Read overrun */
146
-#define SPI_SPSR_ROVR		((uint32_t)(1<<5))
147
-/** Write collision */
148
-#define SPI_SPSR_WCOL		((uint32_t)(1<<6))
149
-/** SPI transfer complete flag */
150
-#define SPI_SPSR_SPIF 		((uint32_t)(1<<7))
151
-/** SPI Status bit mask */
152
-#define SPI_SPSR_BITMASK	((uint32_t)(0xF8))
153
-
154
-/*********************************************************************//**
155
- * Macro defines for SPI Data Register
156
- **********************************************************************/
157
-/** SPI Data low bit-mask */
158
-#define SPI_SPDR_LO_MASK	((uint32_t)(0xFF))
159
-/** SPI Data high bit-mask */
160
-#define SPI_SPDR_HI_MASK	((uint32_t)(0xFF00))
161
-/** SPI Data bit-mask */
162
-#define SPI_SPDR_BITMASK	((uint32_t)(0xFFFF))
163
-
164
-/*********************************************************************//**
165
- * Macro defines for SPI Clock Counter Register
166
- **********************************************************************/
167
-/** SPI clock counter setting */
168
-#define SPI_SPCCR_COUNTER(n) 	((uint32_t)(n&0xFF))
169
-/** SPI clock counter bit-mask */
170
-#define SPI_SPCCR_BITMASK		((uint32_t)(0xFF))
171
-
172
-/***********************************************************************
173
- * Macro defines for SPI Test Control Register
174
- **********************************************************************/
175
-/** SPI Test bit */
176
-#define SPI_SPTCR_TEST_MASK	((uint32_t)(0xFE))
177
-/** SPI Test register bit mask */
178
-#define SPI_SPTCR_BITMASK	((uint32_t)(0xFE))
179
-
180
-/*********************************************************************//**
181
- * Macro defines for SPI Test Status Register
182
- **********************************************************************/
183
-/** Slave abort */
184
-#define SPI_SPTSR_ABRT		((uint32_t)(1<<3))
185
-/** Mode fault */
186
-#define SPI_SPTSR_MODF		((uint32_t)(1<<4))
187
-/** Read overrun */
188
-#define SPI_SPTSR_ROVR		((uint32_t)(1<<5))
189
-/** Write collision */
190
-#define SPI_SPTSR_WCOL		((uint32_t)(1<<6))
191
-/** SPI transfer complete flag */
192
-#define SPI_SPTSR_SPIF 		((uint32_t)(1<<7))
193
-/** SPI Status bit mask */
194
-#define SPI_SPTSR_MASKBIT	((uint32_t)(0xF8))
195
-
196
-/*********************************************************************//**
197
- * Macro defines for SPI Interrupt Register
198
- **********************************************************************/
199
-/** SPI interrupt flag */
200
-#define SPI_SPINT_INTFLAG 	((uint32_t)(1<<0))
201
-/** SPI interrupt register bit mask */
202
-#define SPI_SPINT_BITMASK 	((uint32_t)(0x01))
203
-
204
-
205
-/* ---------------- CHECK PARAMETER DEFINITIONS ---------------------------- */
206
-/** Macro to determine if it is valid SPI port number */
207
-#define PARAM_SPIx(n)	(((uint32_t *)n)==((uint32_t *)LPC_SPI))
208
-
209
-/** Macro check Clock phase control mode */
210
-#define PARAM_SPI_CPHA(n) 	((n==SPI_CPHA_FIRST) || (n==SPI_CPHA_SECOND))
211
-
212
-/** Macro check Clock polarity control mode */
213
-#define PARAM_SPI_CPOL(n)	((n==SPI_CPOL_HI) || (n==SPI_CPOL_LO))
214
-
215
-/** Macro check master/slave mode */
216
-#define PARAM_SPI_MODE(n)	((n==SPI_SLAVE_MODE) || (n==SPI_MASTER_MODE))
217
-
218
-/** Macro check LSB/MSB mode */
219
-#define PARAM_SPI_DATA_ORDER(n) ((n==SPI_DATA_MSB_FIRST) || (n==SPI_DATA_LSB_FIRST))
220
-
221
-/** Macro check databit value */
222
-#define PARAM_SPI_DATABIT(n)	((n==SPI_DATABIT_16) || (n==SPI_DATABIT_8) \
223
-|| (n==SPI_DATABIT_9) || (n==SPI_DATABIT_10) \
224
-|| (n==SPI_DATABIT_11) || (n==SPI_DATABIT_12) \
225
-|| (n==SPI_DATABIT_13) || (n==SPI_DATABIT_14) \
226
-|| (n==SPI_DATABIT_15))
227
-
228
-/** Macro check status flag */
229
-#define PARAM_SPI_STAT(n)	((n==SPI_STAT_ABRT) || (n==SPI_STAT_MODF) \
230
-|| (n==SPI_STAT_ROVR) || (n==SPI_STAT_WCOL) \
231
-|| (n==SPI_STAT_SPIF))
232
-
233
-/**
234
- * @}
235
- */
236
-
237
-
238
-/* Public Types --------------------------------------------------------------- */
239
-/** @defgroup SPI_Public_Types SPI Public Types
240
- * @{
241
- */
242
-
243
-/** @brief SPI configuration structure */
244
-typedef struct {
245
-	uint32_t Databit; 		/** Databit number, should be SPI_DATABIT_x,
246
-							where x is in range from 8 - 16 */
247
-	uint32_t CPHA;			/** Clock phase, should be:
248
-							- SPI_CPHA_FIRST: first clock edge
249
-							- SPI_CPHA_SECOND: second clock edge */
250
-	uint32_t CPOL;			/** Clock polarity, should be:
251
-							- SPI_CPOL_HI: high level
252
-							- SPI_CPOL_LO: low level */
253
-	uint32_t Mode;			/** SPI mode, should be:
254
-							- SPI_MASTER_MODE: Master mode
255
-							- SPI_SLAVE_MODE: Slave mode */
256
-	uint32_t DataOrder;		/** Data order, should be:
257
-							- SPI_DATA_MSB_FIRST: MSB first
258
-							- SPI_DATA_LSB_FIRST: LSB first */
259
-	uint32_t ClockRate;		/** Clock rate,in Hz, should not exceed
260
-							(SPI peripheral clock)/8 */
261
-} SPI_CFG_Type;
262
-
263
-
264
-/**
265
- * @brief SPI Transfer Type definitions
266
- */
267
-typedef enum {
268
-	SPI_TRANSFER_POLLING = 0,	/**< Polling transfer */
269
-	SPI_TRANSFER_INTERRUPT		/**< Interrupt transfer */
270
-} SPI_TRANSFER_Type;
271
-
272
-/**
273
- * @brief SPI Data configuration structure definitions
274
- */
275
-typedef struct {
276
-	void *tx_data;				/**< Pointer to transmit data */
277
-	void *rx_data;				/**< Pointer to transmit data */
278
-	uint32_t length;			/**< Length of transfer data */
279
-	uint32_t counter;			/**< Data counter index */
280
-	uint32_t status;			/**< Current status of SPI activity */
281
-} SPI_DATA_SETUP_Type;
282
-
283
-/**
284
- * @}
285
- */
286
-
287
-
288
-/* Public Functions ----------------------------------------------------------- */
289
-/** @defgroup SPI_Public_Functions SPI Public Functions
290
- * @{
291
- */
292
-
293
-/* SPI Init/DeInit functions ---------*/
294
-void SPI_Init(LPC_SPI_TypeDef *SPIx, SPI_CFG_Type *SPI_ConfigStruct);
295
-void SPI_DeInit(LPC_SPI_TypeDef *SPIx);
296
-void SPI_SetClock (LPC_SPI_TypeDef *SPIx, uint32_t target_clock);
297
-void SPI_ConfigStructInit(SPI_CFG_Type *SPI_InitStruct);
298
-
299
-/* SPI transfer functions ------------*/
300
-void SPI_SendData(LPC_SPI_TypeDef *SPIx, uint16_t Data);
301
-uint16_t SPI_ReceiveData(LPC_SPI_TypeDef *SPIx);
302
-int32_t SPI_ReadWrite (LPC_SPI_TypeDef *SPIx, SPI_DATA_SETUP_Type *dataCfg, SPI_TRANSFER_Type xfType);
303
-
304
-/* SPI Interrupt functions ---------*/
305
-void SPI_IntCmd(LPC_SPI_TypeDef *SPIx, FunctionalState NewState);
306
-IntStatus SPI_GetIntStatus (LPC_SPI_TypeDef *SPIx);
307
-void SPI_ClearIntPending(LPC_SPI_TypeDef *SPIx);
308
-
309
-/* SPI get information functions-----*/
310
-uint8_t SPI_GetDataSize (LPC_SPI_TypeDef *SPIx);
311
-uint32_t SPI_GetStatus(LPC_SPI_TypeDef *SPIx);
312
-FlagStatus SPI_CheckStatus (uint32_t inputSPIStatus,  uint8_t SPIStatus);
313
-
314
-/**
315
- * @}
316
- */
317
-
318
-#ifdef __cplusplus
319
-}
320
-#endif
321
-
322
-#endif /* LPC17XX_SPI_H_ */
323
-
324
-/**
325
- * @}
326
- */
327
-
328
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 472
frameworks/CMSIS/LPC1768/include/lpc17xx_ssp.h Просмотреть файл

@@ -1,472 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_ssp.h				2010-06-18
3
-*//**
4
-* @file		lpc17xx_ssp.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for SSP firmware library on LPC17xx
7
-* @version	3.0
8
-* @date		18. June. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @defgroup SSP SSP (Synchronous Serial Port)
35
- * @ingroup LPC1700CMSIS_FwLib_Drivers
36
- * @{
37
- */
38
-
39
-#ifndef LPC17XX_SSP_H_
40
-#define LPC17XX_SSP_H_
41
-
42
-/* Includes ------------------------------------------------------------------- */
43
-#include "LPC17xx.h"
44
-#include "lpc_types.h"
45
-
46
-
47
-#ifdef __cplusplus
48
-extern "C"
49
-{
50
-#endif
51
-
52
-/* Public Macros -------------------------------------------------------------- */
53
-/** @defgroup SSP_Public_Macros SSP Public Macros
54
- * @{
55
- */
56
-
57
-/*********************************************************************//**
58
- * SSP configuration parameter defines
59
- **********************************************************************/
60
-/** Clock phase control bit */
61
-#define SSP_CPHA_FIRST			((uint32_t)(0))
62
-#define SSP_CPHA_SECOND			SSP_CR0_CPHA_SECOND
63
-
64
-
65
-/** Clock polarity control bit */
66
-/* There's no bug here!!!
67
- * - If bit[6] in SSPnCR0 is 0: SSP controller maintains the bus clock low between frames.
68
- * That means the active clock is in HI state.
69
- * - If bit[6] in SSPnCR0 is 1 (SSP_CR0_CPOL_HI): SSP controller maintains the bus clock
70
- * high between frames. That means the active clock is in LO state.
71
- */
72
-#define SSP_CPOL_HI				((uint32_t)(0))
73
-#define SSP_CPOL_LO				SSP_CR0_CPOL_HI
74
-
75
-/** SSP master mode enable */
76
-#define SSP_SLAVE_MODE			SSP_CR1_SLAVE_EN
77
-#define SSP_MASTER_MODE			((uint32_t)(0))
78
-
79
-/** SSP data bit number defines */
80
-#define SSP_DATABIT_4		SSP_CR0_DSS(4) 			/*!< Databit number = 4 */
81
-#define SSP_DATABIT_5		SSP_CR0_DSS(5) 			/*!< Databit number = 5 */
82
-#define SSP_DATABIT_6		SSP_CR0_DSS(6) 			/*!< Databit number = 6 */
83
-#define SSP_DATABIT_7		SSP_CR0_DSS(7) 			/*!< Databit number = 7 */
84
-#define SSP_DATABIT_8		SSP_CR0_DSS(8) 			/*!< Databit number = 8 */
85
-#define SSP_DATABIT_9		SSP_CR0_DSS(9) 			/*!< Databit number = 9 */
86
-#define SSP_DATABIT_10		SSP_CR0_DSS(10) 		/*!< Databit number = 10 */
87
-#define SSP_DATABIT_11		SSP_CR0_DSS(11) 		/*!< Databit number = 11 */
88
-#define SSP_DATABIT_12		SSP_CR0_DSS(12) 		/*!< Databit number = 12 */
89
-#define SSP_DATABIT_13		SSP_CR0_DSS(13) 		/*!< Databit number = 13 */
90
-#define SSP_DATABIT_14		SSP_CR0_DSS(14) 		/*!< Databit number = 14 */
91
-#define SSP_DATABIT_15		SSP_CR0_DSS(15) 		/*!< Databit number = 15 */
92
-#define SSP_DATABIT_16		SSP_CR0_DSS(16) 		/*!< Databit number = 16 */
93
-
94
-/** SSP Frame Format definition */
95
-/** Motorola SPI mode */
96
-#define SSP_FRAME_SPI		SSP_CR0_FRF_SPI
97
-/** TI synchronous serial mode */
98
-#define SSP_FRAME_TI		SSP_CR0_FRF_TI
99
-/** National Micro-wire mode */
100
-#define SSP_FRAME_MICROWIRE	SSP_CR0_FRF_MICROWIRE
101
-
102
-/*********************************************************************//**
103
- * SSP Status defines
104
- **********************************************************************/
105
-/** SSP status TX FIFO Empty bit */
106
-#define SSP_STAT_TXFIFO_EMPTY		SSP_SR_TFE
107
-/** SSP status TX FIFO not full bit */
108
-#define SSP_STAT_TXFIFO_NOTFULL		SSP_SR_TNF
109
-/** SSP status RX FIFO not empty bit */
110
-#define SSP_STAT_RXFIFO_NOTEMPTY	SSP_SR_RNE
111
-/** SSP status RX FIFO full bit */
112
-#define SSP_STAT_RXFIFO_FULL		SSP_SR_RFF
113
-/** SSP status SSP Busy bit */
114
-#define SSP_STAT_BUSY				SSP_SR_BSY
115
-
116
-/*********************************************************************//**
117
- * SSP Interrupt Configuration defines
118
- **********************************************************************/
119
-/** Receive Overrun */
120
-#define SSP_INTCFG_ROR		SSP_IMSC_ROR
121
-/** Receive TimeOut */
122
-#define SSP_INTCFG_RT		SSP_IMSC_RT
123
-/** Rx FIFO is at least half full */
124
-#define SSP_INTCFG_RX		SSP_IMSC_RX
125
-/** Tx FIFO is at least half empty */
126
-#define SSP_INTCFG_TX		SSP_IMSC_TX
127
-
128
-/*********************************************************************//**
129
- * SSP Configured Interrupt Status defines
130
- **********************************************************************/
131
-/** Receive Overrun */
132
-#define SSP_INTSTAT_ROR		SSP_MIS_ROR
133
-/** Receive TimeOut */
134
-#define SSP_INTSTAT_RT		SSP_MIS_RT
135
-/** Rx FIFO is at least half full */
136
-#define SSP_INTSTAT_RX		SSP_MIS_RX
137
-/** Tx FIFO is at least half empty */
138
-#define SSP_INTSTAT_TX		SSP_MIS_TX
139
-
140
-/*********************************************************************//**
141
- * SSP Raw Interrupt Status defines
142
- **********************************************************************/
143
-/** Receive Overrun */
144
-#define SSP_INTSTAT_RAW_ROR		SSP_RIS_ROR
145
-/** Receive TimeOut */
146
-#define SSP_INTSTAT_RAW_RT		SSP_RIS_RT
147
-/** Rx FIFO is at least half full */
148
-#define SSP_INTSTAT_RAW_RX		SSP_RIS_RX
149
-/** Tx FIFO is at least half empty */
150
-#define SSP_INTSTAT_RAW_TX		SSP_RIS_TX
151
-
152
-/*********************************************************************//**
153
- * SSP Interrupt Clear defines
154
- **********************************************************************/
155
-/** Writing a 1 to this bit clears the "frame was received when
156
- * RxFIFO was full" interrupt */
157
-#define SSP_INTCLR_ROR		SSP_ICR_ROR
158
-/** Writing a 1 to this bit clears the "Rx FIFO was not empty and
159
- * has not been read for a timeout period" interrupt */
160
-#define SSP_INTCLR_RT		SSP_ICR_RT
161
-
162
-/*********************************************************************//**
163
- * SSP DMA defines
164
- **********************************************************************/
165
-/** SSP bit for enabling RX DMA */
166
-#define SSP_DMA_RX		SSP_DMA_RXDMA_EN
167
-/** SSP bit for enabling TX DMA */
168
-#define SSP_DMA_TX		SSP_DMA_TXDMA_EN
169
-
170
-/* SSP Status Implementation definitions */
171
-#define SSP_STAT_DONE		(1UL<<8)		/**< Done */
172
-#define SSP_STAT_ERROR		(1UL<<9)		/**< Error */
173
-
174
-/**
175
- * @}
176
- */
177
-
178
-/* Private Macros ------------------------------------------------------------- */
179
-/** @defgroup SSP_Private_Macros SSP Private Macros
180
- * @{
181
- */
182
-
183
-/* --------------------- BIT DEFINITIONS -------------------------------------- */
184
-/*********************************************************************//**
185
- * Macro defines for CR0 register
186
- **********************************************************************/
187
-/** SSP data size select, must be 4 bits to 16 bits */
188
-#define SSP_CR0_DSS(n)   		((uint32_t)((n-1)&0xF))
189
-/** SSP control 0 Motorola SPI mode */
190
-#define SSP_CR0_FRF_SPI  		((uint32_t)(0<<4))
191
-/** SSP control 0 TI synchronous serial mode */
192
-#define SSP_CR0_FRF_TI   		((uint32_t)(1<<4))
193
-/** SSP control 0 National Micro-wire mode */
194
-#define SSP_CR0_FRF_MICROWIRE  	((uint32_t)(2<<4))
195
-/** SPI clock polarity bit (used in SPI mode only), (1) = maintains the
196
-   bus clock high between frames, (0) = low */
197
-#define SSP_CR0_CPOL_HI		((uint32_t)(1<<6))
198
-/** SPI clock out phase bit (used in SPI mode only), (1) = captures data
199
-   on the second clock transition of the frame, (0) = first */
200
-#define SSP_CR0_CPHA_SECOND	((uint32_t)(1<<7))
201
-/** SSP serial clock rate value load macro, divider rate is
202
-   PERIPH_CLK / (cpsr * (SCR + 1)) */
203
-#define SSP_CR0_SCR(n)   	((uint32_t)((n&0xFF)<<8))
204
-/** SSP CR0 bit mask */
205
-#define SSP_CR0_BITMASK		((uint32_t)(0xFFFF))
206
-
207
-/*********************************************************************//**
208
- * Macro defines for CR1 register
209
- **********************************************************************/
210
-/** SSP control 1 loopback mode enable bit */
211
-#define SSP_CR1_LBM_EN		((uint32_t)(1<<0))
212
-/** SSP control 1 enable bit */
213
-#define SSP_CR1_SSP_EN		((uint32_t)(1<<1))
214
-/** SSP control 1 slave enable */
215
-#define SSP_CR1_SLAVE_EN	((uint32_t)(1<<2))
216
-/** SSP control 1 slave out disable bit, disables transmit line in slave
217
-   mode */
218
-#define SSP_CR1_SO_DISABLE	((uint32_t)(1<<3))
219
-/** SSP CR1 bit mask */
220
-#define SSP_CR1_BITMASK		((uint32_t)(0x0F))
221
-
222
-/*********************************************************************//**
223
- * Macro defines for DR register
224
- **********************************************************************/
225
-/** SSP data bit mask */
226
-#define SSP_DR_BITMASK(n)   ((n)&0xFFFF)
227
-
228
-/*********************************************************************//**
229
- * Macro defines for SR register
230
- **********************************************************************/
231
-/** SSP status TX FIFO Empty bit */
232
-#define SSP_SR_TFE      ((uint32_t)(1<<0))
233
-/** SSP status TX FIFO not full bit */
234
-#define SSP_SR_TNF      ((uint32_t)(1<<1))
235
-/** SSP status RX FIFO not empty bit */
236
-#define SSP_SR_RNE      ((uint32_t)(1<<2))
237
-/** SSP status RX FIFO full bit */
238
-#define SSP_SR_RFF      ((uint32_t)(1<<3))
239
-/** SSP status SSP Busy bit */
240
-#define SSP_SR_BSY      ((uint32_t)(1<<4))
241
-/** SSP SR bit mask */
242
-#define SSP_SR_BITMASK	((uint32_t)(0x1F))
243
-
244
-/*********************************************************************//**
245
- * Macro defines for CPSR register
246
- **********************************************************************/
247
-/** SSP clock prescaler */
248
-#define SSP_CPSR_CPDVSR(n) 	((uint32_t)(n&0xFF))
249
-/** SSP CPSR bit mask */
250
-#define SSP_CPSR_BITMASK	((uint32_t)(0xFF))
251
-
252
-/*********************************************************************//**
253
- * Macro define for (IMSC) Interrupt Mask Set/Clear registers
254
- **********************************************************************/
255
-/** Receive Overrun */
256
-#define SSP_IMSC_ROR	((uint32_t)(1<<0))
257
-/** Receive TimeOut */
258
-#define SSP_IMSC_RT		((uint32_t)(1<<1))
259
-/** Rx FIFO is at least half full */
260
-#define SSP_IMSC_RX		((uint32_t)(1<<2))
261
-/** Tx FIFO is at least half empty */
262
-#define SSP_IMSC_TX		((uint32_t)(1<<3))
263
-/** IMSC bit mask */
264
-#define SSP_IMSC_BITMASK	((uint32_t)(0x0F))
265
-
266
-/*********************************************************************//**
267
- * Macro define for (RIS) Raw Interrupt Status registers
268
- **********************************************************************/
269
-/** Receive Overrun */
270
-#define SSP_RIS_ROR		((uint32_t)(1<<0))
271
-/** Receive TimeOut */
272
-#define SSP_RIS_RT		((uint32_t)(1<<1))
273
-/** Rx FIFO is at least half full */
274
-#define SSP_RIS_RX		((uint32_t)(1<<2))
275
-/** Tx FIFO is at least half empty */
276
-#define SSP_RIS_TX		((uint32_t)(1<<3))
277
-/** RIS bit mask */
278
-#define SSP_RIS_BITMASK	((uint32_t)(0x0F))
279
-
280
-/*********************************************************************//**
281
- * Macro define for (MIS) Masked Interrupt Status registers
282
- **********************************************************************/
283
-/** Receive Overrun */
284
-#define SSP_MIS_ROR		((uint32_t)(1<<0))
285
-/** Receive TimeOut */
286
-#define SSP_MIS_RT		((uint32_t)(1<<1))
287
-/** Rx FIFO is at least half full */
288
-#define SSP_MIS_RX		((uint32_t)(1<<2))
289
-/** Tx FIFO is at least half empty */
290
-#define SSP_MIS_TX		((uint32_t)(1<<3))
291
-/** MIS bit mask */
292
-#define SSP_MIS_BITMASK	((uint32_t)(0x0F))
293
-
294
-/*********************************************************************//**
295
- * Macro define for (ICR) Interrupt Clear registers
296
- **********************************************************************/
297
-/** Writing a 1 to this bit clears the "frame was received when
298
- * RxFIFO was full" interrupt */
299
-#define SSP_ICR_ROR		((uint32_t)(1<<0))
300
-/** Writing a 1 to this bit clears the "Rx FIFO was not empty and
301
- * has not been read for a timeout period" interrupt */
302
-#define SSP_ICR_RT		((uint32_t)(1<<1))
303
-/** ICR bit mask */
304
-#define SSP_ICR_BITMASK	((uint32_t)(0x03))
305
-
306
-/*********************************************************************//**
307
- * Macro defines for DMACR register
308
- **********************************************************************/
309
-/** SSP bit for enabling RX DMA */
310
-#define SSP_DMA_RXDMA_EN  	((uint32_t)(1<<0))
311
-/** SSP bit for enabling TX DMA */
312
-#define SSP_DMA_TXDMA_EN  	((uint32_t)(1<<1))
313
-/** DMACR	bit mask */
314
-#define SSP_DMA_BITMASK		((uint32_t)(0x03))
315
-
316
-
317
-/* ---------------- CHECK PARAMETER DEFINITIONS ---------------------------- */
318
-/** Macro to determine if it is valid SSP port number */
319
-#define PARAM_SSPx(n)	((((uint32_t *)n)==((uint32_t *)LPC_SSP0)) \
320
-|| (((uint32_t *)n)==((uint32_t *)LPC_SSP1)))
321
-
322
-/** Macro check clock phase control mode */
323
-#define PARAM_SSP_CPHA(n) 		((n==SSP_CPHA_FIRST) || (n==SSP_CPHA_SECOND))
324
-
325
-/** Macro check clock polarity mode */
326
-#define PARAM_SSP_CPOL(n)		((n==SSP_CPOL_HI) || (n==SSP_CPOL_LO))
327
-
328
-/* Macro check master/slave mode */
329
-#define PARAM_SSP_MODE(n)		((n==SSP_SLAVE_MODE) || (n==SSP_MASTER_MODE))
330
-
331
-/* Macro check databit value */
332
-#define PARAM_SSP_DATABIT(n) 	((n==SSP_DATABIT_4) || (n==SSP_DATABIT_5) \
333
-|| (n==SSP_DATABIT_6) || (n==SSP_DATABIT_16) \
334
-|| (n==SSP_DATABIT_7) || (n==SSP_DATABIT_8) \
335
-|| (n==SSP_DATABIT_9) || (n==SSP_DATABIT_10) \
336
-|| (n==SSP_DATABIT_11) || (n==SSP_DATABIT_12) \
337
-|| (n==SSP_DATABIT_13) || (n==SSP_DATABIT_14) \
338
-|| (n==SSP_DATABIT_15))
339
-
340
-/* Macro check frame type */
341
-#define PARAM_SSP_FRAME(n) ((n==SSP_FRAME_SPI) || (n==SSP_FRAME_TI)\
342
-|| (n==SSP_FRAME_MICROWIRE))
343
-
344
-/* Macro check SSP status */
345
-#define PARAM_SSP_STAT(n) ((n==SSP_STAT_TXFIFO_EMPTY) || (n==SSP_STAT_TXFIFO_NOTFULL) \
346
-|| (n==SSP_STAT_RXFIFO_NOTEMPTY) || (n==SSP_STAT_RXFIFO_FULL) \
347
-|| (n==SSP_STAT_BUSY))
348
-
349
-/* Macro check interrupt configuration */
350
-#define PARAM_SSP_INTCFG(n)	((n==SSP_INTCFG_ROR) || (n==SSP_INTCFG_RT) \
351
-|| (n==SSP_INTCFG_RX) || (n==SSP_INTCFG_TX))
352
-
353
-/* Macro check interrupt status value */
354
-#define PARAM_SSP_INTSTAT(n) ((n==SSP_INTSTAT_ROR) || (n==SSP_INTSTAT_RT) \
355
-|| (n==SSP_INTSTAT_RX) || (n==SSP_INTSTAT_TX))
356
-
357
-/* Macro check interrupt status raw value */
358
-#define PARAM_SSP_INTSTAT_RAW(n)	((n==SSP_INTSTAT_RAW_ROR) || (n==SSP_INTSTAT_RAW_RT) \
359
-|| (n==SSP_INTSTAT_RAW_RX) || (n==SSP_INTSTAT_RAW_TX))
360
-
361
-/* Macro check interrupt clear mode */
362
-#define PARAM_SSP_INTCLR(n)	((n==SSP_INTCLR_ROR) || (n==SSP_INTCLR_RT))
363
-
364
-/* Macro check DMA mode */
365
-#define PARAM_SSP_DMA(n)	((n==SSP_DMA_TX) || (n==SSP_DMA_RX))
366
-/**
367
- * @}
368
- */
369
-
370
-
371
-/* Public Types --------------------------------------------------------------- */
372
-/** @defgroup SSP_Public_Types SSP Public Types
373
- * @{
374
- */
375
-
376
-/** @brief SSP configuration structure */
377
-typedef struct {
378
-	uint32_t Databit; 		/** Databit number, should be SSP_DATABIT_x,
379
-							where x is in range from 4 - 16 */
380
-	uint32_t CPHA;			/** Clock phase, should be:
381
-							- SSP_CPHA_FIRST: first clock edge
382
-							- SSP_CPHA_SECOND: second clock edge */
383
-	uint32_t CPOL;			/** Clock polarity, should be:
384
-							- SSP_CPOL_HI: high level
385
-							- SSP_CPOL_LO: low level */
386
-	uint32_t Mode;			/** SSP mode, should be:
387
-							- SSP_MASTER_MODE: Master mode
388
-							- SSP_SLAVE_MODE: Slave mode */
389
-	uint32_t FrameFormat;	/** Frame Format:
390
-							- SSP_FRAME_SPI: Motorola SPI frame format
391
-							- SSP_FRAME_TI: TI frame format
392
-							- SSP_FRAME_MICROWIRE: National Microwire frame format */
393
-	uint32_t ClockRate;		/** Clock rate,in Hz */
394
-} SSP_CFG_Type;
395
-
396
-/**
397
- * @brief SSP Transfer Type definitions
398
- */
399
-typedef enum {
400
-	SSP_TRANSFER_POLLING = 0,	/**< Polling transfer */
401
-	SSP_TRANSFER_INTERRUPT		/**< Interrupt transfer */
402
-} SSP_TRANSFER_Type;
403
-
404
-/**
405
- * @brief SPI Data configuration structure definitions
406
- */
407
-typedef struct {
408
-	void *tx_data;				/**< Pointer to transmit data */
409
-	uint32_t tx_cnt;			/**< Transmit counter */
410
-	void *rx_data;				/**< Pointer to transmit data */
411
-	uint32_t rx_cnt;			/**< Receive counter */
412
-	uint32_t length;			/**< Length of transfer data */
413
-	uint32_t status;			/**< Current status of SSP activity */
414
-} SSP_DATA_SETUP_Type;
415
-
416
-
417
-/**
418
- * @}
419
- */
420
-
421
-
422
-/* Public Functions ----------------------------------------------------------- */
423
-/** @defgroup SSP_Public_Functions SSP Public Functions
424
- * @{
425
- */
426
-
427
-/* SSP Init/DeInit functions --------------------------------------------------*/
428
-void SSP_Init(LPC_SSP_TypeDef *SSPx, SSP_CFG_Type *SSP_ConfigStruct);
429
-void SSP_DeInit(LPC_SSP_TypeDef* SSPx);
430
-
431
-/* SSP configure functions ----------------------------------------------------*/
432
-void SSP_ConfigStructInit(SSP_CFG_Type *SSP_InitStruct);
433
-
434
-/* SSP enable/disable functions -----------------------------------------------*/
435
-void SSP_Cmd(LPC_SSP_TypeDef* SSPx, FunctionalState NewState);
436
-void SSP_LoopBackCmd(LPC_SSP_TypeDef* SSPx, FunctionalState NewState);
437
-void SSP_SlaveOutputCmd(LPC_SSP_TypeDef* SSPx, FunctionalState NewState);
438
-void SSP_DMACmd(LPC_SSP_TypeDef *SSPx, uint32_t DMAMode, FunctionalState NewState);
439
-
440
-/* SSP get information functions ----------------------------------------------*/
441
-FlagStatus SSP_GetStatus(LPC_SSP_TypeDef* SSPx, uint32_t FlagType);
442
-uint8_t SSP_GetDataSize(LPC_SSP_TypeDef* SSPx);
443
-IntStatus SSP_GetRawIntStatus(LPC_SSP_TypeDef *SSPx, uint32_t RawIntType);
444
-uint32_t SSP_GetRawIntStatusReg(LPC_SSP_TypeDef *SSPx);
445
-IntStatus SSP_GetIntStatus (LPC_SSP_TypeDef *SSPx, uint32_t IntType);
446
-
447
-/* SSP transfer data functions ------------------------------------------------*/
448
-void SSP_SendData(LPC_SSP_TypeDef* SSPx, uint16_t Data);
449
-uint16_t SSP_ReceiveData(LPC_SSP_TypeDef* SSPx);
450
-int32_t SSP_ReadWrite (LPC_SSP_TypeDef *SSPx, SSP_DATA_SETUP_Type *dataCfg, \
451
-						SSP_TRANSFER_Type xfType);
452
-
453
-/* SSP IRQ function ------------------------------------------------------------*/
454
-void SSP_IntConfig(LPC_SSP_TypeDef *SSPx, uint32_t IntType, FunctionalState NewState);
455
-void SSP_ClearIntPending(LPC_SSP_TypeDef *SSPx, uint32_t IntType);
456
-
457
-
458
-/**
459
- * @}
460
- */
461
-
462
-#ifdef __cplusplus
463
-}
464
-#endif
465
-
466
-#endif /* LPC17XX_SSP_H_ */
467
-
468
-/**
469
- * @}
470
- */
471
-
472
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 119
frameworks/CMSIS/LPC1768/include/lpc17xx_systick.h Просмотреть файл

@@ -1,119 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_systick.h				2010-05-21
3
-*//**
4
-* @file		lpc17xx_systick.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for SYSTICK firmware library on LPC17xx
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @defgroup SYSTICK SYSTICK (System Tick)
35
- * @ingroup LPC1700CMSIS_FwLib_Drivers
36
- * @{
37
- */
38
-
39
-#ifndef LPC17XX_SYSTICK_H_
40
-#define LPC17XX_SYSTICK_H_
41
-
42
-/* Includes ------------------------------------------------------------------- */
43
-#include "LPC17xx.h"
44
-#include "lpc_types.h"
45
-
46
-
47
-#ifdef __cplusplus
48
-extern "C"
49
-{
50
-#endif
51
-
52
-
53
-/* Private Macros ------------------------------------------------------------- */
54
-/** @defgroup SYSTICK_Private_Macros SYSTICK Private Macros
55
- * @{
56
- */
57
-/*********************************************************************//**
58
- * Macro defines for System Timer Control and status (STCTRL) register
59
- **********************************************************************/
60
-#define ST_CTRL_ENABLE		((uint32_t)(1<<0))
61
-#define ST_CTRL_TICKINT		((uint32_t)(1<<1))
62
-#define ST_CTRL_CLKSOURCE	((uint32_t)(1<<2))
63
-#define ST_CTRL_COUNTFLAG	((uint32_t)(1<<16))
64
-
65
-/*********************************************************************//**
66
- * Macro defines for System Timer Reload value (STRELOAD) register
67
- **********************************************************************/
68
-#define ST_RELOAD_RELOAD(n)		((uint32_t)(n & 0x00FFFFFF))
69
-
70
-/*********************************************************************//**
71
- * Macro defines for System Timer Current value (STCURRENT) register
72
- **********************************************************************/
73
-#define ST_RELOAD_CURRENT(n)	((uint32_t)(n & 0x00FFFFFF))
74
-
75
-/*********************************************************************//**
76
- * Macro defines for System Timer Calibration value (STCALIB) register
77
- **********************************************************************/
78
-#define ST_CALIB_TENMS(n)		((uint32_t)(n & 0x00FFFFFF))
79
-#define ST_CALIB_SKEW			((uint32_t)(1<<30))
80
-#define ST_CALIB_NOREF			((uint32_t)(1<<31))
81
-
82
-#define CLKSOURCE_EXT			((uint32_t)(0))
83
-#define CLKSOURCE_CPU			((uint32_t)(1))
84
-
85
-/**
86
- * @}
87
- */
88
-
89
-
90
-/* Public Functions ----------------------------------------------------------- */
91
-/** @defgroup SYSTICK_Public_Functions SYSTICK Public Functions
92
- * @{
93
- */
94
-
95
-void SYSTICK_InternalInit(uint32_t time);
96
-void SYSTICK_ExternalInit(uint32_t freq, uint32_t time);
97
-
98
-void SYSTICK_Cmd(FunctionalState NewState);
99
-void SYSTICK_IntCmd(FunctionalState NewState);
100
-uint32_t SYSTICK_GetCurrentValue(void);
101
-void SYSTICK_ClearCounterFlag(void);
102
-
103
-/**
104
- * @}
105
- */
106
-
107
-
108
-#ifdef __cplusplus
109
-}
110
-#endif
111
-
112
-
113
-#endif /* LPC17XX_SYSTICK_H_ */
114
-
115
-/**
116
- * @}
117
- */
118
-
119
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 348
frameworks/CMSIS/LPC1768/include/lpc17xx_timer.h Просмотреть файл

@@ -1,348 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_timer.h				2010-05-21
3
-*//**
4
-* @file		lpc17xx_timer.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for Timer firmware library on LPC17xx
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @defgroup TIM TIM (Timer)
35
- * @ingroup LPC1700CMSIS_FwLib_Drivers
36
- * @{
37
- */
38
-
39
-#ifndef __LPC17XX_TIMER_H_
40
-#define __LPC17XX_TIMER_H_
41
-
42
-/* Includes ------------------------------------------------------------------- */
43
-#include "LPC17xx.h"
44
-#include "lpc_types.h"
45
-
46
-#ifdef __cplusplus
47
-extern "C"
48
-{
49
-#endif
50
-
51
-/* Private Macros ------------------------------------------------------------- */
52
-/** @defgroup TIM_Private_Macros TIM Private Macros
53
- * @{
54
- */
55
-
56
-/* --------------------- BIT DEFINITIONS -------------------------------------- */
57
-/**********************************************************************
58
-** Interrupt information
59
-**********************************************************************/
60
-/** Macro to clean interrupt pending */
61
-#define TIM_IR_CLR(n) _BIT(n)
62
-
63
-/**********************************************************************
64
-** Timer interrupt register definitions
65
-**********************************************************************/
66
-/** Macro for getting a timer match interrupt bit */
67
-#define TIM_MATCH_INT(n)		(_BIT(n & 0x0F))
68
-/** Macro for getting a capture event interrupt bit */
69
-#define TIM_CAP_INT(n)     (_BIT(((n & 0x0F) + 4)))
70
-
71
-/**********************************************************************
72
-* Timer control register definitions
73
-**********************************************************************/
74
-/** Timer/counter enable bit */
75
-#define TIM_ENABLE			((uint32_t)(1<<0))
76
-/** Timer/counter reset bit */
77
-#define TIM_RESET			((uint32_t)(1<<1))
78
-/** Timer control bit mask */
79
-#define TIM_TCR_MASKBIT		((uint32_t)(3))
80
-
81
-/**********************************************************************
82
-* Timer match control register definitions
83
-**********************************************************************/
84
-/** Bit location for interrupt on MRx match, n = 0 to 3 */
85
-#define TIM_INT_ON_MATCH(n)      	(_BIT((n * 3)))
86
-/** Bit location for reset on MRx match, n = 0 to 3 */
87
-#define TIM_RESET_ON_MATCH(n)    	(_BIT(((n * 3) + 1)))
88
-/** Bit location for stop on MRx match, n = 0 to 3 */
89
-#define TIM_STOP_ON_MATCH(n)     	(_BIT(((n * 3) + 2)))
90
-/** Timer Match control bit mask */
91
-#define TIM_MCR_MASKBIT			   ((uint32_t)(0x0FFF))
92
-/** Timer Match control bit mask for specific channel*/
93
-#define	TIM_MCR_CHANNEL_MASKBIT(n)		((uint32_t)(7<<(n*3)))
94
-
95
-/**********************************************************************
96
-* Timer capture control register definitions
97
-**********************************************************************/
98
-/** Bit location for CAP.n on CRx rising edge, n = 0 to 3 */
99
-#define TIM_CAP_RISING(n)   	(_BIT((n * 3)))
100
-/** Bit location for CAP.n on CRx falling edge, n = 0 to 3 */
101
-#define TIM_CAP_FALLING(n)   	(_BIT(((n * 3) + 1)))
102
-/** Bit location for CAP.n on CRx interrupt enable, n = 0 to 3 */
103
-#define TIM_INT_ON_CAP(n)    	(_BIT(((n * 3) + 2)))
104
-/** Mask bit for rising and falling edge bit */
105
-#define TIM_EDGE_MASK(n)		(_SBF((n * 3), 0x03))
106
-/** Timer capture control bit mask */
107
-#define TIM_CCR_MASKBIT			((uint32_t)(0x3F))
108
-/** Timer Capture control bit mask for specific channel*/
109
-#define	TIM_CCR_CHANNEL_MASKBIT(n)		((uint32_t)(7<<(n*3)))
110
-
111
-/**********************************************************************
112
-* Timer external match register definitions
113
-**********************************************************************/
114
-/** Bit location for output state change of MAT.n when external match
115
-   happens, n = 0 to 3 */
116
-#define TIM_EM(n)    			_BIT(n)
117
-/** Output state change of MAT.n when external match happens: no change */
118
-#define TIM_EM_NOTHING    	((uint8_t)(0x0))
119
-/** Output state change of MAT.n when external match happens: low */
120
-#define TIM_EM_LOW         	((uint8_t)(0x1))
121
-/** Output state change of MAT.n when external match happens: high */
122
-#define TIM_EM_HIGH        	((uint8_t)(0x2))
123
-/** Output state change of MAT.n when external match happens: toggle */
124
-#define TIM_EM_TOGGLE      	((uint8_t)(0x3))
125
-/** Macro for setting for the MAT.n change state bits */
126
-#define TIM_EM_SET(n,s) 	(_SBF(((n << 1) + 4), (s & 0x03)))
127
-/** Mask for the MAT.n change state bits */
128
-#define TIM_EM_MASK(n) 		(_SBF(((n << 1) + 4), 0x03))
129
-/** Timer external match bit mask */
130
-#define TIM_EMR_MASKBIT	0x0FFF
131
-
132
-/**********************************************************************
133
-* Timer Count Control Register definitions
134
-**********************************************************************/
135
-/** Mask to get the Counter/timer mode bits */
136
-#define TIM_CTCR_MODE_MASK  0x3
137
-/** Mask to get the count input select bits */
138
-#define TIM_CTCR_INPUT_MASK 0xC
139
-/** Timer Count control bit mask */
140
-#define TIM_CTCR_MASKBIT	0xF
141
-#define TIM_COUNTER_MODE ((uint8_t)(1))
142
-
143
-
144
-/* ---------------- CHECK PARAMETER DEFINITIONS ---------------------------- */
145
-/** Macro to determine if it is valid TIMER peripheral */
146
-#define PARAM_TIMx(n)	((((uint32_t *)n)==((uint32_t *)LPC_TIM0)) || (((uint32_t *)n)==((uint32_t *)LPC_TIM1)) \
147
-|| (((uint32_t *)n)==((uint32_t *)LPC_TIM2)) || (((uint32_t *)n)==((uint32_t *)LPC_TIM3)))
148
-
149
-/* Macro check interrupt type */
150
-#define PARAM_TIM_INT_TYPE(TYPE)	((TYPE ==TIM_MR0_INT)||(TYPE ==TIM_MR1_INT)\
151
-||(TYPE ==TIM_MR2_INT)||(TYPE ==TIM_MR3_INT)\
152
-||(TYPE ==TIM_CR0_INT)||(TYPE ==TIM_CR1_INT))
153
-
154
-/* Macro check TIMER mode */
155
-#define PARAM_TIM_MODE_OPT(MODE)	((MODE == TIM_TIMER_MODE)||(MODE == TIM_COUNTER_RISING_MODE)\
156
-|| (MODE == TIM_COUNTER_RISING_MODE)||(MODE == TIM_COUNTER_RISING_MODE))
157
-
158
-/* Macro check TIMER prescale value */
159
-#define PARAM_TIM_PRESCALE_OPT(OPT)	((OPT == TIM_PRESCALE_TICKVAL)||(OPT == TIM_PRESCALE_USVAL))
160
-
161
-/* Macro check TIMER counter intput mode */
162
-#define PARAM_TIM_COUNTER_INPUT_OPT(OPT)	((OPT == TIM_COUNTER_INCAP0)||(OPT == TIM_COUNTER_INCAP1))
163
-
164
-/* Macro check TIMER external match mode */
165
-#define PARAM_TIM_EXTMATCH_OPT(OPT)	((OPT == TIM_EXTMATCH_NOTHING)||(OPT == TIM_EXTMATCH_LOW)\
166
-||(OPT == TIM_EXTMATCH_HIGH)||(OPT == TIM_EXTMATCH_TOGGLE))
167
-
168
-/* Macro check TIMER external match mode */
169
-#define PARAM_TIM_CAP_MODE_OPT(OPT)	((OPT == TIM_CAPTURE_NONE)||(OPT == TIM_CAPTURE_RISING) \
170
-||(OPT == TIM_CAPTURE_FALLING)||(OPT == TIM_CAPTURE_ANY))
171
-
172
-/**
173
- * @}
174
- */
175
-
176
-
177
-/* Public Types --------------------------------------------------------------- */
178
-/** @defgroup TIM_Public_Types TIM Public Types
179
- * @{
180
- */
181
-
182
-/***********************************************************************
183
- * Timer device enumeration
184
-**********************************************************************/
185
-/** @brief interrupt type */
186
-typedef enum
187
-{
188
-	TIM_MR0_INT =0, /*!< interrupt for Match channel 0*/
189
-	TIM_MR1_INT =1, /*!< interrupt for Match channel 1*/
190
-	TIM_MR2_INT =2, /*!< interrupt for Match channel 2*/
191
-	TIM_MR3_INT =3, /*!< interrupt for Match channel 3*/
192
-	TIM_CR0_INT =4, /*!< interrupt for Capture channel 0*/
193
-	TIM_CR1_INT =5 /*!< interrupt for Capture channel 1*/
194
-}TIM_INT_TYPE;
195
-
196
-/** @brief Timer/counter operating mode */
197
-typedef enum
198
-{
199
-	TIM_TIMER_MODE = 0,				/*!< Timer mode */
200
-	TIM_COUNTER_RISING_MODE,		/*!< Counter rising mode */
201
-	TIM_COUNTER_FALLING_MODE,		/*!< Counter falling mode */
202
-	TIM_COUNTER_ANY_MODE			/*!< Counter on both edges */
203
-} TIM_MODE_OPT;
204
-
205
-/** @brief Timer/Counter prescale option */
206
-typedef enum
207
-{
208
-	TIM_PRESCALE_TICKVAL = 0,		/*!< Prescale in absolute value */
209
-	TIM_PRESCALE_USVAL				/*!< Prescale in microsecond value */
210
-} TIM_PRESCALE_OPT;
211
-
212
-/** @brief Counter input option */
213
-typedef enum
214
-{
215
-	TIM_COUNTER_INCAP0 = 0,			/*!< CAPn.0 input pin for TIMERn */
216
-	TIM_COUNTER_INCAP1,				/*!< CAPn.1 input pin for TIMERn */
217
-} TIM_COUNTER_INPUT_OPT;
218
-
219
-/** @brief Timer/Counter external match option */
220
-typedef enum
221
-{
222
-	TIM_EXTMATCH_NOTHING = 0,		/*!< Do nothing for external output pin if match */
223
-	TIM_EXTMATCH_LOW,				/*!< Force external output pin to low if match */
224
-	TIM_EXTMATCH_HIGH,				/*!< Force external output pin to high if match */
225
-	TIM_EXTMATCH_TOGGLE				/*!< Toggle external output pin if match */
226
-}TIM_EXTMATCH_OPT;
227
-
228
-/** @brief Timer/counter capture mode options */
229
-typedef enum {
230
-	TIM_CAPTURE_NONE = 0,	/*!< No Capture */
231
-	TIM_CAPTURE_RISING,		/*!< Rising capture mode */
232
-	TIM_CAPTURE_FALLING,	/*!< Falling capture mode */
233
-	TIM_CAPTURE_ANY			/*!< On both edges */
234
-} TIM_CAP_MODE_OPT;
235
-
236
-/** @brief Configuration structure in TIMER mode */
237
-typedef struct
238
-{
239
-
240
-	uint8_t PrescaleOption;		/**< Timer Prescale option, should be:
241
-									- TIM_PRESCALE_TICKVAL: Prescale in absolute value
242
-									- TIM_PRESCALE_USVAL: Prescale in microsecond value
243
-									*/
244
-	uint8_t Reserved[3];		/**< Reserved */
245
-	uint32_t PrescaleValue;		/**< Prescale value */
246
-} TIM_TIMERCFG_Type;
247
-
248
-/** @brief Configuration structure in COUNTER mode */
249
-typedef struct {
250
-
251
-	uint8_t CounterOption;		/**< Counter Option, should be:
252
-								- TIM_COUNTER_INCAP0: CAPn.0 input pin for TIMERn
253
-								- TIM_COUNTER_INCAP1: CAPn.1 input pin for TIMERn
254
-								*/
255
-	uint8_t CountInputSelect;
256
-	uint8_t Reserved[2];
257
-} TIM_COUNTERCFG_Type;
258
-
259
-/** @brief Match channel configuration structure */
260
-typedef struct {
261
-	uint8_t MatchChannel;	/**< Match channel, should be in range
262
-							from 0..3 */
263
-	uint8_t IntOnMatch;		/**< Interrupt On match, should be:
264
-							- ENABLE: Enable this function.
265
-							- DISABLE: Disable this function.
266
-							*/
267
-	uint8_t StopOnMatch;	/**< Stop On match, should be:
268
-							- ENABLE: Enable this function.
269
-							- DISABLE: Disable this function.
270
-							*/
271
-	uint8_t ResetOnMatch;	/**< Reset On match, should be:
272
-							- ENABLE: Enable this function.
273
-							- DISABLE: Disable this function.
274
-							*/
275
-
276
-	uint8_t ExtMatchOutputType;	/**< External Match Output type, should be:
277
-							 -	 TIM_EXTMATCH_NOTHING:	Do nothing for external output pin if match
278
-							 -   TIM_EXTMATCH_LOW:	Force external output pin to low if match
279
-							 - 	 TIM_EXTMATCH_HIGH: Force external output pin to high if match
280
-							 -   TIM_EXTMATCH_TOGGLE: Toggle external output pin if match.
281
-							*/
282
-	uint8_t Reserved[3];	/** Reserved */
283
-	uint32_t MatchValue;	/** Match value */
284
-} TIM_MATCHCFG_Type;
285
-
286
-/** @brief Capture Input configuration structure */
287
-typedef struct {
288
-	uint8_t CaptureChannel;	/**< Capture channel, should be in range
289
-							from 0..1 */
290
-	uint8_t RisingEdge;		/**< caption rising edge, should be:
291
-							- ENABLE: Enable rising edge.
292
-							- DISABLE: Disable this function.
293
-							*/
294
-	uint8_t FallingEdge;		/**< caption falling edge, should be:
295
-							- ENABLE: Enable falling edge.
296
-							- DISABLE: Disable this function.
297
-								*/
298
-	uint8_t IntOnCaption;	/**< Interrupt On caption, should be:
299
-							- ENABLE: Enable interrupt function.
300
-							- DISABLE: Disable this function.
301
-							*/
302
-
303
-} TIM_CAPTURECFG_Type;
304
-
305
-/**
306
- * @}
307
- */
308
-
309
-
310
-/* Public Functions ----------------------------------------------------------- */
311
-/** @defgroup TIM_Public_Functions TIM Public Functions
312
- * @{
313
- */
314
-/* Init/DeInit TIM functions -----------*/
315
-void TIM_Init(LPC_TIM_TypeDef *TIMx, TIM_MODE_OPT TimerCounterMode, void *TIM_ConfigStruct);
316
-void TIM_DeInit(LPC_TIM_TypeDef *TIMx);
317
-
318
-/* TIM interrupt functions -------------*/
319
-void TIM_ClearIntPending(LPC_TIM_TypeDef *TIMx, TIM_INT_TYPE IntFlag);
320
-void TIM_ClearIntCapturePending(LPC_TIM_TypeDef *TIMx, TIM_INT_TYPE IntFlag);
321
-FlagStatus TIM_GetIntStatus(LPC_TIM_TypeDef *TIMx, TIM_INT_TYPE IntFlag);
322
-FlagStatus TIM_GetIntCaptureStatus(LPC_TIM_TypeDef *TIMx, TIM_INT_TYPE IntFlag);
323
-
324
-/* TIM configuration functions --------*/
325
-void TIM_ConfigStructInit(TIM_MODE_OPT TimerCounterMode, void *TIM_ConfigStruct);
326
-void TIM_ConfigMatch(LPC_TIM_TypeDef *TIMx, TIM_MATCHCFG_Type *TIM_MatchConfigStruct);
327
-void TIM_UpdateMatchValue(LPC_TIM_TypeDef *TIMx,uint8_t MatchChannel, uint32_t MatchValue);
328
-void TIM_SetMatchExt(LPC_TIM_TypeDef *TIMx,TIM_EXTMATCH_OPT ext_match );
329
-void TIM_ConfigCapture(LPC_TIM_TypeDef *TIMx, TIM_CAPTURECFG_Type *TIM_CaptureConfigStruct);
330
-void TIM_Cmd(LPC_TIM_TypeDef *TIMx, FunctionalState NewState);
331
-
332
-uint32_t TIM_GetCaptureValue(LPC_TIM_TypeDef *TIMx, TIM_COUNTER_INPUT_OPT CaptureChannel);
333
-void TIM_ResetCounter(LPC_TIM_TypeDef *TIMx);
334
-
335
-/**
336
- * @}
337
- */
338
-#ifdef __cplusplus
339
-}
340
-#endif
341
-
342
-#endif /* __LPC17XX_TIMER_H_ */
343
-
344
-/**
345
- * @}
346
- */
347
-
348
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 656
frameworks/CMSIS/LPC1768/include/lpc17xx_uart.h Просмотреть файл

@@ -1,656 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_uart.h				2010-06-18
3
-*//**
4
-* @file		lpc17xx_uart.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for UART firmware library on LPC17xx
7
-* @version	3.0
8
-* @date		18. June. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @defgroup UART UART (Universal Asynchronous Receiver/Transmitter)
35
- * @ingroup LPC1700CMSIS_FwLib_Drivers
36
- * @{
37
- */
38
-
39
-#ifndef __LPC17XX_UART_H
40
-#define __LPC17XX_UART_H
41
-
42
-/* Includes ------------------------------------------------------------------- */
43
-#include "LPC17xx.h"
44
-#include "lpc_types.h"
45
-
46
-
47
-#ifdef __cplusplus
48
-extern "C"
49
-{
50
-#endif
51
-
52
-/* Public Macros -------------------------------------------------------------- */
53
-/** @defgroup UART_Public_Macros  UART Public Macros
54
- * @{
55
- */
56
-
57
-/** UART time-out definitions in case of using Read() and Write function
58
- * with Blocking Flag mode
59
- */
60
-#define UART_BLOCKING_TIMEOUT			(0xFFFFFFFFUL)
61
-
62
-/**
63
- * @}
64
- */
65
-
66
-/* Private Macros ------------------------------------------------------------- */
67
-/** @defgroup UART_Private_Macros UART Private Macros
68
- * @{
69
- */
70
-
71
-/* Accepted Error baud rate value (in percent unit) */
72
-#define UART_ACCEPTED_BAUDRATE_ERROR	(3)			/*!< Acceptable UART baudrate error */
73
-
74
-
75
-/* --------------------- BIT DEFINITIONS -------------------------------------- */
76
-/*********************************************************************//**
77
- * Macro defines for Macro defines for UARTn Receiver Buffer Register
78
- **********************************************************************/
79
-#define UART_RBR_MASKBIT   	((uint8_t)0xFF) 		/*!< UART Received Buffer mask bit (8 bits) */
80
-
81
-/*********************************************************************//**
82
- * Macro defines for Macro defines for UARTn Transmit Holding Register
83
- **********************************************************************/
84
-#define UART_THR_MASKBIT   	((uint8_t)0xFF) 		/*!< UART Transmit Holding mask bit (8 bits) */
85
-
86
-/*********************************************************************//**
87
- * Macro defines for Macro defines for UARTn Divisor Latch LSB register
88
- **********************************************************************/
89
-#define UART_LOAD_DLL(div)	((div) & 0xFF)	/**< Macro for loading least significant halfs of divisors */
90
-#define UART_DLL_MASKBIT	((uint8_t)0xFF)	/*!< Divisor latch LSB bit mask */
91
-
92
-/*********************************************************************//**
93
- * Macro defines for Macro defines for UARTn Divisor Latch MSB register
94
- **********************************************************************/
95
-#define UART_DLM_MASKBIT	((uint8_t)0xFF)			/*!< Divisor latch MSB bit mask */
96
-#define UART_LOAD_DLM(div)  (((div) >> 8) & 0xFF)	/**< Macro for loading most significant halfs of divisors */
97
-
98
-/*********************************************************************//**
99
- * Macro defines for Macro defines for UART interrupt enable register
100
- **********************************************************************/
101
-#define UART_IER_RBRINT_EN		((uint32_t)(1<<0)) 	/*!< RBR Interrupt enable*/
102
-#define UART_IER_THREINT_EN		((uint32_t)(1<<1)) 	/*!< THR Interrupt enable*/
103
-#define UART_IER_RLSINT_EN		((uint32_t)(1<<2)) 	/*!< RX line status interrupt enable*/
104
-#define UART1_IER_MSINT_EN		((uint32_t)(1<<3))	/*!< Modem status interrupt enable */
105
-#define UART1_IER_CTSINT_EN		((uint32_t)(1<<7))	/*!< CTS1 signal transition interrupt enable */
106
-#define UART_IER_ABEOINT_EN		((uint32_t)(1<<8)) 	/*!< Enables the end of auto-baud interrupt */
107
-#define UART_IER_ABTOINT_EN		((uint32_t)(1<<9)) 	/*!< Enables the auto-baud time-out interrupt */
108
-#define UART_IER_BITMASK		((uint32_t)(0x307)) /*!< UART interrupt enable register bit mask */
109
-#define UART1_IER_BITMASK		((uint32_t)(0x38F)) /*!< UART1 interrupt enable register bit mask */
110
-
111
-/*********************************************************************//**
112
- * Macro defines for Macro defines for UART interrupt identification register
113
- **********************************************************************/
114
-#define UART_IIR_INTSTAT_PEND	((uint32_t)(1<<0))	/*!<Interrupt Status - Active low */
115
-#define UART_IIR_INTID_RLS		((uint32_t)(3<<1)) 	/*!<Interrupt identification: Receive line status*/
116
-#define UART_IIR_INTID_RDA		((uint32_t)(2<<1)) 	/*!<Interrupt identification: Receive data available*/
117
-#define UART_IIR_INTID_CTI		((uint32_t)(6<<1)) 	/*!<Interrupt identification: Character time-out indicator*/
118
-#define UART_IIR_INTID_THRE		((uint32_t)(1<<1)) 	/*!<Interrupt identification: THRE interrupt*/
119
-#define UART1_IIR_INTID_MODEM	((uint32_t)(0<<1)) 	/*!<Interrupt identification: Modem interrupt*/
120
-#define UART_IIR_INTID_MASK		((uint32_t)(7<<1))	/*!<Interrupt identification: Interrupt ID mask */
121
-#define UART_IIR_FIFO_EN		((uint32_t)(3<<6)) 	/*!<These bits are equivalent to UnFCR[0] */
122
-#define UART_IIR_ABEO_INT		((uint32_t)(1<<8)) 	/*!< End of auto-baud interrupt */
123
-#define UART_IIR_ABTO_INT		((uint32_t)(1<<9)) 	/*!< Auto-baud time-out interrupt */
124
-#define UART_IIR_BITMASK		((uint32_t)(0x3CF))	/*!< UART interrupt identification register bit mask */
125
-
126
-/*********************************************************************//**
127
- * Macro defines for Macro defines for UART FIFO control register
128
- **********************************************************************/
129
-#define UART_FCR_FIFO_EN		((uint8_t)(1<<0)) 	/*!< UART FIFO enable */
130
-#define UART_FCR_RX_RS			((uint8_t)(1<<1)) 	/*!< UART FIFO RX reset */
131
-#define UART_FCR_TX_RS			((uint8_t)(1<<2)) 	/*!< UART FIFO TX reset */
132
-#define UART_FCR_DMAMODE_SEL 	((uint8_t)(1<<3)) 	/*!< UART DMA mode selection */
133
-#define UART_FCR_TRG_LEV0		((uint8_t)(0)) 		/*!< UART FIFO trigger level 0: 1 character */
134
-#define UART_FCR_TRG_LEV1		((uint8_t)(1<<6)) 	/*!< UART FIFO trigger level 1: 4 character */
135
-#define UART_FCR_TRG_LEV2		((uint8_t)(2<<6)) 	/*!< UART FIFO trigger level 2: 8 character */
136
-#define UART_FCR_TRG_LEV3		((uint8_t)(3<<6)) 	/*!< UART FIFO trigger level 3: 14 character */
137
-#define UART_FCR_BITMASK		((uint8_t)(0xCF))	/*!< UART FIFO control bit mask */
138
-#define UART_TX_FIFO_SIZE		(16)
139
-
140
-/*********************************************************************//**
141
- * Macro defines for Macro defines for UART line control register
142
- **********************************************************************/
143
-#define UART_LCR_WLEN5     		((uint8_t)(0))   		/*!< UART 5 bit data mode */
144
-#define UART_LCR_WLEN6     		((uint8_t)(1<<0))   	/*!< UART 6 bit data mode */
145
-#define UART_LCR_WLEN7     		((uint8_t)(2<<0))   	/*!< UART 7 bit data mode */
146
-#define UART_LCR_WLEN8     		((uint8_t)(3<<0))   	/*!< UART 8 bit data mode */
147
-#define UART_LCR_STOPBIT_SEL	((uint8_t)(1<<2))   	/*!< UART Two Stop Bits Select */
148
-#define UART_LCR_PARITY_EN		((uint8_t)(1<<3))		/*!< UART Parity Enable */
149
-#define UART_LCR_PARITY_ODD		((uint8_t)(0))         	/*!< UART Odd Parity Select */
150
-#define UART_LCR_PARITY_EVEN	((uint8_t)(1<<4))		/*!< UART Even Parity Select */
151
-#define UART_LCR_PARITY_F_1		((uint8_t)(2<<4))		/*!< UART force 1 stick parity */
152
-#define UART_LCR_PARITY_F_0		((uint8_t)(3<<4))		/*!< UART force 0 stick parity */
153
-#define UART_LCR_BREAK_EN		((uint8_t)(1<<6))		/*!< UART Transmission Break enable */
154
-#define UART_LCR_DLAB_EN		((uint8_t)(1<<7))    	/*!< UART Divisor Latches Access bit enable */
155
-#define UART_LCR_BITMASK		((uint8_t)(0xFF))		/*!< UART line control bit mask */
156
-
157
-/*********************************************************************//**
158
- * Macro defines for Macro defines for UART1 Modem Control Register
159
- **********************************************************************/
160
-#define UART1_MCR_DTR_CTRL		((uint8_t)(1<<0))		/*!< Source for modem output pin DTR */
161
-#define UART1_MCR_RTS_CTRL		((uint8_t)(1<<1))		/*!< Source for modem output pin RTS */
162
-#define UART1_MCR_LOOPB_EN		((uint8_t)(1<<4))		/*!< Loop back mode select */
163
-#define UART1_MCR_AUTO_RTS_EN	((uint8_t)(1<<6))		/*!< Enable Auto RTS flow-control */
164
-#define UART1_MCR_AUTO_CTS_EN	((uint8_t)(1<<7))		/*!< Enable Auto CTS flow-control */
165
-#define UART1_MCR_BITMASK		((uint8_t)(0x0F3))		/*!< UART1 bit mask value */
166
-
167
-/*********************************************************************//**
168
- * Macro defines for Macro defines for UART line status register
169
- **********************************************************************/
170
-#define UART_LSR_RDR		((uint8_t)(1<<0)) 	/*!<Line status register: Receive data ready*/
171
-#define UART_LSR_OE			((uint8_t)(1<<1)) 	/*!<Line status register: Overrun error*/
172
-#define UART_LSR_PE			((uint8_t)(1<<2)) 	/*!<Line status register: Parity error*/
173
-#define UART_LSR_FE			((uint8_t)(1<<3)) 	/*!<Line status register: Framing error*/
174
-#define UART_LSR_BI			((uint8_t)(1<<4)) 	/*!<Line status register: Break interrupt*/
175
-#define UART_LSR_THRE		((uint8_t)(1<<5)) 	/*!<Line status register: Transmit holding register empty*/
176
-#define UART_LSR_TEMT		((uint8_t)(1<<6)) 	/*!<Line status register: Transmitter empty*/
177
-#define UART_LSR_RXFE		((uint8_t)(1<<7)) 	/*!<Error in RX FIFO*/
178
-#define UART_LSR_BITMASK	((uint8_t)(0xFF)) 	/*!<UART Line status bit mask */
179
-
180
-/*********************************************************************//**
181
- * Macro defines for Macro defines for UART Modem (UART1 only) status register
182
- **********************************************************************/
183
-#define UART1_MSR_DELTA_CTS		((uint8_t)(1<<0))	/*!< Set upon state change of input CTS */
184
-#define UART1_MSR_DELTA_DSR		((uint8_t)(1<<1))	/*!< Set upon state change of input DSR */
185
-#define UART1_MSR_LO2HI_RI		((uint8_t)(1<<2))	/*!< Set upon low to high transition of input RI */
186
-#define UART1_MSR_DELTA_DCD		((uint8_t)(1<<3))	/*!< Set upon state change of input DCD */
187
-#define UART1_MSR_CTS			((uint8_t)(1<<4))	/*!< Clear To Send State */
188
-#define UART1_MSR_DSR			((uint8_t)(1<<5))	/*!< Data Set Ready State */
189
-#define UART1_MSR_RI			((uint8_t)(1<<6))	/*!< Ring Indicator State */
190
-#define UART1_MSR_DCD			((uint8_t)(1<<7))	/*!< Data Carrier Detect State */
191
-#define UART1_MSR_BITMASK		((uint8_t)(0xFF))	/*!< MSR register bit-mask value */
192
-
193
-/*********************************************************************//**
194
- * Macro defines for Macro defines for UART Scratch Pad Register
195
- **********************************************************************/
196
-#define UART_SCR_BIMASK		((uint8_t)(0xFF))	/*!< UART Scratch Pad bit mask */
197
-
198
-/*********************************************************************//**
199
- * Macro defines for Macro defines for UART Auto baudrate control register
200
- **********************************************************************/
201
-#define UART_ACR_START				((uint32_t)(1<<0))	/**< UART Auto-baud start */
202
-#define UART_ACR_MODE				((uint32_t)(1<<1))	/**< UART Auto baudrate Mode 1 */
203
-#define UART_ACR_AUTO_RESTART		((uint32_t)(1<<2))	/**< UART Auto baudrate restart */
204
-#define UART_ACR_ABEOINT_CLR		((uint32_t)(1<<8))	/**< UART End of auto-baud interrupt clear */
205
-#define UART_ACR_ABTOINT_CLR		((uint32_t)(1<<9))	/**< UART Auto-baud time-out interrupt clear */
206
-#define UART_ACR_BITMASK			((uint32_t)(0x307))	/**< UART Auto Baudrate register bit mask */
207
-
208
-/*********************************************************************//**
209
- * Macro defines for Macro defines for UART IrDA control register
210
- **********************************************************************/
211
-#define UART_ICR_IRDAEN			((uint32_t)(1<<0))			/**< IrDA mode enable */
212
-#define UART_ICR_IRDAINV		((uint32_t)(1<<1))			/**< IrDA serial input inverted */
213
-#define UART_ICR_FIXPULSE_EN	((uint32_t)(1<<2))			/**< IrDA fixed pulse width mode */
214
-#define UART_ICR_PULSEDIV(n)	((uint32_t)((n&0x07)<<3))	/**< PulseDiv - Configures the pulse when FixPulseEn = 1 */
215
-#define UART_ICR_BITMASK		((uint32_t)(0x3F))			/*!< UART IRDA bit mask */
216
-
217
-/*********************************************************************//**
218
- * Macro defines for Macro defines for UART Fractional divider register
219
- **********************************************************************/
220
-#define UART_FDR_DIVADDVAL(n)	((uint32_t)(n&0x0F))		/**< Baud-rate generation pre-scaler divisor */
221
-#define UART_FDR_MULVAL(n)		((uint32_t)((n<<4)&0xF0))	/**< Baud-rate pre-scaler multiplier value */
222
-#define UART_FDR_BITMASK		((uint32_t)(0xFF))			/**< UART Fractional Divider register bit mask */
223
-
224
-/*********************************************************************//**
225
- * Macro defines for Macro defines for UART Tx Enable register
226
- **********************************************************************/
227
-#define UART_TER_TXEN			((uint8_t)(1<<7)) 		/*!< Transmit enable bit */
228
-#define UART_TER_BITMASK		((uint8_t)(0x80))		/**< UART Transmit Enable Register bit mask */
229
-
230
-/*********************************************************************//**
231
- * Macro defines for Macro defines for UART1 RS485 Control register
232
- **********************************************************************/
233
-#define UART1_RS485CTRL_NMM_EN		((uint32_t)(1<<0))	/*!< RS-485/EIA-485 Normal Multi-drop Mode (NMM)
234
-														is disabled */
235
-#define UART1_RS485CTRL_RX_DIS		((uint32_t)(1<<1))	/*!< The receiver is disabled */
236
-#define UART1_RS485CTRL_AADEN		((uint32_t)(1<<2))	/*!< Auto Address Detect (AAD) is enabled */
237
-#define UART1_RS485CTRL_SEL_DTR		((uint32_t)(1<<3))	/*!< If direction control is enabled
238
-														(bit DCTRL = 1), pin DTR is used for direction control */
239
-#define UART1_RS485CTRL_DCTRL_EN	((uint32_t)(1<<4))	/*!< Enable Auto Direction Control */
240
-#define UART1_RS485CTRL_OINV_1		((uint32_t)(1<<5))	/*!< This bit reverses the polarity of the direction
241
-														control signal on the RTS (or DTR) pin. The direction control pin
242
-														will be driven to logic "1" when the transmitter has data to be sent */
243
-#define UART1_RS485CTRL_BITMASK		((uint32_t)(0x3F))	/**< RS485 control bit-mask value */
244
-
245
-/*********************************************************************//**
246
- * Macro defines for Macro defines for UART1 RS-485 Address Match register
247
- **********************************************************************/
248
-#define UART1_RS485ADRMATCH_BITMASK ((uint8_t)(0xFF)) 	/**< Bit mask value */
249
-
250
-/*********************************************************************//**
251
- * Macro defines for Macro defines for UART1 RS-485 Delay value register
252
- **********************************************************************/
253
-/* Macro defines for UART1 RS-485 Delay value register */
254
-#define UART1_RS485DLY_BITMASK		((uint8_t)(0xFF)) 	/** Bit mask value */
255
-
256
-/*********************************************************************//**
257
- * Macro defines for Macro defines for UART FIFO Level register
258
- **********************************************************************/
259
-#define UART_FIFOLVL_RXFIFOLVL(n)	((uint32_t)(n&0x0F))		/**< Reflects the current level of the UART receiver FIFO */
260
-#define UART_FIFOLVL_TXFIFOLVL(n)	((uint32_t)((n>>8)&0x0F))	/**< Reflects the current level of the UART transmitter FIFO */
261
-#define UART_FIFOLVL_BITMASK		((uint32_t)(0x0F0F))		/**< UART FIFO Level Register bit mask */
262
-
263
-
264
-/* ---------------- CHECK PARAMETER DEFINITIONS ---------------------------- */
265
-
266
-/** Macro to check the input UART_DATABIT parameters */
267
-#define PARAM_UART_DATABIT(databit)	((databit==UART_DATABIT_5) || (databit==UART_DATABIT_6)\
268
-|| (databit==UART_DATABIT_7) || (databit==UART_DATABIT_8))
269
-
270
-/** Macro to check the input UART_STOPBIT parameters */
271
-#define PARAM_UART_STOPBIT(stopbit)	((stopbit==UART_STOPBIT_1) || (stopbit==UART_STOPBIT_2))
272
-
273
-/** Macro to check the input UART_PARITY parameters */
274
-#define PARAM_UART_PARITY(parity)	((parity==UART_PARITY_NONE) || (parity==UART_PARITY_ODD) \
275
-|| (parity==UART_PARITY_EVEN) || (parity==UART_PARITY_SP_1) \
276
-|| (parity==UART_PARITY_SP_0))
277
-
278
-/** Macro to check the input UART_FIFO parameters */
279
-#define PARAM_UART_FIFO_LEVEL(fifo)	((fifo==UART_FIFO_TRGLEV0) \
280
-|| (fifo==UART_FIFO_TRGLEV1) || (fifo==UART_FIFO_TRGLEV2) \
281
-|| (fifo==UART_FIFO_TRGLEV3))
282
-
283
-/** Macro to check the input UART_INTCFG parameters */
284
-#define PARAM_UART_INTCFG(IntCfg)	((IntCfg==UART_INTCFG_RBR) || (IntCfg==UART_INTCFG_THRE) \
285
-|| (IntCfg==UART_INTCFG_RLS) || (IntCfg==UART_INTCFG_ABEO) \
286
-|| (IntCfg==UART_INTCFG_ABTO))
287
-
288
-/** Macro to check the input UART1_INTCFG parameters - expansion input parameter for UART1 */
289
-#define PARAM_UART1_INTCFG(IntCfg)	((IntCfg==UART1_INTCFG_MS) || (IntCfg==UART1_INTCFG_CTS))
290
-
291
-/** Macro to check the input UART_AUTOBAUD_MODE parameters */
292
-#define PARAM_UART_AUTOBAUD_MODE(ABmode)	((ABmode==UART_AUTOBAUD_MODE0) || (ABmode==UART_AUTOBAUD_MODE1))
293
-
294
-/** Macro to check the input UART_AUTOBAUD_INTSTAT parameters */
295
-#define PARAM_UART_AUTOBAUD_INTSTAT(ABIntStat)	((ABIntStat==UART_AUTOBAUD_INTSTAT_ABEO) || \
296
-		(ABIntStat==UART_AUTOBAUD_INTSTAT_ABTO))
297
-
298
-/** Macro to check the input UART_IrDA_PULSEDIV parameters */
299
-#define PARAM_UART_IrDA_PULSEDIV(PulseDiv)	((PulseDiv==UART_IrDA_PULSEDIV2) || (PulseDiv==UART_IrDA_PULSEDIV4) \
300
-|| (PulseDiv==UART_IrDA_PULSEDIV8) || (PulseDiv==UART_IrDA_PULSEDIV16) \
301
-|| (PulseDiv==UART_IrDA_PULSEDIV32) || (PulseDiv==UART_IrDA_PULSEDIV64) \
302
-|| (PulseDiv==UART_IrDA_PULSEDIV128) || (PulseDiv==UART_IrDA_PULSEDIV256))
303
-
304
-/* Macro to check the input UART1_SignalState parameters */
305
-#define PARAM_UART1_SIGNALSTATE(x) ((x==INACTIVE) || (x==ACTIVE))
306
-
307
-/** Macro to check the input PARAM_UART1_MODEM_PIN parameters */
308
-#define PARAM_UART1_MODEM_PIN(x) ((x==UART1_MODEM_PIN_DTR) || (x==UART1_MODEM_PIN_RTS))
309
-
310
-/** Macro to check the input PARAM_UART1_MODEM_MODE parameters */
311
-#define PARAM_UART1_MODEM_MODE(x) ((x==UART1_MODEM_MODE_LOOPBACK) || (x==UART1_MODEM_MODE_AUTO_RTS) \
312
-|| (x==UART1_MODEM_MODE_AUTO_CTS))
313
-
314
-/** Macro to check the direction control pin type */
315
-#define PARAM_UART_RS485_DIRCTRL_PIN(x)	((x==UART1_RS485_DIRCTRL_RTS) || (x==UART1_RS485_DIRCTRL_DTR))
316
-
317
-/* Macro to determine if it is valid UART port number */
318
-#define PARAM_UARTx(x)	((((uint32_t *)x)==((uint32_t *)LPC_UART0)) \
319
-|| (((uint32_t *)x)==((uint32_t *)LPC_UART1)) \
320
-|| (((uint32_t *)x)==((uint32_t *)LPC_UART2)) \
321
-|| (((uint32_t *)x)==((uint32_t *)LPC_UART3)))
322
-#define PARAM_UART_IrDA(x) (((uint32_t *)x)==((uint32_t *)LPC_UART3))
323
-#define PARAM_UART1_MODEM(x) (((uint32_t *)x)==((uint32_t *)LPC_UART1))
324
-
325
-/** Macro to check the input value for UART1_RS485_CFG_MATCHADDRVALUE parameter */
326
-#define PARAM_UART1_RS485_CFG_MATCHADDRVALUE(x) ((x<0xFF))
327
-
328
-/** Macro to check the input value for UART1_RS485_CFG_DELAYVALUE parameter */
329
-#define PARAM_UART1_RS485_CFG_DELAYVALUE(x) ((x<0xFF))
330
-
331
-/**
332
- * @}
333
- */
334
-
335
-
336
-/* Public Types --------------------------------------------------------------- */
337
-/** @defgroup UART_Public_Types UART Public Types
338
- * @{
339
- */
340
-
341
-/**
342
- * @brief UART Databit type definitions
343
- */
344
-typedef enum {
345
-	UART_DATABIT_5		= 0,     		/*!< UART 5 bit data mode */
346
-	UART_DATABIT_6,		     			/*!< UART 6 bit data mode */
347
-	UART_DATABIT_7,		     			/*!< UART 7 bit data mode */
348
-	UART_DATABIT_8		     			/*!< UART 8 bit data mode */
349
-} UART_DATABIT_Type;
350
-
351
-/**
352
- * @brief UART Stop bit type definitions
353
- */
354
-typedef enum {
355
-	UART_STOPBIT_1		= (0),   					/*!< UART 1 Stop Bits Select */
356
-	UART_STOPBIT_2		 							/*!< UART Two Stop Bits Select */
357
-} UART_STOPBIT_Type;
358
-
359
-/**
360
- * @brief UART Parity type definitions
361
- */
362
-typedef enum {
363
-	UART_PARITY_NONE 	= 0,					/*!< No parity */
364
-	UART_PARITY_ODD,	 						/*!< Odd parity */
365
-	UART_PARITY_EVEN, 							/*!< Even parity */
366
-	UART_PARITY_SP_1, 							/*!< Forced "1" stick parity */
367
-	UART_PARITY_SP_0 							/*!< Forced "0" stick parity */
368
-} UART_PARITY_Type;
369
-
370
-/**
371
- * @brief FIFO Level type definitions
372
- */
373
-typedef enum {
374
-	UART_FIFO_TRGLEV0 = 0,	/*!< UART FIFO trigger level 0: 1 character */
375
-	UART_FIFO_TRGLEV1, 		/*!< UART FIFO trigger level 1: 4 character */
376
-	UART_FIFO_TRGLEV2,		/*!< UART FIFO trigger level 2: 8 character */
377
-	UART_FIFO_TRGLEV3		/*!< UART FIFO trigger level 3: 14 character */
378
-} UART_FITO_LEVEL_Type;
379
-
380
-/********************************************************************//**
381
-* @brief UART Interrupt Type definitions
382
-**********************************************************************/
383
-typedef enum {
384
-	UART_INTCFG_RBR = 0,	/*!< RBR Interrupt enable*/
385
-	UART_INTCFG_THRE,		/*!< THR Interrupt enable*/
386
-	UART_INTCFG_RLS,		/*!< RX line status interrupt enable*/
387
-	UART1_INTCFG_MS,		/*!< Modem status interrupt enable (UART1 only) */
388
-	UART1_INTCFG_CTS,		/*!< CTS1 signal transition interrupt enable (UART1 only) */
389
-	UART_INTCFG_ABEO,		/*!< Enables the end of auto-baud interrupt */
390
-	UART_INTCFG_ABTO		/*!< Enables the auto-baud time-out interrupt */
391
-} UART_INT_Type;
392
-
393
-/**
394
- * @brief UART Line Status Type definition
395
- */
396
-typedef enum {
397
-	UART_LINESTAT_RDR	= UART_LSR_RDR,			/*!<Line status register: Receive data ready*/
398
-	UART_LINESTAT_OE	= UART_LSR_OE,			/*!<Line status register: Overrun error*/
399
-	UART_LINESTAT_PE	= UART_LSR_PE,			/*!<Line status register: Parity error*/
400
-	UART_LINESTAT_FE	= UART_LSR_FE,			/*!<Line status register: Framing error*/
401
-	UART_LINESTAT_BI	= UART_LSR_BI,			/*!<Line status register: Break interrupt*/
402
-	UART_LINESTAT_THRE	= UART_LSR_THRE,		/*!<Line status register: Transmit holding register empty*/
403
-	UART_LINESTAT_TEMT	= UART_LSR_TEMT,		/*!<Line status register: Transmitter empty*/
404
-	UART_LINESTAT_RXFE	= UART_LSR_RXFE			/*!<Error in RX FIFO*/
405
-} UART_LS_Type;
406
-
407
-/**
408
- * @brief UART Auto-baudrate mode type definition
409
- */
410
-typedef enum {
411
-	UART_AUTOBAUD_MODE0				= 0,			/**< UART Auto baudrate Mode 0 */
412
-	UART_AUTOBAUD_MODE1							/**< UART Auto baudrate Mode 1 */
413
-} UART_AB_MODE_Type;
414
-
415
-/**
416
- * @brief Auto Baudrate mode configuration type definition
417
- */
418
-typedef struct {
419
-	UART_AB_MODE_Type	ABMode;			/**< Autobaudrate mode */
420
-	FunctionalState		AutoRestart;	/**< Auto Restart state */
421
-} UART_AB_CFG_Type;
422
-
423
-/**
424
- * @brief UART End of Auto-baudrate type definition
425
- */
426
-typedef enum {
427
-	UART_AUTOBAUD_INTSTAT_ABEO		= UART_IIR_ABEO_INT,		/**< UART End of auto-baud interrupt  */
428
-	UART_AUTOBAUD_INTSTAT_ABTO		= UART_IIR_ABTO_INT			/**< UART Auto-baud time-out interrupt  */
429
-}UART_ABEO_Type;
430
-
431
-/**
432
- * UART IrDA Control type Definition
433
- */
434
-typedef enum {
435
-	UART_IrDA_PULSEDIV2		= 0,		/**< Pulse width = 2 * Tpclk
436
-										- Configures the pulse when FixPulseEn = 1 */
437
-	UART_IrDA_PULSEDIV4,				/**< Pulse width = 4 * Tpclk
438
-										- Configures the pulse when FixPulseEn = 1 */
439
-	UART_IrDA_PULSEDIV8,				/**< Pulse width = 8 * Tpclk
440
-										- Configures the pulse when FixPulseEn = 1 */
441
-	UART_IrDA_PULSEDIV16,				/**< Pulse width = 16 * Tpclk
442
-										- Configures the pulse when FixPulseEn = 1 */
443
-	UART_IrDA_PULSEDIV32,				/**< Pulse width = 32 * Tpclk
444
-										- Configures the pulse when FixPulseEn = 1 */
445
-	UART_IrDA_PULSEDIV64,				/**< Pulse width = 64 * Tpclk
446
-										- Configures the pulse when FixPulseEn = 1 */
447
-	UART_IrDA_PULSEDIV128,				/**< Pulse width = 128 * Tpclk
448
-										- Configures the pulse when FixPulseEn = 1 */
449
-	UART_IrDA_PULSEDIV256				/**< Pulse width = 256 * Tpclk
450
-										- Configures the pulse when FixPulseEn = 1 */
451
-} UART_IrDA_PULSE_Type;
452
-
453
-/********************************************************************//**
454
-* @brief UART1 Full modem -  Signal states definition
455
-**********************************************************************/
456
-typedef enum {
457
-	INACTIVE = 0,			/* In-active state */
458
-	ACTIVE = !INACTIVE 		/* Active state */
459
-}UART1_SignalState;
460
-
461
-/**
462
- * @brief UART modem status type definition
463
- */
464
-typedef enum {
465
-	UART1_MODEM_STAT_DELTA_CTS	= UART1_MSR_DELTA_CTS,		/*!< Set upon state change of input CTS */
466
-	UART1_MODEM_STAT_DELTA_DSR	= UART1_MSR_DELTA_DSR,		/*!< Set upon state change of input DSR */
467
-	UART1_MODEM_STAT_LO2HI_RI	= UART1_MSR_LO2HI_RI,		/*!< Set upon low to high transition of input RI */
468
-	UART1_MODEM_STAT_DELTA_DCD	= UART1_MSR_DELTA_DCD,		/*!< Set upon state change of input DCD */
469
-	UART1_MODEM_STAT_CTS		= UART1_MSR_CTS,			/*!< Clear To Send State */
470
-	UART1_MODEM_STAT_DSR		= UART1_MSR_DSR,			/*!< Data Set Ready State */
471
-	UART1_MODEM_STAT_RI			= UART1_MSR_RI,				/*!< Ring Indicator State */
472
-	UART1_MODEM_STAT_DCD		= UART1_MSR_DCD				/*!< Data Carrier Detect State */
473
-} UART_MODEM_STAT_type;
474
-
475
-/**
476
- * @brief Modem output pin type definition
477
- */
478
-typedef enum {
479
-	UART1_MODEM_PIN_DTR			= 0,		/*!< Source for modem output pin DTR */
480
-	UART1_MODEM_PIN_RTS						/*!< Source for modem output pin RTS */
481
-} UART_MODEM_PIN_Type;
482
-
483
-/**
484
- * @brief UART Modem mode type definition
485
- */
486
-typedef enum {
487
-	UART1_MODEM_MODE_LOOPBACK	= 0,		/*!< Loop back mode select */
488
-	UART1_MODEM_MODE_AUTO_RTS,				/*!< Enable Auto RTS flow-control */
489
-	UART1_MODEM_MODE_AUTO_CTS 				/*!< Enable Auto CTS flow-control */
490
-} UART_MODEM_MODE_Type;
491
-
492
-/**
493
- * @brief UART Direction Control Pin type definition
494
- */
495
-typedef enum {
496
-	UART1_RS485_DIRCTRL_RTS = 0,	/**< Pin RTS is used for direction control */
497
-	UART1_RS485_DIRCTRL_DTR			/**< Pin DTR is used for direction control */
498
-} UART_RS485_DIRCTRL_PIN_Type;
499
-
500
-/********************************************************************//**
501
-* @brief UART Configuration Structure definition
502
-**********************************************************************/
503
-typedef struct {
504
-  uint32_t Baud_rate;   		/**< UART baud rate */
505
-  UART_PARITY_Type Parity;    	/**< Parity selection, should be:
506
-							   - UART_PARITY_NONE: No parity
507
-							   - UART_PARITY_ODD: Odd parity
508
-							   - UART_PARITY_EVEN: Even parity
509
-							   - UART_PARITY_SP_1: Forced "1" stick parity
510
-							   - UART_PARITY_SP_0: Forced "0" stick parity
511
-							   */
512
-  UART_DATABIT_Type Databits;   /**< Number of data bits, should be:
513
-							   - UART_DATABIT_5: UART 5 bit data mode
514
-							   - UART_DATABIT_6: UART 6 bit data mode
515
-							   - UART_DATABIT_7: UART 7 bit data mode
516
-							   - UART_DATABIT_8: UART 8 bit data mode
517
-							   */
518
-  UART_STOPBIT_Type Stopbits;   /**< Number of stop bits, should be:
519
-							   - UART_STOPBIT_1: UART 1 Stop Bits Select
520
-							   - UART_STOPBIT_2: UART 2 Stop Bits Select
521
-							   */
522
-} UART_CFG_Type;
523
-
524
-/********************************************************************//**
525
-* @brief UART FIFO Configuration Structure definition
526
-**********************************************************************/
527
-
528
-typedef struct {
529
-	FunctionalState FIFO_ResetRxBuf;	/**< Reset Rx FIFO command state , should be:
530
-										 - ENABLE: Reset Rx FIFO in UART
531
-										 - DISABLE: Do not reset Rx FIFO  in UART
532
-										 */
533
-	FunctionalState FIFO_ResetTxBuf;	/**< Reset Tx FIFO command state , should be:
534
-										 - ENABLE: Reset Tx FIFO in UART
535
-										 - DISABLE: Do not reset Tx FIFO  in UART
536
-										 */
537
-	FunctionalState FIFO_DMAMode;		/**< DMA mode, should be:
538
-										 - ENABLE: Enable DMA mode in UART
539
-										 - DISABLE: Disable DMA mode in UART
540
-										 */
541
-	UART_FITO_LEVEL_Type FIFO_Level;	/**< Rx FIFO trigger level, should be:
542
-										- UART_FIFO_TRGLEV0: UART FIFO trigger level 0: 1 character
543
-										- UART_FIFO_TRGLEV1: UART FIFO trigger level 1: 4 character
544
-										- UART_FIFO_TRGLEV2: UART FIFO trigger level 2: 8 character
545
-										- UART_FIFO_TRGLEV3: UART FIFO trigger level 3: 14 character
546
-										*/
547
-} UART_FIFO_CFG_Type;
548
-
549
-/********************************************************************//**
550
-* @brief UART1 Full modem -  RS485 Control configuration type
551
-**********************************************************************/
552
-typedef struct {
553
-	FunctionalState NormalMultiDropMode_State; /*!< Normal MultiDrop mode State:
554
-													- ENABLE: Enable this function.
555
-													- DISABLE: Disable this function. */
556
-	FunctionalState Rx_State;					/*!< Receiver State:
557
-													- ENABLE: Enable Receiver.
558
-													- DISABLE: Disable Receiver. */
559
-	FunctionalState AutoAddrDetect_State;		/*!< Auto Address Detect mode state:
560
-												- ENABLE: ENABLE this function.
561
-												- DISABLE: Disable this function. */
562
-	FunctionalState AutoDirCtrl_State;			/*!< Auto Direction Control State:
563
-												- ENABLE: Enable this function.
564
-												- DISABLE: Disable this function. */
565
-	UART_RS485_DIRCTRL_PIN_Type DirCtrlPin;		/*!< If direction control is enabled, state:
566
-												- UART1_RS485_DIRCTRL_RTS:
567
-												pin RTS is used for direction control.
568
-												- UART1_RS485_DIRCTRL_DTR:
569
-												pin DTR is used for direction control. */
570
-	 SetState DirCtrlPol_Level;					/*!< Polarity of the direction control signal on
571
-												the RTS (or DTR) pin:
572
-												- RESET: The direction control pin will be driven
573
-												to logic "0" when the transmitter has data to be sent.
574
-												- SET: The direction control pin will be driven
575
-												to logic "1" when the transmitter has data to be sent. */
576
-	uint8_t MatchAddrValue;					/*!< address match value for RS-485/EIA-485 mode, 8-bit long */
577
-	uint8_t DelayValue;						/*!< delay time is in periods of the baud clock, 8-bit long */
578
-} UART1_RS485_CTRLCFG_Type;
579
-
580
-/**
581
- * @}
582
- */
583
-
584
-
585
-/* Public Functions ----------------------------------------------------------- */
586
-/** @defgroup UART_Public_Functions UART Public Functions
587
- * @{
588
- */
589
-/* UART Init/DeInit functions --------------------------------------------------*/
590
-void UART_Init(LPC_UART_TypeDef *UARTx, UART_CFG_Type *UART_ConfigStruct);
591
-void UART_DeInit(LPC_UART_TypeDef* UARTx);
592
-void UART_ConfigStructInit(UART_CFG_Type *UART_InitStruct);
593
-
594
-/* UART Send/Receive functions -------------------------------------------------*/
595
-void UART_SendByte(LPC_UART_TypeDef* UARTx, uint8_t Data);
596
-uint8_t UART_ReceiveByte(LPC_UART_TypeDef* UARTx);
597
-uint32_t UART_Send(LPC_UART_TypeDef *UARTx, uint8_t *txbuf,
598
-		uint32_t buflen, TRANSFER_BLOCK_Type flag);
599
-uint32_t UART_Receive(LPC_UART_TypeDef *UARTx, uint8_t *rxbuf, \
600
-		uint32_t buflen, TRANSFER_BLOCK_Type flag);
601
-
602
-/* UART FIFO functions ----------------------------------------------------------*/
603
-void UART_FIFOConfig(LPC_UART_TypeDef *UARTx, UART_FIFO_CFG_Type *FIFOCfg);
604
-void UART_FIFOConfigStructInit(UART_FIFO_CFG_Type *UART_FIFOInitStruct);
605
-
606
-/* UART get information functions -----------------------------------------------*/
607
-uint32_t UART_GetIntId(LPC_UART_TypeDef* UARTx);
608
-uint8_t UART_GetLineStatus(LPC_UART_TypeDef* UARTx);
609
-
610
-/* UART operate functions -------------------------------------------------------*/
611
-void UART_IntConfig(LPC_UART_TypeDef *UARTx, UART_INT_Type UARTIntCfg, \
612
-				FunctionalState NewState);
613
-void UART_TxCmd(LPC_UART_TypeDef *UARTx, FunctionalState NewState);
614
-FlagStatus UART_CheckBusy(LPC_UART_TypeDef *UARTx);
615
-void UART_ForceBreak(LPC_UART_TypeDef* UARTx);
616
-
617
-/* UART Auto-baud functions -----------------------------------------------------*/
618
-void UART_ABClearIntPending(LPC_UART_TypeDef *UARTx, UART_ABEO_Type ABIntType);
619
-void UART_ABCmd(LPC_UART_TypeDef *UARTx, UART_AB_CFG_Type *ABConfigStruct, \
620
-				FunctionalState NewState);
621
-
622
-/* UART1 FullModem functions ----------------------------------------------------*/
623
-void UART_FullModemForcePinState(LPC_UART1_TypeDef *UARTx, UART_MODEM_PIN_Type Pin, \
624
-							UART1_SignalState NewState);
625
-void UART_FullModemConfigMode(LPC_UART1_TypeDef *UARTx, UART_MODEM_MODE_Type Mode, \
626
-							FunctionalState NewState);
627
-uint8_t UART_FullModemGetStatus(LPC_UART1_TypeDef *UARTx);
628
-
629
-/* UART RS485 functions ----------------------------------------------------------*/
630
-void UART_RS485Config(LPC_UART1_TypeDef *UARTx, \
631
-		UART1_RS485_CTRLCFG_Type *RS485ConfigStruct);
632
-void UART_RS485ReceiverCmd(LPC_UART1_TypeDef *UARTx, FunctionalState NewState);
633
-void UART_RS485SendSlvAddr(LPC_UART1_TypeDef *UARTx, uint8_t SlvAddr);
634
-uint32_t UART_RS485SendData(LPC_UART1_TypeDef *UARTx, uint8_t *pData, uint32_t size);
635
-
636
-/* UART IrDA functions-------------------------------------------------------------*/
637
-void UART_IrDAInvtInputCmd(LPC_UART_TypeDef* UARTx, FunctionalState NewState);
638
-void UART_IrDACmd(LPC_UART_TypeDef* UARTx, FunctionalState NewState);
639
-void UART_IrDAPulseDivConfig(LPC_UART_TypeDef *UARTx, UART_IrDA_PULSE_Type PulseDiv);
640
-/**
641
- * @}
642
- */
643
-
644
-
645
-#ifdef __cplusplus
646
-}
647
-#endif
648
-
649
-
650
-#endif /* __LPC17XX_UART_H */
651
-
652
-/**
653
- * @}
654
- */
655
-
656
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 154
frameworks/CMSIS/LPC1768/include/lpc17xx_wdt.h Просмотреть файл

@@ -1,154 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc17xx_wdt.h				2010-05-21
3
-*//**
4
-* @file		lpc17xx_wdt.h
5
-* @brief	Contains all macro definitions and function prototypes
6
-* 			support for WDT firmware library on LPC17xx
7
-* @version	2.0
8
-* @date		21. May. 2010
9
-* @author	NXP MCU SW Application Team
10
-*
11
-* Copyright(C) 2010, NXP Semiconductor
12
-* All rights reserved.
13
-*
14
-***********************************************************************
15
-* Software that is described herein is for illustrative purposes only
16
-* which provides customers with programming information regarding the
17
-* products. This software is supplied "AS IS" without any warranties.
18
-* NXP Semiconductors assumes no responsibility or liability for the
19
-* use of the software, conveys no license or title under any patent,
20
-* copyright, or mask work right to the product. NXP Semiconductors
21
-* reserves the right to make changes in the software without
22
-* notification. NXP Semiconductors also make no representation or
23
-* warranty that such application will be suitable for the specified
24
-* use without further testing or modification.
25
-* Permission to use, copy, modify, and distribute this software and its
26
-* documentation is hereby granted, under NXP Semiconductors'
27
-* relevant copyright in the software, without fee, provided that it
28
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
29
-* copyright, permission, and disclaimer notice must appear in all copies of
30
-* this code.
31
-**********************************************************************/
32
-
33
-/* Peripheral group ----------------------------------------------------------- */
34
-/** @defgroup WDT WDT (Watch-Dog Timer)
35
- * @ingroup LPC1700CMSIS_FwLib_Drivers
36
- * @{
37
- */
38
-
39
-#ifndef LPC17XX_WDT_H_
40
-#define LPC17XX_WDT_H_
41
-
42
-/* Includes ------------------------------------------------------------------- */
43
-#include "LPC17xx.h"
44
-#include "lpc_types.h"
45
-
46
-
47
-#ifdef __cplusplus
48
-extern "C"
49
-{
50
-#endif
51
-
52
-
53
-/* Private Macros ------------------------------------------------------------- */
54
-/** @defgroup WDT_Private_Macros WDT Private Macros
55
- * @{
56
- */
57
-
58
-/* --------------------- BIT DEFINITIONS -------------------------------------- */
59
-/** WDT interrupt enable bit */
60
-#define WDT_WDMOD_WDEN			    ((uint32_t)(1<<0))
61
-/** WDT interrupt enable bit */
62
-#define WDT_WDMOD_WDRESET			((uint32_t)(1<<1))
63
-/** WDT time out flag bit */
64
-#define WDT_WDMOD_WDTOF				((uint32_t)(1<<2))
65
-/** WDT Time Out flag bit */
66
-#define WDT_WDMOD_WDINT				((uint32_t)(1<<3))
67
-/** WDT Mode */
68
-#define WDT_WDMOD(n)				((uint32_t)(1<<1))
69
-
70
-/** Define divider index for microsecond ( us ) */
71
-#define WDT_US_INDEX	((uint32_t)(1000000))
72
-/** WDT Time out minimum value */
73
-#define WDT_TIMEOUT_MIN	((uint32_t)(0xFF))
74
-/** WDT Time out maximum value */
75
-#define WDT_TIMEOUT_MAX	((uint32_t)(0xFFFFFFFF))
76
-
77
-/** Watchdog mode register mask */
78
-#define WDT_WDMOD_MASK			(uint8_t)(0x02)
79
-/** Watchdog timer constant register mask */
80
-#define WDT_WDTC_MASK			(uint8_t)(0xFFFFFFFF)
81
-/** Watchdog feed sequence register mask */
82
-#define WDT_WDFEED_MASK 		(uint8_t)(0x000000FF)
83
-/** Watchdog timer value register mask */
84
-#define WDT_WDCLKSEL_MASK 		(uint8_t)(0x03)
85
-/** Clock selected from internal RC */
86
-#define WDT_WDCLKSEL_RC			(uint8_t)(0x00)
87
-/** Clock selected from PCLK */
88
-#define WDT_WDCLKSEL_PCLK		(uint8_t)(0x01)
89
-/** Clock selected from external RTC */
90
-#define WDT_WDCLKSEL_RTC		(uint8_t)(0x02)
91
-
92
-/* ---------------- CHECK PARAMETER DEFINITIONS ---------------------------- */
93
-/* Macro check clock source selection  */
94
-#define PARAM_WDT_CLK_OPT(OPTION)  ((OPTION ==WDT_CLKSRC_IRC)||(OPTION ==WDT_CLKSRC_PCLK)\
95
-||(OPTION ==WDT_CLKSRC_RTC))
96
-
97
-/* Macro check WDT mode */
98
-#define PARAM_WDT_MODE_OPT(OPTION)  ((OPTION ==WDT_MODE_INT_ONLY)||(OPTION ==WDT_MODE_RESET))
99
-/**
100
- * @}
101
- */
102
-
103
-
104
-/* Public Types --------------------------------------------------------------- */
105
-/** @defgroup WDT_Public_Types WDT Public Types
106
- * @{
107
- */
108
-
109
-/** @brief Clock source option for WDT */
110
-typedef enum {
111
-	WDT_CLKSRC_IRC = 0, /*!< Clock source from Internal RC oscillator */
112
-	WDT_CLKSRC_PCLK = 1, /*!< Selects the APB peripheral clock (PCLK) */
113
-	WDT_CLKSRC_RTC = 2 /*!< Selects the RTC oscillator */
114
-} WDT_CLK_OPT;
115
-
116
-/** @brief WDT operation mode */
117
-typedef enum {
118
-	WDT_MODE_INT_ONLY = 0, /*!< Use WDT to generate interrupt only */
119
-	WDT_MODE_RESET = 1    /*!< Use WDT to generate interrupt and reset MCU */
120
-} WDT_MODE_OPT;
121
-
122
-/**
123
- * @}
124
- */
125
-
126
-
127
-/* Public Functions ----------------------------------------------------------- */
128
-/** @defgroup WDT_Public_Functions WDT Public Functions
129
- * @{
130
- */
131
-
132
-void WDT_Init (WDT_CLK_OPT ClkSrc, WDT_MODE_OPT WDTMode);
133
-void WDT_Start(uint32_t TimeOut);
134
-void WDT_Feed (void);
135
-void WDT_UpdateTimeOut ( uint32_t TimeOut);
136
-FlagStatus WDT_ReadTimeOutFlag (void);
137
-void WDT_ClrTimeOutFlag (void);
138
-uint32_t WDT_GetCurrentCount(void);
139
-
140
-/**
141
- * @}
142
- */
143
-
144
-#ifdef __cplusplus
145
-}
146
-#endif
147
-
148
-#endif /* LPC17XX_WDT_H_ */
149
-
150
-/**
151
- * @}
152
- */
153
-
154
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 205
frameworks/CMSIS/LPC1768/include/lpc_types.h Просмотреть файл

@@ -1,205 +0,0 @@
1
-/**********************************************************************
2
-* $Id$		lpc_types.h		2008-07-27
3
-*//**
4
-* @file		lpc_types.h
5
-* @brief	Contains the NXP ABL typedefs for C standard types.
6
-*     		It is intended to be used in ISO C conforming development
7
-*     		environments and checks for this insofar as it is possible
8
-*     		to do so.
9
-* @version	2.0
10
-* @date		27 July. 2008
11
-* @author	NXP MCU SW Application Team
12
-*
13
-* Copyright(C) 2008, NXP Semiconductor
14
-* All rights reserved.
15
-*
16
-***********************************************************************
17
-* Software that is described herein is for illustrative purposes only
18
-* which provides customers with programming information regarding the
19
-* products. This software is supplied "AS IS" without any warranties.
20
-* NXP Semiconductors assumes no responsibility or liability for the
21
-* use of the software, conveys no license or title under any patent,
22
-* copyright, or mask work right to the product. NXP Semiconductors
23
-* reserves the right to make changes in the software without
24
-* notification. NXP Semiconductors also make no representation or
25
-* warranty that such application will be suitable for the specified
26
-* use without further testing or modification.
27
-* Permission to use, copy, modify, and distribute this software and its
28
-* documentation is hereby granted, under NXP Semiconductors'
29
-* relevant copyright in the software, without fee, provided that it
30
-* is used in conjunction with NXP Semiconductors microcontrollers.  This
31
-* copyright, permission, and disclaimer notice must appear in all copies of
32
-* this code.
33
-**********************************************************************/
34
-
35
-/* Type group ----------------------------------------------------------- */
36
-/** @defgroup LPC_Types LPC_Types
37
- * @ingroup LPC1700CMSIS_FwLib_Drivers
38
- * @{
39
- */
40
-
41
-#ifndef LPC_TYPES_H
42
-#define LPC_TYPES_H
43
-
44
-/* Includes ------------------------------------------------------------------- */
45
-#include <stdint.h>
46
-
47
-
48
-/* Public Types --------------------------------------------------------------- */
49
-/** @defgroup LPC_Types_Public_Types LPC_Types Public Types
50
- * @{
51
- */
52
-
53
-/**
54
- * @brief Boolean Type definition
55
- */
56
-typedef enum {FALSE = 0, TRUE = !FALSE} Bool;
57
-
58
-/**
59
- * @brief Flag Status and Interrupt Flag Status type definition
60
- */
61
-typedef enum {RESET = 0, SET = !RESET} FlagStatus, IntStatus, SetState;
62
-#define PARAM_SETSTATE(State) ((State==RESET) || (State==SET))
63
-
64
-/**
65
- * @brief Functional State Definition
66
- */
67
-typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
68
-#define PARAM_FUNCTIONALSTATE(State) ((State==DISABLE) || (State==ENABLE))
69
-
70
-/**
71
- * @ Status type definition
72
- */
73
-typedef enum {ERROR = 0, SUCCESS = !ERROR} Status;
74
-
75
-
76
-/**
77
- * Read/Write transfer type mode (Block or non-block)
78
- */
79
-typedef enum
80
-{
81
-	NONE_BLOCKING = 0,		/**< None Blocking type */
82
-	BLOCKING				/**< Blocking type */
83
-} TRANSFER_BLOCK_Type;
84
-
85
-
86
-/** Pointer to Function returning Void (any number of parameters) */
87
-typedef void (*PFV)();
88
-
89
-/** Pointer to Function returning int32_t (any number of parameters) */
90
-typedef int32_t(*PFI)();
91
-
92
-/**
93
- * @}
94
- */
95
-
96
-
97
-/* Public Macros -------------------------------------------------------------- */
98
-/** @defgroup LPC_Types_Public_Macros  LPC_Types Public Macros
99
- * @{
100
- */
101
-
102
-/* _BIT(n) sets the bit at position "n"
103
- * _BIT(n) is intended to be used in "OR" and "AND" expressions:
104
- * e.g., "(_BIT(3) | _BIT(7))".
105
- */
106
-#undef _BIT
107
-/* Set bit macro */
108
-#define _BIT(n)	(1<<n)
109
-
110
-/* _SBF(f,v) sets the bit field starting at position "f" to value "v".
111
- * _SBF(f,v) is intended to be used in "OR" and "AND" expressions:
112
- * e.g., "((_SBF(5,7) | _SBF(12,0xF)) & 0xFFFF)"
113
- */
114
-#undef _SBF
115
-/* Set bit field macro */
116
-#define _SBF(f,v) (v<<f)
117
-
118
-/* _BITMASK constructs a symbol with 'field_width' least significant
119
- * bits set.
120
- * e.g., _BITMASK(5) constructs '0x1F', _BITMASK(16) == 0xFFFF
121
- * The symbol is intended to be used to limit the bit field width
122
- * thusly:
123
- * <a_register> = (any_expression) & _BITMASK(x), where 0 < x <= 32.
124
- * If "any_expression" results in a value that is larger than can be
125
- * contained in 'x' bits, the bits above 'x - 1' are masked off.  When
126
- * used with the _SBF example above, the example would be written:
127
- * a_reg = ((_SBF(5,7) | _SBF(12,0xF)) & _BITMASK(16))
128
- * This ensures that the value written to a_reg is no wider than
129
- * 16 bits, and makes the code easier to read and understand.
130
- */
131
-#undef _BITMASK
132
-/* Bitmask creation macro */
133
-#define _BITMASK(field_width) ( _BIT(field_width) - 1)
134
-
135
-/* NULL pointer */
136
-#ifndef NULL
137
-  #define NULL ((void*) 0)
138
-#endif
139
-
140
-/* Number of elements in an array */
141
-#define NELEMENTS(array)  (sizeof (array) / sizeof (array[0]))
142
-
143
-/* Static data/function define */
144
-#define STATIC static
145
-/* External data/function define */
146
-#define EXTERN extern
147
-
148
-/**
149
- * @}
150
- */
151
-
152
-
153
-/* Old Type Definition compatibility ------------------------------------------ */
154
-/** @addtogroup LPC_Types_Public_Types LPC_Types Public Types
155
- * @{
156
- */
157
-
158
-/** SMA type for character type */
159
-typedef char CHAR;
160
-
161
-/** SMA type for 8 bit unsigned value */
162
-typedef uint8_t UNS_8;
163
-
164
-/** SMA type for 8 bit signed value */
165
-typedef int8_t INT_8;
166
-
167
-/** SMA type for 16 bit unsigned value */
168
-typedef	uint16_t UNS_16;
169
-
170
-/** SMA type for 16 bit signed value */
171
-typedef	int16_t INT_16;
172
-
173
-/** SMA type for 32 bit unsigned value */
174
-typedef	uint32_t UNS_32;
175
-
176
-/** SMA type for 32 bit signed value */
177
-typedef	int32_t INT_32;
178
-
179
-/** SMA type for 64 bit signed value */
180
-typedef int64_t INT_64;
181
-
182
-/** SMA type for 64 bit unsigned value */
183
-typedef uint64_t UNS_64;
184
-
185
-/** 32 bit boolean type */
186
-typedef Bool BOOL_32;
187
-
188
-/** 16 bit boolean type */
189
-typedef Bool BOOL_16;
190
-
191
-/** 8 bit boolean type */
192
-typedef Bool BOOL_8;
193
-
194
-/**
195
- * @}
196
- */
197
-
198
-
199
-#endif /* LPC_TYPES_H */
200
-
201
-/**
202
- * @}
203
- */
204
-
205
-/* --------------------------------- End Of File ------------------------------ */

+ 0
- 60
frameworks/CMSIS/LPC1768/include/system_LPC17xx.h Просмотреть файл

@@ -1,60 +0,0 @@
1
-/******************************************************************************
2
- * @file:    system_LPC17xx.h
3
- * @purpose: CMSIS Cortex-M3 Device Peripheral Access Layer Header File
4
- *           for the NXP LPC17xx Device Series
5
- * @version: V1.02
6
- * @date:    27. July 2009
7
- *----------------------------------------------------------------------------
8
- *
9
- * Copyright (C) 2009 ARM Limited. All rights reserved.
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.
14
- *
15
- * THIS SOFTWARE IS PROVIDED "AS IS".  NO WARRANTIES, WHETHER EXPRESS, IMPLIED
16
- * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
17
- * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
18
- * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
19
- * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
20
- *
21
- ******************************************************************************/
22
-
23
-
24
-#ifndef __SYSTEM_LPC17xx_H
25
-#define __SYSTEM_LPC17xx_H
26
-
27
-#ifdef __cplusplus
28
- extern "C" {
29
-#endif
30
-
31
-extern uint32_t SystemCoreClock;     /*!< System Clock Frequency (Core Clock)  */
32
-
33
-
34
-/**
35
- * Initialize the system
36
- *
37
- * @param  none
38
- * @return none
39
- *
40
- * @brief  Setup the microcontroller system.
41
- *         Initialize the System and update the SystemCoreClock variable.
42
- */
43
-extern void SystemInit (void);
44
-
45
-/**
46
- * Update SystemCoreClock variable
47
- *
48
- * @param  none
49
- * @return none
50
- *
51
- * @brief  Updates the SystemCoreClock with current core Clock
52
- *         retrieved from cpu registers.
53
- */
54
-extern void SystemCoreClockUpdate (void);
55
-
56
-#ifdef __cplusplus
57
-}
58
-#endif
59
-
60
-#endif /* __SYSTEM_LPC17xx_H */

+ 0
- 326
frameworks/CMSIS/LPC1768/lib/LiquidCrystal.cpp Просмотреть файл

@@ -1,326 +0,0 @@
1
-#include "LiquidCrystal.h"
2
-
3
-#include <stdio.h>
4
-#include <string.h>
5
-#include <inttypes.h>
6
-#include <Arduino.h>
7
-
8
-// When the display powers up, it is configured as follows:
9
-//
10
-// 1. Display clear
11
-// 2. Function set:
12
-//    DL = 1; 8-bit interface data
13
-//    N = 0; 1-line display
14
-//    F = 0; 5x8 dot character font
15
-// 3. Display on/off control:
16
-//    D = 0; Display off
17
-//    C = 0; Cursor off
18
-//    B = 0; Blinking off
19
-// 4. Entry mode set:
20
-//    I/D = 1; Increment by 1
21
-//    S = 0; No shift
22
-//
23
-// Note, however, that resetting the Arduino doesn't reset the LCD, so we
24
-// can't assume that its in that state when a sketch starts (and the
25
-// LiquidCrystal constructor is called).
26
-
27
-LiquidCrystal::LiquidCrystal(pin_t rs, pin_t rw, pin_t enable,
28
-                             pin_t d0, pin_t d1, pin_t d2, pin_t d3,
29
-                             pin_t d4, pin_t d5, pin_t d6, pin_t d7)
30
-{
31
-  init(0, rs, rw, enable, d0, d1, d2, d3, d4, d5, d6, d7);
32
-}
33
-
34
-LiquidCrystal::LiquidCrystal(pin_t rs, pin_t enable,
35
-                             pin_t d0, pin_t d1, pin_t d2, pin_t d3,
36
-                             pin_t d4, pin_t d5, pin_t d6, pin_t d7)
37
-{
38
-  init(0, rs, P_NC, enable, d0, d1, d2, d3, d4, d5, d6, d7);
39
-}
40
-
41
-LiquidCrystal::LiquidCrystal(pin_t rs, pin_t rw, pin_t enable,
42
-                             pin_t d0, pin_t d1, pin_t d2, pin_t d3)
43
-{
44
-  init(1, rs, rw, enable, d0, d1, d2, d3, P_NC, P_NC, P_NC, P_NC);
45
-}
46
-
47
-LiquidCrystal::LiquidCrystal(pin_t rs,  pin_t enable,
48
-                             pin_t d0, pin_t d1, pin_t d2, pin_t d3)
49
-{
50
-  init(1, rs, P_NC, enable, d0, d1, d2, d3, P_NC, P_NC, P_NC, P_NC);
51
-}
52
-
53
-void LiquidCrystal::init(uint8_t fourbitmode, pin_t rs, pin_t rw, pin_t enable,
54
-                         pin_t d0, pin_t d1, pin_t d2, pin_t d3,
55
-                         pin_t d4, pin_t d5, pin_t d6, pin_t d7)
56
-{
57
-  _rs_pin = rs;
58
-  _rw_pin = rw;
59
-  _enable_pin = enable;
60
-
61
-  _data_pins[0] = d0;
62
-  _data_pins[1] = d1;
63
-  _data_pins[2] = d2;
64
-  _data_pins[3] = d3;
65
-  _data_pins[4] = d4;
66
-  _data_pins[5] = d5;
67
-  _data_pins[6] = d6;
68
-  _data_pins[7] = d7;
69
-
70
-  if (fourbitmode)
71
-    _displayfunction = LCD_4BITMODE | LCD_1LINE | LCD_5x8DOTS;
72
-  else
73
-    _displayfunction = LCD_8BITMODE | LCD_1LINE | LCD_5x8DOTS;
74
-
75
-  begin(16, 1);
76
-}
77
-
78
-void LiquidCrystal::begin(uint8_t cols, uint8_t lines, uint8_t dotsize) {
79
-  if (lines > 1) {
80
-    _displayfunction |= LCD_2LINE;
81
-  }
82
-  _numlines = lines;
83
-
84
-  setRowOffsets(0x00, 0x40, 0x00 + cols, 0x40 + cols);
85
-
86
-  // for some 1 line displays you can select a 10 pixel high font
87
-  if ((dotsize != LCD_5x8DOTS) && (lines == 1)) {
88
-    _displayfunction |= LCD_5x10DOTS;
89
-  }
90
-
91
-  pinMode(_rs_pin, OUTPUT);
92
-  // we can save 1 pin by not using RW. Indicate by passing 255 instead of pin#
93
-  if (_rw_pin != 255) {
94
-    pinMode(_rw_pin, OUTPUT);
95
-  }
96
-  pinMode(_enable_pin, OUTPUT);
97
-
98
-  // Do these once, instead of every time a character is drawn for speed reasons.
99
-  for (int i=0; i<((_displayfunction & LCD_8BITMODE) ? 8 : 4); ++i)
100
-  {
101
-    pinMode(_data_pins[i], OUTPUT);
102
-   }
103
-
104
-  // SEE PAGE 45/46 FOR INITIALIZATION SPECIFICATION!
105
-  // according to datasheet, we need at least 40ms after power rises above 2.7V
106
-  // before sending commands. Arduino can turn on way before 4.5V so we'll wait 50
107
-  delayMicroseconds(50000);
108
-  // Now we pull both RS and R/W low to begin commands
109
-  digitalWrite(_rs_pin, LOW);
110
-  digitalWrite(_enable_pin, LOW);
111
-  if (_rw_pin != 255) {
112
-    digitalWrite(_rw_pin, LOW);
113
-  }
114
-
115
-  //put the LCD into 4 bit or 8 bit mode
116
-  if (! (_displayfunction & LCD_8BITMODE)) {
117
-    // this is according to the hitachi HD44780 datasheet
118
-    // figure 24, pg 46
119
-
120
-    // we start in 8bit mode, try to set 4 bit mode
121
-    write4bits(0x03);
122
-    delayMicroseconds(4500); // wait min 4.1ms
123
-
124
-    // second try
125
-    write4bits(0x03);
126
-    delayMicroseconds(4500); // wait min 4.1ms
127
-
128
-    // third go!
129
-    write4bits(0x03);
130
-    delayMicroseconds(150);
131
-
132
-    // finally, set to 4-bit interface
133
-    write4bits(0x02);
134
-  } else {
135
-    // this is according to the hitachi HD44780 datasheet
136
-    // page 45 figure 23
137
-
138
-    // Send function set command sequence
139
-    command(LCD_FUNCTIONSET | _displayfunction);
140
-    delayMicroseconds(4500);  // wait more than 4.1ms
141
-
142
-    // second try
143
-    command(LCD_FUNCTIONSET | _displayfunction);
144
-    delayMicroseconds(150);
145
-
146
-    // third go
147
-    command(LCD_FUNCTIONSET | _displayfunction);
148
-  }
149
-
150
-  // finally, set # lines, font size, etc.
151
-  command(LCD_FUNCTIONSET | _displayfunction);
152
-
153
-  // turn the display on with no cursor or blinking default
154
-  _displaycontrol = LCD_DISPLAYON | LCD_CURSOROFF | LCD_BLINKOFF;
155
-  display();
156
-
157
-  // clear it off
158
-  clear();
159
-
160
-  // Initialize to default text direction (for romance languages)
161
-  _displaymode = LCD_ENTRYLEFT | LCD_ENTRYSHIFTDECREMENT;
162
-  // set the entry mode
163
-  command(LCD_ENTRYMODESET | _displaymode);
164
-
165
-}
166
-
167
-void LiquidCrystal::setRowOffsets(int row0, int row1, int row2, int row3)
168
-{
169
-  _row_offsets[0] = row0;
170
-  _row_offsets[1] = row1;
171
-  _row_offsets[2] = row2;
172
-  _row_offsets[3] = row3;
173
-}
174
-
175
-/********** high level commands, for the user! */
176
-void LiquidCrystal::clear()
177
-{
178
-  command(LCD_CLEARDISPLAY);  // clear display, set cursor position to zero
179
-  delayMicroseconds(2000);  // this command takes a long time!
180
-}
181
-
182
-void LiquidCrystal::home()
183
-{
184
-  command(LCD_RETURNHOME);  // set cursor position to zero
185
-  delayMicroseconds(2000);  // this command takes a long time!
186
-}
187
-
188
-void LiquidCrystal::setCursor(uint8_t col, uint8_t row)
189
-{
190
-  const size_t max_lines = sizeof(_row_offsets) / sizeof(*_row_offsets);
191
-  if ( row >= max_lines ) {
192
-    row = max_lines - 1;    // we count rows starting w/0
193
-  }
194
-  if ( row >= _numlines ) {
195
-    row = _numlines - 1;    // we count rows starting w/0
196
-  }
197
-
198
-  command(LCD_SETDDRAMADDR | (col + _row_offsets[row]));
199
-}
200
-
201
-// Turn the display on/off (quickly)
202
-void LiquidCrystal::noDisplay() {
203
-  _displaycontrol &= ~LCD_DISPLAYON;
204
-  command(LCD_DISPLAYCONTROL | _displaycontrol);
205
-}
206
-void LiquidCrystal::display() {
207
-  _displaycontrol |= LCD_DISPLAYON;
208
-  command(LCD_DISPLAYCONTROL | _displaycontrol);
209
-}
210
-
211
-// Turns the underline cursor on/off
212
-void LiquidCrystal::noCursor() {
213
-  _displaycontrol &= ~LCD_CURSORON;
214
-  command(LCD_DISPLAYCONTROL | _displaycontrol);
215
-}
216
-void LiquidCrystal::cursor() {
217
-  _displaycontrol |= LCD_CURSORON;
218
-  command(LCD_DISPLAYCONTROL | _displaycontrol);
219
-}
220
-
221
-// Turn on and off the blinking cursor
222
-void LiquidCrystal::noBlink() {
223
-  _displaycontrol &= ~LCD_BLINKON;
224
-  command(LCD_DISPLAYCONTROL | _displaycontrol);
225
-}
226
-void LiquidCrystal::blink() {
227
-  _displaycontrol |= LCD_BLINKON;
228
-  command(LCD_DISPLAYCONTROL | _displaycontrol);
229
-}
230
-
231
-// These commands scroll the display without changing the RAM
232
-void LiquidCrystal::scrollDisplayLeft(void) {
233
-  command(LCD_CURSORSHIFT | LCD_DISPLAYMOVE | LCD_MOVELEFT);
234
-}
235
-void LiquidCrystal::scrollDisplayRight(void) {
236
-  command(LCD_CURSORSHIFT | LCD_DISPLAYMOVE | LCD_MOVERIGHT);
237
-}
238
-
239
-// This is for text that flows Left to Right
240
-void LiquidCrystal::leftToRight(void) {
241
-  _displaymode |= LCD_ENTRYLEFT;
242
-  command(LCD_ENTRYMODESET | _displaymode);
243
-}
244
-
245
-// This is for text that flows Right to Left
246
-void LiquidCrystal::rightToLeft(void) {
247
-  _displaymode &= ~LCD_ENTRYLEFT;
248
-  command(LCD_ENTRYMODESET | _displaymode);
249
-}
250
-
251
-// This will 'right justify' text from the cursor
252
-void LiquidCrystal::autoscroll(void) {
253
-  _displaymode |= LCD_ENTRYSHIFTINCREMENT;
254
-  command(LCD_ENTRYMODESET | _displaymode);
255
-}
256
-
257
-// This will 'left justify' text from the cursor
258
-void LiquidCrystal::noAutoscroll(void) {
259
-  _displaymode &= ~LCD_ENTRYSHIFTINCREMENT;
260
-  command(LCD_ENTRYMODESET | _displaymode);
261
-}
262
-
263
-// Allows us to fill the first 8 CGRAM locations
264
-// with custom characters
265
-void LiquidCrystal::createChar(uint8_t location, uint8_t charmap[]) {
266
-  location &= 0x7; // we only have 8 locations 0-7
267
-  command(LCD_SETCGRAMADDR | (location << 3));
268
-  for (int i=0; i<8; i++) {
269
-    write(charmap[i]);
270
-  }
271
-}
272
-
273
-/*********** mid level commands, for sending data/cmds */
274
-
275
-inline void LiquidCrystal::command(uint8_t value) {
276
-  send(value, LOW);
277
-}
278
-
279
-inline size_t LiquidCrystal::write(uint8_t value) {
280
-  send(value, HIGH);
281
-  return 1; // assume sucess
282
-}
283
-
284
-/************ low level data pushing commands **********/
285
-
286
-// write either command or data, with automatic 4/8-bit selection
287
-void LiquidCrystal::send(uint8_t value, uint8_t mode) {
288
-  digitalWrite(_rs_pin, mode);
289
-
290
-  // if there is a RW pin indicated, set it low to Write
291
-  if (_rw_pin != 255) {
292
-    digitalWrite(_rw_pin, LOW);
293
-  }
294
-
295
-  if (_displayfunction & LCD_8BITMODE) {
296
-    write8bits(value);
297
-  } else {
298
-    write4bits(value>>4);
299
-    write4bits(value);
300
-  }
301
-}
302
-
303
-void LiquidCrystal::pulseEnable(void) {
304
-  digitalWrite(_enable_pin, LOW);
305
-  delayMicroseconds(1);
306
-  digitalWrite(_enable_pin, HIGH);
307
-  delayMicroseconds(1);    // enable pulse must be >450ns
308
-  digitalWrite(_enable_pin, LOW);
309
-  delayMicroseconds(100);   // commands need > 37us to settle
310
-}
311
-
312
-void LiquidCrystal::write4bits(uint8_t value) {
313
-  for (int i = 0; i < 4; i++) {
314
-    digitalWrite(_data_pins[i], (value >> i) & 0x01);
315
-  }
316
-
317
-  pulseEnable();
318
-}
319
-
320
-void LiquidCrystal::write8bits(uint8_t value) {
321
-  for (int i = 0; i < 8; i++) {
322
-    digitalWrite(_data_pins[i], (value >> i) & 0x01);
323
-  }
324
-
325
-  pulseEnable();
326
-}

+ 0
- 0
frameworks/CMSIS/LPC1768/lib/LiquidCrystal.h Просмотреть файл


Некоторые файлы не были показаны из-за большого количества измененных файлов

Загрузка…
Отмена
Сохранить