Browse Source

autotest: start and stop mavproxy for setpoint tests

These work in terrain frame - but autotest won't satisfy terrain
requests yet
zr-v5.1
Peter Barker 4 years ago committed by Peter Barker
parent
commit
19e5351631
  1. 16
      Tools/autotest/common.py

16
Tools/autotest/common.py

@ -7800,6 +7800,11 @@ Also, ignores heartbeats not from our target system''' @@ -7800,6 +7800,11 @@ Also, ignores heartbeats not from our target system'''
self.wait_ready_to_arm()
self.arm_vehicle()
# we must start mavproxy here as otherwise we can't get the
# terrain database tiles - this leads to random failures in
# CI!
mavproxy = self.start_mavproxy()
if self.is_copter() or self.is_heli():
self.user_takeoff(alt_min=50)
@ -8002,6 +8007,9 @@ Also, ignores heartbeats not from our target system''' @@ -8002,6 +8007,9 @@ Also, ignores heartbeats not from our target system'''
self.wait_yaw_speed(target_rate, timeout=timeout,
called_function=lambda plop, empty: send_yaw_rate(
target_rate, None), minimum_duration=5)
self.stop_mavproxy(mavproxy)
self.start_test("Getting back to home and disarm")
self.do_RTL(distance_min=0, distance_max=wp_accuracy)
self.disarm_vehicle()
@ -8023,6 +8031,11 @@ Also, ignores heartbeats not from our target system''' @@ -8023,6 +8031,11 @@ Also, ignores heartbeats not from our target system'''
self.wait_ready_to_arm()
self.arm_vehicle()
# we must start mavproxy here as otherwise we can't get the
# terrain database tiles - this leads to random failures in
# CI!
mavproxy = self.start_mavproxy()
if self.is_copter() or self.is_heli():
self.user_takeoff(alt_min=50)
@ -8366,6 +8379,9 @@ Also, ignores heartbeats not from our target system''' @@ -8366,6 +8379,9 @@ Also, ignores heartbeats not from our target system'''
frame),
minimum_duration=2
)
self.stop_mavproxy(mavproxy)
self.start_test("Getting back to home and disarm")
self.do_RTL(distance_min=0, distance_max=wp_accuracy)
self.disarm_vehicle()

Loading…
Cancel
Save