mirror of https://github.com/ArduPilot/ardupilot
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:
parent
66544a5db2
commit
d9457ecc38
|
@ -309,7 +309,7 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan)
|
||||||
|
|
||||||
mavlink_msg_gps_raw_int_send(
|
mavlink_msg_gps_raw_int_send(
|
||||||
chan,
|
chan,
|
||||||
micros(),
|
g_gps->last_fix_time*(uint64_t)1000,
|
||||||
fix,
|
fix,
|
||||||
g_gps->latitude, // in 1E7 degrees
|
g_gps->latitude, // in 1E7 degrees
|
||||||
g_gps->longitude, // 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
|
#else // MAVLINK10
|
||||||
mavlink_msg_gps_raw_send(
|
mavlink_msg_gps_raw_send(
|
||||||
chan,
|
chan,
|
||||||
micros(),
|
g_gps->last_fix_time*(uint64_t)1000,
|
||||||
g_gps->status(),
|
g_gps->status(),
|
||||||
g_gps->latitude / 1.0e7,
|
g_gps->latitude / 1.0e7,
|
||||||
g_gps->longitude / 1.0e7,
|
g_gps->longitude / 1.0e7,
|
||||||
|
|
|
@ -345,7 +345,7 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan)
|
||||||
|
|
||||||
mavlink_msg_gps_raw_int_send(
|
mavlink_msg_gps_raw_int_send(
|
||||||
chan,
|
chan,
|
||||||
micros(),
|
g_gps->last_fix_time*(uint64_t)1000,
|
||||||
fix,
|
fix,
|
||||||
g_gps->latitude, // in 1E7 degrees
|
g_gps->latitude, // in 1E7 degrees
|
||||||
g_gps->longitude, // 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
|
#else // MAVLINK10
|
||||||
mavlink_msg_gps_raw_send(
|
mavlink_msg_gps_raw_send(
|
||||||
chan,
|
chan,
|
||||||
micros(),
|
g_gps->last_fix_time*(uint64_t)1000,
|
||||||
g_gps->status(),
|
g_gps->status(),
|
||||||
g_gps->latitude / 1.0e7,
|
g_gps->latitude / 1.0e7,
|
||||||
g_gps->longitude / 1.0e7,
|
g_gps->longitude / 1.0e7,
|
||||||
|
|
Loading…
Reference in New Issue