MAVLink: send time of GPS fix accurately

when we send a GPS_RAW message, set the usec field to the time we got
the fix from the GPS, not the current time. This makes it possible for
aerial photo processing to be more accurate, as the usec field with
more accurately reflect the planes position/time pair
This commit is contained in:
Andrew Tridgell 2012-05-23 17:29:52 +10:00
parent 5b5d43f5d0
commit 1fc8347af3
2 changed files with 4 additions and 4 deletions

View File

@ -309,7 +309,7 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan)
mavlink_msg_gps_raw_int_send(
chan,
micros(),
g_gps->last_fix_time*(uint64_t)1000,
fix,
g_gps->latitude, // in 1E7 degrees
g_gps->longitude, // in 1E7 degrees
@ -323,7 +323,7 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan)
#else // MAVLINK10
mavlink_msg_gps_raw_send(
chan,
micros(),
g_gps->last_fix_time*(uint64_t)1000,
g_gps->status(),
g_gps->latitude / 1.0e7,
g_gps->longitude / 1.0e7,

View File

@ -345,7 +345,7 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan)
mavlink_msg_gps_raw_int_send(
chan,
micros(),
g_gps->last_fix_time*(uint64_t)1000,
fix,
g_gps->latitude, // in 1E7 degrees
g_gps->longitude, // in 1E7 degrees
@ -359,7 +359,7 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan)
#else // MAVLINK10
mavlink_msg_gps_raw_send(
chan,
micros(),
g_gps->last_fix_time*(uint64_t)1000,
g_gps->status(),
g_gps->latitude / 1.0e7,
g_gps->longitude / 1.0e7,