mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
Tools: autotest: correct gripper tests
set_rc swallows messages - like the statustext messages we are looking for
This commit is contained in:
parent
88f34a8456
commit
2ef24e700e
@ -696,13 +696,16 @@ class AutoTest(ABC):
|
|||||||
need_set[chan] = default_value
|
need_set[chan] = default_value
|
||||||
self.set_rc_from_map(need_set)
|
self.set_rc_from_map(need_set)
|
||||||
|
|
||||||
|
def send_set_rc(self, chan, pwm):
|
||||||
|
self.mavproxy.send('rc %u %u\n' % (chan, pwm))
|
||||||
|
|
||||||
def set_rc(self, chan, pwm, timeout=2000):
|
def set_rc(self, chan, pwm, timeout=2000):
|
||||||
"""Setup a simulated RC control to a PWM value"""
|
"""Setup a simulated RC control to a PWM value"""
|
||||||
self.drain_mav()
|
self.drain_mav()
|
||||||
tstart = self.get_sim_time()
|
tstart = self.get_sim_time()
|
||||||
wclock = time.time()
|
wclock = time.time()
|
||||||
while self.get_sim_time_cached() < tstart + timeout:
|
while self.get_sim_time_cached() < tstart + timeout:
|
||||||
self.mavproxy.send('rc %u %u\n' % (chan, pwm))
|
self.send_set_rc(chan, pwm)
|
||||||
m = self.mav.recv_match(type='RC_CHANNELS', blocking=True)
|
m = self.mav.recv_match(type='RC_CHANNELS', blocking=True)
|
||||||
chan_pwm = getattr(m, "chan" + str(chan) + "_raw")
|
chan_pwm = getattr(m, "chan" + str(chan) + "_raw")
|
||||||
wclock_delta = time.time() - wclock
|
wclock_delta = time.time() - wclock
|
||||||
@ -2143,13 +2146,13 @@ class AutoTest(ABC):
|
|||||||
self.progress("Test gripper with RC9_OPTION")
|
self.progress("Test gripper with RC9_OPTION")
|
||||||
self.progress("Releasing load")
|
self.progress("Releasing load")
|
||||||
# non strict string matching because of catching text issue....
|
# non strict string matching because of catching text issue....
|
||||||
self.wait_text("Gripper load releas", the_function=lambda: self.set_rc(9, 1000))
|
self.wait_text("Gripper load releas", the_function=lambda: self.send_set_rc(9, 1000))
|
||||||
self.progress("Grabbing load")
|
self.progress("Grabbing load")
|
||||||
self.wait_text("Gripper load grabb", the_function=lambda: self.set_rc(9, 2000))
|
self.wait_text("Gripper load grabb", the_function=lambda: self.send_set_rc(9, 2000))
|
||||||
self.progress("Releasing load")
|
self.progress("Releasing load")
|
||||||
self.wait_text("Gripper load releas", the_function=lambda: self.set_rc(9, 1000))
|
self.wait_text("Gripper load releas", the_function=lambda: self.send_set_rc(9, 1000))
|
||||||
self.progress("Grabbing load")
|
self.progress("Grabbing load")
|
||||||
self.wait_text("Gripper load grabb", the_function=lambda: self.set_rc(9, 2000))
|
self.wait_text("Gripper load grabb", the_function=lambda: self.send_set_rc(9, 2000))
|
||||||
self.progress("Test gripper with Mavlink cmd")
|
self.progress("Test gripper with Mavlink cmd")
|
||||||
self.progress("Releasing load")
|
self.progress("Releasing load")
|
||||||
self.wait_text("Gripper load releas",
|
self.wait_text("Gripper load releas",
|
||||||
|
Loading…
Reference in New Issue
Block a user