aboutsummaryrefslogtreecommitdiff
path: root/src/drivers
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2015-01-03 19:05:42 +0100
committerLorenz Meier <lm@inf.ethz.ch>2015-01-03 19:05:42 +0100
commit2a95b4a9b89324354967c7a45974a534142efec0 (patch)
tree4af0254752da0f677ee3b04c790a8cd17f7e6270 /src/drivers
parentb37b181818edf2fbb66b978c1cdd90cb8588e322 (diff)
downloadpx4-firmware-2a95b4a9b89324354967c7a45974a534142efec0.tar.gz
px4-firmware-2a95b4a9b89324354967c7a45974a534142efec0.tar.bz2
px4-firmware-2a95b4a9b89324354967c7a45974a534142efec0.zip
GPS: Update the RTC even when RTC is enabled
Diffstat (limited to 'src/drivers')
-rw-r--r--src/drivers/gps/ubx.cpp11
1 files changed, 6 insertions, 5 deletions
diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp
index b0eb4ab66..91ecdb474 100644
--- a/src/drivers/gps/ubx.cpp
+++ b/src/drivers/gps/ubx.cpp
@@ -808,7 +808,7 @@ UBX::payload_rx_done(void)
UBX_TRACE_RXMSG("Rx NAV-TIMEUTC\n");
{
- /* convert to unix timestamp */
+ // convert to unix timestamp
struct tm timeinfo;
timeinfo.tm_year = _buf.payload_rx_nav_timeutc.year - 1900;
timeinfo.tm_mon = _buf.payload_rx_nav_timeutc.month - 1;
@@ -818,14 +818,15 @@ UBX::payload_rx_done(void)
timeinfo.tm_sec = _buf.payload_rx_nav_timeutc.sec;
time_t epoch = mktime(&timeinfo);
-#ifndef CONFIG_RTC
- //Since we lack a hardware RTC, set the system time clock based on GPS UTC
- //TODO generalize this by moving into gps.cpp?
+ // FMUv2+ have a hardware RTC, but GPS helps us to configure it
+ // and control its drift. Since we rely on the HRT for our monotonic
+ // clock, updating it from time to time is safe.
+
+ // TODO generalize this by moving into gps.cpp?
timespec ts;
ts.tv_sec = epoch;
ts.tv_nsec = _buf.payload_rx_nav_timeutc.nano;
clock_settime(CLOCK_REALTIME, &ts);
-#endif
_gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this
_gps_position->time_gps_usec += (uint64_t)(_buf.payload_rx_nav_timeutc.nano * 1e-3f);