Skip to content

Commit 99b5d5b

Browse files
ohyaiamherepeterbarker
authored andcommitted
Tools: add test for no short FS in auto mode
1 parent 6b0fa0a commit 99b5d5b

File tree

1 file changed

+23
-0
lines changed

1 file changed

+23
-0
lines changed

Tools/autotest/arduplane.py

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1351,6 +1351,28 @@ def ThrottleFailsafeFence(self):
13511351
raise NotAchievedException("Fence not enabled after RC fail")
13521352
self.do_fence_disable() # Ensure the fence is disabled after test
13531353

1354+
def NoShortFailsafe(self):
1355+
'''No short failsafe in auto mode'''
1356+
self.set_parameters({
1357+
"FS_GCS_ENABL": 1, # GCS failsafe : heartbeat
1358+
"FS_SHORT_ACTN": 0, # Short failsafe action: ignore if in auto|guided|loiter, otherwise circle
1359+
"FS_LONG_ACTN": 0, # Long failsafe action: continue
1360+
"RTL_AUTOLAND": 1,
1361+
"MAV_GCS_SYSID": self.mav.source_system,
1362+
})
1363+
self.start_flying_simple_relhome_mission([
1364+
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
1365+
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 0, 0),
1366+
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 800, 0),
1367+
])
1368+
self.wait_current_waypoint(2)
1369+
self.progress("Disconnecting GCS")
1370+
self.set_heartbeat_rate(0)
1371+
self.delay_sim_time(10)
1372+
self.wait_mode("AUTO", timeout=10)
1373+
self.set_heartbeat_rate(self.speedup)
1374+
self.fly_home_land_and_disarm()
1375+
13541376
def GCSFailsafe(self):
13551377
'''Ensure Long-Failsafe works on GCS loss'''
13561378
self.start_subtest("Test Failsafe: RTL")
@@ -7985,6 +8007,7 @@ def tests1a(self):
79858007
self.ThrottleFailsafe,
79868008
self.NeedEKFToArm,
79878009
self.ThrottleFailsafeFence,
8010+
self.NoShortFailsafe,
79888011
self.SoaringClimbRate,
79898012
self.TestFlaps,
79908013
self.DO_CHANGE_SPEED,

0 commit comments

Comments
 (0)