|
|
|
@ -200,9 +200,20 @@ static void NOINLINE send_meminfo(mavlink_channel_t chan)
@@ -200,9 +200,20 @@ static void NOINLINE send_meminfo(mavlink_channel_t chan)
|
|
|
|
|
|
|
|
|
|
static void NOINLINE send_location(mavlink_channel_t chan) |
|
|
|
|
{ |
|
|
|
|
uint32_t fix_time; |
|
|
|
|
// if we have a GPS fix, take the time as the last fix time. That |
|
|
|
|
// allows us to correctly calculate velocities and extrapolate |
|
|
|
|
// positions. |
|
|
|
|
// If we don't have a GPS fix then we are dead reckoning, and will |
|
|
|
|
// use the current boot time as the fix time. |
|
|
|
|
if (g_gps->status() == GPS::GPS_OK) { |
|
|
|
|
fix_time = g_gps->last_fix_time; |
|
|
|
|
} else { |
|
|
|
|
fix_time = millis(); |
|
|
|
|
} |
|
|
|
|
mavlink_msg_global_position_int_send( |
|
|
|
|
chan, |
|
|
|
|
millis(), |
|
|
|
|
fix_time, |
|
|
|
|
current_loc.lat, // in 1E7 degrees |
|
|
|
|
current_loc.lng, // in 1E7 degrees |
|
|
|
|
g_gps->altitude * 10, // millimeters above sea level |
|
|
|
|