mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
autotest: fix DO_CHANGE_SPEED test
we could arrive back at our home location and stop before enough time passed to satisfy the test. i.e. doing exactly the same steps out and back again without allowing for differences in timing leads to random failure
This commit is contained in:
parent
89bd6ab218
commit
d946877fd4
@ -10191,14 +10191,18 @@ class AutoTestCopter(AutoTest):
|
||||
'''test Copter DO_CHANGE_SPEED handling in guided mode'''
|
||||
self.takeoff(20, mode='GUIDED')
|
||||
|
||||
loc = self.mav.location()
|
||||
new_loc = self.mav.location()
|
||||
new_loc_offset_n = 2000
|
||||
new_loc_offset_e = 0
|
||||
self.location_offset_ne(new_loc, new_loc_offset_n, new_loc_offset_e)
|
||||
|
||||
second_loc_offset_n = -1000
|
||||
second_loc_offset_e = 0
|
||||
second_loc = self.mav.location()
|
||||
self.location_offset_ne(second_loc, second_loc_offset_n, second_loc_offset_e)
|
||||
|
||||
# for run_cmd we fly away from home
|
||||
for (tloc, command) in (new_loc, self.run_cmd), (loc, self.run_cmd_int):
|
||||
for (tloc, command) in (new_loc, self.run_cmd), (second_loc, self.run_cmd_int):
|
||||
self.run_cmd_int(
|
||||
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
|
||||
p1=-1, # "default"
|
||||
@ -10218,7 +10222,7 @@ class AutoTestCopter(AutoTest):
|
||||
p3=-1, # throttle, -1 is no-change
|
||||
p4=0, # absolute value, not relative
|
||||
)
|
||||
self.wait_groundspeed(speed-0.2, speed+0.2, minimum_duration=2)
|
||||
self.wait_groundspeed(speed-0.2, speed+0.2, minimum_duration=10, timeout=20)
|
||||
|
||||
# we've made random changes to vehicle guided speeds above;
|
||||
# reboot vehicle to reset those:
|
||||
|
Loading…
Reference in New Issue
Block a user