Analyze UAV Autopilot Flight Log Using Flight Log Analyzer
Import flight log data, create figures and plots, export signals, and use custom signal mapping in the Flight Log Analyzer app.
The Flight Log Analyzer app enables you to analyze log files generated by simulated or real flights.
Log analysis helps find the root cause of a crash, or monitor the health during a flight of a vehicle. You can perform basic analysis to determine:
How well the controllers track their references
Whether there is any strong vibration
If the vehicle experiences power failures
Open Flight Log Analyzer App
In the Apps tab, under Robotics and Autonomous Systems, click Flight Log Analyzer.
Alternatively, you can use the flightLogAnalyzer
function from the MATLAB® command prompt.
Import ULOG File
Load the ULOG file.
ulg = ulogreader("flight.ulg")
ulg = ulogreader with properties: FileName: "flight.ulg" StartTime: 00:00:00.176000 EndTime: 00:02:15.224000 AvailableTopics: [51x5 table] DropoutIntervals: [0x2 duration]
On the Flight Log Analyzer app toolstrip, select Import > From Workspace. In the Log Data section of the Import flight log signal mapping and log data from workspace dialog box, select the ulogreader
object ulg
and click Import.
By default, the app displays a satellite map with logged GPS data and the flight modes as a table. The flight modes, along with their corresponding start and end times, are tabulated in the Flight Modes pane.
Create Figures and Plots
Every UAV (fixed or multi-rotor) is equipped with a set of sensors, such as a gyroscope, accelerometer, magnetometer, and barometer, to determine the vehicle state. A vehicle state includes the position, velocity, altitude, speed, and rates of rotation of the vehicle.
Add Predefined Plot
In the Plot section of the app toolstrip, click Add Figure to add an empty figure to the plotting pane.
In the plot gallery, click IMU to add plots to the figure for the gyroscope, Gyro, and accelerometer, Accelerometer.
You can use various predefined plots from the plot gallery to visualize data from different sensors.
Change Plot Focus Using Panner
In the Flight Modes pane, find the first instance of the Loiter flight mode and note its Start Time and End Time values.
Focus on the flight mode by, in the Panner pane, dragging the red and blue handles to the Start Time and End Time, respectively, of the desired flight mode.
Alternatively, you can type the Start Time and End Time values in the From (sec) and To (sec) boxes, beneath the strip plot. Click the Acceleration plot to focus on it.
If UAV vibration is in a good range, then z
-axis acceleration should remain below x
-axis and y
-axis acceleration. The plotted flight data indicates that, at this point in the flight, UAV vibration is in a good range. Using the Panner, focus on the other three Loiter flight modes and observe the acceleration of the UAV.
Add Custom Plot
Next, create a custom Timeseries plot to compare the estimated roll against the roll target.
First, in the Custom Plots section of the plot gallery, click Timeseries.
In the Signals pane, click Add Signal twice to add two signals.
Double-click the Y-Axis column of the first signal and, in the Signal Browser window, type
RollTarget
in the Search box, and then click the arrow next toAttitudeTargetEuler
and selectRollTarget
. Then, click Update.Repeat the previous three steps for the second signal to add
Roll
.Rename the first signal to
RollTarget
and the second signal toRoll
. To rename a signal, double-click its entry in the Signal Name column and type the new name.In the Details pane, select Show Legend to show the legend on the plot.
The plot shows that the estimated roll closely follows the roll target until the last few seconds of the flight.
Export Signals
Select Export > Export Signal to export the signals as a timetable to the MATLAB workspace or a MAT file (.mat
).
Select the signals to export. To export them to a MAT file, select To MAT-file and specify a file name for the MAT file. To select a destination folder for the MAT file, click Browse and navigate to the folder to which you want to export.
To export the signals to the MATLAB workspace, select To MATLAB workspace and specify a name for the output workspace variable.
The signals are exported as a timetable.
Using Custom Signal Mapping in Flight Log Analyzer App
The default signal mapping returns a predefined set of signals.
flsmObj = flightLogSignalMapping("ulog"); info(flsmObj,"Signal")
ans=18×4 table
SignalName IsMapped SignalFields FieldUnits
_____________________ ________ __________________________________________________________________________________________________________________________________________________________________________________________________________ ___________________________________________________
"Accel" true "AccelX, AccelY, AccelZ" "m/s^2, m/s^2, m/s^2"
"Airspeed" true "PressDiff, IndicatedAirSpeed, Temperature" "Pa, m/s, degreeC"
"AttitudeEuler" true "Roll, Pitch, Yaw" "rad, rad, rad"
"AttitudeRate" true "BodyRotationRateX, BodyRotationRateY, BodyRotationRateZ" "rad/s, rad/s, rad/s"
"AttitudeTargetEuler" true "RollTarget, PitchTarget, YawTarget" "rad, rad, rad"
"Barometer" true "PressAbs, PressAltitude, Temperature" "Pa, m, degreeC"
"Battery" true "Voltage_1, Voltage_2, Voltage_3, Voltage_4, Voltage_5, Voltage_6, Voltage_7, Voltage_8, Voltage_9, Voltage_10, Voltage_11, Voltage_12, Voltage_13, Voltage_14, Voltage_15, Voltage_16, RemainingCapacity" "v, v, v, v, v, v, v, v, v, v, v, v, v, v, v, v, %"
"GPS" true "Latitude, Longitude, Altitude, GroundSpeed, CourseAngle, SatellitesVisible" "degree, degree, m, m/s, degree, N/A"
"Gyro" true "GyroX, GyroY, GyroZ" "rad/s, rad/s, rad/s"
"LocalENU" true "X, Y, Z" "m, m, m"
"LocalENUTarget" true "XTarget, YTarget, ZTarget" "m, m, m"
"LocalENUVel" true "VX, VY, VZ" "m/s, m/s, m/s"
"LocalENUVelTarget" true "VXTarget, VYTarget, VZTarget" "m/s, m/s, m/s"
"LocalNED" true "X, Y, Z" "m, m, m"
"LocalNEDTarget" true "XTarget, YTarget, ZTarget" "m, m, m"
"LocalNEDVel" true "VX, VY, VZ" "m/s, m/s, m/s"
⋮
In addition the predefined set of signals, you can map other signals present in the flight log. For example, use mapSignal
to map WindSpeed
to the flightLogSignalMapping
object, flsmObj
.
mapSignal(flsmObj,"WindSpeed", ... @(data)getTime(getTable(data,"wind_estimate")), ... @(data)getModeValue(getTable(data,"wind_estimate")), ... ["WindSpeed_East","WindSpeed_North"]);
Check that flsmObj
now contains the new signal.
info(flsmObj,"Signal")
ans=19×4 table
SignalName IsMapped SignalFields FieldUnits
_____________________ ________ __________________________________________________________________________________________________________________________________________________________________________________________________________ ___________________________________________________
"Accel" true "AccelX, AccelY, AccelZ" "m/s^2, m/s^2, m/s^2"
"Airspeed" true "PressDiff, IndicatedAirSpeed, Temperature" "Pa, m/s, degreeC"
"AttitudeEuler" true "Roll, Pitch, Yaw" "rad, rad, rad"
"AttitudeRate" true "BodyRotationRateX, BodyRotationRateY, BodyRotationRateZ" "rad/s, rad/s, rad/s"
"AttitudeTargetEuler" true "RollTarget, PitchTarget, YawTarget" "rad, rad, rad"
"Barometer" true "PressAbs, PressAltitude, Temperature" "Pa, m, degreeC"
"Battery" true "Voltage_1, Voltage_2, Voltage_3, Voltage_4, Voltage_5, Voltage_6, Voltage_7, Voltage_8, Voltage_9, Voltage_10, Voltage_11, Voltage_12, Voltage_13, Voltage_14, Voltage_15, Voltage_16, RemainingCapacity" "v, v, v, v, v, v, v, v, v, v, v, v, v, v, v, v, %"
"GPS" true "Latitude, Longitude, Altitude, GroundSpeed, CourseAngle, SatellitesVisible" "degree, degree, m, m/s, degree, N/A"
"Gyro" true "GyroX, GyroY, GyroZ" "rad/s, rad/s, rad/s"
"LocalENU" true "X, Y, Z" "m, m, m"
"LocalENUTarget" true "XTarget, YTarget, ZTarget" "m, m, m"
"LocalENUVel" true "VX, VY, VZ" "m/s, m/s, m/s"
"LocalENUVelTarget" true "VXTarget, VYTarget, VZTarget" "m/s, m/s, m/s"
"LocalNED" true "X, Y, Z" "m, m, m"
"LocalNEDTarget" true "XTarget, YTarget, ZTarget" "m, m, m"
"LocalNEDVel" true "VX, VY, VZ" "m/s, m/s, m/s"
⋮
To use this custom signal mapping in the Flight Log Analyzer app:
On the app toolstrip, click Import and select From Workspace.
In the dialog box, select
flsmObj
from the Signal Mapping list.Select the
ulogreader
objectulg
from the Log Data section.Click Import.
Create a custom Timeseries plot and follow the steps in Add Custom Plot to add the WindSpeed_East
and WindSpeed_North
signals from the Signal Browser.
You can use this process to map other signals to the custom signal mapping object and visualize them in the app.
References
[1] PX4 Autopilot. "Flight Log Analysis." PX4 User Guide. Accessed December 14, 2020. https://docs.px4.io/main/en/log/flight_log_analysis.html
[2] PX4 Autopilot. "Log Analysis Using Flight Review." PX4 User Guide. Accessed December 14, 2020. https://docs.px4.io/main/en/log/flight_review.html