Skip to content

Commit 0f908af

Browse files
peterbarkerlthall
andcommitted
autotest: send command for guided_achieve_heading only once
no need to send this in multiple times - since it has an angle target it won't time out Co-authored-by: Leonard Hall <[email protected]>
1 parent 5e45088 commit 0f908af

File tree

1 file changed

+7
-7
lines changed

1 file changed

+7
-7
lines changed

Tools/autotest/vehicle_test_suite.py

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -7320,16 +7320,16 @@ def reach_distance_manual(self, distance):
73207320

73217321
def guided_achieve_heading(self, heading, accuracy=None):
73227322
tstart = self.get_sim_time()
7323+
self.run_cmd(
7324+
mavutil.mavlink.MAV_CMD_CONDITION_YAW,
7325+
p1=heading, # target angle
7326+
p2=10, # degrees/second
7327+
p3=1, # -1 is counter-clockwise, 1 clockwise
7328+
p4=0, # 1 for relative, 0 for absolute
7329+
)
73237330
while True:
73247331
if self.get_sim_time_cached() - tstart > 200:
73257332
raise NotAchievedException("Did not achieve heading")
7326-
self.run_cmd(
7327-
mavutil.mavlink.MAV_CMD_CONDITION_YAW,
7328-
p1=heading, # target angle
7329-
p2=10, # degrees/second
7330-
p3=1, # -1 is counter-clockwise, 1 clockwise
7331-
p4=0, # 1 for relative, 0 for absolute
7332-
)
73337333
m = self.assert_receive_message('VFR_HUD')
73347334
self.progress("heading=%d want=%d" % (m.heading, int(heading)))
73357335
if accuracy is not None:

0 commit comments

Comments
 (0)