mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
autotest: neaten Copter Loiter test
This commit is contained in:
parent
f930ba788b
commit
37886b36e0
@ -435,48 +435,39 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
|
||||
self.context_push()
|
||||
|
||||
ex = None
|
||||
try:
|
||||
self.set_parameters({
|
||||
"PLND_ENABLED": 1,
|
||||
"PLND_TYPE": 4,
|
||||
})
|
||||
|
||||
self.set_parameters({
|
||||
"PLND_ENABLED": 1,
|
||||
"PLND_TYPE": 4,
|
||||
})
|
||||
self.set_analog_rangefinder_parameters()
|
||||
|
||||
self.set_analog_rangefinder_parameters()
|
||||
self.reboot_sitl()
|
||||
|
||||
self.reboot_sitl()
|
||||
num_wp = self.load_mission("copter_loiter_to_alt.txt")
|
||||
|
||||
num_wp = self.load_mission("copter_loiter_to_alt.txt")
|
||||
self.change_mode('LOITER')
|
||||
|
||||
self.change_mode('LOITER')
|
||||
self.install_terrain_handlers_context()
|
||||
self.wait_ready_to_arm()
|
||||
|
||||
self.install_terrain_handlers_context()
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
|
||||
self.arm_vehicle()
|
||||
self.change_mode('AUTO')
|
||||
|
||||
self.change_mode('AUTO')
|
||||
self.set_rc(3, 1550)
|
||||
|
||||
self.set_rc(3, 1550)
|
||||
self.wait_current_waypoint(2)
|
||||
|
||||
self.wait_current_waypoint(2)
|
||||
self.set_rc(3, 1500)
|
||||
|
||||
self.set_rc(3, 1500)
|
||||
self.wait_waypoint(0, num_wp-1, timeout=500)
|
||||
|
||||
self.wait_waypoint(0, num_wp-1, timeout=500)
|
||||
|
||||
self.wait_disarmed()
|
||||
except Exception as e:
|
||||
self.print_exception_caught(e)
|
||||
ex = e
|
||||
self.wait_disarmed()
|
||||
|
||||
self.context_pop()
|
||||
self.reboot_sitl()
|
||||
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
||||
# Tests all actions and logic behind the radio failsafe
|
||||
def ThrottleFailsafe(self, side=60, timeout=360):
|
||||
'''Test Throttle Failsafe'''
|
||||
|
Loading…
Reference in New Issue
Block a user