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


ccny_asctec_firmware_2
Author(s): Ivan Dryanovski, Roberto G. Valenti
autogenerated on Tue Jan 7 2014 11:04:17