mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
autotest: add test which force-switches to DCM and watches plane land
This commit is contained in:
parent
ba5e94ad9a
commit
b82b6f1e50
@ -727,7 +727,7 @@ class AutoTestPlane(AutoTest):
|
||||
def fly_home_land_and_disarm(self, timeout=120):
|
||||
filename = "flaps.txt"
|
||||
self.progress("Using %s to fly home" % filename)
|
||||
self.load_mission(filename)
|
||||
self.load_generic_mission(filename)
|
||||
self.change_mode("AUTO")
|
||||
# don't set current waypoint to 8 unless we're distant from it
|
||||
# or we arrive instantly and never see it as our current
|
||||
@ -3068,6 +3068,19 @@ class AutoTestPlane(AutoTest):
|
||||
|
||||
self.fly_mission("ap-circuit.txt", mission_timeout=1200)
|
||||
|
||||
def ForcedDCM(self):
|
||||
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
|
||||
self.takeoff(50)
|
||||
self.context_collect('STATUSTEXT')
|
||||
self.set_parameter("AHRS_EKF_TYPE", 0)
|
||||
self.wait_statustext("DCM Active", check_context=True)
|
||||
self.context_stop_collecting('STATUSTEXT')
|
||||
|
||||
self.fly_home_land_and_disarm()
|
||||
|
||||
def tests(self):
|
||||
'''return list of all tests'''
|
||||
ret = super(AutoTestPlane, self).tests()
|
||||
@ -3281,6 +3294,10 @@ class AutoTestPlane(AutoTest):
|
||||
"Circuit with baro drift",
|
||||
self.fly_landing_baro_drift),
|
||||
|
||||
("ForcedDCM",
|
||||
"Switch to DCM mid-flight",
|
||||
self.ForcedDCM),
|
||||
|
||||
("LogUpload",
|
||||
"Log upload",
|
||||
self.log_upload),
|
||||
|
Loading…
Reference in New Issue
Block a user