Dataflash Log explanations

Hi,

I’m newbie and i investigate dataflash flight logs. I collect several flight log from there and compare. I utilise discussion forum and arducopter doc but some logs datas did not explain or i couldnt find explanations. For example NKF1, PIDA, UBX1 logs. Is there any documentation about all subtitle of logs and parameters.

Thanks

http://ardupilot.org/dev/docs/ekf2-estimation-system.html#ekf2-log-data

Packets NKF1 to NKF 4 contain information for the first EKF instance. Packets NKF6 to NKF9 contain the same information, for the second instance if enabled using the EK2_IMU_MASK parameter. Packet NKF5 contains optical flow information for the EKF instance that is the primary for flight control.
The available EKF2 available log data is listed below. Some plots showing example flight data have been included. This data was logged using a Pixhawk on a 3DR Iris+ quadcopter with the following parameter changes followed by a reboot:

EKF_ENABLE = 0 (turns off the legacy EKF)
EK2_ENABLE = 1 (turns on EKF2)
EK2_IMU_MASK = 3 (Instructs EKF2 to run two instances, one for IMU1 (MPU6000) and one for IMU2 (LDG20H + LSM303D)
AHRS_EKF_TYPE = 2 (tells the flight control system to use EKF2
LOG_BITMASK = 131071 (logs 50Hz data from startup)
1 Like

The source code is your friend…

> struct log_EKF1 pkt = {
>     LOG_PACKET_HEADER_INIT(LOG_NKF1_MSG),
>     time_us : time_us,
>     roll    : (int16_t)(100*degrees(euler.x)), // roll angle (centi-deg, displayed as deg due to format string)
>     pitch   : (int16_t)(100*degrees(euler.y)), // pitch angle (centi-deg, displayed as deg due to format string)
>     yaw     : (uint16_t)wrap_360_cd(100*degrees(euler.z)), // yaw angle (centi-deg, displayed as deg due to format string)
>     velN    : (float)(velNED.x), // velocity North (m/s)
>     velE    : (float)(velNED.y), // velocity East (m/s)
>     velD    : (float)(velNED.z), // velocity Down (m/s)
>     posD_dot : (float)(posDownDeriv), // first derivative of down position
>     posN    : (float)(posNE.x), // metres North
>     posE    : (float)(posNE.y), // metres East
>     posD    : (float)(posD), // metres Down
>     gyrX    : (int16_t)(100*degrees(gyroBias.x)), // cd/sec, displayed as deg/sec due to format string
>     gyrY    : (int16_t)(100*degrees(gyroBias.y)), // cd/sec, displayed as deg/sec due to format string
>     gyrZ    : (int16_t)(100*degrees(gyroBias.z)), // cd/sec, displayed as deg/sec due to format string
>     originHgt : originLLH.alt // WGS-84 altitude of EKF origin in cm
> };

PID logs contains the internal state of the PID controller and UBX contains the values of different internal Ublox gps hardware registers

>     struct log_Ubx1 pkt = {
>         pkt.noisePerMS = _buffer.mon_hw_68.noisePerMS;
>         pkt.jamInd     = _buffer.mon_hw_68.jamInd;
>         pkt.aPower     = _buffer.mon_hw_68.aPower;
>         pkt.agcCnt     = _buffer.mon_hw_68.agcCnt;
>     }
> 
>     struct log_Ubx2 pkt = {
>         LOG_PACKET_HEADER_INIT(_ubx_msg_log_index(LOG_GPS_UBX2_MSG)),
>         time_us   : AP_HAL::micros64(),
>         instance  : state.instance,
>         ofsI      : _buffer.mon_hw2.ofsI,
>         magI      : _buffer.mon_hw2.magI,
>         ofsQ      : _buffer.mon_hw2.ofsQ,
>         magQ      : _buffer.mon_hw2.magQ,
>     };
>
1 Like

Sadly, very, very little. I’m still working on adding the ability to add
metadata to our code for these entries.

1 Like