Skip to content

Commit 8ad6da0

Browse files
rmackay9andyp1per
authored andcommitted
Tools: copter and sub autotests delay 2 sec after setting origin
This gives more time for the AHRS update to consume the origin and output the global-position-int mavlink message
1 parent dd8f90d commit 8ad6da0

File tree

2 files changed

+4
-1
lines changed

2 files changed

+4
-1
lines changed

Tools/autotest/arducopter.py

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3775,6 +3775,7 @@ def set_origin(self, loc, timeout=60):
37753775
int(loc.lng * 1e7),
37763776
int(loc.alt * 1e3)
37773777
)
3778+
self.delay_sim_time(2)
37783779
gpi = self.assert_receive_message('GLOBAL_POSITION_INT')
37793780
self.progress("gpi=%s" % str(gpi))
37803781
if gpi.lat != 0:
@@ -4384,6 +4385,7 @@ def VisionPosition(self):
43844385
old_pos.lat,
43854386
old_pos.lon,
43864387
old_pos.alt)
4388+
self.delay_sim_time(2)
43874389
gpi = self.assert_receive_message('GLOBAL_POSITION_INT')
43884390
self.progress("gpi=%s" % str(gpi))
43894391
if gpi.lat != 0:
@@ -4454,6 +4456,7 @@ def BodyFrameOdom(self):
44544456
old_pos.lat,
44554457
old_pos.lon,
44564458
old_pos.alt)
4459+
self.delay_sim_time(2)
44574460
gpi = self.assert_receive_message('GLOBAL_POSITION_INT')
44584461
self.progress("gpi=%s" % str(gpi))
44594462
if gpi.lat != 0:

Tools/autotest/ardusub.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -901,7 +901,7 @@ def SetGlobalOrigin(self):
901901

902902
# This should set the EKF origin, write an ORGN msg to df and a GPS_GLOBAL_ORIGIN msg to MAVLink
903903
self.mav.mav.set_gps_global_origin_send(1, int(47.607584 * 1e7), int(-122.343911 * 1e7), 0)
904-
self.delay_sim_time(1)
904+
self.delay_sim_time(2)
905905

906906
if not self.current_onboard_log_contains_message('ORGN'):
907907
raise NotAchievedException("Did not find expected ORGN message")

0 commit comments

Comments
 (0)