ulogreader
Description
The ulogreader
object reads a ULOG file
(.ulg
). The object stores information about the file, including start and
end logging times, summary of available topics, and dropout intervals.
Creation
Properties
This property is read-only.
Name of the ULOG file, specified as a string scalar or character vector. The
FileName
is the path specified in the
filePath
input.
Data Types: char
| string
This property is read-only.
Start time of logging offset from the system start time in the ULOG file, specified
as a duration
object in the
'hh:mm:ss.SSSSSS'
format.
Data Types: duration
This property is read-only.
Timestamp of the last timestamped message logged in the ULOG file, specified as a
duration
object in the
'hh:mm:ss.SSSSSS'
format.
Data Types: duration
This property is read-only.
Summary of all the logged topics, specified as a table that contains the columns:
TopicNames
InstanceID
StartTimestamp
LastTimestamp
NumMessages
Data Types: table
This property is read-only.
Time intervals in which messages were dropped while logging, specified as an
n-by-2 matrix of duration
arrays in the 'hh:mm:ss.SSSSSS'
format, where
n is the number of dropouts.
Data Types: duration
Object Functions
readTopicMsgs | Read topic messages |
readSystemInformation | Read information messages |
readParameters | Read parameter values |
readLoggedOutput | Read logged output messages |
Examples
Load the ULOG file. Specify the relative path of the file
ulog = ulogreader('flight.ulg');
Read all topic messages.
msg = readTopicMsgs(ulog);
Specify the time interval between which to select messages.
d1 = ulog.StartTime; d2 = d1 + duration([0 0 55],'Format','hh:mm:ss.SSSSSS');
Read messages from the topic 'vehicle_attitude'
with an instance ID of 0
in the time interval [d1 d2]
.
data = readTopicMsgs(ulog,'TopicNames',{'vehicle_attitude'}, ... 'InstanceID',{0},'Time',[d1 d2]);
Extract topic messages for the topic.
vehicle_attitude = data.TopicMessages{1,1}
vehicle_attitude=1066×3 timetable
timestamp q delta_q_reset quat_reset_counter
_______________ ______________________________________________ ___________________________________________________ __________________
00:00:01.952000 0.68231 0.0017879 -0.014252 0.73092 0.6823 2.1123e-10 6.8316e-10 0.73107 1
00:00:01.956000 0.68231 0.0017974 -0.014259 0.73092 0.6823 2.1123e-10 6.8316e-10 0.73107 1
00:00:02.004000 0.68126 0.001916 -0.014383 0.73189 1 0 -2.2119e-09 0.0013563 2
00:00:02.052000 0.68112 0.0019686 -0.014534 0.73202 1 0 -2.2119e-09 0.0013563 2
00:00:02.104000 0.68092 0.002101 -0.014752 0.73221 1 0 -2.2119e-09 0.0013563 2
00:00:02.152000 0.68067 0.0022023 -0.014936 0.73243 1 0 -2.2119e-09 0.0013563 2
00:00:02.204000 0.68045 0.0023886 -0.015088 0.73263 1 0 -2.2119e-09 0.0013563 2
00:00:02.252000 0.68016 0.0025014 -0.015266 0.7329 1 0 -2.2119e-09 0.0013563 2
00:00:02.304000 0.67995 0.0026582 -0.015413 0.73309 1 0 -2.2119e-09 0.0013563 2
00:00:02.352000 0.67983 0.0027451 -0.015558 0.7332 1 0 -2.2119e-09 0.0013563 2
00:00:02.404000 0.67979 0.0028021 -0.015723 0.73323 1 0 -2.2119e-09 0.0013563 2
00:00:02.452000 0.67975 0.0029118 -0.015801 0.73327 1 0 -2.2119e-09 0.0013563 2
00:00:02.504000 0.67972 0.002982 -0.015947 0.73329 1 0 -2.2119e-09 0.0013563 2
00:00:02.552000 0.67975 0.0030121 -0.016096 0.73326 1 0 -2.2119e-09 0.0013563 2
00:00:02.604000 0.6798 0.0030043 -0.016209 0.73321 1 0 -2.2119e-09 0.0013563 2
00:00:02.652000 0.67985 0.0030682 -0.016367 0.73317 1 0 -2.2119e-09 0.0013563 2
⋮
Read all system information.
systeminfo = readSystemInformation(ulog)
systeminfo=12×2 table
InformationField Value
_______________________ __________________________________________
"ver_sw" "8763d71bf0b603e0da42ea16fceae7fd2590546f"
"ver_sw_release" "v1.11.0.RC"
"ver_vendor_sw_release" "192"
"ver_hw" "PX4_SITL"
"sys_name" "PX4"
"sys_os_name" "Linux"
"ver_sw_branch" "master"
"sys_os_ver_release" "84148479"
"sys_toolchain" "GNU GCC"
"sys_toolchain_ver" "9.3.0"
"ver_data_format" "1"
"time_ref_utc" "0"
Read all initial parameter values.
params = readParameters(ulog)
params=631×2 table
Parameters Values
_________________ ______
"ASPD_BETA_GATE" 1
"ASPD_BETA_NOISE" 0.3
"ASPD_DO_CHECKS" 0
"ASPD_FALLBACK" 0
"ASPD_FS_INNOV" 1
"ASPD_FS_INTEG" -1
"ASPD_FS_T1" 3
"ASPD_FS_T2" 100
"ASPD_PRIMARY" 1
"ASPD_SCALE" 1
"ASPD_SCALE_EST" 0
"ASPD_SC_P_NOISE" 0.0001
"ASPD_STALL" 10
"ASPD_TAS_GATE" 3
"ASPD_TAS_NOISE" 1.4
"ASPD_W_P_NOISE" 0.1
⋮
Read logged output messages in the time interval.
log = readLoggedOutput(ulog,'Time',[d1 d2])
log=23×2 timetable
timestamp LogLevel Messages
_______________ ________ _____________________________________________________________________________________
00:00:00.176000 "INFO" "[logger] [logger] ./log/2020-07-07/15_07_10.ulg"
00:00:00.176000 "INFO" "[logger] Opened full log file: ./log/2020-07-07/15_07_10.ulg"
00:00:00.176000 "INFO" "[mavlink] MAVLink only on localhost (set param MAV_BROADCAST = 1 to enable network)"
00:00:00.184000 "INFO" "[px4] Startup script returned successfully"
00:00:01.044000 "INFO" "[mavlink] partner IP: 127.0.0.1"
00:00:01.096000 "INFO" "[ecl/EKF] 888000: GPS checks passed"
00:00:01.948000 "INFO" "[ecl/EKF] 1780000: reset position to last known position"
00:00:01.948000 "INFO" "[ecl/EKF] 1780000: reset velocity to zero"
00:00:05.548000 "INFO" "[ecl/EKF] 5380000: reset velocity to GPS"
00:00:05.548000 "INFO" "[ecl/EKF] 5380000: starting GPS fusion"
00:00:26.668000 "INFO" "[commander] ARMED by Arm/Disarm component command"
00:00:31.268000 "INFO" "[fw_pos_control_l1] Takeoff on runway"
00:00:31.360000 "INFO" "[commander] Takeoff detected"
00:00:31.688000 "INFO" "[runway_takeoff] #Takeoff airspeed reached"
00:00:33.548000 "INFO" "[runway_takeoff] #Climbout"
00:00:34.088000 "INFO" "[runway_takeoff] #Navigating to waypoint"
⋮
References
[1] PX4 Developer Guide. "ULog File Format." Accessed December 6, 2019. https://docs.px4.io/main/en/dev_log/ulog_file_format.html.
Version History
Introduced in R2020b
See Also
MATLAB Command
You clicked a link that corresponds to this MATLAB command:
Run the command by entering it in the MATLAB Command Window. Web browsers do not support MATLAB commands.
Select a Web Site
Choose a web site to get translated content where available and see local events and offers. Based on your location, we recommend that you select: .
You can also select a web site from the following list
How to Get Best Site Performance
Select the China site (in Chinese or English) for best site performance. Other MathWorks country sites are not optimized for visits from your location.
Americas
- América Latina (Español)
- Canada (English)
- United States (English)
Europe
- Belgium (English)
- Denmark (English)
- Deutschland (Deutsch)
- España (Español)
- Finland (English)
- France (Français)
- Ireland (English)
- Italia (Italiano)
- Luxembourg (English)
- Netherlands (English)
- Norway (English)
- Österreich (Deutsch)
- Portugal (English)
- Sweden (English)
- Switzerland
- United Kingdom (English)