Tools: Autotest: fix and re-enable Subs's MAV_CMD_DO_CHANGE_SPEED test

This commit is contained in:
Willian Galvani 2023-10-23 14:03:01 -03:00 committed by Peter Barker
parent 9dbd6f335a
commit 24bed08c4e
1 changed files with 4 additions and 8 deletions

View File

@ -422,7 +422,6 @@ class AutoTestSub(vehicle_test_suite.TestSuite):
ret = super(AutoTestSub, self).disabled_tests()
ret.update({
"ConfigErrorLoop": "Sub does not instantiate AP_Stats. Also see https://github.com/ArduPilot/ardupilot/issues/10247", # noqa
"MAV_CMD_DO_CHANGE_SPEED": "Doesn't work",
})
return ret
@ -458,21 +457,18 @@ class AutoTestSub(vehicle_test_suite.TestSuite):
def MAV_CMD_DO_CHANGE_SPEED(self):
'''ensure vehicle changes speeds when DO_CHANGE_SPEED received'''
items = [
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 0),
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, -1),
(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),
]
items = []
for i in range(0, 2000, 10):
items.append((mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, i, 0, 0))
self.upload_simple_relhome_mission(items)
self.wait_ready_to_arm()
self.arm_vehicle()
self.run_cmd(mavutil.mavlink.MAV_CMD_MISSION_START)
self.progress("SENT MISSION START")
for run_cmd in self.run_cmd, self.run_cmd_int:
for speed in [1, 2, 3, 1]:
for speed in [1, 1.5, 0.5]:
run_cmd(mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, p2=speed)
self.wait_groundspeed(speed-0.02, speed+0.02, minimum_duration=2)
self.wait_groundspeed(speed-0.2, speed+0.2, minimum_duration=2, timeout=60)
self.disarm_vehicle()
def _MAV_CMD_CONDITION_YAW(self, run_cmd):