mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
autotest: tidy various tests to take account of new framework capabilities
autotest: simplify AutoDock test autotest: tidy AP_Proximity_MAV test autotest: tidy DriveSquare test autotest: tidy BatteryFailsafe test autotest: tidy GPSViconSwitching test autotest: tidy RangeFinder test
This commit is contained in:
parent
478d26d69c
commit
bedc76e0e8
@ -961,21 +961,6 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
# Tests all actions and logic behind the battery failsafe
|
||||
def BatteryFailsafe(self, timeout=300):
|
||||
'''Fly Battery Failsafe'''
|
||||
self.context_push()
|
||||
ex = None
|
||||
try:
|
||||
self.test_battery_failsafe(timeout=timeout)
|
||||
except Exception as e:
|
||||
self.print_exception_caught(e)
|
||||
self.disarm_vehicle(force=True)
|
||||
ex = e
|
||||
self.context_pop()
|
||||
self.reboot_sitl()
|
||||
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
||||
def test_battery_failsafe(self, timeout=300):
|
||||
self.progress("Configure battery failsafe parameters")
|
||||
self.set_parameters({
|
||||
'SIM_SPEEDUP': 4,
|
||||
@ -3730,12 +3715,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
|
||||
def GPSViconSwitching(self):
|
||||
"""Fly GPS and Vicon switching test"""
|
||||
self.customise_SITL_commandline(["--serial5=sim:vicon:"])
|
||||
|
||||
"""Setup parameters including switching to EKF3"""
|
||||
self.context_push()
|
||||
ex = None
|
||||
try:
|
||||
self.set_parameters({
|
||||
"VISO_TYPE": 2, # enable vicon
|
||||
"SERIAL5_PROTOCOL": 2,
|
||||
@ -3750,7 +3730,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
"EK2_ENABLE": 0,
|
||||
"AHRS_EKF_TYPE": 3,
|
||||
})
|
||||
self.reboot_sitl()
|
||||
self.customise_SITL_commandline(["--serial5=sim:vicon:"])
|
||||
|
||||
# switch to use GPS
|
||||
self.set_rc(8, 1000)
|
||||
@ -3798,15 +3778,6 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
self.set_rc(2, 1500)
|
||||
self.do_RTL()
|
||||
|
||||
except Exception as e:
|
||||
self.print_exception_caught(e)
|
||||
ex = e
|
||||
self.context_pop()
|
||||
self.disarm_vehicle(force=True)
|
||||
self.reboot_sitl()
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
||||
def RTLSpeed(self):
|
||||
"""Test RTL Speed parameters"""
|
||||
rtl_speed_ms = 7
|
||||
@ -3885,9 +3856,6 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
|
||||
def RangeFinder(self):
|
||||
'''Test RangeFinder Basic Functionality'''
|
||||
ex = None
|
||||
self.context_push()
|
||||
|
||||
self.progress("Making sure we don't ordinarily get RANGEFINDER")
|
||||
m = self.mav.recv_match(type='RANGEFINDER',
|
||||
blocking=True,
|
||||
@ -3903,7 +3871,6 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
if self.current_onboard_log_contains_message("RFND"):
|
||||
raise NotAchievedException("Found unexpected RFND message")
|
||||
|
||||
try:
|
||||
self.set_analog_rangefinder_parameters()
|
||||
self.set_parameter("RC9_OPTION", 10) # rangefinder
|
||||
self.set_rc(9, 2000)
|
||||
@ -3958,14 +3925,6 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
if not self.current_onboard_log_contains_message("RFND"):
|
||||
raise NotAchievedException("Did not see expected RFND message")
|
||||
|
||||
except Exception as e:
|
||||
self.print_exception_caught(e)
|
||||
ex = e
|
||||
self.context_pop()
|
||||
self.reboot_sitl()
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
||||
def SplineTerrain(self):
|
||||
'''Test Splines and Terrain'''
|
||||
self.set_parameter("TERRAIN_ENABLE", 0)
|
||||
|
@ -86,9 +86,6 @@ class AutoTestRover(vehicle_test_suite.TestSuite):
|
||||
def DriveSquare(self, side=50):
|
||||
"""Learn/Drive Square with Ch7 option"""
|
||||
|
||||
self.context_push()
|
||||
ex = None
|
||||
try:
|
||||
self.progress("TEST SQUARE")
|
||||
self.set_parameters({
|
||||
"RC7_OPTION": 7,
|
||||
@ -157,15 +154,8 @@ class AutoTestRover(vehicle_test_suite.TestSuite):
|
||||
# TODO: actually drive the mission
|
||||
|
||||
self.clear_wp(9)
|
||||
except Exception as e:
|
||||
self.print_exception_caught(e)
|
||||
ex = e
|
||||
|
||||
self.disarm_vehicle()
|
||||
self.context_pop()
|
||||
|
||||
if ex:
|
||||
raise ex
|
||||
|
||||
def drive_left_circuit(self):
|
||||
"""Drive a left circuit, 50m on a side."""
|
||||
@ -5592,9 +5582,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
||||
|
||||
def AP_Proximity_MAV(self):
|
||||
'''Test MAV proximity backend'''
|
||||
self.context_push()
|
||||
ex = None
|
||||
try:
|
||||
|
||||
self.set_parameters({
|
||||
"PRX1_TYPE": 2, # AP_Proximity_MAV
|
||||
"OA_TYPE": 2, # dijkstra
|
||||
@ -5644,14 +5632,6 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
||||
{"orientation": 7, "distance": 1190},
|
||||
])
|
||||
|
||||
except Exception as e:
|
||||
self.print_exception_caught(e)
|
||||
ex = e
|
||||
self.context_pop()
|
||||
self.reboot_sitl()
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
||||
def SendToComponents(self):
|
||||
'''Test ArduPilot send_to_components function'''
|
||||
self.set_parameter("CAM1_TYPE", 5) # Camera with MAVlink trigger
|
||||
@ -6295,8 +6275,6 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
||||
|
||||
def AutoDock(self):
|
||||
'''Test automatic docking of rover for multiple FOVs of simulated beacon'''
|
||||
self.context_push()
|
||||
|
||||
self.set_parameters({
|
||||
"PLND_ENABLED": 1,
|
||||
"PLND_TYPE": 4,
|
||||
@ -6322,8 +6300,6 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
||||
})
|
||||
|
||||
for type in range(0, 3): # CYLINDRICAL FOV, CONICAL FOV, SPHERICAL FOV
|
||||
ex = None
|
||||
try:
|
||||
self.set_parameter("SIM_PLD_TYPE", type)
|
||||
self.reboot_sitl()
|
||||
self.change_mode('GUIDED')
|
||||
@ -6345,17 +6321,6 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
||||
if not self.current_onboard_log_contains_message("PL"):
|
||||
raise NotAchievedException("Did not see expected PL message")
|
||||
|
||||
except Exception as e:
|
||||
self.print_exception_caught(e)
|
||||
ex = e
|
||||
break
|
||||
|
||||
self.context_pop()
|
||||
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
||||
self.reboot_sitl()
|
||||
self.progress("All done")
|
||||
|
||||
def PrivateChannel(self):
|
||||
|
Loading…
Reference in New Issue
Block a user