$search
00001 #include "LPC214x.h" 00002 #include "interrupt_utils.h" 00003 #include "system.h" 00004 #include "main.h" 00005 #include "uart1.h" 00006 #include "irq.h" 00007 #include "hardware.h" 00008 #include "gpsmath.h" 00009 #include "ssp.h" 00010 00011 unsigned char packets; 00012 unsigned char DataOutputsPerSecond; 00013 unsigned int uart_cnt; 00014 00015 unsigned char data_requested=0; 00016 extern int ZeroDepth; 00017 00018 unsigned short current_chksum; 00019 unsigned char chksum_to_check=0; 00020 unsigned char chksum_trigger=1; 00021 00022 unsigned char transmission1_running=0; 00023 unsigned char trigger_transmission=0; 00024 00025 volatile unsigned char baudrate1_change=0; 00026 00027 unsigned char send_buffer[16]; 00028 unsigned char *tx_buff; 00029 unsigned char UART1_syncstate=0; 00030 unsigned int UART1_rxcount=0; 00031 unsigned char *UART1_rxptr; 00032 00033 unsigned char UART_CalibDoneFlag = 0; 00034 00035 static volatile unsigned char rb_busy=0; 00036 00037 static volatile unsigned char GPS_ACK_received=0; 00038 00039 /* 00040 //configuration commands for GPS 00041 const unsigned char GPS_CFG_PRT[26] = 00042 { 0x06, 0x00, 0x14, 0x00, 0x01, 0x00, 0x00, 0x00, 0xd0, 0x08, 0x08, 0x00, 0x00, 00043 0xe1, 0x00, 0x00, 0x07, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe4, 0x2d }; 00044 const unsigned char GPS_CFG_ANT[10] = 00045 { 0x06, 0x13, 0x04, 0x00, 0x0b, 0x00, 0x0f, 0x38, 0x6f, 0x4f }; 00046 const unsigned char GPS_CFG_MSG[11][12] = 00047 { {0x06, 0x01, 0x06, 0x00, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x0f, 0x80}, 00048 {0x06, 0x01, 0x06, 0x00, 0x01, 0x02, 0x00, 0x01, 0x00, 0x00, 0x11, 0x88}, 00049 {0x06, 0x01, 0x06, 0x00, 0x01, 0x03, 0x00, 0x01, 0x00, 0x00, 0x12, 0x8d}, 00050 {0x06, 0x01, 0x06, 0x00, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x12, 0x8f}, 00051 {0x06, 0x01, 0x06, 0x00, 0x01, 0x06, 0x00, 0x01, 0x00, 0x00, 0x15, 0x9c}, 00052 {0x06, 0x01, 0x06, 0x00, 0x01, 0x11, 0x00, 0x00, 0x00, 0x00, 0x1f, 0xd0}, 00053 {0x06, 0x01, 0x06, 0x00, 0x01, 0x12, 0x00, 0x01, 0x00, 0x00, 0x21, 0xd8}, 00054 {0x06, 0x01, 0x06, 0x00, 0x01, 0x20, 0x00, 0x00, 0x00, 0x00, 0x2e, 0x1b}, 00055 {0x06, 0x01, 0x06, 0x00, 0x01, 0x21, 0x00, 0x00, 0x00, 0x00, 0x2f, 0x20}, 00056 {0x06, 0x01, 0x06, 0x00, 0x01, 0x22, 0x00, 0x00, 0x00, 0x00, 0x30, 0x25}, 00057 {0x06, 0x01, 0x06, 0x00, 0x01, 0x30, 0x00, 0x00, 0x00, 0x00, 0x3e, 0x6b} }; 00058 const unsigned char GPS_CFG_NAV2[46] = 00059 { 0x06, 0x1a, 0x28, 0x00, 0x05, 0x00, 0x00, 0x00, 0x04, 0x03, 0x10, 0x02, 00060 0x50, 0xc3, 0x00, 0x00, 0x0f, 0x0a, 0x0a, 0x3c, 0x00, 0x01, 0x00, 0x00, 00061 0xfa, 0x00, 0xfa, 0x00, 0x64, 0x00, 0x2c, 0x01, 0x00, 0x00, 0x00, 0x00, 00062 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5e, 0x30 }; 00063 const unsigned char GPS_CFG_RATE[12] = 00064 { 0x06, 0x08, 0x06, 0x00, 0xc8, 0x00, 0x01, 0x00, 0x00, 0x00, 0xdd, 0x68 }; 00065 const unsigned char GPS_CFG_SBAS[14] = 00066 { 0x06, 0x16, 0x08, 0x00, 0x03, 0x07, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 00067 0x2f, 0xd9 }; 00068 const unsigned char GPS_CFG_CFG[19] = 00069 { 0x06, 0x09, 0x0d, 0x00, 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0x00, 0x00, 00070 0x00, 0x00, 0x00, 0x00, 0x07, 0x21, 0xaf }; 00071 */ 00072 00073 // new commands for gps, sbas disabled 00074 const unsigned char GPS_CFG_PRT[26] = 00075 { 0x06, 0x00, 0x14, 0x00, 0x01, 0x00, 0x00, 0x00, 0xd0, 0x08, 0x08, 0x00, 0x00, 00076 0xe1, 0x00, 0x00, 0x07, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe4, 0x2d }; 00077 const unsigned char GPS_CFG_ANT[10] = 00078 { 0x06, 0x13, 0x04, 0x00, 0x0b, 0x00, 0x0f, 0x38, 0x6f, 0x4f }; 00079 const unsigned char GPS_CFG_MSG[11][12] = 00080 { {0x06, 0x01, 0x06, 0x00, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x0f, 0x80}, 00081 {0x06, 0x01, 0x06, 0x00, 0x01, 0x02, 0x00, 0x01, 0x00, 0x00, 0x11, 0x88}, 00082 {0x06, 0x01, 0x06, 0x00, 0x01, 0x03, 0x00, 0x01, 0x00, 0x00, 0x12, 0x8d}, 00083 {0x06, 0x01, 0x06, 0x00, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x12, 0x8f}, 00084 {0x06, 0x01, 0x06, 0x00, 0x01, 0x06, 0x00, 0x01, 0x00, 0x00, 0x15, 0x9c}, 00085 {0x06, 0x01, 0x06, 0x00, 0x01, 0x11, 0x00, 0x00, 0x00, 0x00, 0x1f, 0xd0}, 00086 {0x06, 0x01, 0x06, 0x00, 0x01, 0x12, 0x00, 0x01, 0x00, 0x00, 0x21, 0xd8}, 00087 {0x06, 0x01, 0x06, 0x00, 0x01, 0x20, 0x00, 0x00, 0x00, 0x00, 0x2e, 0x1b}, 00088 {0x06, 0x01, 0x06, 0x00, 0x01, 0x21, 0x00, 0x00, 0x00, 0x00, 0x2f, 0x20}, 00089 {0x06, 0x01, 0x06, 0x00, 0x01, 0x22, 0x00, 0x00, 0x00, 0x00, 0x30, 0x25}, 00090 {0x06, 0x01, 0x06, 0x00, 0x01, 0x30, 0x00, 0x00, 0x00, 0x00, 0x3e, 0x6b} }; 00091 const unsigned char GPS_CFG_SBAS[14] = 00092 { 0x06, 0x16, 0x08, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 00093 0x25, 0x90 }; //SBAS OFF 00094 const unsigned char GPS_CFG_NAV2[46] = 00095 { 0x06, 0x1a, 0x28, 0x00, 0x05, 0x00, 0x00, 0x00, 0x04, 0x03, 0x0A, 0x02, 00096 0x50, 0xc3, 0x00, 0x00, 0x0f, 0x0a, 0x0a, 0x3c, 0x00, 0x01, 0x00, 0x00, 00097 0xfa, 0x00, 0xfa, 0x00, 0x64, 0x00, 0x2c, 0x01, 0x00, 0x00, 0x00, 0x00, 00098 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x58, 0x64 }; //max SV=10 00099 const unsigned char GPS_CFG_RATE[12] = 00100 { 0x06, 0x08, 0x06, 0x00, 0xc8, 0x00, 0x01, 0x00, 0x00, 0x00, 0xdd, 0x68 }; //5Hz 00101 const unsigned char GPS_CFG_CFG[19] = 00102 { 0x06, 0x09, 0x0d, 0x00, 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0x00, 0x00, 00103 0x00, 0x00, 0x00, 0x00, 0x07, 0x21, 0xaf }; 00104 00105 /* 00106 00107 //globals for NMEA parser 00108 double latitudeDeg; 00109 double longitudeDeg; 00110 char gprmc_string[5]="GPRMC"; 00111 static unsigned char gpsState=GPS_IDLE; 00112 static unsigned char gpsCnt=0; 00113 static unsigned char gpsFieldStart=1; 00114 static unsigned char gpsFieldCnt=0; 00115 static unsigned char gpsInitString[5]; 00116 static unsigned char gpsValue[20]; 00117 //<- globals 00118 */ 00119 unsigned char startstring[]={'>','*','>'}; 00120 unsigned char stopstring[]={'<','#','<'}; 00121 00122 void parse_POSLLH(unsigned char, unsigned char); 00123 void parse_POSUTM(unsigned char, unsigned char); 00124 void parse_VELNED(unsigned char, unsigned char); 00125 void parse_STATUS(unsigned char, unsigned char); 00126 void parse_NAVSOL(unsigned char, unsigned char); 00127 00128 inline void parse_VELNED(unsigned char c, unsigned char reset) 00129 { 00130 static unsigned char cnt=0; 00131 static int VE, VN, heading; 00132 static unsigned int sacc; 00133 00134 if(reset) cnt=0; 00135 else 00136 { 00137 if(cnt==0) VN=c; 00138 else if(cnt==1) VN+=c<<8; 00139 else if(cnt==2) VN+=c<<16; 00140 else if(cnt==3) VN+=c<<24; 00141 else if(cnt==4) VE=c; 00142 else if(cnt==5) VE+=c<<8; 00143 else if(cnt==6) VE+=c<<16; 00144 else if(cnt==7) VE+=c<<24; 00145 else if(cnt==20) heading=c; 00146 else if(cnt==21) heading+=c<<8; 00147 else if(cnt==22) heading+=c<<16; 00148 else if(cnt==23) heading+=c<<24; 00149 else if(cnt==24) sacc=c; 00150 else if(cnt==25) sacc+=c<<8; 00151 else if(cnt==26) sacc+=c<<16; 00152 else if(cnt==27) 00153 { 00154 sacc+=c<<24; 00155 GPS_Data.speed_x=VE*10; //convert to mm/s 00156 GPS_Data.speed_y=VN*10; //convert to mm/s 00157 GPS_Data.heading=heading/100; //convert to deg * 1000 00158 GPS_Data.speed_accuracy=sacc*10; //convert to mm/s 00159 gpsDataOkTrigger=1; 00160 } 00161 cnt++; 00162 } 00163 } 00164 inline void parse_POSLLH(unsigned char c, unsigned char reset) 00165 { 00166 static unsigned char cnt=0; 00167 static int lat, lon, height; 00168 static unsigned int hacc, vacc; 00169 00170 if(reset) cnt=0; 00171 else 00172 { 00173 if(cnt==0) lon=c; 00174 else if(cnt==1) lon+=c<<8; 00175 else if(cnt==2) lon+=c<<16; 00176 else if(cnt==3) lon+=c<<24; 00177 else if(cnt==4) lat=c; 00178 else if(cnt==5) lat+=c<<8; 00179 else if(cnt==6) lat+=c<<16; 00180 else if(cnt==7) lat+=c<<24; 00181 else if(cnt==12) height=c; 00182 else if(cnt==13) height+=c<<8; 00183 else if(cnt==14) height+=c<<16; 00184 else if(cnt==15) height+=c<<24; 00185 else if(cnt==16) hacc=c; 00186 else if(cnt==17) hacc+=c<<8; 00187 else if(cnt==18) hacc+=c<<16; 00188 else if(cnt==19) hacc+=c<<24; 00189 else if(cnt==20) vacc=c; 00190 else if(cnt==21) vacc+=c<<8; 00191 else if(cnt==22) vacc+=c<<16; 00192 else if(cnt==23) 00193 { 00194 vacc+=c<<24; 00195 GPS_Data.latitude=lat; 00196 GPS_Data.longitude=lon; 00197 GPS_Data.height=height; 00198 GPS_Data.horizontal_accuracy=hacc; 00199 GPS_Data.vertical_accuracy=vacc; 00200 } 00201 cnt++; 00202 } 00203 } 00204 inline void parse_POSUTM(unsigned char c, unsigned char reset) 00205 { 00206 static unsigned char cnt=0; 00207 static int E, N; 00208 00209 if(reset) cnt=0; 00210 else 00211 { 00212 if(cnt==0) E=c; 00213 else if(cnt==1) E+=c<<8; 00214 else if(cnt==2) E+=c<<16; 00215 else if(cnt==3) E+=c<<24; 00216 else if(cnt==4) N=c; 00217 else if(cnt==5) N+=c<<8; 00218 else if(cnt==6) N+=c<<16; 00219 else if(cnt==7) 00220 { 00221 N+=c<<24; 00222 // GPS_Data.x=E; 00223 // GPS_Data.y=N; 00224 } 00225 cnt++; 00226 } 00227 } 00228 00229 //NAVSOL is the only packet where the first 4 bytes need to be parsed. Any other packet discardes the first 4 bytes!!! 00230 inline void parse_NAVSOL(unsigned char c, unsigned char reset) 00231 { 00232 static unsigned char cnt=0; 00233 static unsigned int tow; 00234 static unsigned short week; 00235 00236 if(reset) cnt=0; 00237 else 00238 { 00239 if(cnt==0) tow=c; 00240 else if(cnt==1) tow+=c<<8; 00241 else if(cnt==2) tow+=c<<16; 00242 else if(cnt==3) tow+=c<<24; 00243 else if(cnt==8) week=c; 00244 else if(cnt==9) 00245 { 00246 week+=c<<8; 00247 GPS_Time.time_of_week=tow; 00248 GPS_Time.week=week; 00249 } 00250 else if(cnt==47) 00251 { 00252 GPS_Data.numSV=c; 00253 } 00254 cnt++; 00255 } 00256 } 00257 00258 inline void parse_STATUS(unsigned char c, unsigned char reset) 00259 { 00260 static unsigned char cnt=0; 00261 static unsigned char GPSfix, flags, diffs; 00262 00263 if(reset) cnt=0; 00264 else 00265 { 00266 if(cnt==0) GPSfix=c; 00267 else if(cnt==1) flags=c; 00268 else if(cnt==2) 00269 { 00270 diffs=c; 00271 GPS_Data.status=GPSfix|(flags<<8)|(diffs<<16); 00272 } 00273 cnt++; 00274 } 00275 } 00276 00277 void uart1ISR(void) __irq 00278 { 00279 static unsigned char state; 00280 static unsigned char current_packet; 00281 static unsigned short cnt, length; 00282 unsigned char t; 00283 unsigned char c; 00284 IENABLE; 00285 unsigned iir = U1IIR; 00286 // Handle UART interrupt 00287 switch ((iir >> 1) & 0x7) 00288 { 00289 case 1: 00290 // THRE interrupt 00291 00292 if (ringbuffer1(RBREAD, &t, 1)) 00293 { 00294 transmission1_running=1; 00295 UART1WriteChar(t); 00296 } 00297 else 00298 { 00299 transmission1_running=0; 00300 if (baudrate1_change) //baudrate change after first GPS config command 00301 { 00302 UART1Initialize(57600); 00303 baudrate1_change=0; 00304 } 00305 } 00306 break; 00307 case 2: 00308 c=U1RBR; 00309 00310 //UARTWriteChar(c); 00311 00312 #ifndef INDOOR_GPS //run GPS statemachine 00313 00314 //parse UBX (U0RBR); 00315 00316 //SSP_trans_cnt++; 00317 switch (state) 00318 { 00319 case 0: 00320 if(c==0xB5) 00321 { 00322 state=1; 00323 } 00324 break; 00325 case 1: 00326 if(c==0x62) 00327 { 00328 state=2; 00329 } 00330 else state=0; 00331 break; 00332 case 2: 00333 if(c==0x01) //NAV message 00334 { 00335 state=3; 00336 } 00337 else if (c==0x05) //ACK message 00338 { 00339 state=10; 00340 } 00341 else state=0; 00342 break; 00343 case 3: 00344 current_packet=c; 00345 cnt=0; 00346 state=4; 00347 break; 00348 case 4: 00349 if(!cnt) length=c; 00350 if(current_packet==0x06) parse_NAVSOL(0,1); 00351 if(++cnt==2) 00352 { 00353 cnt=0; 00354 state=5; 00355 } 00356 break; 00357 case 5: //Four bytes ITOW 00358 //NAVSOL is the only packets where the first 4 bytes need to be parsed. Any other packet discardes the first 4 bytes!!! 00359 if(current_packet==0x06) parse_NAVSOL(c,0); 00360 if(++cnt==4) 00361 { 00362 cnt=0; 00363 state=6; 00364 if(current_packet==0x02) parse_POSLLH(0,1); 00365 //else if(current_packet==0x08) parse_POSUTM(0,1); 00366 else if(current_packet==0x03) parse_STATUS(0,1); 00367 else if(current_packet==0x12) parse_VELNED(0,1); 00368 } 00369 break; 00370 case 6: 00371 if(current_packet==0x02) 00372 { 00373 parse_POSLLH(c,0); 00374 } 00375 /* else if(current_packet==0x08 //POSUTM currently not used 00376 { 00377 parse_POSUTM(c,0); 00378 } 00379 */ else if(current_packet==0x03) 00380 { 00381 parse_STATUS(c,0); 00382 } 00383 else if(current_packet==0x12) 00384 { 00385 parse_VELNED(c,0); 00386 } 00387 else if(current_packet==0x06) 00388 { 00389 parse_NAVSOL(c,0); 00390 } 00391 else state=0; 00392 00393 if(++cnt>=length-4) 00394 { 00395 state=0; 00396 } 00397 break; 00398 case 10: 00399 if (c==0x01) 00400 { 00401 cnt=0; 00402 state=11; 00403 } else 00404 state=0; 00405 break; 00406 case 11: 00407 if (!cnt) length=c; 00408 if (cnt++==1) 00409 { 00410 cnt=0; 00411 state=12; 00412 } 00413 break; 00414 case 12: 00415 if (c==0x06) //ACK of a CFG-message 00416 { 00417 state=13; 00418 } else 00419 state=0; 00420 break; 00421 case 13: 00422 state=14; 00423 break; 00424 case 14: 00425 if (!GPS_ACK_received) 00426 { 00427 GPS_ACK_received=1; 00428 state=0; 00429 } 00430 break; 00431 default: 00432 state=0; 00433 break; 00434 } 00435 00436 #else //run optical tracking statemachine 00437 switch (state) 00438 { 00439 case 0: 00440 if(c=='>') state=1; 00441 break; 00442 case 1: 00443 if(c=='*') state=2; 00444 else state=0; 00445 break; 00446 case 2: 00447 if(c=='>') //Startstring received 00448 { 00449 UART1_rxcount=sizeof(OF_Data); 00450 UART1_rxptr=(unsigned char *)&OF_Data_e; 00451 state=3; 00452 } 00453 else state=0; 00454 break; 00455 case 3: 00456 UART1_rxcount--; 00457 *UART1_rxptr=c; 00458 UART1_rxptr++; 00459 if (UART1_rxcount==0) 00460 { 00461 state=0; 00462 OF_data_updated=0; 00463 } 00464 break; 00465 default: 00466 state=0; 00467 break; 00468 } 00469 #endif 00470 00471 break; 00472 case 3: 00473 // RLS interrupt 00474 break; 00475 case 6: 00476 // CTI interrupt 00477 break; 00478 } 00479 IDISABLE; 00480 VICVectAddr = 0; /* Acknowledge Interrupt */ 00481 } 00482 00483 void UART1Initialize(unsigned int baud) 00484 { 00485 unsigned int divisor = peripheralClockFrequency() / (16 * baud); 00486 //UART1 00487 U1LCR = 0x83; /* 8 bit, 1 stop bit, no parity, enable DLAB */ 00488 U1DLL = divisor & 0xFF; 00489 U1DLM = (divisor >> 8) & 0xFF; 00490 U1LCR &= ~0x80; /* Disable DLAB */ 00491 U1FCR = 1; 00492 } 00493 00494 //Write to UART1 00495 void UART1WriteChar(unsigned char ch) 00496 { 00497 while ((U1LSR & 0x20) == 0); 00498 U1THR = ch; 00499 } 00500 00501 unsigned char UART1ReadChar(void) 00502 { 00503 while ((U1LSR & 0x01) == 0); 00504 return U1RBR; 00505 } 00506 00507 void UART1_send(unsigned char *buffer, unsigned char length) 00508 { 00509 unsigned char cnt=0; 00510 while(length--) 00511 { 00512 while (!(U0LSR & 0x20)); //wait until U0THR is empty 00513 U1THR = buffer[cnt++]; 00514 } 00515 } 00516 00517 void UART1_send_ringbuffer(void) 00518 { 00519 unsigned char t; 00520 if(!transmission1_running) 00521 { 00522 if(ringbuffer1(RBREAD, &t, 1)) 00523 { 00524 transmission1_running=1; 00525 UART1WriteChar(t); 00526 } 00527 } 00528 } 00529 00530 int ringbuffer1(unsigned char rw, unsigned char *data, unsigned int count) //returns 1 when write/read was successful, 0 elsewise 00531 { 00532 static volatile unsigned char buffer[RINGBUFFERSIZE]; 00533 // static volatile unsigned int pfirst=0, plast=0; //Pointers to first and last to read byte 00534 static volatile unsigned int read_pointer, write_pointer; 00535 static volatile unsigned int content=0; 00536 unsigned int p=0; 00537 unsigned int p2=0; 00538 00539 if(rw==RBWRITE) 00540 { 00541 if(count<RINGBUFFERSIZE-content) //enough space in buffer? 00542 { 00543 while(p<count) 00544 { 00545 buffer[write_pointer++]=data[p++]; 00546 } 00547 content+=count; 00548 return(1); 00549 } 00550 } 00551 else if(rw==RBREAD) 00552 { 00553 if(content>=count) 00554 { 00555 while(p2<count) 00556 { 00557 data[p2++]=buffer[read_pointer++]; 00558 } 00559 content-=count; 00560 if(!content) //buffer empty 00561 { 00562 write_pointer=0; 00563 read_pointer=0; 00564 } 00565 return(1); 00566 } 00567 } 00568 else if(rw==RBFREE) 00569 { 00570 if(content) return 0; 00571 else return(RINGBUFFERSIZE-11); 00572 } 00573 00574 return(0); 00575 } 00576 00577 void GPS_configure(void) 00578 { 00579 const unsigned char gps_startstring[2]={ 0xb5, 0x62 }; //sync chars 00580 00581 static unsigned char gpsconf_state, gps_cfg_msg_counter; 00582 int written; 00583 static unsigned char gpsconfig_timeout; 00584 static unsigned char StartWithHighBaudrate = 0; 00585 00586 switch (gpsconf_state) 00587 { 00588 case 0: 00589 if (StartWithHighBaudrate) 00590 { 00591 UART1Initialize(57600); 00592 StartWithHighBaudrate = 0; 00593 } 00594 else 00595 UART1Initialize(9600); 00596 if ((ringbuffer1(RBFREE, 0, 0))>28) 00597 { 00598 written=ringbuffer1(RBWRITE, (unsigned char*)gps_startstring, 2); 00599 written=ringbuffer1(RBWRITE, (unsigned char*)GPS_CFG_PRT, 26); 00600 UART1_send_ringbuffer(); 00601 baudrate1_change=1; 00602 gpsconf_state++; 00603 } 00604 gpsconfig_timeout=0; 00605 break; 00606 case 1: 00607 if (GPS_ACK_received) 00608 { 00609 GPS_ACK_received=0; 00610 if (ringbuffer1(RBFREE, 0, 0)>12) 00611 { 00612 ringbuffer1(RBWRITE, (unsigned char*)gps_startstring, 2); 00613 ringbuffer1(RBWRITE, (unsigned char*)GPS_CFG_ANT, 10); 00614 UART1_send_ringbuffer(); 00615 gps_cfg_msg_counter=0; 00616 gpsconf_state++; 00617 } 00618 gpsconfig_timeout=0; 00619 StartWithHighBaudrate = 0; 00620 } else 00621 { 00622 gpsconfig_timeout++; 00623 StartWithHighBaudrate = 1; 00624 } 00625 break; 00626 case 2: 00627 if (GPS_ACK_received) 00628 { 00629 GPS_ACK_received=0; 00630 if (ringbuffer1(RBFREE, 0, 0)>14) 00631 { 00632 ringbuffer1(RBWRITE, (unsigned char*)gps_startstring, 2); 00633 ringbuffer1(RBWRITE, (unsigned char*)GPS_CFG_MSG[gps_cfg_msg_counter], 12); 00634 UART1_send_ringbuffer(); 00635 if (++gps_cfg_msg_counter==11) 00636 { 00637 gpsconf_state++; 00638 } 00639 } 00640 gpsconfig_timeout=0; 00641 } else 00642 gpsconfig_timeout++; 00643 break; 00644 case 3: 00645 if (GPS_ACK_received) 00646 { 00647 GPS_ACK_received=0; 00648 if (ringbuffer1(RBFREE, 0, 0)>48) 00649 { 00650 ringbuffer1(RBWRITE, (unsigned char*)gps_startstring, 2); 00651 ringbuffer1(RBWRITE, (unsigned char*)GPS_CFG_NAV2, 46); 00652 UART1_send_ringbuffer(); 00653 gpsconf_state++; 00654 } 00655 gpsconfig_timeout=0; 00656 } else 00657 gpsconfig_timeout++; 00658 break; 00659 case 4: 00660 if (GPS_ACK_received) 00661 { 00662 GPS_ACK_received=0; 00663 if (ringbuffer1(RBFREE, 0, 0)>14) 00664 { 00665 ringbuffer1(RBWRITE, (unsigned char*)gps_startstring, 2); 00666 ringbuffer1(RBWRITE, (unsigned char*)GPS_CFG_RATE, 12); 00667 UART1_send_ringbuffer(); 00668 gpsconf_state++; 00669 } 00670 gpsconfig_timeout=0; 00671 } else 00672 gpsconfig_timeout++; 00673 break; 00674 case 5: 00675 if (GPS_ACK_received) 00676 { 00677 GPS_ACK_received=0; 00678 if (ringbuffer1(RBFREE, 0, 0)>16) 00679 { 00680 ringbuffer1(RBWRITE, (unsigned char*)gps_startstring, 2); 00681 ringbuffer1(RBWRITE, (unsigned char*)GPS_CFG_SBAS, 14); 00682 UART1_send_ringbuffer(); 00683 gpsconf_state++; 00684 } 00685 gpsconfig_timeout=0; 00686 } else 00687 gpsconfig_timeout++; 00688 break; 00689 case 6: 00690 if (GPS_ACK_received) 00691 { 00692 GPS_ACK_received=0; 00693 if (ringbuffer1(RBFREE, 0, 0)>21) 00694 { 00695 ringbuffer1(RBWRITE, (unsigned char*)gps_startstring, 2); 00696 ringbuffer1(RBWRITE, (unsigned char*)GPS_CFG_CFG, 19); 00697 UART1_send_ringbuffer(); 00698 gpsconf_state++; 00699 } 00700 gpsconfig_timeout=0; 00701 } else 00702 gpsconfig_timeout++; 00703 break; 00704 case 7: 00705 if (GPS_ACK_received) 00706 { 00707 GPS_ACK_received=0; 00708 GPS_init_status=GPS_IS_CONFIGURED; 00709 gpsconf_state=0; 00710 gpsconfig_timeout=0; 00711 } else 00712 gpsconfig_timeout++; 00713 break; 00714 default: 00715 gpsconf_state=0; 00716 break; 00717 } 00718 if (gpsconfig_timeout>GPSCONF_TIMEOUT) //timeout for ACK receiving 00719 { 00720 if (StartWithHighBaudrate) 00721 { 00722 gpsconf_state=0; 00723 gpsconfig_timeout=0; 00724 } else 00725 { 00726 gpsconf_state=0; 00727 gpsconfig_timeout=0; 00728 GPS_init_status=GPS_CONFIG_ERROR; 00729 } 00730 } 00731 }