mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tools: plane: test gcs failsafe: RTL
This commit is contained in:
parent
a0634d8b5b
commit
ea206670c4
13
Tools/autotest/ArduPlane_Tests/GCSFailsafe/flaps.txt
Normal file
13
Tools/autotest/ArduPlane_Tests/GCSFailsafe/flaps.txt
Normal file
@ -0,0 +1,13 @@
|
|||||||
|
QGC WPL 110
|
||||||
|
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 584.390015 1
|
||||||
|
1 0 3 22 15.000000 0.000000 0.000000 0.000000 -35.361279 149.164230 30.000000 1
|
||||||
|
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361229 149.163025 80.000000 1
|
||||||
|
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364563 149.163773 80.000000 1
|
||||||
|
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364384 149.164795 80.000000 1
|
||||||
|
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361027 149.164093 80.000000 1
|
||||||
|
6 0 0 177 2.000000 3.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||||
|
7 0 3 189 0.000000 0.000000 0.000000 0.000000 -35.362915 149.162613 60.000000 1
|
||||||
|
8 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363136 149.162750 60.000000 1
|
||||||
|
9 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365467 149.164215 55.000000 1
|
||||||
|
10 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365009 149.165482 39.889999 1
|
||||||
|
11 0 3 21 0.000000 0.000000 0.000000 1.000000 -35.363041 149.165222 0.000000 1
|
@ -1164,6 +1164,24 @@ class AutoTestPlane(AutoTest):
|
|||||||
raise NotAchievedException("Fence not enabled after RC fail")
|
raise NotAchievedException("Fence not enabled after RC fail")
|
||||||
self.do_fence_disable() # Ensure the fence is disabled after test
|
self.do_fence_disable() # Ensure the fence is disabled after test
|
||||||
|
|
||||||
|
def GCSFailsafe(self):
|
||||||
|
'''Ensure Long-Failsafe works on GCS loss'''
|
||||||
|
self.start_subtest("Test Failsafe: RTL")
|
||||||
|
self.load_sample_mission()
|
||||||
|
self.set_parameter("RTL_AUTOLAND", 1)
|
||||||
|
self.change_mode("AUTO")
|
||||||
|
self.takeoff()
|
||||||
|
self.set_parameter("FS_GCS_ENABL", 1)
|
||||||
|
self.set_parameter("FS_LONG_ACTN", 1)
|
||||||
|
self.progress("Disconnecting GCS")
|
||||||
|
self.set_heartbeat_rate(0)
|
||||||
|
self.delay_sim_time(5)
|
||||||
|
self.wait_mode("RTL")
|
||||||
|
self.set_heartbeat_rate(self.speedup)
|
||||||
|
self.fly_home_land_and_disarm()
|
||||||
|
self.end_subtest("Completed RTL Failsafe test")
|
||||||
|
|
||||||
|
|
||||||
def TestGripperMission(self):
|
def TestGripperMission(self):
|
||||||
'''Test Gripper mission items'''
|
'''Test Gripper mission items'''
|
||||||
self.context_push()
|
self.context_push()
|
||||||
@ -4470,6 +4488,7 @@ class AutoTestPlane(AutoTest):
|
|||||||
self.AltResetBadGPS,
|
self.AltResetBadGPS,
|
||||||
self.AirspeedCal,
|
self.AirspeedCal,
|
||||||
self.MissionJumpTags,
|
self.MissionJumpTags,
|
||||||
|
self.GCSFailsafe,
|
||||||
])
|
])
|
||||||
return ret
|
return ret
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user