Get current time using gps (#5520)

* Get time using gps with nmea and ublox protocol. The rtctime is set once gps time is available.

* Fix issues with Gps time

* Fix problems with gpstime
This commit is contained in:
zuim 2018-03-26 14:04:41 +02:00 committed by Michael Keller
parent 3a8901daa8
commit 605962d9a5
1 changed files with 33 additions and 1 deletions

View File

@ -635,6 +635,8 @@ typedef struct gpsDataNmea_s {
uint16_t altitude; uint16_t altitude;
uint16_t speed; uint16_t speed;
uint16_t ground_course; uint16_t ground_course;
uint32_t time;
uint32_t date;
} gpsDataNmea_t; } gpsDataNmea_t;
static bool gpsNewFrameNMEA(char c) static bool gpsNewFrameNMEA(char c)
@ -703,12 +705,18 @@ static bool gpsNewFrameNMEA(char c)
break; break;
case FRAME_RMC: //************* GPRMC FRAME parsing case FRAME_RMC: //************* GPRMC FRAME parsing
switch (param) { switch (param) {
case 1:
gps_Msg.time = grab_fields(string, 2); // UTC time hhmmss.ss
break;
case 7: case 7:
gps_Msg.speed = ((grab_fields(string, 1) * 5144L) / 1000L); // speed in cm/s added by Mis gps_Msg.speed = ((grab_fields(string, 1) * 5144L) / 1000L); // speed in cm/s added by Mis
break; break;
case 8: case 8:
gps_Msg.ground_course = (grab_fields(string, 1)); // ground course deg * 10 gps_Msg.ground_course = (grab_fields(string, 1)); // ground course deg * 10
break; break;
case 9:
gps_Msg.date = grab_fields(string, 0); // date dd/mm/yy
break;
} }
break; break;
case FRAME_GSV: case FRAME_GSV:
@ -789,6 +797,20 @@ static bool gpsNewFrameNMEA(char c)
*gpsPacketLogChar = LOG_NMEA_RMC; *gpsPacketLogChar = LOG_NMEA_RMC;
gpsSol.groundSpeed = gps_Msg.speed; gpsSol.groundSpeed = gps_Msg.speed;
gpsSol.groundCourse = gps_Msg.ground_course; gpsSol.groundCourse = gps_Msg.ground_course;
#ifdef USE_RTC_TIME
// This check will miss 00:00:00.00, but we shouldn't care - next report will be valid
if(!rtcHasTime() && gps_Msg.date != 0 && gps_Msg.time != 0) {
dateTime_t temp_time;
temp_time.year = (gps_Msg.date % 100) + 2000;
temp_time.month = (gps_Msg.date / 100) % 100;
temp_time.day = (gps_Msg.date / 10000) % 100;
temp_time.hours = (gps_Msg.time / 1000000) % 100;
temp_time.minutes = (gps_Msg.time / 10000) % 100;
temp_time.seconds = (gps_Msg.time / 100) % 100;
temp_time.millis = (gps_Msg.time & 100) * 10;
rtcSetDateTime(&temp_time);
}
#endif
break; break;
} // end switch } // end switch
} else { } else {
@ -917,7 +939,9 @@ enum {
} ubs_nav_fix_type; } ubs_nav_fix_type;
enum { enum {
NAV_STATUS_FIX_VALID = 1 NAV_STATUS_FIX_VALID = 1,
NAV_STATUS_TIME_WEEK_VALID = 4,
NAV_STATUS_TIME_SECOND_VALID = 8
} ubx_nav_status_bits; } ubx_nav_status_bits;
// Packet checksum accumulators // Packet checksum accumulators
@ -1010,6 +1034,14 @@ static bool UBLOX_parse_gps(void)
DISABLE_STATE(GPS_FIX); DISABLE_STATE(GPS_FIX);
gpsSol.numSat = _buffer.solution.satellites; gpsSol.numSat = _buffer.solution.satellites;
gpsSol.hdop = _buffer.solution.position_DOP; gpsSol.hdop = _buffer.solution.position_DOP;
#ifdef USE_RTC_TIME
//set clock, when gps time is available
if(!rtcHasTime() && (_buffer.solution.fix_status & NAV_STATUS_TIME_SECOND_VALID) && (_buffer.solution.fix_status & NAV_STATUS_TIME_WEEK_VALID)) {
//calculate rtctime: week number * ms in a week + ms of week + fractions of second + offset to UNIX reference year - 18 leap seconds
rtcTime_t temp_time = (((int64_t) _buffer.solution.week)*7*24*60*60*1000) + _buffer.solution.time + (_buffer.solution.time_nsec/1000000) + 315964800000LL - 18000;
rtcSet(&temp_time);
}
#endif
break; break;
case MSG_VELNED: case MSG_VELNED:
*gpsPacketLogChar = LOG_UBLOX_VELNED; *gpsPacketLogChar = LOG_UBLOX_VELNED;