aboutsummaryrefslogtreecommitdiff
path: root/src/drivers
diff options
context:
space:
mode:
Diffstat (limited to 'src/drivers')
-rw-r--r--src/drivers/frsky_telemetry/frsky_data.c4
-rw-r--r--src/drivers/gps/ashtech.cpp4
-rw-r--r--src/drivers/gps/mtk.cpp4
-rw-r--r--src/drivers/gps/ubx.cpp8
4 files changed, 10 insertions, 10 deletions
diff --git a/src/drivers/frsky_telemetry/frsky_data.c b/src/drivers/frsky_telemetry/frsky_data.c
index dd9b90fb3..890fada16 100644
--- a/src/drivers/frsky_telemetry/frsky_data.c
+++ b/src/drivers/frsky_telemetry/frsky_data.c
@@ -223,7 +223,7 @@ void frsky_send_frame2(int uart)
char lat_ns = 0, lon_ew = 0;
int sec = 0;
if (global_pos.timestamp != 0 && hrt_absolute_time() < global_pos.timestamp + 20000) {
- time_t time_gps = global_pos.time_gps_usec / 1000000;
+ time_t time_gps = global_pos.time_utc_usec / 1000000ULL;
struct tm *tm_gps = gmtime(&time_gps);
course = (global_pos.yaw + M_PI_F) / M_PI_F * 180.0f;
@@ -274,7 +274,7 @@ void frsky_send_frame3(int uart)
orb_copy(ORB_ID(vehicle_global_position), global_position_sub, &global_pos);
/* send formatted frame */
- time_t time_gps = global_pos.time_gps_usec / 1000000;
+ time_t time_gps = global_pos.time_utc_usec / 1000000ULL;
struct tm *tm_gps = gmtime(&time_gps);
uint16_t hour_min = (tm_gps->tm_min << 8) | (tm_gps->tm_hour & 0xff);
frsky_send_data(uart, FRSKY_ID_GPS_DAY_MONTH, tm_gps->tm_mday);
diff --git a/src/drivers/gps/ashtech.cpp b/src/drivers/gps/ashtech.cpp
index f1c5ca549..99dbe5984 100644
--- a/src/drivers/gps/ashtech.cpp
+++ b/src/drivers/gps/ashtech.cpp
@@ -112,8 +112,8 @@ int ASHTECH::handle_message(int len)
warn("failed setting clock");
}
- _gps_position->time_gps_usec = static_cast<uint64_t>(epoch) * 1000000ULL;
- _gps_position->time_gps_usec += usecs;
+ _gps_position->time_utc_usec = static_cast<uint64_t>(epoch) * 1000000ULL;
+ _gps_position->time_utc_usec += usecs;
_gps_position->timestamp_time = hrt_absolute_time();
}
diff --git a/src/drivers/gps/mtk.cpp b/src/drivers/gps/mtk.cpp
index c4f4f7bec..d808b59a9 100644
--- a/src/drivers/gps/mtk.cpp
+++ b/src/drivers/gps/mtk.cpp
@@ -282,8 +282,8 @@ MTK::handle_message(gps_mtk_packet_t &packet)
timeinfo_conversion_temp -= timeinfo.tm_sec * 1e3;
time_t epoch = mktime(&timeinfo);
- _gps_position->time_gps_usec = epoch * 1e6; //TODO: test this
- _gps_position->time_gps_usec += timeinfo_conversion_temp * 1e3;
+ _gps_position->time_utc_usec = epoch * 1e6; //TODO: test this
+ _gps_position->time_utc_usec += timeinfo_conversion_temp * 1e3;
_gps_position->timestamp_position = _gps_position->timestamp_time = hrt_absolute_time();
// Position and velocity update always at the same time
diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp
index c67965487..6b4e1630b 100644
--- a/src/drivers/gps/ubx.cpp
+++ b/src/drivers/gps/ubx.cpp
@@ -759,8 +759,8 @@ UBX::payload_rx_done(void)
warn("failed setting clock");
}
- _gps_position->time_gps_usec = static_cast<uint64_t>(epoch) * 1000000ULL;
- _gps_position->time_gps_usec += _buf.payload_rx_nav_timeutc.nano / 1000;
+ _gps_position->time_utc_usec = static_cast<uint64_t>(epoch) * 1000000ULL;
+ _gps_position->time_utc_usec += _buf.payload_rx_nav_timeutc.nano / 1000;
}
_gps_position->timestamp_time = hrt_absolute_time();
@@ -831,8 +831,8 @@ UBX::payload_rx_done(void)
warn("failed setting clock");
}
- _gps_position->time_gps_usec = static_cast<uint64_t>(epoch) * 1000000ULL;
- _gps_position->time_gps_usec += _buf.payload_rx_nav_timeutc.nano / 1000;
+ _gps_position->time_utc_usec = static_cast<uint64_t>(epoch) * 1000000ULL;
+ _gps_position->time_utc_usec += _buf.payload_rx_nav_timeutc.nano / 1000;
}
_gps_position->timestamp_time = hrt_absolute_time();