From 2793e432ff8bce337edd9044466b46e0b39439eb Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 31 Oct 2012 21:50:55 +1100 Subject: [PATCH] APM: use raw GPS velocity in GLOBAL_POSITION_INT a much more useful value to log --- ArduPlane/GCS_Mavlink.pde | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 194e8aeb02..c875654ddd 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -238,9 +238,9 @@ static void NOINLINE send_location(mavlink_channel_t chan) current_loc.lng, // in 1E7 degrees g_gps->altitude * 10, // millimeters above sea level (current_loc.alt-home.alt) * 10, // millimeters above ground - g_gps->ground_speed * rot.a.x, // X speed cm/s - g_gps->ground_speed * rot.b.x, // Y speed cm/s - g_gps->ground_speed * rot.c.x, + g_gps->velocity_north() * 100, // X speed cm/s (+ve North) + g_gps->velocity_east() * 100, // Y speed cm/s (+ve East) + g_gps->velocity_down() * -100, // Z speed cm/s (+ve up) ahrs.yaw_sensor); }