mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
autotest: flake8 fixes
This commit is contained in:
parent
c7aff4eb11
commit
dc8e1bd4a4
@ -23,6 +23,7 @@ FENCE = 'ArduPlane-Missions/Dalby-OBC2016-fence.txt'
|
|||||||
WIND = "0,180,0.2" # speed,direction,variance
|
WIND = "0,180,0.2" # speed,direction,variance
|
||||||
SITL_START_LOCATION = mavutil.location(-27.274439, 151.290064, 343, 8.7)
|
SITL_START_LOCATION = mavutil.location(-27.274439, 151.290064, 343, 8.7)
|
||||||
|
|
||||||
|
|
||||||
class AutoTestQuadPlane(AutoTest):
|
class AutoTestQuadPlane(AutoTest):
|
||||||
|
|
||||||
@staticmethod
|
@staticmethod
|
||||||
@ -247,7 +248,7 @@ class AutoTestQuadPlane(AutoTest):
|
|||||||
tstart = self.get_sim_time()
|
tstart = self.get_sim_time()
|
||||||
self.progress("Hovering for %u seconds" % hover_time)
|
self.progress("Hovering for %u seconds" % hover_time)
|
||||||
while self.get_sim_time_cached() < tstart + hover_time:
|
while self.get_sim_time_cached() < tstart + hover_time:
|
||||||
attitude = self.mav.recv_match(type='ATTITUDE', blocking=True)
|
self.mav.recv_match(type='ATTITUDE', blocking=True)
|
||||||
vfr_hud = self.mav.recv_match(type='VFR_HUD', blocking=True)
|
vfr_hud = self.mav.recv_match(type='VFR_HUD', blocking=True)
|
||||||
tend = self.get_sim_time()
|
tend = self.get_sim_time()
|
||||||
|
|
||||||
@ -348,7 +349,7 @@ class AutoTestQuadPlane(AutoTest):
|
|||||||
self.progress("Hovering for %u seconds" % hover_time)
|
self.progress("Hovering for %u seconds" % hover_time)
|
||||||
tstart = self.get_sim_time()
|
tstart = self.get_sim_time()
|
||||||
while self.get_sim_time_cached() < tstart + hover_time:
|
while self.get_sim_time_cached() < tstart + hover_time:
|
||||||
attitude = self.mav.recv_match(type='ATTITUDE', blocking=True)
|
self.mav.recv_match(type='ATTITUDE', blocking=True)
|
||||||
tend = self.get_sim_time()
|
tend = self.get_sim_time()
|
||||||
|
|
||||||
self.do_RTL()
|
self.do_RTL()
|
||||||
|
Loading…
Reference in New Issue
Block a user