Tools: autotest: include mavproxy output in all vehicle test log files
This commit is contained in:
parent
236ab29e51
commit
19f51813f2
@ -85,7 +85,9 @@ class AutoTestTracker(AutoTest):
|
||||
breakpoints=self.breakpoints,
|
||||
)
|
||||
self.mavproxy = util.start_MAVProxy_SITL(
|
||||
'AntennaTracker', options=self.mavproxy_options())
|
||||
'AntennaTracker',
|
||||
logfile=self.mavproxy_logfile,
|
||||
options=self.mavproxy_options())
|
||||
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
|
||||
self.logfile = self.mavproxy.match.group(1)
|
||||
self.progress("LOGFILE %s" % self.logfile)
|
||||
|
@ -90,7 +90,9 @@ class AutoTestCopter(AutoTest):
|
||||
vicon=True,
|
||||
wipe=True)
|
||||
self.mavproxy = util.start_MAVProxy_SITL(
|
||||
'ArduCopter', options=self.mavproxy_options())
|
||||
'ArduCopter',
|
||||
logfile=self.mavproxy_logfile,
|
||||
options=self.mavproxy_options())
|
||||
|
||||
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
|
||||
self.logfile = self.mavproxy.match.group(1)
|
||||
|
@ -72,7 +72,9 @@ class AutoTestPlane(AutoTest):
|
||||
gdbserver=self.gdbserver,
|
||||
breakpoints=self.breakpoints)
|
||||
self.mavproxy = util.start_MAVProxy_SITL(
|
||||
'ArduPlane', options=self.mavproxy_options())
|
||||
'ArduPlane',
|
||||
logfile=self.mavproxy_logfile,
|
||||
options=self.mavproxy_options())
|
||||
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
|
||||
self.logfile = self.mavproxy.match.group(1)
|
||||
self.progress("LOGFILE %s" % self.logfile)
|
||||
|
@ -67,7 +67,9 @@ class AutoTestSub(AutoTest):
|
||||
breakpoints=self.breakpoints,
|
||||
wipe=True)
|
||||
self.mavproxy = util.start_MAVProxy_SITL(
|
||||
'ArduSub', options=self.mavproxy_options())
|
||||
'ArduSub',
|
||||
logfile=self.mavproxy_logfile,
|
||||
options=self.mavproxy_options())
|
||||
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
|
||||
self.logfile = self.mavproxy.match.group(1)
|
||||
self.progress("LOGFILE %s" % self.logfile)
|
||||
|
@ -74,7 +74,9 @@ class AutoTestQuadPlane(AutoTest):
|
||||
breakpoints=self.breakpoints,
|
||||
)
|
||||
self.mavproxy = util.start_MAVProxy_SITL(
|
||||
'QuadPlane', options=self.mavproxy_options())
|
||||
'QuadPlane',
|
||||
logfile=self.mavproxy_logfile,
|
||||
options=self.mavproxy_options())
|
||||
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
|
||||
self.logfile = self.mavproxy.match.group(1)
|
||||
self.progress("LOGFILE %s" % self.logfile)
|
||||
|
Loading…
Reference in New Issue
Block a user