|
|
|
@ -5838,6 +5838,21 @@ class AutoTest(ABC):
@@ -5838,6 +5838,21 @@ class AutoTest(ABC):
|
|
|
|
|
if comparator(m_value, value): |
|
|
|
|
return m_value |
|
|
|
|
|
|
|
|
|
def assert_servo_channel_value(self, channel, value, comparator=operator.eq): |
|
|
|
|
"""assert channel value (default condition is equality)""" |
|
|
|
|
channel_field = "servo%u_raw" % channel |
|
|
|
|
opstring = ("%s" % comparator)[-3:-1] |
|
|
|
|
m = self.assert_receive_message('SERVO_OUTPUT_RAW', timeout=1) |
|
|
|
|
m_value = getattr(m, channel_field, None) |
|
|
|
|
if m_value is None: |
|
|
|
|
raise ValueError("message (%s) has no field %s" % |
|
|
|
|
(str(m), channel_field)) |
|
|
|
|
self.progress("assert SERVO_OUTPUT_RAW.%s=%u %s %u" % |
|
|
|
|
(channel_field, m_value, opstring, value)) |
|
|
|
|
if comparator(m_value, value): |
|
|
|
|
return m_value |
|
|
|
|
raise NotAchievedException("Wrong value") |
|
|
|
|
|
|
|
|
|
def get_rc_channel_value(self, channel, timeout=2): |
|
|
|
|
"""wait for channel to hit value""" |
|
|
|
|
channel_field = "chan%u_raw" % channel |
|
|
|
@ -5870,6 +5885,16 @@ class AutoTest(ABC):
@@ -5870,6 +5885,16 @@ class AutoTest(ABC):
|
|
|
|
|
if value == m_value: |
|
|
|
|
return |
|
|
|
|
|
|
|
|
|
def assert_rc_channel_value(self, channel, value): |
|
|
|
|
channel_field = "chan%u_raw" % channel |
|
|
|
|
|
|
|
|
|
m_value = self.get_rc_channel_value(channel, timeout=1) |
|
|
|
|
self.progress("RC_CHANNELS.%s=%u want=%u" % |
|
|
|
|
(channel_field, m_value, value)) |
|
|
|
|
if value != m_value: |
|
|
|
|
raise NotAchievedException("Expected %s to be %u got %u" % |
|
|
|
|
(channel, value, m_value)) |
|
|
|
|
|
|
|
|
|
def wait_location(self, |
|
|
|
|
loc, |
|
|
|
|
accuracy=5.0, |
|
|
|
|