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" /* LPC21XX Peripheral Registers */ 00030 #include "type.h" 00031 #include "irq.h" 00032 #include "ssp.h" 00033 #include "main.h" 00034 #include "system.h" 00035 #include "LL_HL_comm.h" 00036 #include "sdk.h" 00037 00038 char SPIWRData[128]; 00039 char SPIRDData[128]; 00040 int CurrentTxIndex; 00041 int CurrentRxIndex; 00042 unsigned int SPIWR_num_bytes; 00043 00044 volatile unsigned int SSP_trans_cnt=0; 00045 00046 unsigned char data_sent_to_LL=1; 00047 00048 unsigned char SSP_receiption_complete=1; 00049 00050 char data_sent_to_HL=1; 00051 00052 inline void SSPReceive(unsigned char); 00053 00054 void SSPHandler (void) __irq 00055 { 00056 int regValue; 00057 unsigned short input_data; 00058 // unsigned char timeout=0; 00059 00060 IENABLE; /* handles nested interrupt */ 00061 00062 regValue = SSPMIS; 00063 if ( regValue & SSPMIS_RORMIS ) /* Receive overrun interrupt */ 00064 { 00065 SSPICR = SSPICR_RORIC; /* clear interrupt */ 00066 } 00067 if ( regValue & SSPMIS_RTMIS ) /* Receive timeout interrupt */ 00068 { 00069 SSPICR = SSPICR_RTIC; /* clear interrupt */ 00070 } 00071 00072 if ( regValue & SSPMIS_RXMIS ) /* Rx at least half full */ 00073 { 00074 /* receive until it's empty */ 00075 while ( SSPSR & SSPSR_RNE ) 00076 { 00077 input_data=SSPDR; 00078 //SSPReceive(input_data&0xFF); 00079 //SSPReceive(input_data>>8); 00080 00081 SSP_rx_handler_HL(input_data&0xFF); 00082 SSP_rx_handler_HL(input_data>>8); 00083 00084 //SSP_trans_cnt+=2; 00085 /* Wait until the Busy bit is cleared */ 00086 // while ( (!(SSPSR & SSPSR_BSY) )&&(timeout++<50) ); 00087 } /* interrupt will be cleared when */ 00088 /* data register is read or written */ 00089 } 00090 00091 if ( regValue & SSPMIS_TXMIS ) /* Tx at least half empty */ 00092 { 00093 /* transmit until it's full */ 00094 while ( (SSPSR & SSPSR_TNF) ) 00095 { 00096 if(CurrentTxIndex<SPIWR_num_bytes) 00097 { 00098 SSPDR = SPIWRData[CurrentTxIndex]|(SPIWRData[CurrentTxIndex+1]<<8); 00099 CurrentTxIndex+=2; 00100 } 00101 else 00102 { 00103 CurrentTxIndex=0; 00104 SPIWR_num_bytes=0; 00105 data_sent_to_LL=1; 00106 SSPDR=0; 00107 } 00108 00109 /* Wait until the Busy bit is cleared */ 00110 // while ( !(SSPSR & SSPSR_BSY) ); 00111 } /* interrupt will be cleared when */ 00112 /* data register is read or written */ 00113 } 00114 00115 IDISABLE; 00116 VICVectAddr = 0; /* Acknowledge Interrupt */ 00117 } 00118 00119 void LL_write_init(void) 00120 { 00121 SPIWRData[0]='>'; 00122 SPIWRData[1]='*'; 00123 SPIWRData[2]='>'; 00124 } 00125 00126 int LL_write(unsigned char *data, unsigned short cnt, unsigned char PD ) //write data to high-level processor 00127 { 00128 unsigned int i; 00129 00130 if(data_sent_to_LL) 00131 { 00132 SPIWRData[3]=PD; 00133 for(i=0; i<cnt; i++) 00134 { 00135 SPIWRData[i+4]=data[i]; 00136 } 00137 SPIWRData[cnt+4]=0; 00138 SPIWR_num_bytes=cnt+5; 00139 } 00140 else if(SPIWR_num_bytes+cnt<127) 00141 { 00142 SPIWRData[SPIWR_num_bytes-1]='>'; 00143 SPIWRData[0+SPIWR_num_bytes]='*'; 00144 SPIWRData[1+SPIWR_num_bytes]='>'; 00145 SPIWRData[2+SPIWR_num_bytes]=PD; 00146 for(i=SPIWR_num_bytes; i<cnt+SPIWR_num_bytes; i++) 00147 { 00148 SPIWRData[i+3]=data[i-SPIWR_num_bytes]; 00149 } 00150 SPIWR_num_bytes+=cnt+5; 00151 SPIWRData[SPIWR_num_bytes-1]=0; 00152 } 00153 else return(0); 00154 data_sent_to_LL=0; 00155 00156 return(1); 00157 } 00158 00159 00160 00161 00162 00163 /* old file 00164 #include "LPC214x.h" //LPC21XX Peripheral Registers 00165 #include "type.h" 00166 #include "irq.h" 00167 #include "ssp.h" 00168 #include "main.h" 00169 #include "system.h" 00170 #include "LL_HL_comm.h" 00171 00172 char SPIWRData[128]; 00173 char SPIRDData[128]; 00174 int CurrentTxIndex; 00175 int CurrentRxIndex; 00176 unsigned int SPIWR_num_bytes; 00177 00178 volatile unsigned int SSP_trans_cnt=0; 00179 00180 unsigned char data_sent_to_LL=1; 00181 00182 unsigned char SSP_receiption_complete=1; 00183 unsigned char IMU_CalcData_updated=0; 00184 00185 00186 char data_sent_to_HL=1; 00187 00188 inline void SSPReceive(unsigned char); 00189 00190 void SSPHandler (void) __irq 00191 { 00192 int regValue; 00193 unsigned short input_data; 00194 // unsigned char timeout=0; 00195 00196 IENABLE; // handles nested interrupt 00197 00198 regValue = SSPMIS; 00199 if ( regValue & SSPMIS_RORMIS ) // Receive overrun interrupt 00200 { 00201 SSPICR = SSPICR_RORIC; // clear interrupt 00202 } 00203 if ( regValue & SSPMIS_RTMIS ) // Receive timeout interrupt 00204 { 00205 SSPICR = SSPICR_RTIC; // clear interrupt 00206 } 00207 00208 if ( regValue & SSPMIS_RXMIS ) // Rx at least half full 00209 { 00210 // receive until it's empty 00211 while ( SSPSR & SSPSR_RNE ) 00212 { 00213 input_data=SSPDR; 00214 //SSPReceive(input_data&0xFF); 00215 //SSPReceive(input_data>>8); 00216 00217 SSP_rx_handler_HL(input_data&0xFF); 00218 SSP_rx_handler_HL(input_data>>8); 00219 00220 //SSP_trans_cnt+=2; 00221 // Wait until the Busy bit is cleared 00222 // while ( (!(SSPSR & SSPSR_BSY) )&&(timeout++<50) ); 00223 } // interrupt will be cleared when 00224 // data register is read or written 00225 } 00226 00227 if ( regValue & SSPMIS_TXMIS ) // Tx at least half empty 00228 { 00229 // transmit until it's full 00230 while ( (SSPSR & SSPSR_TNF) ) 00231 { 00232 if(CurrentTxIndex<SPIWR_num_bytes) 00233 { 00234 SSPDR = SPIWRData[CurrentTxIndex]|(SPIWRData[CurrentTxIndex+1]<<8); 00235 CurrentTxIndex+=2; 00236 } 00237 else 00238 { 00239 CurrentTxIndex=0; 00240 SPIWR_num_bytes=0; 00241 data_sent_to_LL=1; 00242 SSPDR=0; 00243 } 00244 00245 // Wait until the Busy bit is cleared 00246 // while ( !(SSPSR & SSPSR_BSY) ); 00247 } // interrupt will be cleared when 00248 // data register is read or written 00249 } 00250 00251 IDISABLE; 00252 VICVectAddr = 0; // Acknowledge Interrupt 00253 } 00254 00255 00256 inline void SSPReceive(unsigned char SPI_rxdata) 00257 { 00258 static unsigned char SPI_syncstate=0; 00259 static unsigned char SPI_rxcount=0; 00260 static unsigned char *SPI_rxptr; 00261 static volatile unsigned char incoming_data; 00262 00263 //receive handler 00264 if (SPI_syncstate==0) 00265 { 00266 if (SPI_rxdata=='>') SPI_syncstate++; else SPI_syncstate=0; 00267 } 00268 else if (SPI_syncstate==1) 00269 { 00270 if (SPI_rxdata=='*') SPI_syncstate++; else SPI_syncstate=0; 00271 } 00272 else if (SPI_syncstate==2) 00273 { 00274 if (SPI_rxdata=='>') SPI_syncstate++; else SPI_syncstate=0; 00275 } 00276 else if (SPI_syncstate==3) 00277 { 00278 if (SPI_rxdata==PD_IMUCALCDATA) //IMU CalcData 00279 { 00280 SPI_rxcount=sizeof(IMU_CalcData); 00281 SPI_rxptr=(unsigned char *)&IMU_CalcData_tmp; 00282 SPI_syncstate=4; 00283 incoming_data=PD_IMUCALCDATA; 00284 } 00285 else if (SPI_rxdata==PD_IMURAWDATA) //IMU CalcData 00286 { 00287 SPI_rxcount=sizeof(IMU_RawData); 00288 SPI_rxptr=(unsigned char *)&IMU_RawData; 00289 SPI_syncstate=4; 00290 incoming_data=PD_IMURAWDATA; 00291 } 00292 else SPI_syncstate=0; 00293 } 00294 else if (SPI_syncstate==4) 00295 { 00296 SPI_rxcount--; 00297 *SPI_rxptr=SPI_rxdata; 00298 SPI_rxptr++; 00299 if (SPI_rxcount==0) 00300 { 00301 SPI_syncstate=5; 00302 if(incoming_data==PD_IMUCALCDATA) 00303 { 00304 IMU_CalcData_updated=1; 00305 } 00306 incoming_data=0; 00307 } 00308 } 00309 else if(SPI_syncstate==5) //check if another packet is pending 00310 { 00311 if(SPI_rxdata==0) 00312 { 00313 SPI_syncstate=0; 00314 } 00315 else SPI_syncstate=1; 00316 } 00317 else SPI_syncstate=0; 00318 00319 if(!SPI_syncstate) SSP_receiption_complete=1; 00320 else SSP_receiption_complete=0; 00321 } 00322 00323 void LL_write_init(void) 00324 { 00325 SPIWRData[0]='>'; 00326 SPIWRData[1]='*'; 00327 SPIWRData[2]='>'; 00328 } 00329 00330 int LL_write(unsigned char *data, unsigned short cnt, unsigned char PD ) //write data to high-level processor 00331 { 00332 unsigned int i; 00333 // 00334 // if(data_sent_to_LL) 00335 // { 00336 //SSP_trans_cnt++; 00337 // if(!SPIWR_num_bytes) 00338 // { 00339 // SPIWRData[3]=PD; 00340 // for(i=0; i<cnt; i++) 00341 // { 00342 // SPIWRData[i+4]=data[i]; 00343 // } 00344 // SPIWRData[cnt+4]=0; 00345 // SPIWR_num_bytes=cnt+5; 00346 00347 // } 00348 // } 00349 00350 if(data_sent_to_LL) 00351 { 00352 SPIWRData[3]=PD; 00353 for(i=0; i<cnt; i++) 00354 { 00355 SPIWRData[i+4]=data[i]; 00356 } 00357 SPIWRData[cnt+4]=0; 00358 SPIWR_num_bytes=cnt+5; 00359 } 00360 else if(SPIWR_num_bytes+cnt<127) 00361 { 00362 SPIWRData[SPIWR_num_bytes-1]='>'; 00363 SPIWRData[0+SPIWR_num_bytes]='*'; 00364 SPIWRData[1+SPIWR_num_bytes]='>'; 00365 SPIWRData[2+SPIWR_num_bytes]=PD; 00366 for(i=SPIWR_num_bytes; i<cnt+SPIWR_num_bytes; i++) 00367 { 00368 SPIWRData[i+3]=data[i-SPIWR_num_bytes]; 00369 } 00370 SPIWR_num_bytes+=cnt+5; 00371 SPIWRData[SPIWR_num_bytes-1]=0; 00372 } 00373 else return(0); 00374 data_sent_to_LL=0; 00375 00376 return(1); 00377 } 00378 //end old file */ 00379