From f39d8dbde85d70920b07f0193ade299eae612e48 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 8 Mar 2012 18:13:19 +1100 Subject: [PATCH] GCS: get_integrator() is now get_gyro_drift() in DCM --- ArduCopter/GCS_Mavlink.pde | 2 +- ArduPlane/GCS_Mavlink.pde | 2 +- ArduPlane/Log.pde | 6 +++--- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 9ac2fd7e07..aac172ba6a 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -127,7 +127,7 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan) #if HIL_MODE != HIL_MODE_ATTITUDE static void NOINLINE send_dcm(mavlink_channel_t chan) { - Vector3f omega_I = dcm.get_integrator(); + Vector3f omega_I = dcm.get_gyro_drift(); mavlink_msg_dcm_send( chan, omega_I.x, diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index a2e8a40cb4..f1d4cda07d 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -488,7 +488,7 @@ static void NOINLINE send_raw_imu3(mavlink_channel_t chan) static void NOINLINE send_dcm(mavlink_channel_t chan) { - Vector3f omega_I = dcm.get_integrator(); + Vector3f omega_I = dcm.get_gyro_drift(); mavlink_msg_dcm_send( chan, omega_I.x, diff --git a/ArduPlane/Log.pde b/ArduPlane/Log.pde index 5c7883a83e..ece99ea6c2 100644 --- a/ArduPlane/Log.pde +++ b/ArduPlane/Log.pde @@ -245,9 +245,9 @@ static void Log_Write_Performance() DataFlash.WriteByte(dcm.renorm_blowup_count); DataFlash.WriteByte(gps_fix_count); DataFlash.WriteInt((int)(dcm.get_health() * 1000)); - DataFlash.WriteInt((int)(dcm.get_integrator().x * 1000)); - DataFlash.WriteInt((int)(dcm.get_integrator().y * 1000)); - DataFlash.WriteInt((int)(dcm.get_integrator().z * 1000)); + DataFlash.WriteInt((int)(dcm.get_gyro_drift().x * 1000)); + DataFlash.WriteInt((int)(dcm.get_gyro_drift().y * 1000)); + DataFlash.WriteInt((int)(dcm.get_gyro_drift().z * 1000)); DataFlash.WriteInt(pmTest1); DataFlash.WriteByte(END_BYTE); }