Skip to content

Commit

Permalink
autotest: fixed incorrect use of min/max/accuracy
Browse files Browse the repository at this point in the history
we were accepting values outside the specified range
  • Loading branch information
tridge committed Sep 30, 2024
1 parent f48b037 commit 0681243
Showing 1 changed file with 4 additions and 4 deletions.
8 changes: 4 additions & 4 deletions Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -7308,13 +7308,13 @@ def validator(value2, target2=None):

self.wait_and_maintain(
value_name="Altitude",
target=altitude_min,
target=(altitude_min + altitude_max)*0.5,
current_value_getter=lambda: self.get_altitude(
relative=relative,
timeout=timeout,
altitude_source=altitude_source,
),
accuracy=(altitude_max - altitude_min),
accuracy=(altitude_max - altitude_min)*0.5,
validator=lambda value2, target2: validator(value2, target2),
timeout=timeout,
**kwargs
Expand Down Expand Up @@ -7439,8 +7439,8 @@ def wait_and_maintain(self, value_name, target, current_value_getter, validator=
)
return self.wait_and_maintain_range(
value_name,
minimum=target - accuracy/2,
maximum=target + accuracy/2,
minimum=target - accuracy,
maximum=target + accuracy,
current_value_getter=current_value_getter,
validator=validator,
timeout=timeout,
Expand Down

0 comments on commit 0681243

Please sign in to comment.