4 play back a mavlink log as a FlightGear FG NET stream, and as a 5 realtime mavlink stream 7 Useful for visualising flights 9 from __future__
import print_function
10 from future
import standard_library
11 standard_library.install_aliases()
13 from builtins
import object
20 from pymavlink
import fgFDM
22 from argparse
import ArgumentParser
23 parser = ArgumentParser(description=__doc__)
25 parser.add_argument(
"--planner", action=
'store_true', help=
"use planner file format")
26 parser.add_argument(
"--condition", default=
None, help=
"select packets by condition")
27 parser.add_argument(
"--gpsalt", action=
'store_true', default=
False, help=
"Use GPS altitude")
28 parser.add_argument(
"--mav10", action=
'store_true', default=
False, help=
"Use MAVLink protocol 1.0")
29 parser.add_argument(
"--out", help=
"MAVLink output port (IP:port)",
30 action=
'append', default=[
'127.0.0.1:14550'])
31 parser.add_argument(
"--fgout", action=
'append', default=[
'127.0.0.1:5503'],
32 help=
"flightgear FDM NET output (IP:port)")
33 parser.add_argument(
"--baudrate", type=int, default=57600, help=
'baud rate')
34 parser.add_argument(
"log", metavar=
"LOG")
35 args = parser.parse_args()
38 os.environ[
'MAVLINK10'] =
'1' 39 from pymavlink
import mavutil
45 '''return an image from the images/ directory''' 46 app_dir = os.path.dirname(os.path.realpath(__file__))
47 path = os.path.join(app_dir,
'images', filename)
48 return tkinter.PhotoImage(file=path)
58 self.
mlog = mavutil.mavlink_connection(filename, planner_format=args.planner,
62 self.mout.append(mavutil.mavlink_connection(m, input=
False, baud=args.baudrate))
70 self.
msg = self.mlog.recv_match(condition=args.condition)
78 self.topframe.pack(side=tkinter.TOP)
81 self.frame.pack(side=tkinter.LEFT)
84 orient=tkinter.HORIZONTAL, command=self.
slew)
85 self.slider.pack(side=tkinter.LEFT)
88 self.clock.pack(side=tkinter.RIGHT)
91 self.playback.pack(side=tkinter.BOTTOM)
92 self.playback.delete(0,
"end")
93 self.playback.insert(0, 1)
96 self.
button(
'quit',
'gtk-quit.gif', self.frame.quit)
97 self.
button(
'pause',
'media-playback-pause.gif', self.
pause)
98 self.
button(
'rewind',
'media-seek-backward.gif', self.
rewind)
99 self.
button(
'forward',
'media-seek-forward.gif', self.
forward)
102 self.flightmode.pack(side=tkinter.RIGHT)
107 def button(self, name, filename, command):
111 b = tkinter.Button(self.
frame, image=img, command=command)
114 b = tkinter.Button(self.
frame, text=filename, command=command)
115 b.pack(side=tkinter.LEFT)
128 self.mlog.f.seek(pos)
136 self.mlog.f.seek(pos)
141 for m
in sorted(self.mlog.messages.keys()):
142 print(
str(self.mlog.messages[m]))
147 '''find the next valid message''' 149 self.
msg = self.mlog.recv_match(condition=args.condition)
150 if self.
msg is not None and self.msg.get_type() !=
'BAD_DATA':
152 if self.mlog.f.tell() > self.
filesize - 10:
158 '''move to a given position in the file''' 161 self.mlog.f.seek(
int(pos))
166 '''called as each msg is ready''' 177 speed =
float(self.playback.get())
180 timestamp = getattr(msg,
'_timestamp')
182 now = time.strftime(
"%H:%M:%S", time.localtime(timestamp))
183 self.clock.configure(text=now)
192 self.
msg = self.mlog.recv_match(condition=args.condition)
193 if self.
msg is None and self.mlog.f.tell() > self.
filesize - 10:
196 if self.
msg is not None and self.msg.get_type() !=
"BAD_DATA":
201 self.
filepos = self.slider.get()
203 if msg.get_type() !=
"BAD_DATA":
205 m.write(msg.get_msgbuf())
207 if msg.get_type() ==
"GPS_RAW":
208 self.fdm.set(
'latitude', msg.lat, units=
'degrees')
209 self.fdm.set(
'longitude', msg.lon, units=
'degrees')
211 self.fdm.set(
'altitude', msg.alt, units=
'meters')
213 if msg.get_type() ==
"GPS_RAW_INT":
214 self.fdm.set(
'latitude', msg.lat/1.0e7, units=
'degrees')
215 self.fdm.set(
'longitude', msg.lon/1.0e7, units=
'degrees')
217 self.fdm.set(
'altitude', msg.alt/1.0e3, units=
'meters')
219 if msg.get_type() ==
"VFR_HUD":
221 self.fdm.set(
'altitude', msg.alt, units=
'meters')
222 self.fdm.set(
'num_engines', 1)
223 self.fdm.set(
'vcas', msg.airspeed, units=
'mps')
225 if msg.get_type() ==
"ATTITUDE":
226 self.fdm.set(
'phi', msg.roll, units=
'radians')
227 self.fdm.set(
'theta', msg.pitch, units=
'radians')
228 self.fdm.set(
'psi', msg.yaw, units=
'radians')
229 self.fdm.set(
'phidot', msg.rollspeed, units=
'rps')
230 self.fdm.set(
'thetadot', msg.pitchspeed, units=
'rps')
231 self.fdm.set(
'psidot', msg.yawspeed, units=
'rps')
233 if msg.get_type() ==
"RC_CHANNELS_SCALED":
234 self.fdm.set(
"right_aileron", msg.chan1_scaled*0.0001)
235 self.fdm.set(
"left_aileron", -msg.chan1_scaled*0.0001)
236 self.fdm.set(
"rudder", msg.chan4_scaled*0.0001)
237 self.fdm.set(
"elevator", msg.chan2_scaled*0.0001)
238 self.fdm.set(
'rpm', msg.chan3_scaled*0.01)
240 if msg.get_type() ==
'STATUSTEXT':
241 print(
"APM: %s" % msg.text)
243 if msg.get_type() ==
'SYS_STATUS':
244 self.flightmode.configure(text=self.mlog.flightmode)
246 if msg.get_type() ==
"BAD_DATA":
247 if mavutil.all_printable(msg.data):
248 sys.stdout.write(msg.data)
251 if self.fdm.get(
'latitude') != 0:
253 f.write(self.fdm.pack())