mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
autotest: add test for Plane flying with a very slow GPS
This commit is contained in:
parent
4dbff85de7
commit
dd49d79798
@ -3084,6 +3084,24 @@ class AutoTestPlane(AutoTest):
|
||||
|
||||
self.fly_mission("ap-circuit.txt", mission_timeout=1200)
|
||||
|
||||
def DCMFallback(self):
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
|
||||
self.takeoff(50)
|
||||
self.context_collect('STATUSTEXT')
|
||||
self.set_parameter("EK3_POS_I_GATE", 25)
|
||||
self.set_parameter("SIM_GPS_HZ", 1)
|
||||
self.wait_statustext("DCM Active", check_context=True)
|
||||
self.wait_statustext("EKF3 Active", check_context=True)
|
||||
self.wait_statustext("DCM Active", check_context=True)
|
||||
self.wait_statustext("EKF3 Active", check_context=True)
|
||||
self.wait_statustext("DCM Active", check_context=True)
|
||||
self.wait_statustext("EKF3 Active", check_context=True)
|
||||
self.context_stop_collecting('STATUSTEXT')
|
||||
|
||||
self.fly_home_land_and_disarm()
|
||||
|
||||
def ForcedDCM(self):
|
||||
|
||||
self.wait_ready_to_arm()
|
||||
@ -3314,6 +3332,10 @@ class AutoTestPlane(AutoTest):
|
||||
"Switch to DCM mid-flight",
|
||||
self.ForcedDCM),
|
||||
|
||||
("DCMFallback",
|
||||
"Really annoy the EKF and force fallback",
|
||||
self.DCMFallback),
|
||||
|
||||
("MAVFTP",
|
||||
"Test MAVProxy can talk FTP to autopilot",
|
||||
self.MAVFTP),
|
||||
|
Loading…
Reference in New Issue
Block a user