mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
autotest: improve diagnostics for bad field values
print out enumeration name and enumeration value name when ng comparisons
This commit is contained in:
parent
2d42028db3
commit
a5ed5f4f82
@ -3968,13 +3968,27 @@ class AutoTest(ABC):
|
|||||||
else:
|
else:
|
||||||
equal = got == value
|
equal = got == value
|
||||||
|
|
||||||
|
value_string = value
|
||||||
|
got_string = got
|
||||||
|
enum_name = m.fieldenums_by_name.get(fieldname, None)
|
||||||
|
if enum_name is not None:
|
||||||
|
enum = mavutil.mavlink.enums[enum_name]
|
||||||
|
if value not in enum:
|
||||||
|
raise ValueError("Expected value %s not in enum %s" % (value, enum_name))
|
||||||
|
if got not in enum:
|
||||||
|
raise ValueError("Received value %s not in enum %s" % (value, enum_name))
|
||||||
|
value_string = "%s (%s)" % (value, enum[value].name)
|
||||||
|
got_string = "%s (%s)" % (got, enum[got].name)
|
||||||
|
|
||||||
if not equal:
|
if not equal:
|
||||||
|
# see if this is an enumerated field:
|
||||||
|
self.progress(self.dump_message_verbose(m))
|
||||||
self.progress("Expected %s.%s to be %s, got %s" %
|
self.progress("Expected %s.%s to be %s, got %s" %
|
||||||
(m.get_type(), fieldname, value, got))
|
(m.get_type(), fieldname, value_string, got_string))
|
||||||
return False
|
return False
|
||||||
if verbose:
|
if verbose:
|
||||||
self.progress("%s.%s has expected value %s" %
|
self.progress("%s.%s has expected value %s" %
|
||||||
(m.get_type(), fieldname, value))
|
(m.get_type(), fieldname, value_string))
|
||||||
return True
|
return True
|
||||||
|
|
||||||
def assert_message_field_values(self, m, fieldvalues, verbose=True, epsilon=None):
|
def assert_message_field_values(self, m, fieldvalues, verbose=True, epsilon=None):
|
||||||
|
Loading…
Reference in New Issue
Block a user