This is HGM's notes file for analyzing Plane logs. Ardupilot/libraries/DataFlash/LogStructure.h has lots of info Ardupilot/libraries/DataFlash/LogFile.cpp has actual writing code Seen lists all msg types for which data has been observed in a log. - So log msg types which are defined, but have no data, are not in Seen PARM contains all parameter values **************** Primary Estimates and Status **************** POS_label: (Best position estimate) Lat,Lng,Alt = from "ahrs.get_position()" - Calls EKFx.getLLH() and .getPosD() and .getOriginLLH() -- EKF2 gets these from the primary computation core -- Appears to return GPS measurments if an up-to-date estimate isn't available RelAlt = from "ahrs.get_relative_position_NED()" - Calls EKFx.getPosNE() and .getPosD() -- EKF2 gets these from the primary computation core -- Returns best guess, with "false" flag if data not available ATT_label: (Best attitude estimate, desired and actual) DesRoll,DesPitch,DesYaw = targets.x, targets.y, targets.z - From nav_roll_cd,nav_pitch_cd. (Plane.h: The instantaneous desired roll/bank angle) - targets.z always set to 0, not valid for plane, included for copter compatibility Roll,Pitch,Yaw = ahrs.roll_sensor,.pitch_sensor,.yaw_sensor - From AP_AHRS.cpp::update_cd_values(), sets *_sensor to * value - looks like roll,pitch,yaw managed by AP_AHRS_DCM and/or AP_AHRS_NavEKF - values updated regularly from EKF2 (or EKF1, or DCM) -- Plane schedules ahrs_update() -> ahrs.update() -> EKF2.getEulerAngles(-1,eulers); -- roll = eulers.x; pitch = eulers.y; yaw = eulers.z; ErrRP,ErrYaw = ahrs.get_error_rp()*100,.get_error_yaw()*100 - error_rp comes from AP_AHRS_DCM, calculated in AP_AHRS_DCM::drift_correction. -- Looks like a .8(last_val)+.2(new_val) running filter... -- comments say this is drift-correction code, gives paper ref, etc. - error_yaw has identical form but on yaw (of course) STAT_label: (State of flying/armed/crashed/etc?, Arduplane/Log.cpp adds) isFlying = 1 if plane is flying, 0 if not. Sometimes no value... - From is_flying.cpp, a logic script to attempt to determine status isFlyProb = A 0-to-1 probablity the plane is flying - If disarmed, isFlying = (isFlyProb > .9), If Armed, isFlying = (isFlyProb > .1) Armed = armed status Safety = 0(No state), 1(disarmed), 2(armed) from safety_switch_state() Crash = 0(Not crashed), 1(crashed) from is_flying.cpp Still = 0(Not still), 1(still) if any vibe msmts above _still_threshold (AP_InertialSensor.cpp) Stage = 1(Takeoff), 2(VTOL), 3(Normal), 4(Land_approach), 5(Land_preflare), 6(Land_final), 7(Land_abort) Hit = 0(no impact), 1(impact_detected) from is_flying.cpp CMD_label: (Commands from GCS or Mission: MavCmd) - At time of writing, always called for Missions, no "generic" Mav Commands CTot = Total # of commands in mission CNum = This command's number in mission (0=home, 1=1st cmd, etc.) CId = Mavlink Message ID Prm# = Command param # Lat = Command's Lat Lng = Command's Lng Alt = Command's Alt MODE_label: (Flight Mode, called on startup and from set_mode (also do_RTL?)) Mode = integer mode number (see "enum FlightMode" in ArduPlane/defines.h) ModeNum = (exact same as Mode) Rsn = integer mode number (see "enum mode_reason_t" in ArduPlane/defines.h) (presently unsupported?) - HGM: the do_RTL() logs mode-change separately... so a do_RTL would log twice? MSG_label: (A message written from Log_Write_Message) Message = Some set of characters giving useful info - For example, could be a GCS statustext, Firmware/software version, Mission start, etc. **************** Sensor Logs **************** ARSP_label: (Airspeed, scheduled from read_airspeed in plane, NTUN.ArspdErr uses _airspeed) - the _airspeed is a 70% filtered value of _raw_airspeed, used in other places but not logged here Airspeed = get_raw_airspeed() (unfiltered airspeed, from AP_Airspeed::read()) DiffPress = get_differential_pressure() (zero-bounded differential pressure msmt) Temp = get_temperature() (0 if temperature not available, e.g. for analog) - Not clear that this is actually used anywhere? Perhaps to adjust the barometer? RawPress = get_corrected_pressure() (raw_pressure - _offset) Offset = get_offset() (_offset) U = use() (identical to param USE, don't see alternate way to change it) BARO_label: (Barometer, scheduled from update_alt in plane, Baro is multi-device-capable) Alt = baro.get_altitude(0) - HGM: Why 0, and not _primary? (Answer: Maybe BARO2 should log others?) Press = .get_pressure() Temp = .get_temperature(0) CRt = .get_climb_rate() (from DerivativeFilter acting on Alt, SMS) SMS = .get_last_update(0) (time of last update, milliseconds?) Offset = .get_baro_drift_offset() (_alt_offset_active is 95% filtered version of _alt_offset) - _alt_offset appears to be controllable via an unused set() function, or from GCS via Param IMU_label: (Inertial Sensor, scheduled from update_ahrs() or update_logging1 in Plane) GyrX,GyrY,GyrZ, = ins.get_gyro(0).x,.y,.z AccX,AccY,AccZ, = ins.get_accel(0).x,.y,.z ErrG = ins.get_gyro_error_count(0) ErrA = ins.get_accel_error_count(0) Temp = ins.get_temperature(0) GyHlt = ins.get_gyro_health(0) (primary is switched to first healthy one) AcHlt = ins.get_accel_health(0) (primary is switched to first healthy one) VIBE_label: (Vibrations from AP_InertialSensor, scheduled from Plane::update_logging2) VibeX,VibeY,VibeZ = XYZ axis vibrations, ins.get_vibration_levels.x,.y,.z - Come from _accel_vibe_filter.get(), likely square-rooted Clip# = Count of accelerometer clipped values (axis #) for hitting maximums IMU2_label: (IMU3_label has no data, didn't put below) Identical to IMU, except for 2nd IMU MAG_label: MagX,MagY,MagZ = compass.get_field(0).x,.y,.z (data from publish_filtered_field()) OfsX,OfsY,OfsZ = compass.get_offsets(0).x,.y,.z (from calibration/learning, already added in field) MOfsX,MOfsY,MOfsZ, = compass.get_motor_offsets(0).x,.y,.z - Looks like param MOTCT enables/disables compensation Health = compass.healthy(0) (compass becomes unhealthy if no msmts for 500ms) S = compass.last_update_usec(0) (set from publish_filtered_field()) MAG2_label: (MAG3_label has no data, omitted below) Identical to MAG, except for 2nd Compass POWR_label: (Power supplied logs, only available for PX4) Vcc = Vcc into PX4, hal.analogin->board_voltage set by PX4AnalogIn::_timer_tick() VServo = Voltage on servo rail, _servorail_voltage set by PX4AnalogIn::_timer_tick() Flags = MAV_POWER_STATUS flags, "or"ed together. Normal value is 3. - MAV_POWER_STATUS_BRICK_VALID=1, /* main brick power supply valid | */ - MAV_POWER_STATUS_SERVO_VALID=2, /* main servo power supply valid for FMU | */ - MAV_POWER_STATUS_USB_CONNECTED=4, /* USB power is connected | */ - MAV_POWER_STATUS_PERIPH_OVERCURRENT=8, /* peripheral supply is in over-current state | */ - MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT=16, /* hi-power peripheral supply is in over-current state | */ - MAV_POWER_STATUS_CHANGED=32, /* Power status has changed since boot | */ - MAV_POWER_STATUS_ENUM_END=33, /* | */ CURR_label: (Battery Monitor logging message) Volt = Voltage of battery from AP_BattMonitor Curr = Instantaneous current drawn in A CurrTot = Total power drawn in mAh since startup CUR2_label: Same as CURR except for 2nd battery RCIN_label: (On-Period values of inputs) C# = value of input channel # RCOU_label: (On-Period values of outputs) C# = value of output channel # GPS_label: (GPS1 info, Actual processing code depends of course on GPS type) - GPS (and GPA) messages record TimeUS at logging, NOT upon receipt. - In ArduPlane, GPS logging happens from 50Hz loop, only if GPS info is new Status = 0(no GPS detected), 1(Valid msg, no lock), 2(2D lock), 3(3D lock), 4(DGPS), 5(RTK) GMS,GWk,NSats,HDop = gps.time_week_ms(),.time_week(),.num_sats(),.get_hdop() - All seem to be set when GPS message is received Lat,Lng,Alt = gps.location().lat,.lng,.alt - Set when GPS info received Spd,GCrs,VZ = gps.ground_speed(),.ground_course(),.velocity().z - Comes from GPS, depends on GPS whether it's calc'ed and from where GPA_label: (GPA1 info, Actual processing depends of course on GPS type) VDop = vdop (from GPS_State struct, same as other measurements) HAcc,VAcc,SAcc = gps.horizontal_accuracy(),.vertical_accuracy(),.speed_accuracy() - Some GPS don't have, but looks like most do. What is metric? (depends on GPS?) VV = gps.have_vertical_velocity() SMS = gps.last_message_time_ms() GPS2_label: Identical to GPS, except for 2nd GPS GPA2_label: Identical to GPA, except for 2nd GPS UBX1_label: (UBLOX GPS message 1, logged manually from AP_GPS_UBLOX::log_mon_hw) Instance = state.instance noisePerMS = _buffer.mon_hw_60.noisePerMS jamInd = _buffer.mon_hw_60.jamInd aPower = _buffer.mon_hw_60.aPower agcCnt = _buffer.mon_hw_60.agcCnt UBX2_label: (UBLOX GPS message 2, logged manually from AP_GPS_UBLOX::log_mon_hw2) Instance = state.instance ofsI = _buffer.mon_hw2.ofsI magI = _buffer.mon_hw2.magI ofsQ = _buffer.mon_hw2.ofsQ magQ = _buffer.mon_hw2.magQ UBY1_label: (UBLOX GPS2 message 1, identical to UBX1) Instance, noisePerMS, jamInd, aPower, agcCnt UBY2_label: (UBLOX GPS2 message 2, identical to UBX2) Instance, ofsI, magI, ofsQ, magQ RFND_label: (AP_RangeFinder logging, HGM did not investigate what this is) Dist1 = rangefinder.distance_cm(0), 0 if no 1st rangefinder Dist2 = rangefinder.distance_cm(1), 0 if no 2nd rangefinder SONR_label: (A Sonar message, perhaps related to RangeFinder, Arduplane/Log.cpp adds) - HGM: I didn't investigate this Dist = rangefinder.distance_cm() but in m Volt = rangefinder.voltage_mv() but in V Cnt = rangefinder_state.in_range_count Corr = rangefinder_state.correction SBR1_label: (Raw SBP messages, part 1, ref http://docs.swift-nav.com/ for SBP format) msgtype = Message type, see AP_GPS_SBP.h for types supported by driver. At time of writing: - SBP_STARTUP_MSGTYPE = 0xFF00; - SBP_HEARTBEAT_MSGTYPE = 0xFFFF; - SBP_GPS_TIME_MSGTYPE = 0x0100; - SBP_DOPS_MSGTYPE = 0x0206; - SBP_POS_ECEF_MSGTYPE = 0x0200; - SBP_POS_LLH_MSGTYPE = 0x0201; - SBP_BASELINE_ECEF_MSGTYPE = 0x0202; - SBP_BASELINE_NED_MSGTYPE = 0x0203; - SBP_VEL_ECEF_MSGTYPE = 0x0204; - SBP_VEL_NED_MSGTYPE = 0x0205; - SBP_TRACKING_STATE_MSGTYPE = 0x0016; - SBP_IAR_STATE_MSGTYPE = 0x0019; senderid = senderid - HGM: not sure how this gets filled? Maybe in a memcpy? msglen = length of message, if over 64, SBR2 message is needed to contain it all d1 = data of message (up to length = 64) SBR2_label: (Raw SBP messages, part 2, only used if msglen > 64) msgtype = Message type, see AP_GPS_SBP.h for types supported by driver d2 = data of message (continued from SBR1) d3 = (more data? Will this ever happen?) d4 = (more data? Will this ever happen?) SBPH_label: (SBP Health) CrcError = Counter of CRC errors (since initialization), crc_error_counter in AP_GPS_SBP.cpp LastInject = Time (in ms) of last call to AP_GPS_SBP::inject_data(), last_injected_data_ms in code IARhyp = Number of hypotheses from IAR_STATE message, iar->num_hypotheses in code **************** Extra Estimates and Status **************** ORGN_label: (Origin, Written when home is initialized at startup or via MavLink) - HGM: How can this be set? When is it set? Type = Origin_type: 0=ekf_origin, 1=ahrs_home Lat,Lng,Alt = loc passed to call - ahrs.get_origin() if type=0, ahrs.get_home() if type=1 -- ahrs.get_origin() gets EKF_origin, declared in AP_NavEKF2_core.h -- ahrs.get_home() gets _home, declared in AP_AHRS.h --- _home is set only by DCM::set_home, NavEKF::set_home calls it. STRT_label: (Log of startup, from Plane::Log_Write_Vehicle_Startup_Messages(), Arduplane/Log.cpp adds) SType = Start type, ArduPlane/defines.h has TYPE_AIRSTART_MSG and TYPE_GROUNDSTART_MSG CTot = Total number of commands in a mission, (AP_Mission._cmd_total) AHR2_label: (These are AHRS estimates, most likely from DCM AHRS) Roll,Pitch,Yaw=ahrs.get_secondary_attitude() - These "secondary" values come from the DCM AHRS Alt,Lat,Lng=ahrs.get_secondary_position() - These "secondary" values come from the DCM AHRS NTUN_label: (Navigation Tuning, Arduplane/Log.cpp adds) WpDist = Distance to next waypoint - auto_state.wp_distance set in Plane::navigate() or Plane::setup_glide_slope() TargBrg = Bearing to target - AP_L1_Control._target_bearing_cd, set by "update" functions in AP_L1_Control NavBrg = Bearing to L1 point - AP_L1_Control._nav_bearing, set by "update" functions in AP_L1_Control AltErr = Target Alt - Adjusted alt - From Plane::calc_altitude_error_cm(), accounts for mission-specific altitude offsets and such XT = Crosstrack error, from _crosstrack_error, didn't investigate further XTi = Crosstrack error integrator, from _L1_xtrack_i, didn't investigate further ArspdErr = Airspeed error, from Plane::calc_airspeed_errors - compares filtered airspeed to target from SpdHgt_Controller (TECS) CTUN_label: (Control Tuning, Arduplane/Log.cpp adds) NavRoll,NavPitch = nav_roll_cd,nav_pitch_cd - Repeated from ATT Roll,Pitch = ahrs.roll_sensor,.pitch_sensor - Repeated from ATT ThrOut = channel_throttle->get_servo_out() - HGM: are these repeated from anywhere? RdrOut = channel_rudder->get_servo_out() - HGM: are these repeated from anywhere? ThrDem = SpdHgt_Controller->get_throttle_demand() (TECS._throttle_dem variable) - HGM: are these repeated from anywhere? NKF1_label: (Main States & GyroBias) Roll,Pitch,Yaw = ahrs.get_NavEKF2().getEulerAngles(0).x,.y,.z VN,VE,VD = ahrs.get_NavEKF2().getVelNED(0).x,.y,.z dPD = ahrs.get_NavEKF2().getPosDownDerivative(0) PN,PE = ahrs.get_NavEKF2().getPosNE(0).x,.y PD = ahrs.get_NavEKF2().getPosD(0) GX,GY,GZ = ahrs.get_NavEKF2().getGyroBias(0).x,.y,.z NKF2_label: (Auxillary States) AZbias = ahrs.get_NavEKF2().getAccelZBias(0) GSX,GSY,GSZ = ahrs.get_NavEKF2().getGyroScaleErrorPercentage(0).x,.y,.z VWN,VWE = ahrs.get_NavEKF2().getWind(0).x,.y MN,ME,MD = ahrs.get_NavEKF2().getMagNED(0).x,.y,.z MX,MY,MZ = ahrs.get_NavEKF2().getMagXYZ(0).x,.y,.z MI = ahrs.get_NavEKF2().getActiveMag(0) NKF3_label: (Innovations) [All these come from ahrs.get_NavEKF2().getInnovations(0)] IVN,IVE,IVD = (velocity Innovations) IPN,IPE,IPD = (position Innovations) IMX,IMY,IMZ = ("mag" Innovations) - HGM is this magnetometer? IYAW = (yaw Innovations) - HGM what is this? IVT = (tas Innovations) - HGM what is this? NKF4_label: (Square-Root Variances and Status) SV = velocity variance SP = position variance SH = height variance SM = mag variance SVT = "tasVariance" errRP = getTiltError(0) OFN,OFE = "offsets from getVariances()" FS = getFilterFaults(0) TS = getFilterTimeouts(0) SS = getFilterStatus(0) ("solution status") GPS = getFilterGpsStatus(0) PI = getPrimaryCoreIndex() NKF5_label: (Optical Flow + ...) [getFlowDebug(-1), getOutputTrackingError(-1)] normInnov, FIX, FIY, AFI, HAGL, offset, RI, meaRng, errHAGL NKF6_label: (2nd IMU, identical fields to NKF1) Roll, Pitch, Yaw, VN, VE, VD, dPD, PN, PE, PD, GX, GY, GZ NKF7_label: (2nd IMU, identical fields to NKF2) AZbias, GSX, GSY, GSZ, VWN, VWE, MN, ME, MD, MX, MY, MZ, MI NKF8_label: (2nd IMU, identical fields to NKF3) IVN, IVE, IVD, IPN, IPE, IPD, IMX, IMY, IMZ, IYAW, IVT NKF9_label: (2nd IMU, identical fields to NKF4) SV, SP, SH, SM, SVT, errRP, OFN, OFE, FS, TS, SS, GPS, PI PIDP_label: (PID Pitch Contributions) Des = _pid_info.desired_rate P,I,D = contribution to commanded rate from P, I, and D terms FF = contribution from Feedforward term AFF (unused, why still here?) PIDR_label: (PID Roll Contributions) Des, P, I, D, FF, AFF (Same as PIDP) PIDY_label: (PID Yaw Contributions) Des, P, I, D, FF, AFF (Same as PIDP) PIDS_label: (PID Steer Contributions) Des, P, I, D, FF, AFF (Same as PIDP) PIDA_label: (Quadplane PID Accel_z) Des, P, I, D, FF, AFF (Same as PIDP) PM_label: (Performance Monitoring, calculated in Plane::loop(), Arduplane/Log.cpp adds) - HGM: Didn't figure out this part. Plane schedules log_perf_info which writes to the log and resets the data (resetPerfData). NLon = Number of long-running loops since last PM log msg, perf.num_long NLoop = Total number of loops since last PM log msg, perf.mainLoop_count MaxT = Max time any loop took since last PM log msg, perf.G_Dt_max MinT = Min time any loop took since last PM log msg, perf.G_Dt_min LogDrop = Number of log messages dropped since last PM log msg TECS_label: (TECS log message 1, logged manually from AP_TECS::update_pitch_throttle()) - HGM: Didn't investigate what these acutally mean h = _height dh = _climb_rate hdem = _hgt_dem_adj dhdem = _hgt_rate_dem spdem = _TAS_dem_adj sp = _TAS_state dsp = _vel_dot ith = _integTHR_state iph = _integSEB_state th = _throttle_dem ph = _pitch_dem dspdem = _TAS_rate_dem w = logging.SKE_weighting f = _flags_byte TEC2_label: (TECS log message 2, logged manually from AP_TECS::update_pitch_throttle()) KErr = logging.SKE_error PErr = logging.SPE_error EDelta = logging.SEB_delta LF = load_factor TERR_label: (This is AP_Terrain. Didn't spend much time learning) Status, Lat, Lng, Spacing, TerrH, CHeight, Pending, Loaded Status = status() = 0(not enabled), 1(no terrain data for loc), 2(terrain avail) Lat,Lng = ahrs.get_postition().lat,.lon Spacing = grid_spacing (meters between grid points) TerrH = height_amsl() output, calc from linear interp btn points CHeight = current_height() output, comparing ahrs.get_position().alt with terrain_height Pending,Loaded = pending,loaded from TerrainGCS.cpp, AP_Terrain::get_statistics() ****************** No Data, _label only ****************** ACC1_label: ACC2_label: ACC3_label: looks like 'SampleUS' and then accellerometer data (X, Y, Z) ARM_label: (Arduplane/Log.cpp adds) 'ArmState' and 'ArmChecks' (but no data) ATRP_label: (Arduplane/Log.cpp adds) BAR2_label: BAR3_label: (no "Offset" field?) CAM_label: (Time and position when camera shutter was activated) GPSTime, GPSWeek, Lat, Lng, Alt, RelAlt, GPSAlt, Roll, Pitch, Yaw DMS_label: (???) N, Dp, RT, RS, Er, Fa, Fmn, Fmx, Pa, Pmn, Pmx, Sa, Smn, Smx EKF1_label: (all diff fields... different EKFs?) EKF2_label EKF3_label EKF4_label EKF5_label ESC1_label: RPM, Volt, Curr, Temp ESC2_label: RPM, Volt, Curr, Temp . . (and so on) . ESC8_label: RPM, Volt, Curr, Temp FMT_label: (NO TimeUS), Type, Length, Name, Format, Columns GMB1_label: GMB2_label: GMB3_label: GRAW_label GRXH_label GRXS_label GYR1_label GYR2_label GYR3_label IMT_label IMT2_label IMT3_label OF_label: (Arduplane/Log.cpp adds, requires OPTFLOW==ENABLED) Qual, flowX, flowY, bodyX, bodyY QTUN_label: (Arduplane/Log.cpp adds) AngBst, ThrOut, DAlt, Alt, BarAlt, DCRt, CRt, DVx, DVy, DAx, DAy RAD_label: RSSI, RemRSSI, TxBuf, Noise, RemNoise, RxErrors, Fixed RALY_label: Tot, Seq, Lat, Lng, Alt RATE_label: RDes, R, ROut, PDes, P, POut, YDes, Y, YOut, ADes, A, AOut RPM_label: rpm1, rpm2 RSSI_label: RXRSSI SBFE_label: TOW, WN, Mode, Err, Lat, Lng, Height, Undul, Vn, Ve, Vu, COG SIM_label: Roll, Pitch, Yaw, Alt, Lat, Lng TRIG_label: GPSTime, GPSWeek, Lat, Lng, Alt, RelAlt, GPSAlt, Roll, Pitch, Yaw **************************************************************** Looks like every *_label begins with 'LineNo' and 'TimeUS' EXCEPT: FMT_label omits 'TimeUS', {DMS_label, GMB1_label, GMB2_label, GMB3_label} have 'TimeMS'. FMT is message specifying log formatting, so no time associated with it DMS is Mavlink Stats (don't know what DF is yet) GMB# is for a Gimbal **************************************************************** Quad logs: What's different? (Depends on firmware version, too) Ones with data: DU32 = ?? (Id, Value) ERR = some sort of subsys error, with ECode EV = ?? (Id) MOTB = ?? (LiftMax, BatVolt, BatRes, ThLimit) List of labels: ACC1_label ACC2_label ACC3_label AHR2_label ARSP_label ATDE_label ATT_label ATUN_label BAR2_label BARO_label CAM_label CMD_label CTUN_label CURR_label D16_label D32_label DFLT_label DU16_label DU32_label EKF1_label EKF2_label EKF3_label EKF4_label EKF5_label ERR_label ESC1_label ESC2_label ESC3_label ESC4_label ESC5_label ESC6_label ESC7_label ESC8_label EV_label FMT_label GPS2_label GPS_label GRAW_label GRXH_label GRXS_label GYR1_label GYR2_label GYR3_label HELI_label IMT2_label IMT3_label IMT_label IMU2_label IMU3_label IMU_label MAG2_label MAG3_label MAG_label MODE_label MOTB_label MSG_label NTUN_label OF_label ORGN_label PIDA_label PIDP_label PIDR_label PIDS_label PIDY_label PM_label POS_label POWR_label PTUN_label RAD_label RATE_label RCIN_label RCOU_label RPM_label SBPH_label SBR1_label SBR2_label SIM_label STRT_label TERR_label UBX1_label UBX2_label UBX3_label VIBE_label