Skip to content

Commit

Permalink
autotest: pass kwargs straight through in wait_ekf_args
Browse files Browse the repository at this point in the history
this allows minimum_duration to be passed through to the underlying methods, for example
  • Loading branch information
peterbarker committed May 19, 2024
1 parent 0b8c72c commit 3e868be
Showing 1 changed file with 4 additions and 2 deletions.
6 changes: 4 additions & 2 deletions Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -8035,8 +8035,10 @@ def wait_heartbeat(self, drain_mav=True, quiet=False, *args, **x):
if m.get_srcSystem() == self.sysid_thismav():
return m

def wait_ekf_happy(self, timeout=45, require_absolute=True):
def wait_ekf_happy(self, require_absolute=True, **kwargs):
"""Wait for EKF to be happy"""
if "timeout" not in kwargs:
kwargs["timeout"] = 45

""" if using SITL estimates directly """
if (int(self.get_parameter('AHRS_EKF_TYPE')) == 10):
Expand All @@ -8056,7 +8058,7 @@ def wait_ekf_happy(self, timeout=45, require_absolute=True):
mavutil.mavlink.ESTIMATOR_POS_VERT_ABS |
mavutil.mavlink.ESTIMATOR_PRED_POS_HORIZ_ABS)
error_bits |= mavutil.mavlink.ESTIMATOR_GPS_GLITCH
self.wait_ekf_flags(required_value, error_bits, timeout=timeout)
WaitAndMaintainEKFFlags(self, required_value, error_bits, **kwargs).run()

def wait_ekf_flags(self, required_value, error_bits, **kwargs):
WaitAndMaintainEKFFlags(self, required_value, error_bits, **kwargs).run()
Expand Down

0 comments on commit 3e868be

Please sign in to comment.