mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-11 02:13:57 -04:00
autotest: add an autotest for DO_PAUSE_CONTINUE
This commit is contained in:
parent
c729fc7796
commit
09f06be17e
@ -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 -35.362881 149.165222 20.000000 1
|
||||||
|
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364652 149.163501 0.000000 1
|
||||||
|
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365361 149.163501 0.000000 1
|
||||||
|
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365361 149.163995 40.000000 1
|
||||||
|
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365361 149.164563 20.000000 1
|
||||||
|
6 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364652 149.164531 20.000000 1
|
||||||
|
7 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364652 149.163995 20.000000 1
|
||||||
|
8 0 3 16 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||||
|
9 0 0 20 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
@ -7396,6 +7396,41 @@ class AutoTestCopter(AutoTest):
|
|||||||
if ex is not None:
|
if ex is not None:
|
||||||
raise ex
|
raise ex
|
||||||
|
|
||||||
|
def PAUSE_CONTINUE(self):
|
||||||
|
self.load_mission("copter_mission.txt", strict=False)
|
||||||
|
|
||||||
|
self.set_parameter("AUTO_OPTIONS", 3)
|
||||||
|
self.change_mode('AUTO')
|
||||||
|
self.wait_ready_to_arm()
|
||||||
|
self.arm_vehicle()
|
||||||
|
|
||||||
|
self.wait_waypoint(4, 4)
|
||||||
|
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE,
|
||||||
|
0, # param1
|
||||||
|
0, # param2
|
||||||
|
0, # param3
|
||||||
|
0, # param4
|
||||||
|
0, # param5
|
||||||
|
0, # param6
|
||||||
|
0 # param7
|
||||||
|
)
|
||||||
|
|
||||||
|
self.wait_groundspeed(0, 1, minimum_duration=5)
|
||||||
|
|
||||||
|
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE,
|
||||||
|
1, # param1
|
||||||
|
0, # param2
|
||||||
|
0, # param3
|
||||||
|
0, # param4
|
||||||
|
0, # param5
|
||||||
|
0, # param6
|
||||||
|
0 # param7
|
||||||
|
)
|
||||||
|
|
||||||
|
self.wait_groundspeed(5, 100)
|
||||||
|
|
||||||
|
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 = ([])
|
||||||
@ -7891,6 +7926,10 @@ class AutoTestCopter(AutoTest):
|
|||||||
"Test Different Altitude Types",
|
"Test Different Altitude Types",
|
||||||
self.test_altitude_types),
|
self.test_altitude_types),
|
||||||
|
|
||||||
|
("PAUSE_CONTINUE",
|
||||||
|
"Test MAV_CMD_PAUSE_CONTINUE",
|
||||||
|
self.PAUSE_CONTINUE),
|
||||||
|
|
||||||
("RichenPower",
|
("RichenPower",
|
||||||
"Test RichenPower generator",
|
"Test RichenPower generator",
|
||||||
self.test_richenpower),
|
self.test_richenpower),
|
||||||
|
@ -3415,6 +3415,7 @@ class AutoTest(ABC):
|
|||||||
mavutil.mavlink.MAV_CMD_DO_JUMP,
|
mavutil.mavlink.MAV_CMD_DO_JUMP,
|
||||||
mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,
|
mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,
|
||||||
mavutil.mavlink.MAV_CMD_DO_SET_SERVO,
|
mavutil.mavlink.MAV_CMD_DO_SET_SERVO,
|
||||||
|
mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE,
|
||||||
]
|
]
|
||||||
|
|
||||||
def assert_mission_files_same(self, file1, file2, match_comments=False):
|
def assert_mission_files_same(self, file1, file2, match_comments=False):
|
||||||
|
Loading…
Reference in New Issue
Block a user