autotest: add test for DO_CHANGE_SPEED
This commit is contained in:
parent
14c9d4e6a3
commit
dc312260de
11
Tools/autotest/ArduCopter_Tests/DO_CHANGE_SPEED/mission.txt
Normal file
11
Tools/autotest/ArduCopter_Tests/DO_CHANGE_SPEED/mission.txt
Normal file
@ -0,0 +1,11 @@
|
|||||||
|
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 17.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
|
@ -7744,6 +7744,42 @@ class AutoTestCopter(AutoTest):
|
|||||||
|
|
||||||
self.wait_disarmed()
|
self.wait_disarmed()
|
||||||
|
|
||||||
|
def DO_CHANGE_SPEED(self):
|
||||||
|
self.load_mission("mission.txt", strict=False)
|
||||||
|
|
||||||
|
self.set_parameters({
|
||||||
|
"AUTO_OPTIONS": 3,
|
||||||
|
"ANGLE_MAX": 4500,
|
||||||
|
})
|
||||||
|
|
||||||
|
self.change_mode('AUTO')
|
||||||
|
self.wait_ready_to_arm()
|
||||||
|
self.arm_vehicle()
|
||||||
|
|
||||||
|
self.wait_current_waypoint(2)
|
||||||
|
self.wait_groundspeed(
|
||||||
|
14.5, 15.5,
|
||||||
|
minimum_duration=10,
|
||||||
|
timeout=60,
|
||||||
|
)
|
||||||
|
|
||||||
|
self.wait_current_waypoint(4)
|
||||||
|
self.wait_groundspeed(
|
||||||
|
9.5, 11.5,
|
||||||
|
minimum_duration=10,
|
||||||
|
timeout=60,
|
||||||
|
)
|
||||||
|
|
||||||
|
self.set_parameter("ANGLE_MAX", 6000)
|
||||||
|
self.wait_current_waypoint(6)
|
||||||
|
self.wait_groundspeed(
|
||||||
|
16.5, 18.5,
|
||||||
|
minimum_duration=10,
|
||||||
|
timeout=60,
|
||||||
|
)
|
||||||
|
|
||||||
|
self.wait_disarmed()
|
||||||
|
|
||||||
# a wrapper around all the 1A,1B,1C..etc tests for travis
|
# a wrapper around all the 1A,1B,1C..etc tests for travis
|
||||||
def tests1(self):
|
def tests1(self):
|
||||||
ret = ([])
|
ret = ([])
|
||||||
@ -8443,6 +8479,10 @@ class AutoTestCopter(AutoTest):
|
|||||||
"Test EKF's handling of takeoff-expected",
|
"Test EKF's handling of takeoff-expected",
|
||||||
self.GroundEffectCompensation_takeOffExpected),
|
self.GroundEffectCompensation_takeOffExpected),
|
||||||
|
|
||||||
|
Test("DO_CHANGE_SPEED",
|
||||||
|
"Change speed during misison using waypoint items",
|
||||||
|
self.DO_CHANGE_SPEED),
|
||||||
|
|
||||||
Test("WPNAV_SPEED",
|
Test("WPNAV_SPEED",
|
||||||
"Change speed during misison",
|
"Change speed during misison",
|
||||||
self.WPNAV_SPEED),
|
self.WPNAV_SPEED),
|
||||||
|
Loading…
Reference in New Issue
Block a user