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


asctec_hl_firmware
Author(s): Markus Achtelik, Michael Achtelik, Stephan Weiss, Laurent Kneip
autogenerated on Tue Jan 7 2014 11:05:19