Skip to content

Commit

Permalink
autotest: set parameter value so context pop resets it
Browse files Browse the repository at this point in the history
if a vehicle magically sets a parameter (eg. via compass learn) then it can persist pat test end and reboots and everything,.

In this case it can randomly cause the next test to fail with a megneti field difference error
  • Loading branch information
peterbarker committed Feb 6, 2025
1 parent b931baa commit 034a760
Showing 1 changed file with 2 additions and 0 deletions.
2 changes: 2 additions & 0 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -12542,6 +12542,8 @@ def CompassLearnCopyFromEKF(self):
'COMPASS_USE3': 0,
})
self.assert_parameter_value("COMPASS_OFS_X", 20, epsilon=30)
# set the parameter so it gets reset at context pop time:
self.set_parameter("COMPASS_OFS_X", 20)
new_compass_ofs_x = 200
self.set_parameters({
"SIM_MAG1_OFS_X": new_compass_ofs_x,
Expand Down

0 comments on commit 034a760

Please sign in to comment.