mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
autotest: add a test for Spline missions showing terrain requirement
This commit is contained in:
parent
b5ebf9022c
commit
e4c405b77b
6
Tools/autotest/ArduCopter_Tests/SplineTerrain/wp.txt
Normal file
6
Tools/autotest/ArduCopter_Tests/SplineTerrain/wp.txt
Normal file
@ -0,0 +1,6 @@
|
|||||||
|
QGC WPL 110
|
||||||
|
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 584.090027 1
|
||||||
|
1 0 3 22 0.000000 0.000000 0.000000 0.000000 -35.362991 149.165192 50.000000 1
|
||||||
|
2 0 3 82 0.000000 0.000000 0.000000 0.000000 -35.362845 149.165666 50.000000 1
|
||||||
|
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363214 149.165905 50.000000 1
|
||||||
|
4 0 0 20 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
@ -2725,6 +2725,16 @@ class AutoTestCopter(AutoTest):
|
|||||||
if ex is not None:
|
if ex is not None:
|
||||||
raise ex
|
raise ex
|
||||||
|
|
||||||
|
def test_terrain_spline_mission(self):
|
||||||
|
self.set_parameter("AUTO_OPTIONS", 3)
|
||||||
|
self.set_parameter("TERRAIN_ENABLE", 0)
|
||||||
|
self.load_mission("wp.txt")
|
||||||
|
self.change_mode('AUTO')
|
||||||
|
self.wait_ready_to_arm()
|
||||||
|
self.arm_vehicle()
|
||||||
|
self.wait_waypoint(4, 4)
|
||||||
|
self.wait_disarmed()
|
||||||
|
|
||||||
def test_surface_tracking(self):
|
def test_surface_tracking(self):
|
||||||
ex = None
|
ex = None
|
||||||
self.context_push()
|
self.context_push()
|
||||||
@ -6657,6 +6667,10 @@ class AutoTestCopter(AutoTest):
|
|||||||
"Test setpoint global velocity",
|
"Test setpoint global velocity",
|
||||||
self.test_set_velocity_global_int),
|
self.test_set_velocity_global_int),
|
||||||
|
|
||||||
|
("SplineTerrain",
|
||||||
|
"Test Splines and Terrain",
|
||||||
|
self.test_terrain_spline_mission),
|
||||||
|
|
||||||
])
|
])
|
||||||
return ret
|
return ret
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user