autotest: Add plane test for landing with barometer drift.
This commit is contained in:
parent
7498d5c296
commit
3a185e7533
11
Tools/autotest/ArduPlane_Tests/Landing-Drift/ap-circuit.txt
Normal file
11
Tools/autotest/ArduPlane_Tests/Landing-Drift/ap-circuit.txt
Normal file
@ -0,0 +1,11 @@
|
|||||||
|
QGC WPL 110
|
||||||
|
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363257 149.165237 584.099976 1
|
||||||
|
1 0 3 22 15.000000 0.000000 0.000000 0.000000 0.000000 0.000000 80.000000 1
|
||||||
|
2 0 3 19 600.000000 0.000000 1.000000 0.000000 -35.356752 149.164022 100.000000 1
|
||||||
|
3 0 3 189 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 1
|
||||||
|
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.360205 149.164455 100.430000 1
|
||||||
|
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.360629 149.160695 94.470001 1
|
||||||
|
6 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.368664 149.161993 83.139999 1
|
||||||
|
7 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.368122 149.166056 60.000000 1
|
||||||
|
8 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.366814 149.165878 50.000000 1
|
||||||
|
9 0 3 21 0.000000 0.000000 0.000000 1.000000 -35.362911 149.165222 0.000000 1
|
@ -3048,6 +3048,26 @@ class AutoTestPlane(AutoTest):
|
|||||||
if ex is not None:
|
if ex is not None:
|
||||||
raise ex
|
raise ex
|
||||||
|
|
||||||
|
def fly_landing_baro_drift(self):
|
||||||
|
|
||||||
|
self.customise_SITL_commandline([], wipe=True)
|
||||||
|
|
||||||
|
self.set_parameters({
|
||||||
|
"SIM_BARO_DRIFT": -0.02,
|
||||||
|
"SIM_TERRAIN": 0,
|
||||||
|
"RNGFND_LANDING": 1,
|
||||||
|
"RNGFND1_MAX_CM": 4000,
|
||||||
|
"LAND_SLOPE_RCALC": 2,
|
||||||
|
"LAND_ABORT_DEG": 2,
|
||||||
|
})
|
||||||
|
|
||||||
|
self.reboot_sitl()
|
||||||
|
|
||||||
|
self.wait_ready_to_arm()
|
||||||
|
self.arm_vehicle()
|
||||||
|
|
||||||
|
self.fly_mission("ap-circuit.txt", mission_timeout=1200)
|
||||||
|
|
||||||
def tests(self):
|
def tests(self):
|
||||||
'''return list of all tests'''
|
'''return list of all tests'''
|
||||||
ret = super(AutoTestPlane, self).tests()
|
ret = super(AutoTestPlane, self).tests()
|
||||||
@ -3257,6 +3277,10 @@ class AutoTestPlane(AutoTest):
|
|||||||
"AHRS trim testing",
|
"AHRS trim testing",
|
||||||
self.ahrstrim),
|
self.ahrstrim),
|
||||||
|
|
||||||
|
("Landing-Drift",
|
||||||
|
"Circuit with baro drift",
|
||||||
|
self.fly_landing_baro_drift),
|
||||||
|
|
||||||
("LogUpload",
|
("LogUpload",
|
||||||
"Log upload",
|
"Log upload",
|
||||||
self.log_upload),
|
self.log_upload),
|
||||||
|
Loading…
Reference in New Issue
Block a user