Browse Source

ACM: removed the special case for quaternions in GCS code

mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
7291dfc25a
  1. 2
      ArduCopter/GCS_Mavlink.pde

2
ArduCopter/GCS_Mavlink.pde

@ -99,7 +99,6 @@ static void NOINLINE send_meminfo(mavlink_channel_t chan) @@ -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) @@ -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)

Loading…
Cancel
Save