mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
autotest: tidy advanced failsafe test
This commit is contained in:
parent
7456d8149f
commit
4249fc04b7
@ -10707,13 +10707,15 @@ switch value'''
|
||||
|
||||
def AdvancedFailsafe(self):
|
||||
'''Test Advanced Failsafe'''
|
||||
self.context_push()
|
||||
ex = None
|
||||
try:
|
||||
self.drain_mav()
|
||||
self.assert_no_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION)
|
||||
self.set_parameter("AFS_ENABLE", 1)
|
||||
self.set_parameter("SYSID_MYGCS", self.mav.source_system)
|
||||
if self.is_plane(): # other vehicles can always terminate
|
||||
self.assert_no_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION)
|
||||
self.set_parameters({
|
||||
"AFS_ENABLE": 1,
|
||||
"SYSID_MYGCS": self.mav.source_system,
|
||||
})
|
||||
self.drain_mav()
|
||||
self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION)
|
||||
self.set_parameter("AFS_TERM_ACTION", 42)
|
||||
@ -10721,19 +10723,29 @@ switch value'''
|
||||
self.context_collect("STATUSTEXT")
|
||||
self.change_mode("AUTO") # must go to auto for AFS to latch on
|
||||
self.wait_statustext("AFS State: AFS_AUTO", check_context=True)
|
||||
self.change_mode("MANUAL")
|
||||
if self.is_plane():
|
||||
self.change_mode("MANUAL")
|
||||
elif self.is_copter():
|
||||
self.change_mode("STABILIZE")
|
||||
|
||||
self.start_subtest("RC Failure")
|
||||
self.set_parameter("AFS_RC_FAIL_TIME", 1)
|
||||
self.set_parameter("SIM_RC_FAIL", 1)
|
||||
self.context_push()
|
||||
self.context_collect("STATUSTEXT")
|
||||
self.set_parameters({
|
||||
"AFS_RC_FAIL_TIME": 1,
|
||||
"SIM_RC_FAIL": 1,
|
||||
})
|
||||
self.wait_statustext("Terminating due to RC failure", check_context=True)
|
||||
self.set_parameter("AFS_RC_FAIL_TIME", 0)
|
||||
self.set_parameter("SIM_RC_FAIL", 0)
|
||||
self.context_pop()
|
||||
self.set_parameter("AFS_TERMINATE", 0)
|
||||
|
||||
if not self.is_plane():
|
||||
# plane requires a polygon fence...
|
||||
self.start_subtest("Altitude Limit breach")
|
||||
self.set_parameter("AFS_AMSL_LIMIT", 100)
|
||||
self.set_parameters({
|
||||
"AFS_AMSL_LIMIT": 100,
|
||||
"AFS_QNH_PRESSURE": 1015.2,
|
||||
})
|
||||
self.do_fence_enable()
|
||||
self.wait_statustext("Terminating due to fence breach", check_context=True)
|
||||
self.set_parameter("AFS_AMSL_LIMIT", 0)
|
||||
@ -10741,13 +10753,19 @@ switch value'''
|
||||
self.do_fence_disable()
|
||||
|
||||
self.start_subtest("GPS Failure")
|
||||
self.set_parameter("AFS_MAX_GPS_LOSS", 1)
|
||||
self.set_parameter("SIM_GPS_DISABLE", 1)
|
||||
self.context_push()
|
||||
self.context_collect("STATUSTEXT")
|
||||
self.set_parameters({
|
||||
"AFS_MAX_GPS_LOSS": 1,
|
||||
"SIM_GPS_DISABLE": 1,
|
||||
})
|
||||
self.wait_statustext("AFS State: GPS_LOSS", check_context=True)
|
||||
self.set_parameter("SIM_GPS_DISABLE", 0)
|
||||
self.set_parameter("AFS_MAX_GPS_LOSS", 0)
|
||||
self.context_pop()
|
||||
self.set_parameter("AFS_TERMINATE", 0)
|
||||
|
||||
self.start_subtest("GCS Request")
|
||||
self.context_push()
|
||||
self.context_collect("STATUSTEXT")
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_FLIGHTTERMINATION,
|
||||
1, # terminate
|
||||
@ -10759,6 +10777,8 @@ switch value'''
|
||||
0,
|
||||
)
|
||||
self.wait_statustext("Terminating due to GCS request", check_context=True)
|
||||
self.context_pop()
|
||||
self.set_parameter("AFS_TERMINATE", 0)
|
||||
|
||||
except Exception as e:
|
||||
ex = e
|
||||
@ -10767,7 +10787,6 @@ switch value'''
|
||||
except ValueError:
|
||||
# may not actually be enabled....
|
||||
pass
|
||||
self.context_pop()
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user