mirror of https://github.com/ArduPilot/ardupilot
Tools: copter do-change-speed autotest checks takeoff
This commit is contained in:
parent
5718c49928
commit
fdb1c26ae8
|
@ -1,11 +1,12 @@
|
|||
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 0.000000 0.000000 20.000000 1
|
||||
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.362656 149.165072 20.000000 1
|
||||
3 0 0 178 1.000000 15.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.360174 149.167908 14.000000 1
|
||||
5 0 0 178 1.000000 10.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||
6 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363296 149.169244 18.000000 1
|
||||
7 0 0 178 1.000000 16.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||
8 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364115 149.165747 20.000000 1
|
||||
9 0 0 20 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||
0 1 0 16 0 0 0 0 -35.3632620 149.1652370 584.090000 1
|
||||
1 0 3 22 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 20.000000 1
|
||||
2 0 3 178 0.00000000 4.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.000000 1
|
||||
3 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36265600 149.16507200 20.000000 1
|
||||
4 0 0 178 1.00000000 15.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.000000 1
|
||||
5 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36017400 149.16790800 14.000000 1
|
||||
6 0 0 178 1.00000000 10.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.000000 1
|
||||
7 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36329600 149.16924400 18.000000 1
|
||||
8 0 0 178 1.00000000 16.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.000000 1
|
||||
9 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36411500 149.16574700 20.000000 1
|
||||
10 0 0 20 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.000000 1
|
||||
|
|
|
@ -9505,14 +9505,21 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
|
||||
self.wait_current_waypoint(2)
|
||||
self.wait_current_waypoint(1)
|
||||
self.wait_groundspeed(
|
||||
3.5, 4.5,
|
||||
minimum_duration=5,
|
||||
timeout=60,
|
||||
)
|
||||
|
||||
self.wait_current_waypoint(3)
|
||||
self.wait_groundspeed(
|
||||
14.5, 15.5,
|
||||
minimum_duration=10,
|
||||
timeout=60,
|
||||
)
|
||||
|
||||
self.wait_current_waypoint(4)
|
||||
self.wait_current_waypoint(5)
|
||||
self.wait_groundspeed(
|
||||
9.5, 11.5,
|
||||
minimum_duration=10,
|
||||
|
@ -9520,7 +9527,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
)
|
||||
|
||||
self.set_parameter("ANGLE_MAX", 6000)
|
||||
self.wait_current_waypoint(6)
|
||||
self.wait_current_waypoint(7)
|
||||
self.wait_groundspeed(
|
||||
15.5, 16.5,
|
||||
minimum_duration=10,
|
||||
|
|
Loading…
Reference in New Issue