mirror of https://github.com/ArduPilot/ardupilot
autotest: adjust for terrain arming requirements
Lots of tests really did need terrain stuff but weren't able to get it
This commit is contained in:
parent
c2d91a3bdb
commit
5ee8f99e7b
|
@ -487,7 +487,9 @@ class AutoTestCopter(AutoTest):
|
||||||
|
|
||||||
self.change_mode('LOITER')
|
self.change_mode('LOITER')
|
||||||
|
|
||||||
self.wait_ready_to_arm()
|
mavproxy = self.start_mavproxy()
|
||||||
|
self.wait_ready_to_arm(timeout=120*60) # terrain takes time
|
||||||
|
self.stop_mavproxy(mavproxy)
|
||||||
|
|
||||||
self.arm_vehicle()
|
self.arm_vehicle()
|
||||||
|
|
||||||
|
|
|
@ -282,7 +282,7 @@ class AutoTestQuadPlane(AutoTest):
|
||||||
self.disarm_vehicle()
|
self.disarm_vehicle()
|
||||||
self.wait_ready_to_arm()
|
self.wait_ready_to_arm()
|
||||||
|
|
||||||
def fly_mission(self, filename, fence=None, height_accuracy=-1):
|
def fly_mission(self, filename, fence=None, height_accuracy=-1, include_terrain_timeout=False):
|
||||||
"""Fly a mission from a file."""
|
"""Fly a mission from a file."""
|
||||||
self.progress("Flying mission %s" % filename)
|
self.progress("Flying mission %s" % filename)
|
||||||
self.load_mission(filename)
|
self.load_mission(filename)
|
||||||
|
@ -290,7 +290,12 @@ class AutoTestQuadPlane(AutoTest):
|
||||||
self.load_fence(fence)
|
self.load_fence(fence)
|
||||||
if self.mavproxy is not None:
|
if self.mavproxy is not None:
|
||||||
self.mavproxy.send('wp list\n')
|
self.mavproxy.send('wp list\n')
|
||||||
self.wait_ready_to_arm()
|
# terrain can take a *long* time to load:
|
||||||
|
timeout = 120
|
||||||
|
if include_terrain_timeout:
|
||||||
|
timeout *= 1000 # yes, *that* long
|
||||||
|
mavproxy = self.start_mavproxy()
|
||||||
|
self.wait_ready_to_arm(timeout=timeout)
|
||||||
self.arm_vehicle()
|
self.arm_vehicle()
|
||||||
self.change_mode('AUTO')
|
self.change_mode('AUTO')
|
||||||
self.wait_waypoint(1, 19, max_dist=60, timeout=1200)
|
self.wait_waypoint(1, 19, max_dist=60, timeout=1200)
|
||||||
|
@ -298,12 +303,13 @@ class AutoTestQuadPlane(AutoTest):
|
||||||
self.wait_disarmed(timeout=120) # give quadplane a long time to land
|
self.wait_disarmed(timeout=120) # give quadplane a long time to land
|
||||||
# wait for blood sample here
|
# wait for blood sample here
|
||||||
self.set_current_waypoint(20)
|
self.set_current_waypoint(20)
|
||||||
self.wait_ready_to_arm()
|
self.wait_ready_to_arm(timeout=timeout)
|
||||||
self.arm_vehicle()
|
self.arm_vehicle()
|
||||||
self.wait_waypoint(20, 34, max_dist=60, timeout=1200)
|
self.wait_waypoint(20, 34, max_dist=60, timeout=1200)
|
||||||
|
|
||||||
self.wait_disarmed(timeout=120) # give quadplane a long time to land
|
self.wait_disarmed(timeout=120) # give quadplane a long time to land
|
||||||
self.progress("Mission OK")
|
self.progress("Mission OK")
|
||||||
|
self.stop_mavproxy(mavproxy)
|
||||||
|
|
||||||
def enum_state_name(self, enum_name, state, pretrim=None):
|
def enum_state_name(self, enum_name, state, pretrim=None):
|
||||||
e = mavutil.mavlink.enums[enum_name]
|
e = mavutil.mavlink.enums[enum_name]
|
||||||
|
@ -887,7 +893,12 @@ class AutoTestQuadPlane(AutoTest):
|
||||||
self.EXTENDED_SYS_STATE),
|
self.EXTENDED_SYS_STATE),
|
||||||
|
|
||||||
("Mission", "Dalby Mission",
|
("Mission", "Dalby Mission",
|
||||||
lambda: self.fly_mission("Dalby-OBC2016.txt", "Dalby-OBC2016-fence.txt")),
|
lambda: self.fly_mission(
|
||||||
|
"Dalby-OBC2016.txt",
|
||||||
|
"Dalby-OBC2016-fence.txt",
|
||||||
|
include_terrain_timeout=True
|
||||||
|
)
|
||||||
|
),
|
||||||
|
|
||||||
("Weathervane",
|
("Weathervane",
|
||||||
"Test Weathervane Functionality",
|
"Test Weathervane Functionality",
|
||||||
|
|
Loading…
Reference in New Issue