static bool gpsNewFrameNMEA(char c) { static gpsDataNmea_t gps_Msg; uint8_t frameOK = 0; static uint8_t param = 0, offset = 0, parity = 0; static char string[15]; static uint8_t checksum_param, gps_frame = NO_FRAME; static uint8_t svMessageNum = 0; uint8_t svSatNum = 0, svPacketIdx = 0, svSatParam = 0; switch (c) { case '$': param = 0; offset = 0; parity = 0; break; case ',': case '*': string[offset] = 0; if (param == 0) { //frame identification gps_frame = NO_FRAME; if (string[0] == 'G' && string[1] == 'P' && string[2] == 'G' && string[3] == 'G' && string[4] == 'A') gps_frame = FRAME_GGA; if (string[0] == 'G' && string[1] == 'P' && string[2] == 'R' && string[3] == 'M' && string[4] == 'C') gps_frame = FRAME_RMC; if (string[0] == 'G' && string[1] == 'P' && string[2] == 'G' && string[3] == 'S' && string[4] == 'V') gps_frame = FRAME_GSV; } switch (gps_frame) { case FRAME_GGA: //************* GPGGA FRAME parsing switch(param) { // case 1: // Time information // break; case 2: gps_Msg.latitude = GPS_coord_to_degrees(string); break; case 3: if (string[0] == 'S') gps_Msg.latitude *= -1; break; case 4: gps_Msg.longitude = GPS_coord_to_degrees(string); break; case 5: if (string[0] == 'W') gps_Msg.longitude *= -1; break; case 6: if (string[0] > '0') { ENABLE_STATE(GPS_FIX); } else { DISABLE_STATE(GPS_FIX); } break; case 7: gps_Msg.numSat = grab_fields(string, 0); break; case 9: gps_Msg.altitude = grab_fields(string, 0); // altitude in meters added by Mis break; } break; case FRAME_RMC: //************* GPRMC FRAME parsing switch(param) { case 7: gps_Msg.speed = ((grab_fields(string, 1) * 5144L) / 1000L); // speed in cm/s added by Mis break; case 8: gps_Msg.ground_course = (grab_fields(string, 1)); // ground course deg * 10 break; } break; case FRAME_GSV: switch(param) { /*case 1: // Total number of messages of this type in this cycle break; */ case 2: // Message number svMessageNum = grab_fields(string, 0); break; case 3: // Total number of SVs visible GPS_numCh = grab_fields(string, 0); break; } if(param < 4) break; svPacketIdx = (param - 4) / 4 + 1; // satellite number in packet, 1-4 svSatNum = svPacketIdx + (4 * (svMessageNum - 1)); // global satellite number svSatParam = param - 3 - (4 * (svPacketIdx - 1)); // parameter number for satellite if(svSatNum > GPS_SV_MAXSATS) break; switch(svSatParam) { case 1: // SV PRN number GPS_svinfo_chn[svSatNum - 1] = svSatNum; GPS_svinfo_svid[svSatNum - 1] = grab_fields(string, 0); break; /*case 2: // Elevation, in degrees, 90 maximum break; case 3: // Azimuth, degrees from True North, 000 through 359 break; */ case 4: // SNR, 00 through 99 dB (null when not tracking) GPS_svinfo_cno[svSatNum - 1] = grab_fields(string, 0); GPS_svinfo_quality[svSatNum - 1] = 0; // only used by ublox break; } GPS_svInfoReceivedCount++; break; } param++; offset = 0; if (c == '*') checksum_param = 1; else parity ^= c; break; case '\r': case '\n': if (checksum_param) { //parity checksum shiftPacketLog(); uint8_t checksum = 16 * ((string[0] >= 'A') ? string[0] - 'A' + 10 : string[0] - '0') + ((string[1] >= 'A') ? string[1] - 'A' + 10 : string[1] - '0'); if (checksum == parity) { *gpsPacketLogChar = LOG_IGNORED; GPS_packetCount++; switch (gps_frame) { case FRAME_GGA: *gpsPacketLogChar = LOG_NMEA_GGA; frameOK = 1; if (STATE(GPS_FIX)) { GPS_coord[LAT] = gps_Msg.latitude; GPS_coord[LON] = gps_Msg.longitude; GPS_numSat = gps_Msg.numSat; GPS_altitude = gps_Msg.altitude; } break; case FRAME_RMC: *gpsPacketLogChar = LOG_NMEA_RMC; GPS_speed = gps_Msg.speed; GPS_ground_course = gps_Msg.ground_course; break; } // end switch } else { *gpsPacketLogChar = LOG_ERROR; } } checksum_param = 0; break; default: if (offset < 15) string[offset++] = c; if (!checksum_param) parity ^= c; } return frameOK; }
static bool gpsNewFrameUBLOX(uint8_t data) { bool parsed = false; switch (_step) { case 0: // Sync char 1 (0xB5) if (PREAMBLE1 == data) { _skip_packet = false; _step++; } else { GPS_garbageByteCount++; } break; case 1: // Sync char 2 (0x62) if (PREAMBLE2 != data) { _step = 0; break; } _step++; break; case 2: // Class _step++; _class = data; _ck_b = _ck_a = data; // reset the checksum accumulators break; case 3: // Id _step++; _ck_b += (_ck_a += data); // checksum byte _msg_id = data; break; case 4: // Payload length (part 1) _step++; _ck_b += (_ck_a += data); // checksum byte _payload_length = data; // payload length low byte break; case 5: // Payload length (part 2) _step++; _ck_b += (_ck_a += data); // checksum byte _payload_length |= (uint16_t)(data << 8); if (_payload_length > MAX_UBLOX_PAYLOAD_SIZE ) { // we can't receive the whole packet, just log the error and start searching for the next packet. shiftPacketLog(); *gpsPacketLogChar = LOG_SKIPPED; gpsData.errors++; _step = 0; break; } if (_payload_length > UBLOX_BUFFER_SIZE) { _skip_packet = true; } // prepare to receive payload _payload_counter = 0; if (_payload_length == 0) { _step = 7; } break; case 6: _ck_b += (_ck_a += data); // checksum byte if (_payload_counter < UBLOX_BUFFER_SIZE) { _buffer.bytes[_payload_counter] = data; } // NOTE: check counter BEFORE increasing so that a payload_size of 65535 is correctly handled. This can happen if garbage data is received. if (_payload_counter == _payload_length - 1) { _step++; } _payload_counter++; break; case 7: _step++; if (_ck_a != data) { _skip_packet = true; // bad checksum gpsData.errors++; } break; case 8: _step = 0; shiftPacketLog(); if (_ck_b != data) { *gpsPacketLogChar = LOG_ERROR; gpsData.errors++; break; // bad checksum } GPS_packetCount++; if (_skip_packet) { *gpsPacketLogChar = LOG_SKIPPED; break; } if (UBLOX_parse_gps()) { parsed = true; } } return parsed; }
static bool gpsNewFrameUBLOX(uint8_t data) { bool parsed = false; switch (_step) { case 0: // Sync char 1 (0xB5) if (PREAMBLE1 == data) { _skip_packet = false; _step++; } break; case 1: // Sync char 2 (0x62) if (PREAMBLE2 != data) { _step = 0; break; } _step++; break; case 2: // Class _step++; _class = data; _ck_b = _ck_a = data; // reset the checksum accumulators break; case 3: // Id _step++; _ck_b += (_ck_a += data); // checksum byte _msg_id = data; break; case 4: // Payload length (part 1) _step++; _ck_b += (_ck_a += data); // checksum byte _payload_length = data; // payload length low byte break; case 5: // Payload length (part 2) _step++; _ck_b += (_ck_a += data); // checksum byte _payload_length += (uint16_t)(data << 8); if (_payload_length > UBLOX_PAYLOAD_SIZE) { _skip_packet = true; } _payload_counter = 0; // prepare to receive payload if (_payload_length == 0) { _step = 7; } break; case 6: _ck_b += (_ck_a += data); // checksum byte if (_payload_counter < UBLOX_PAYLOAD_SIZE) { _buffer.bytes[_payload_counter] = data; } if (++_payload_counter >= _payload_length) { _step++; } break; case 7: _step++; if (_ck_a != data) { _skip_packet = true; // bad checksum gpsData.errors++; } break; case 8: _step = 0; shiftPacketLog(); if (_ck_b != data) { *gpsPacketLogChar = LOG_ERROR; gpsData.errors++; break; // bad checksum } GPS_packetCount++; if (_skip_packet) { *gpsPacketLogChar = LOG_SKIPPED; break; } if (UBLOX_parse_gps()) { parsed = true; } } return parsed; }