mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tools: move setGCSfailsafe in common
This commit is contained in:
parent
837ebd4491
commit
0b7ef942b4
@ -309,19 +309,6 @@ class AutoTestCopter(AutoTest):
|
||||
)
|
||||
self.hover()
|
||||
|
||||
def setGCSfailsafe(self, paramValue=0):
|
||||
# Slow down the sim rate if GCS Failsafe is in use
|
||||
if paramValue == 0:
|
||||
self.set_parameters({
|
||||
"FS_GCS_ENABLE": paramValue,
|
||||
"SIM_SPEEDUP": 10,
|
||||
})
|
||||
else:
|
||||
self.set_parameters({
|
||||
"SIM_SPEEDUP": 4,
|
||||
"FS_GCS_ENABLE": paramValue,
|
||||
})
|
||||
|
||||
def RecordThenPlayMission(self, side=50, timeout=300):
|
||||
'''Use switches to toggle in mission, then fly it'''
|
||||
self.takeoff(20, mode="ALT_HOLD")
|
||||
|
@ -13302,3 +13302,16 @@ SERIAL5_BAUD 128
|
||||
|
||||
self.progress("vtol and landed states match")
|
||||
return
|
||||
|
||||
def setGCSfailsafe(self, paramValue=0):
|
||||
# Slow down the sim rate if GCS Failsafe is in use
|
||||
if paramValue == 0:
|
||||
self.set_parameters({
|
||||
"FS_GCS_ENABLE": paramValue,
|
||||
"SIM_SPEEDUP": 10,
|
||||
})
|
||||
else:
|
||||
self.set_parameters({
|
||||
"SIM_SPEEDUP": 4,
|
||||
"FS_GCS_ENABLE": paramValue,
|
||||
})
|
||||
|
Loading…
Reference in New Issue
Block a user