GCS: get_integrator() is now get_gyro_drift() in DCM

This commit is contained in:
Andrew Tridgell 2012-03-08 18:13:19 +11:00
parent b67b0afd10
commit f39d8dbde8
3 changed files with 5 additions and 5 deletions

View File

@ -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,

View File

@ -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,

View File

@ -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);
}