Browse Source

Plane: log NTUN:ArspdErr airspeed error (in meters)

master
Tom Pittenger 9 years ago
parent
commit
ba5b4e694c
  1. 6
      ArduPlane/Log.cpp

6
ArduPlane/Log.cpp

@ -281,6 +281,7 @@ struct PACKED log_Nav_Tuning { @@ -281,6 +281,7 @@ struct PACKED log_Nav_Tuning {
int16_t altitude_error_cm;
float xtrack_error;
float xtrack_error_i;
float airspeed_error;
};
// Write a navigation tuning packet
@ -294,7 +295,8 @@ void Plane::Log_Write_Nav_Tuning() @@ -294,7 +295,8 @@ void Plane::Log_Write_Nav_Tuning()
nav_bearing_cd : (int16_t)nav_controller->nav_bearing_cd(),
altitude_error_cm : (int16_t)altitude_error_cm,
xtrack_error : nav_controller->crosstrack_error(),
xtrack_error_i : nav_controller->crosstrack_error_integrator()
xtrack_error_i : nav_controller->crosstrack_error_integrator(),
airspeed_error : airspeed_error
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}
@ -486,7 +488,7 @@ const struct LogStructure Plane::log_structure[] = { @@ -486,7 +488,7 @@ const struct LogStructure Plane::log_structure[] = {
{ LOG_CTUN_MSG, sizeof(log_Control_Tuning),
"CTUN", "Qcccchhh", "TimeUS,NavRoll,Roll,NavPitch,Pitch,ThrOut,RdrOut,ThrDem" },
{ LOG_NTUN_MSG, sizeof(log_Nav_Tuning),
"NTUN", "Qfcccff", "TimeUS,WpDist,TargBrg,NavBrg,AltErr,XT,XTi" },
"NTUN", "Qfcccfff", "TimeUS,WpDist,TargBrg,NavBrg,AltErr,XT,XTi,ArspdErr" },
{ LOG_SONAR_MSG, sizeof(log_Sonar),
"SONR", "QHfffbBf", "TimeUS,DistCM,Volt,BaroAlt,GSpd,Thr,Cnt,Corr" },
{ LOG_ARM_DISARM_MSG, sizeof(log_Arm_Disarm),

Loading…
Cancel
Save