mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
ACM: removed the special case for quaternions in GCS code
This commit is contained in:
parent
1547977e1b
commit
13bddf05b0
@ -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)
|
||||
|
Loading…
Reference in New Issue
Block a user