From 7291dfc25a87bdaba0975dfd4f029f5ce9f9982d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 7 Mar 2012 15:11:58 +1100 Subject: [PATCH] ACM: removed the special case for quaternions in GCS code --- ArduCopter/GCS_Mavlink.pde | 2 -- 1 file changed, 2 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 78fc8f2530..9ac2fd7e07 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -99,7 +99,6 @@ static void NOINLINE send_meminfo(mavlink_channel_t chan) static void NOINLINE send_location(mavlink_channel_t chan) { -#if QUATERNION_ENABLE == DISABLED Matrix3f rot = dcm.get_dcm_matrix(); // neglecting angle of attack for now mavlink_msg_global_position_int_send( chan, @@ -109,7 +108,6 @@ static void NOINLINE send_location(mavlink_channel_t chan) g_gps->ground_speed * rot.a.x, g_gps->ground_speed * rot.b.x, g_gps->ground_speed * rot.c.x); -#endif } static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)