Skip to content

Commit 2b2db3d

Browse files
authored
Merge branch 'master' into bengterik-auto-create-output-dir
2 parents 68b9f91 + 723f514 commit 2b2db3d

File tree

2 files changed

+332
-0
lines changed

2 files changed

+332
-0
lines changed
Lines changed: 37 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,37 @@
1+
# Wireshark Mavlink Telemetry Log (TLOG) file reader
2+
3+
This is a Wireshark LUA plugin, which allows Mavlink TLOG files to be read in Wireshark.
4+
TLOG files are typically created by tools such as [MavProxy](https://ardupilot.org/mavproxy/),
5+
[Mission Planner](https://ardupilot.org/planner/) and others, to provide a log of the
6+
Mavlink communication between the tool and the attached vehicle.
7+
8+
Note that this LUA script provides the capability to read TLOG files, while the message
9+
decoding is provided by the [MAVLink Lua Plugin](https://mavlink.io/en/guide/wireshark.html)
10+
which should also be installed to make use of this plugin.
11+
12+
## Installation
13+
14+
To install this plugin, download the [mavlink-tlog-reader.lua](mavlink-tlog-reader.lua) file,
15+
and place it in your LUA plugins folder.
16+
You can find your global and personal LUA plugins folders from the Folders tab on the
17+
Wireshark About dialog.
18+
19+
Follow the build and installation instructions on the [MAVLink Lua Plugin](https://mavlink.io/en/guide/wireshark.html)
20+
page, to install the associated Mavlink message decoder.
21+
22+
## Usage
23+
24+
Within the Wireshark GUI, select File/Open, and choose any .tlog file to load. Note that
25+
the default "All Capture Files" filter does not include .tlog files, so you will need to
26+
select "All Files" to see them. The file should then load, showing all Mavlink messages
27+
recorded in the file.
28+
29+
Note that if the MAVLink Lua Plugin is not also installed, then messages with show with
30+
"UNKNOWN" in the protocol column, and "WTAP_ENCAP = 45" in the Info column.
31+
32+
## File Format
33+
34+
TLOG files consist of a stream of [Mavlink](https://mavlink.io/en/) messages, including
35+
their complete [header, checksum and signature](https://mavlink.io/en/guide/serialization.html)
36+
(if applicable). Each message is preceeded by a 8-byte [Unix time](https://www.unixtimestamp.com/)
37+
timestamp in microseconds.
Lines changed: 295 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,295 @@
1+
-- mavlink-tlog-reader.lua
2+
--------------------------------------------------------------------------------
3+
--[[
4+
This is a Wireshark file reader for Mavlink Telemetry Log (tlog) files.
5+
Author: Simon Hancock
6+
--]]
7+
--------------------------------------------------------------------------------
8+
9+
--------------------------------------------------------------------------------
10+
-- set up debugging level
11+
--------------------------------------------------------------------------------
12+
13+
local debug = {
14+
DISABLED = 0,
15+
LEVEL_1 = 1,
16+
LEVEL_2 = 2
17+
}
18+
19+
-- set this DEBUG to debug.LEVEL_1 to enable printing debug info
20+
-- set it to debug.LEVEL_2 to enable really verbose printing
21+
local DEBUG = debug.LEVEL_1
22+
23+
24+
local dprint = function() end
25+
local dprint2 = function() end
26+
local function reset_debug()
27+
if DEBUG > debug.DISABLED then
28+
dprint = function(...)
29+
print(table.concat({"Lua:", ...}," "))
30+
end
31+
32+
if DEBUG > debug.LEVEL_1 then
33+
dprint2 = dprint
34+
end
35+
end
36+
end
37+
-- call it now
38+
reset_debug()
39+
40+
--------------------------------------------------------------------------------
41+
-- check for compatability with this version of Wireshark
42+
--------------------------------------------------------------------------------
43+
44+
-- Set the name of Wireshark or Tshark application, for use in error
45+
-- messages
46+
local wireshark_name = "Wireshark"
47+
if not GUI_ENABLED then
48+
wireshark_name = "Tshark"
49+
end
50+
51+
-- verify Wireshark is new enough
52+
local major, minor, micro = get_version():match("(%d+)%.(%d+)%.(%d+)")
53+
if major and tonumber(major) <= 1 and ((tonumber(minor) <= 10) or (tonumber(minor) == 11 and tonumber(micro) < 3)) then
54+
error( "Sorry, but your " .. wireshark_name .. " version (" .. get_version() .. ") is too old for this script!\n" ..
55+
"This script needs " .. wireshark_name .. "version 1.11.3 or higher.\n" )
56+
end
57+
58+
-- verify we have the FileHandler class in wireshark
59+
assert(FileHandler.new, wireshark_name .. " does not have the FileHandler class!")
60+
61+
--------------------------------------------------------------------------------
62+
-- definitions
63+
--------------------------------------------------------------------------------
64+
65+
-- declare name of functions we'll define later
66+
local read_common
67+
68+
-- handy consts
69+
MAVLINK1_MAGIC_BYTE = 0xfe
70+
MAVLINK1_FRAME_OVERHEAD = 8
71+
MAVLINK2_MAGIC_BYTE = 0xfd
72+
MAVLINK2_FRAME_OVERHEAD = 12
73+
MAVLINK2_SIGNATURE_LEN = 13
74+
75+
--------------------------------------------------------------------------------
76+
-- file reader handling functions for Wireshark to use
77+
--------------------------------------------------------------------------------
78+
79+
----------------------------------------
80+
-- The read_open() is called by Wireshark once per file, to see if the file is this reader's type.
81+
-- Wireshark passes in (1) a File object and (2) CaptureInfo object to this function
82+
-- It expects in return either nil or false to mean it's not our file type, or true if it is
83+
-- We do a quick check of the file to make sure that a Mavlink magic byte exists at location 9 -
84+
-- i.e. directly after the 8-byte timestamp.
85+
local function read_open(file, capture)
86+
dprint2("read_open() called")
87+
88+
-- read 9 bytes from the start of the file
89+
local line = file:read(9)
90+
91+
-- if we couldn't read these bytes, return false
92+
if not line then return false end
93+
94+
-- unpack into 8 byte timestamp and 1 byte Mavlink magic byte
95+
local fields = { Struct.unpack(">E I1", line) }
96+
97+
-- check we got what we expected (note that #fields is the number of returned fields PLUS ONE)
98+
if #fields ~= 3 then
99+
dprint2("Incorrect number of fields fields returned: " .. #fields)
100+
return false
101+
elseif fields[2] ~= MAVLINK2_MAGIC_BYTE and fields[2] ~= MAVLINK1_MAGIC_BYTE then
102+
dprint2("No Mavlink magic byte " .. fields[1])
103+
return false
104+
end
105+
106+
dprint2("read_open: success, file is for us")
107+
108+
-- if the file is for us, we MUST set the file position cursor to
109+
-- where we want the first call to read() function to get it the next time
110+
file:seek("set",0)
111+
112+
-- these we can also set per record later during read operations
113+
capture.time_precision = wtap_filetypes.TSPREC_USEC
114+
capture.encap = wtap_encaps.USER0 -- we use USER0 for Mavlink
115+
116+
return true
117+
end
118+
119+
----------------------------------------
120+
-- Wireshark/tshark calls read() for each frame/record in the file
121+
-- It passes in (1) a File, (2) CaptureInfo, and (3) FrameInfo object to this function
122+
-- It expects in return the file offset position the record starts at,
123+
-- or nil/false if there's an error or end-of-file is reached.
124+
-- The offset position is used later: wireshark remembers it and gives
125+
-- it to seek_read() at various random times
126+
local function read(file, capture, frame)
127+
dprint2("read() called")
128+
129+
-- remember where we are in the file
130+
local position = file:seek()
131+
132+
-- call our common reader function
133+
if not read_common("read", file, capture, frame) then
134+
-- this isnt' actually an error, because it might just mean we reached end-of-file
135+
-- so let's test for that (read(0) is a special case in Lua, see Lua docs)
136+
if file:read(0) ~= nil then
137+
dprint("read: failed to call read_common")
138+
else
139+
dprint2("read: reached end of file")
140+
end
141+
return false
142+
end
143+
144+
dprint2("read: success")
145+
146+
-- return the position we got to (or nil if we hit EOF/error)
147+
return position
148+
end
149+
150+
----------------------------------------
151+
-- Wireshark/tshark calls seek_read() for each frame/record in the file, at random times
152+
-- It passes in (1) a File, (2) CaptureInfo, (3) FrameInfo object, and the offset position number
153+
-- It expects in return true for successful parsing, or nil/false if there's an error.
154+
local function seek_read(file, capture, frame, offset)
155+
dprint2("seek_read() called")
156+
157+
-- first move to the right position in the file
158+
file:seek("set",offset)
159+
160+
-- call our common reader function
161+
if not read_common("seek_read", file, capture, frame) then
162+
dprint("seek_read: failed to call read_common")
163+
return false
164+
end
165+
166+
return true
167+
end
168+
169+
----------------------------------------
170+
-- Wireshark/tshark calls read_close() when it's closing the file completely
171+
-- It passes in (1) a File and (2) CaptureInfo object to this function
172+
-- this is a good opportunity to clean up any state you may have created during
173+
-- file reading. (in our case there's no real state)
174+
local function read_close(file, capture)
175+
dprint2("read_close() called")
176+
return true
177+
end
178+
179+
----------------------------------------
180+
-- An often unused function, Wireshark calls this when the sequential walk-through is over
181+
-- (i.e., no more calls to read(), only to seek_read()).
182+
-- It passes in (1) a File and (2) CaptureInfo object to this function
183+
-- This gives you a chance to clean up any state you used during read() calls, but remember
184+
-- that there will be calls to seek_read() after this (in Wireshark, though not Tshark)
185+
local function seq_read_close(file, capture)
186+
dprint2("First pass of read() calls are over, but there may be seek_read() calls after this")
187+
return true
188+
end
189+
190+
----------------------------------------
191+
-- internal functions declared previously
192+
----------------------------------------
193+
194+
----------------------------------------
195+
-- this is used by both read() and seek_read()
196+
-- the calling function to this should have already set the file position correctly
197+
read_common = function(funcname, file, capture, frame)
198+
dprint2(funcname,": read_common() called")
199+
200+
-- remember where we are in the file, as we'll need to come back here
201+
-- once we figure out the message length
202+
local position = file:seek()
203+
204+
-- read 11 bytes from the start of the record
205+
local line = file:read(11)
206+
207+
-- it's ok for us to not be able to read it, if it's end of file
208+
if not line then return false end
209+
210+
-- this is: time_usec (8 bytes), Mavlink magic byte, message length, incompat_flags
211+
local fields = { Struct.unpack(">E I1 I1 I1", line) }
212+
if #fields ~= 5 then -- #fields is number of returned fields PLUS ONE
213+
dprint(funcname, ": read_common: incorrect number of fields returned: " .. #fields)
214+
return false
215+
end
216+
217+
-- now move back to where we were, plus the 8 bytes of timestamp
218+
file:seek('set', position + 8)
219+
220+
-- set the timestamp of this frame
221+
local ts = fields[1]:tonumber()
222+
local sec = math.floor(ts / 1000000.0)
223+
local usec = ((ts % 1000000) * 1000)
224+
frame.time = NSTime(sec, usec)
225+
226+
-- set the captured length and original length of this frame
227+
-- (we add the Mavlink header length to the message length)
228+
if fields[2] == MAVLINK2_MAGIC_BYTE then
229+
if fields[4] & 0x01 ~= 0 then
230+
frame.captured_length = fields[3] + MAVLINK2_FRAME_OVERHEAD + MAVLINK2_SIGNATURE_LEN
231+
else
232+
frame.captured_length = fields[3] + MAVLINK2_FRAME_OVERHEAD
233+
end
234+
elseif fields[2] == MAVLINK1_MAGIC_BYTE then
235+
frame.captured_length = fields[3] + MAVLINK1_FRAME_OVERHEAD
236+
else
237+
dprint("Unrecognised Mavlink magic byte " .. fields[2])
238+
return false
239+
end
240+
frame.original_length = frame.captured_length
241+
242+
-- set the flags to say we have a timestamp
243+
frame.flags = wtap_presence_flags.TS
244+
245+
-- now we need to get the packet bytes from the file record into the frame...
246+
-- we *could* read them into a string using file:read(numbytes), and then
247+
-- set them to frame.data so that wireshark gets it...
248+
-- but that would mean the packet's string would be copied into Lua
249+
-- and then sent right back into wireshark, which is gonna slow things
250+
-- down; instead FrameInfo has a read_data() method, which makes
251+
-- wireshark read directly from the file into the frame buffer, so we use that
252+
if not frame:read_data(file, frame.captured_length) then
253+
dprint(funcname, ": read_common: failed to read data from file into buffer")
254+
return false
255+
end
256+
257+
return true
258+
end
259+
260+
--------------------------------------------------------------------------------
261+
-- register the FileHandler with Wireshark
262+
--------------------------------------------------------------------------------
263+
264+
----------------------------------------
265+
-- ok, so let's create a FileHandler object
266+
--
267+
-- note the last argument defines our file handler type (r=reader), and its magic/heuristic
268+
-- capability - this is used to determine the ordering of this file reader compared with
269+
-- the built-in file readers in wireshark. When a user opens a file, wireshark automatically
270+
-- tries to find a matching file reader for the file. The file extensions are used as hints,
271+
-- but really the ordering is more important. So wireshark first tries all the "magic" readers,
272+
-- meaning ones that can figure out if a file is their format based on a magic byte sequence
273+
-- at the beginning of the file, and then wireshark runs through the "heuristic" file readers,
274+
-- meaning ones that have to guess if the file is their format or not. The ordering of these
275+
-- is very important, since a weak heuristic will incorrectly think a file is its format and
276+
-- prevent a lower-ordered file reader from getting to check it. So if your file reader uses
277+
-- a magic value, you should use the "m" flag, and if it uses a heuristic then no flag means
278+
-- a weak heuristic, whereas a "s" means a strong one.
279+
--
280+
-- We consider our file format to have weak heuristic, as we rely only on byte 9 being a
281+
-- Mavlink magic byte.
282+
local fh = FileHandler.new("Mavlink Telemetry log file reader", "tlog", "A Lua-based file reader for Ardupilot DF log file","r")
283+
284+
-- set above functions to the FileHandler
285+
fh.read_open = read_open
286+
fh.read = read
287+
fh.seek_read = seek_read
288+
fh.read_close = read_close
289+
fh.seq_read_close = seq_read_close
290+
fh.extensions = "tlog" -- this is just a hint
291+
292+
-- and finally, register the FileHandler!
293+
register_filehandler(fh)
294+
295+
dprint2("Mavlink TLOG FileHandler registered")

0 commit comments

Comments
 (0)