mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
GCS: get_integrator() is now get_gyro_drift() in DCM
This commit is contained in:
parent
b67b0afd10
commit
f39d8dbde8
@ -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,
|
||||
|
@ -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,
|
||||
|
@ -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…
Reference in New Issue
Block a user