mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
autotest: tweak plan GCS failsafe test
taking off when we're already aloft also correct the test to make things actually tested; things were setup in such a way they'd pass without testing the things they were supposed to be
This commit is contained in:
parent
34494bb7d1
commit
3f7d245c2c
@ -21,6 +21,8 @@ from common import NotAchievedException
|
|||||||
from common import PreconditionFailedException
|
from common import PreconditionFailedException
|
||||||
from common import WaitModeTimeout
|
from common import WaitModeTimeout
|
||||||
from common import OldpymavlinkException
|
from common import OldpymavlinkException
|
||||||
|
from common import Test
|
||||||
|
|
||||||
from pymavlink.rotmat import Vector3
|
from pymavlink.rotmat import Vector3
|
||||||
from pysim import vehicleinfo
|
from pysim import vehicleinfo
|
||||||
|
|
||||||
@ -1302,29 +1304,28 @@ class AutoTestPlane(AutoTest):
|
|||||||
'''Ensure Long-Failsafe works on GCS loss'''
|
'''Ensure Long-Failsafe works on GCS loss'''
|
||||||
self.start_subtest("Test Failsafe: RTL")
|
self.start_subtest("Test Failsafe: RTL")
|
||||||
self.load_sample_mission()
|
self.load_sample_mission()
|
||||||
self.set_parameter("RTL_AUTOLAND", 1)
|
|
||||||
self.change_mode("AUTO")
|
|
||||||
self.takeoff()
|
|
||||||
self.set_parameters({
|
self.set_parameters({
|
||||||
"FS_GCS_ENABL": 1,
|
"FS_GCS_ENABL": 1,
|
||||||
"FS_LONG_ACTN": 1,
|
"FS_LONG_ACTN": 1,
|
||||||
|
"RTL_AUTOLAND": 1,
|
||||||
|
"SYSID_MYGCS": self.mav.source_system,
|
||||||
})
|
})
|
||||||
|
self.takeoff()
|
||||||
|
self.change_mode('LOITER')
|
||||||
self.progress("Disconnecting GCS")
|
self.progress("Disconnecting GCS")
|
||||||
self.set_heartbeat_rate(0)
|
self.set_heartbeat_rate(0)
|
||||||
self.wait_mode("RTL", timeout=5)
|
self.wait_mode("RTL", timeout=10)
|
||||||
self.set_heartbeat_rate(self.speedup)
|
self.set_heartbeat_rate(self.speedup)
|
||||||
self.end_subtest("Completed RTL Failsafe test")
|
self.end_subtest("Completed RTL Failsafe test")
|
||||||
|
|
||||||
self.start_subtest("Test Failsafe: FBWA Glide")
|
self.start_subtest("Test Failsafe: FBWA Glide")
|
||||||
self.set_parameters({
|
self.set_parameters({
|
||||||
"RTL_AUTOLAND": 1,
|
|
||||||
"FS_LONG_ACTN": 2,
|
"FS_LONG_ACTN": 2,
|
||||||
})
|
})
|
||||||
self.change_mode("AUTO")
|
self.change_mode('AUTO')
|
||||||
self.takeoff()
|
|
||||||
self.progress("Disconnecting GCS")
|
self.progress("Disconnecting GCS")
|
||||||
self.set_heartbeat_rate(0)
|
self.set_heartbeat_rate(0)
|
||||||
self.wait_mode("FBWA", timeout=5)
|
self.wait_mode("FBWA", timeout=10)
|
||||||
self.set_heartbeat_rate(self.speedup)
|
self.set_heartbeat_rate(self.speedup)
|
||||||
self.end_subtest("Completed FBWA Failsafe test")
|
self.end_subtest("Completed FBWA Failsafe test")
|
||||||
|
|
||||||
@ -4705,7 +4706,7 @@ class AutoTestPlane(AutoTest):
|
|||||||
self.AltResetBadGPS,
|
self.AltResetBadGPS,
|
||||||
self.AirspeedCal,
|
self.AirspeedCal,
|
||||||
self.MissionJumpTags,
|
self.MissionJumpTags,
|
||||||
self.GCSFailsafe,
|
Test(self.GCSFailsafe, speedup=8),
|
||||||
self.SDCardWPTest,
|
self.SDCardWPTest,
|
||||||
self.NoArmWithoutMissionItems,
|
self.NoArmWithoutMissionItems,
|
||||||
self.MODE_SWITCH_RESET,
|
self.MODE_SWITCH_RESET,
|
||||||
|
Loading…
Reference in New Issue
Block a user