mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Tools: autotest: add test for spline-as-last-waypoint
This commit is contained in:
parent
89cfdb678f
commit
d68c9572d9
@ -2615,6 +2615,28 @@ class AutoTestCopter(AutoTest):
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
||||
def test_spline_last_waypoint(self):
|
||||
self.context_push()
|
||||
ex = None
|
||||
try:
|
||||
self.load_mission("copter-spline-last-waypoint.txt")
|
||||
self.mavproxy.send('mode loiter\n')
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
self.mavproxy.send('mode auto\n')
|
||||
self.wait_mode('AUTO')
|
||||
self.set_rc(3, 1500)
|
||||
self.wait_altitude(10, 3000, relative=True)
|
||||
except Exception as e:
|
||||
self.progress("Exception caught: %s" % (
|
||||
self.get_exception_stacktrace(e)))
|
||||
ex = e
|
||||
self.context_pop()
|
||||
self.do_RTL()
|
||||
self.mav.motors_disarmed_wait()
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
||||
def fly_manual_throttle_mode_change(self):
|
||||
self.set_parameter("FS_GCS_ENABLE", 0) # avoid GUIDED instant disarm
|
||||
self.change_mode("STABILIZE")
|
||||
@ -3673,7 +3695,10 @@ class AutoTestCopter(AutoTest):
|
||||
"Fly copter mission",
|
||||
self.fly_auto_test),
|
||||
|
||||
# Gripper test
|
||||
("SplineLastWaypoint",
|
||||
"Test Spline as last waypoint",
|
||||
self.test_spline_last_waypoint),
|
||||
|
||||
("Gripper",
|
||||
"Test gripper",
|
||||
self.test_gripper),
|
||||
|
4
Tools/autotest/copter-spline-last-waypoint.txt
Normal file
4
Tools/autotest/copter-spline-last-waypoint.txt
Normal file
@ -0,0 +1,4 @@
|
||||
QGC WPL 110
|
||||
0 0 0 16 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||
1 0 3 22 0.000000 0.000000 0.000000 0.000000 -35.362297 149.164734 10.000000 1
|
||||
2 0 3 82 0.000000 0.000000 0.000000 0.000000 -35.362072 149.165909 100.000000 1
|
Loading…
Reference in New Issue
Block a user