Skip to content

Commit

Permalink
support MAV_CMD_EXTERNAL_WIND_ESTIMATE with autotest (remove lambda)
Browse files Browse the repository at this point in the history
  • Loading branch information
python36 committed Aug 28, 2024
1 parent e6463c7 commit bebfbf5
Showing 1 changed file with 2 additions and 6 deletions.
8 changes: 2 additions & 6 deletions Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down

0 comments on commit bebfbf5

Please sign in to comment.