From bebfbf56b945ec2159bd9ad3927df419746b5721 Mon Sep 17 00:00:00 2001 From: Andrii Fil Date: Wed, 28 Aug 2024 17:45:27 +0300 Subject: [PATCH] support MAV_CMD_EXTERNAL_WIND_ESTIMATE with autotest (remove lambda) --- Tools/autotest/arduplane.py | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 0c9f5f4df47e1b..5ab3b4be16fc56 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -6053,12 +6053,8 @@ def ForceArm(self): self.disarm_vehicle() def _MAV_CMD_EXTERNAL_WIND_ESTIMATE(self, command): - cmp_with_variance = lambda a, b, p: abs(a - b) < p - - self.set_parameters({ - "SIM_WIND_SPD": 0, - "SIM_WIND_DIR": 180, - }) + def cmp_with_variance(a, b, p): + return abs(a - b) < p def check_eq(speed, direction, ret_dir): command(mavutil.mavlink.MAV_CMD_EXTERNAL_WIND_ESTIMATE, p1=speed, p3=direction)