Browse Source

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

mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
d75e883fe8
  1. 2
      ArduCopter/GCS_Mavlink.pde
  2. 2
      ArduPlane/GCS_Mavlink.pde
  3. 6
      ArduPlane/Log.pde

2
ArduCopter/GCS_Mavlink.pde

@ -127,7 +127,7 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan) @@ -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,

2
ArduPlane/GCS_Mavlink.pde

@ -488,7 +488,7 @@ static void NOINLINE send_raw_imu3(mavlink_channel_t chan) @@ -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,

6
ArduPlane/Log.pde

@ -245,9 +245,9 @@ static void Log_Write_Performance() @@ -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);
}

Loading…
Cancel
Save