mirror of https://github.com/ArduPilot/ardupilot
Add logging of DCM drift correction integrator in PM
This may be a temporary feature… Mostly added to check new (lower) integrator limit.
This commit is contained in:
parent
2d3f97667f
commit
9fe554236b
|
@ -355,6 +355,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(pmTest1);
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue