00001 /* 00002 00003 Copyright (c) 2011, Ascending Technologies GmbH 00004 All rights reserved. 00005 00006 Redistribution and use in source and binary forms, with or without 00007 modification, are permitted provided that the following conditions are met: 00008 00009 * Redistributions of source code must retain the above copyright notice, 00010 this list of conditions and the following disclaimer. 00011 * Redistributions in binary form must reproduce the above copyright 00012 notice, this list of conditions and the following disclaimer in the 00013 documentation and/or other materials provided with the distribution. 00014 00015 THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND ANY 00016 EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 00017 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00018 DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE FOR ANY 00019 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 00020 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 00021 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00022 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00023 LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY 00024 OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH 00025 DAMAGE. 00026 00027 */ 00028 00029 #include "LPC214x.h" 00030 #include "system.h" 00031 #include "uart.h" 00032 #include "uart1.h" 00033 #include "main.h" 00034 #include "hardware.h" 00035 #include "LPC2k_ee.h" 00036 #include "type.h" 00037 #include "irq.h" 00038 #include "i2c.h" 00039 #include "ssp.h" 00040 #include "adc.h" 00041 00042 #include "sdk.h" 00043 00044 void init(void) 00045 { 00046 MAMCR=0x00; 00047 MAMTIM=0x03; 00048 MAMCR=0x02; 00049 VPBDIV = 0x01; //0x01: peripheral frequency == cpu frequency, 0x00: per. freq. = crystal freq. 00050 pll_init(); 00051 pll_feed(); 00052 init_ports(); 00053 UARTInitialize(57600); //debug / command 00054 UART1Initialize(57600); //57600 Servo / GPS, 38400 "indoor GPS" 00055 init_spi(); 00056 init_spi1(); 00057 init_timer0(); 00058 init_timer1(); 00059 // I2CInit(I2CMASTER); 00060 PWM_Init(); 00061 ADCInit(ADC_CLK); 00062 init_interrupts(); 00063 } 00064 00065 void init_interrupts(void) 00066 { 00067 init_VIC(); 00068 00069 //Timer0 interrupt 00070 install_irq( TIMER0_INT, (void *) timer0ISR ); 00071 00072 //Timer1 interrupt 00073 install_irq( TIMER1_INT, (void *) timer1ISR ); 00074 00075 //UART1 interrupt 00076 install_irq( UART1_INT, (void *) uart1ISR ); 00077 U1IER = 3; //=3; enable THRE and RX interrupt 00078 00079 //UART0 interrupt 00080 install_irq( UART0_INT, (void *) uart0ISR ); 00081 U0IER = 3; //=3; enable THRE and RX interrupt 00082 00083 //I2C0 interrupt 00084 // install_irq( I2C0_INT, (void *) I2C0MasterHandler ); 00085 // I20CONSET = I2CONSET_I2EN; 00086 00087 //SSP interrupt 00088 install_irq( SPI1_INT, (void *) SSPHandler ); 00089 /* Set SSPINMS registers to enable interrupts */ 00090 /* enable all interrupts, Rx overrun, Rx timeout, RX FIFO half full int, 00091 TX FIFO half empty int */ 00092 SSPIMSC = SSPIMSC_TXIM | SSPIMSC_RXIM | SSPIMSC_RORIM;// | SSPIMSC_RTIM; 00093 /* SSP Enabled */ 00094 SSPCR1 |= SSPCR1_SSE; 00095 } 00096 00097 00098 void init_ports(void) 00099 { 00100 /* PINSEL0 00101 * 00102 * PORT0: 00103 * P0.0: TXD0 -> 01 00104 * P0.1: RXD0 -> 01 00105 * P0.2: SCO0 -> 01 00106 * P0.3: SDA0 -> 01 00107 * Byte0_sel = 0b01010101 = 0x55 00108 * 00109 * P0.4: SCK0 -> 01 00110 * P0.5: MISO0 -> 01 00111 * P0.6: MOSI0 -> 01 00112 * P0.7: LL_NCS/IO_out -> 00 00113 * or: PWM2 -> 10 00114 * Byte1_sel = 0x00010101 = 0x15 00115 * Byte0_io_dir = 0x80 00116 * 00117 * P0.8: TXD1 -> 01 00118 * P0.9: RXD1 -> 01 00119 * P0.10: IO_in -> 00 00120 * P0.11: SCL1 -> 11 00121 * or Falcon8: IO_out -> 00 00122 * Byte2_sel = 0b11000101 = 0xC5 00123 * 00124 * P0.12: IO_in -> 00 00125 * P0.13: IO_in -> 00 00126 * P0.14: SDA1 -> 11 00127 * or IO_out (CS SD-Card) => SD_Logging 00128 * P0.15: IO_in -> 00 00129 * Byte3_sel = 0b00110000 = 0x30 00130 * Byte1_io_dir = 0x00 00131 * or SD_Logging => Byte1_io_dir=0x40 00132 */ 00133 00134 PINSEL0=0x30C51555; 00135 00136 /* PINSEL1 00137 * 00138 * P0.16: IO_in -> 00 00139 * P0.17: SCK1 -> 10 00140 * P0.18: MISO1 -> 10 00141 * P0.19: MOSI1-> 10 00142 * Byte0: 0b10101000 = 0xA8 00143 * 00144 * P0.20: SSEL1 -> 10 00145 * P0.21: PWM5 -> 01 00146 * P0.22: IO_in -> 00 00147 * P0.23: IO_in -> 00 00148 * Byte1: 0b00000110 = 0x06 00149 * Byte2_io_dir: 0x30 //0x11 00150 * 00151 * P0.24: 00 00152 * P0.25: VOLTAGE_2: -> 01 00153 * or IO_in (FALCON) -> 00 00154 * P0.26: 00 00155 * P0.27: 00 00156 * Byte2: 0b00000100 = 0x04 00157 * 00158 * P0.28: CURRENT_2: -> 01 00159 * P0.29: VOLTAGE_1: -> 01 00160 * P0.30: CURRENT_1: -> 01 00161 * P0.31: IO_in -> 00 00162 * Byte3: 0b00010101 = 0x15 00163 * Byte3_io_dir=0x00 00164 */ 00165 PINSEL1 = 0x150406A8; 00166 00167 PINSEL2 = 0x00000004; 00168 00169 IODIR0 = 0x0030B480; 00170 00171 IOSET0 = (1<<EXT_NCS)|(1<<11); //all nCS high 00172 //IOSET0 = (1<<LL_nCS); //CS LL_Controller 00173 00174 /* P1.16: IO_1/IO_out => FET for camera power supply 00175 * P1.17: Beeper/IO_out 00176 * . 00177 * . 00178 * P1.24: LED1/IO_out 00179 * P1.25: LED2/IO_out 00180 * 00181 */ 00182 00183 IODIR1 = 0x03030000; 00184 IOSET1 = ((1<<24)|(1<<16)); //turn off LED1, turn beeper off 00185 00186 } 00187 00188 void init_timer0(void) 00189 { 00190 T0TC=0; 00191 T0TCR=0x0; //Reset timer0 00192 T0MCR=0x3; //Interrupt on match MR0 and reset counter 00193 T0PR=0; 00194 T0PC=0; //Prescale Counter = 0 00195 T0MR0=peripheralClockFrequency()/ControllerCyclesPerSecond; // /200 => 200 Hz Period 00196 T0TCR=0x1; //Set timer0 00197 } 00198 00199 //Weiss:{ 00200 void init_timer1(void) 00201 { 00202 T1TC=0; 00203 T1TCR=0x0; //disable timer1 00204 T1MCR=0x3; //Interrupt on match MR0 and reset counter 00205 T1PR=0; 00206 T1PC=0; //Prescale Counter = 0 00207 T1MR0=processorClockFrequency(); // match every s 00208 T1TCR=0x1; //enable timer1 00209 } 00210 //} 00211 00212 void PWM_Init( void ) 00213 { 00214 // match_counter = 0; 00215 // PINSEL0 = 0x000A800A; /* set GPIOs for all PWMs */ 00216 // PINSEL1 = 0x00000400; 00217 PWMTCR = TCR_RESET; /* Counter Reset */ 00218 00219 PWMPR = 0x00; /* count frequency:Fpclk */ 00220 PWMMCR = PWMMR0R; /* interrupt on PWMMR0, reset on PWMMR0, reset 00221 TC if PWM0 matches */ 00222 PWMMR0 = 1179648 ; 00223 PWMMR5 = 88470; 00224 00225 /* all PWM latch enabled */ 00226 PWMLER = LER5_EN; 00227 00228 /* All single edge, all enable */ 00229 PWMPCR = PWMENA1 | PWMENA2 | PWMENA3 | PWMENA4 | PWMENA5 | PWMENA6; 00230 PWMTCR = TCR_CNT_EN | TCR_PWM_EN; /* counter enable, PWM enable */ 00231 } 00232 00233 00234 void init_spi(void) 00235 { 00236 S0SPCCR=0x04; //30 clock-cycles (~60MHz) = 1 SPI cycle => SPI @ 2MHz 00237 S0SPCR=0x20; //LPC is Master 00238 } 00239 00240 void init_spi1(void) 00241 { 00242 unsigned char i, Dummy; 00243 00244 /* Set DSS data to 8-bit, Frame format SPI, CPOL = 0, CPHA = 0, and SCR is 3 */ 00245 SSPCR0 = 0x040F; 00246 00247 /* SSPCPSR clock prescale register, master mode, minimum divisor is 0x02 */ 00248 SSPCPSR = 0x1B; 00249 00250 for ( i = 0; i < FIFOSIZE; i++ ) 00251 { 00252 Dummy = SSPDR; /* clear the RxFIFO */ 00253 } 00254 00255 /*all ints deactivated*/ 00256 SSPIMSC = 0; 00257 00258 /* Device select as master, SSP Enabled */ 00259 SSPCR1 = 0x00;// | SSPCR1_SSE; 00260 00261 return; 00262 00263 00264 } 00265 00266 void pll_init(void) 00267 { 00268 PLLCFG=0x23; //0b00100011; => M=4,0690; P=2; 00269 PLLCON=0x03; //PLLE=1, PLLC=1 => PLL enabled as system clock 00270 } 00271 00272 void pll_feed(void) 00273 { 00274 PLLFEED=0xAA; 00275 PLLFEED=0x55; 00276 } 00277 00278 unsigned int processorClockFrequency(void) 00279 { 00280 return 58982400; 00281 } 00282 00283 unsigned int peripheralClockFrequency(void) 00284 { 00285 unsigned int divider; 00286 switch (VPBDIV & 3) 00287 { 00288 case 0: 00289 divider = 4; 00290 break; 00291 case 1: 00292 divider = 1; 00293 break; 00294 case 2: 00295 divider = 2; 00296 break; 00297 } 00298 return processorClockFrequency() / divider; 00299 } 00300 00301 void delay(int n) 00302 { 00303 volatile int i; 00304 for (i = 0; i < n; ++i); 00305 } 00306 00307