autotest: replace wait_seconds with delay_sim_time

These did exactly the same thing
This commit is contained in:
Peter Barker 2019-11-08 17:22:30 +11:00 committed by Peter Barker
parent 2dd47e54e7
commit ece59f8233
3 changed files with 52 additions and 61 deletions

View File

@ -181,7 +181,7 @@ class AutoTestCopter(AutoTest):
self.progress("Fly eastbound away from home")
self.set_rc(2, 1800)
self.wait_seconds(10)
self.delay_sim_time(10)
self.set_rc(2, 1500)
self.hover()
self.progress("Cotper staging 50 meters east of home at 50 meters altitude In mode Alt Hold")
@ -476,10 +476,10 @@ class AutoTestCopter(AutoTest):
self.set_parameter('FS_OPTIONS', 0)
self.takeoffAndMoveAway()
self.set_parameter("SIM_RC_FAIL", 1)
self.wait_seconds(5)
self.delay_sim_time(5)
self.wait_mode("ALT_HOLD")
self.set_parameter("SIM_RC_FAIL", 0)
self.wait_seconds(5)
self.delay_sim_time(5)
self.wait_mode("ALT_HOLD")
self.end_subtest("Completed Radio failsafe disabled test")
@ -488,9 +488,9 @@ class AutoTestCopter(AutoTest):
self.set_parameter('FS_THR_ENABLE', 1)
self.set_parameter("SIM_RC_FAIL", 1)
self.wait_mode("RTL")
self.wait_seconds(5)
self.delay_sim_time(5)
self.set_parameter("SIM_RC_FAIL", 0)
self.wait_seconds(5)
self.delay_sim_time(5)
self.set_rc(5, 1050)
self.wait_mode("CIRCLE")
self.set_rc(5, 1950)
@ -540,7 +540,7 @@ class AutoTestCopter(AutoTest):
self.set_parameter('FS_THR_ENABLE', 1)
self.takeoffAndMoveAway()
self.set_parameter('SIM_GPS_DISABLE', 1)
self.wait_seconds(5)
self.delay_sim_time(5)
self.set_parameter("SIM_RC_FAIL", 1)
self.wait_mode("LAND")
self.mav.motors_disarmed_wait()
@ -554,7 +554,7 @@ class AutoTestCopter(AutoTest):
self.set_parameter('FS_THR_ENABLE', 4)
self.takeoffAndMoveAway()
self.set_parameter('SIM_GPS_DISABLE', 1)
self.wait_seconds(5)
self.delay_sim_time(5)
self.set_parameter("SIM_RC_FAIL", 1)
self.wait_mode("LAND")
self.mav.motors_disarmed_wait()
@ -568,7 +568,7 @@ class AutoTestCopter(AutoTest):
self.set_parameter('FS_THR_ENABLE', 5)
self.takeoffAndMoveAway()
self.set_parameter('SIM_GPS_DISABLE', 1)
self.wait_seconds(5)
self.delay_sim_time(5)
self.set_parameter("SIM_RC_FAIL", 1)
self.wait_mode("LAND")
self.mav.motors_disarmed_wait()
@ -585,7 +585,7 @@ class AutoTestCopter(AutoTest):
self.mavproxy.expect("SmartRTL deactivated: bad position")
self.set_parameter('SIM_GPS_DISABLE', 0)
self.wait_ekf_happy()
self.wait_seconds(5)
self.delay_sim_time(5)
self.set_parameter("SIM_RC_FAIL", 1)
self.wait_mode("RTL")
self.mav.motors_disarmed_wait()
@ -600,7 +600,7 @@ class AutoTestCopter(AutoTest):
self.mavproxy.expect("SmartRTL deactivated: bad position")
self.set_parameter('SIM_GPS_DISABLE', 0)
self.wait_ekf_happy()
self.wait_seconds(5)
self.delay_sim_time(5)
self.set_parameter("SIM_RC_FAIL", 1)
self.wait_mode("LAND")
self.mav.motors_disarmed_wait()
@ -615,10 +615,10 @@ class AutoTestCopter(AutoTest):
self.takeoffAndMoveAway()
self.change_mode("GUIDED")
self.set_parameter("SIM_RC_FAIL", 1)
self.wait_seconds(5)
self.delay_sim_time(5)
self.wait_mode("GUIDED")
self.set_parameter("SIM_RC_FAIL", 0)
self.wait_seconds(5)
self.delay_sim_time(5)
self.change_mode("ALT_HOLD")
self.setGCSfailsafe(0)
# self.change_mode("RTL")
@ -635,10 +635,10 @@ class AutoTestCopter(AutoTest):
self.takeoffAndMoveAway()
self.change_mode("AUTO")
self.set_parameter("SIM_RC_FAIL", 1)
self.wait_seconds(5)
self.delay_sim_time(5)
self.wait_mode("AUTO")
self.set_parameter("SIM_RC_FAIL", 0)
self.wait_seconds(5)
self.delay_sim_time(5)
self.wait_mode("AUTO")
# self.change_mode("RTL")
# self.mav.motors_disarmed_wait()
@ -665,10 +665,10 @@ class AutoTestCopter(AutoTest):
self.setGCSfailsafe(0)
self.takeoffAndMoveAway()
self.setHeartbeat(False)
self.wait_seconds(5)
self.delay_sim_time(5)
self.wait_mode("ALT_HOLD")
self.setHeartbeat(True)
self.wait_seconds(5)
self.delay_sim_time(5)
self.wait_mode("ALT_HOLD")
self.end_subtest("Completed GCS failsafe disabled test")
@ -746,7 +746,7 @@ class AutoTestCopter(AutoTest):
self.progress("Testing continue in pilot controlled modes")
self.setHeartbeat(False)
self.mavproxy.expect("GCS Failsafe - Continuing Pilot Control")
self.wait_seconds(5)
self.delay_sim_time(5)
self.wait_mode("ALT_HOLD")
self.setHeartbeat(True)
self.mavproxy.expect("GCS Failsafe Cleared")
@ -754,10 +754,10 @@ class AutoTestCopter(AutoTest):
self.progress("Testing continue in auto mission")
self.set_parameter('FS_OPTIONS', 2)
self.change_mode("AUTO")
self.wait_seconds(5)
self.delay_sim_time(5)
self.setHeartbeat(False)
self.mavproxy.expect("GCS Failsafe - Continuing Auto Mode")
self.wait_seconds(5)
self.delay_sim_time(5)
self.wait_mode("AUTO")
self.setHeartbeat(True)
self.mavproxy.expect("GCS Failsafe Cleared")
@ -765,10 +765,10 @@ class AutoTestCopter(AutoTest):
self.progress("Testing continue landing in land mode")
self.set_parameter('FS_OPTIONS', 8)
self.change_mode("LAND")
self.wait_seconds(5)
self.delay_sim_time(5)
self.setHeartbeat(False)
self.mavproxy.expect("GCS Failsafe - Continuing Landing")
self.wait_seconds(5)
self.delay_sim_time(5)
self.wait_mode("LAND")
self.mav.motors_disarmed_wait()
self.setHeartbeat(True)
@ -796,11 +796,11 @@ class AutoTestCopter(AutoTest):
self.takeoffAndMoveAway()
self.set_parameter('SIM_BATT_VOLTAGE', 11.4)
self.mavproxy.expect("Battery 1 is low")
self.wait_seconds(5)
self.delay_sim_time(5)
self.wait_mode("ALT_HOLD")
self.set_parameter('SIM_BATT_VOLTAGE', 10.0)
self.mavproxy.expect("Battery 1 is critical")
self.wait_seconds(5)
self.delay_sim_time(5)
self.wait_mode("ALT_HOLD")
self.change_mode("RTL")
self.mav.motors_disarmed_wait()
@ -811,17 +811,17 @@ class AutoTestCopter(AutoTest):
# TWO STAGE BATTERY FAILSAFE: Trigger low battery condition, then critical battery condition. Verify RTL and Land actions complete.
self.start_subtest("Two stage battery failsafe test with RTL and Land")
self.takeoffAndMoveAway()
self.wait_seconds(3)
self.delay_sim_time(3)
self.set_parameter('BATT_FS_LOW_ACT', 2)
self.set_parameter('BATT_FS_CRT_ACT', 1)
self.set_parameter('SIM_BATT_VOLTAGE', 11.4)
self.mavproxy.expect("Battery 1 is low")
self.wait_seconds(5)
self.delay_sim_time(5)
self.wait_mode("RTL")
self.wait_seconds(10)
self.delay_sim_time(10)
self.set_parameter('SIM_BATT_VOLTAGE', 10.0)
self.mavproxy.expect("Battery 1 is critical")
self.wait_seconds(5)
self.delay_sim_time(5)
self.wait_mode("LAND")
self.mav.motors_disarmed_wait()
self.set_parameter('SIM_BATT_VOLTAGE', 12.5)
@ -833,16 +833,16 @@ class AutoTestCopter(AutoTest):
self.takeoffAndMoveAway()
self.set_parameter('BATT_FS_LOW_ACT', 3)
self.set_parameter('BATT_FS_CRT_ACT', 4)
self.wait_seconds(10)
self.delay_sim_time(10)
self.set_parameter('SIM_BATT_VOLTAGE', 11.4)
self.mavproxy.expect("Battery 1 is low")
self.wait_seconds(5)
self.delay_sim_time(5)
self.wait_mode("SMART_RTL")
self.change_mode("LOITER")
self.wait_seconds(10)
self.delay_sim_time(10)
self.set_parameter('SIM_BATT_VOLTAGE', 10.0)
self.mavproxy.expect("Battery 1 is critical")
self.wait_seconds(5)
self.delay_sim_time(5)
self.wait_mode("SMART_RTL")
self.mav.motors_disarmed_wait()
self.set_parameter('SIM_BATT_VOLTAGE', 12.5)
@ -854,10 +854,10 @@ class AutoTestCopter(AutoTest):
self.takeoffAndMoveAway()
self.set_parameter('FS_OPTIONS', 8)
self.change_mode("LAND")
self.wait_seconds(5)
self.delay_sim_time(5)
self.set_parameter('SIM_BATT_VOLTAGE', 11.4)
self.mavproxy.expect("Battery 1 is low")
self.wait_seconds(5)
self.delay_sim_time(5)
self.wait_mode("LAND")
self.mav.motors_disarmed_wait()
self.set_parameter('SIM_BATT_VOLTAGE', 12.5)
@ -871,13 +871,13 @@ class AutoTestCopter(AutoTest):
self.set_parameter('BATT_FS_LOW_ACT', 1)
self.set_parameter('BATT_FS_CRT_ACT', 1)
self.set_parameter('FS_THR_ENABLE', 1)
self.wait_seconds(5)
self.delay_sim_time(5)
self.set_parameter('SIM_BATT_VOLTAGE', 10.0)
self.mavproxy.expect("Battery 1 is critical")
self.wait_mode("LAND")
self.wait_seconds(10)
self.delay_sim_time(10)
self.set_parameter("SIM_RC_FAIL", 1)
self.wait_seconds(10)
self.delay_sim_time(10)
self.wait_mode("LAND")
self.mav.motors_disarmed_wait()
self.set_parameter('SIM_BATT_VOLTAGE', 12.5)
@ -889,7 +889,7 @@ class AutoTestCopter(AutoTest):
self.start_subtest("Battery failsafe terminate")
self.takeoffAndMoveAway()
self.set_parameter('BATT_FS_LOW_ACT', 5)
self.wait_seconds(10)
self.delay_sim_time(10)
self.set_parameter('SIM_BATT_VOLTAGE', 11.4)
self.mavproxy.expect("Battery 1 is low")
self.mav.motors_disarmed_wait()
@ -3396,7 +3396,7 @@ class AutoTestCopter(AutoTest):
self.progress("current heading %u" % m.heading)
self.set_parameter("SERVO%u_FUNCTION" % yaw_servo, 0) # yaw
self.progress("Waiting for check_servo_map to do its job")
self.wait_seconds(5)
self.delay_sim_time(5)
start = self.mav.location()
self.progress("Moving to guided/position controller")
self.fly_guided_move_global_relative_alt(1, 0, 0)
@ -3682,7 +3682,7 @@ class AutoTestCopter(AutoTest):
self.set_rc(3, 1000)
self.wait_ready_to_arm()
self.arm_vehicle()
self.wait_seconds(2)
self.delay_sim_time(2)
# check we are still on the ground...
m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
if abs(m.relative_alt) > 100:
@ -3690,7 +3690,7 @@ class AutoTestCopter(AutoTest):
self.progress("Pushing throttle up")
self.set_rc(3, 1710)
self.wait_seconds(0.5)
self.delay_sim_time(0.5)
self.progress("Bringing back to hover throttle")
self.set_rc(3, 1500)
@ -4315,7 +4315,7 @@ class AutoTestHeli(AutoTestCopter):
self.mavproxy.send('wp set 1\n')
# wait for motor runup
self.wait_seconds(20)
self.delay_sim_time(20)
# switch into AUTO mode and raise throttle
self.mavproxy.send('switch 4\n') # auto mode
@ -4353,14 +4353,14 @@ class AutoTestHeli(AutoTestCopter):
self.set_rc(8, 2000)
self.progress("wait for rotor runup to complete")
self.wait_servo_channel_value(8, 1900, timeout=10)
self.wait_seconds(20)
self.delay_sim_time(20)
# check we are still on the ground...
m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
if abs(m.relative_alt) > 100:
raise NotAchievedException("Took off prematurely")
self.progress("Pushing throttle past half-way")
self.set_rc(3, 1600)
self.wait_seconds(0.5)
self.delay_sim_time(0.5)
self.progress("Bringing back to hover throttle")
self.set_rc(3, 1500)
@ -4403,7 +4403,7 @@ class AutoTestHeli(AutoTestCopter):
self.arm_vehicle()
self.progress("Raising rotor speed")
self.set_rc(8, 2000)
self.wait_seconds(20)
self.delay_sim_time(20)
self.change_mode("AUTO")
self.set_rc(3, 1500)
tstart = self.get_sim_time()

View File

@ -758,10 +758,10 @@ class AutoTestPlane(AutoTest):
# do a short flight in FBWA, watching for flaps
# self.mavproxy.send('switch 4\n')
# self.wait_mode('FBWA')
# self.wait_seconds(10)
# self.delay_sim_time(10)
# self.mavproxy.send('switch 6\n')
# self.wait_mode('MANUAL')
# self.wait_seconds(10)
# self.delay_sim_time(10)
self.progress("Flaps OK")
except Exception as e:

View File

@ -563,15 +563,6 @@ class AutoTest(ABC):
raise NotAchievedException("No cached time available")
return x.time_boot_ms * 1.0e-3
def delay_sim_time(self, delay):
'''delay for delay seconds in simulation time'''
m = self.mav.recv_match(type='SYSTEM_TIME', blocking=True)
start = m.time_boot_ms
while True:
m = self.mav.recv_match(type='SYSTEM_TIME', blocking=True)
if m.time_boot_ms - start > delay * 1000:
return
def sim_location(self):
"""Return current simulator location."""
m = self.mav.recv_match(type='SIMSTATE', blocking=True)
@ -583,19 +574,19 @@ class AutoTest(ABC):
def save_wp(self, ch=7):
"""Trigger RC Aux to save waypoint."""
self.set_rc(ch, 1000)
self.wait_seconds(1)
self.delay_sim_time(1)
self.set_rc(ch, 2000)
self.wait_seconds(1)
self.delay_sim_time(1)
self.set_rc(ch, 1000)
self.wait_seconds(1)
self.delay_sim_time(1)
def clear_wp(self, ch=8):
"""Trigger RC Aux to clear waypoint."""
self.progress("Clearing waypoints")
self.set_rc(ch, 1000)
self.wait_seconds(0.5)
self.delay_sim_time(0.5)
self.set_rc(ch, 2000)
self.wait_seconds(0.5)
self.delay_sim_time(0.5)
self.set_rc(ch, 1000)
self.mavproxy.send('wp list\n')
self.mavproxy.expect('Requesting 0 waypoints')
@ -1714,7 +1705,7 @@ class AutoTest(ABC):
#################################################
# WAIT UTILITIES
#################################################
def wait_seconds(self, seconds_to_wait):
def delay_sim_time(self, seconds_to_wait):
"""Wait some second in SITL time."""
tstart = self.get_sim_time()
tnow = tstart