autotest: stop set_parameter from using get_parameter

Setting a parameter on ArduPilot causes the autopilot to emit the new
value in a PARAM_VALUE message, so we do not need to fetch it ourselves.

Fetching it ourselves causes subtle problems for the autotest suite
where a PARAM_VALUE is currently in the uart buffer - so the autotest
set_parameter has consumed one PARAM_VALUE message (the auto-emitted
one).  If it immediately does a set_parameter then the next
PARAM_VALUE it sees will be the OLD value as the value comes out of the
uart.
This commit is contained in:
Peter Barker 2020-09-15 08:39:39 +10:00 committed by Peter Barker
parent 3e708b9b29
commit 1075e13352

View File

@ -3010,7 +3010,13 @@ class AutoTest(ABC):
old_value = self.get_parameter(name, attempts=2)
for i in range(1, retries+2):
self.send_set_parameter(name, value)
returned_value = self.get_parameter(name, verbose=verbose)
# ArduPilot instantly volunteers the new value:
m = self.mav.recv_match(type='PARAM_VALUE', blocking=True, timeout=5)
if verbose:
self.progress("set_parameter(%s): %s" % (name, str(m), ))
if m is None:
raise NotAchievedException("Did not receive volunteered parameter %s" % str(name))
returned_value = m.param_value
delta = float(value) - returned_value
if abs(delta) < epsilon:
# yes, near-enough-to-equal.