mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Tools: autotest: add test for channel override cancel
This commit is contained in:
parent
2646e37e2c
commit
2834fd8017
@ -660,6 +660,71 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
||||
def test_rc_override_cancel(self):
|
||||
self.change_mode('MANUAL')
|
||||
self.wait_ready_to_arm()
|
||||
self.set_throttle_zero()
|
||||
self.arm_vehicle()
|
||||
# start moving forward a little:
|
||||
normal_rc_throttle = 1700
|
||||
throttle_override = 1900
|
||||
|
||||
self.progress("Establishing baseline RC input")
|
||||
self.mavproxy.send('rc 3 %u\n' % normal_rc_throttle)
|
||||
tstart = self.get_sim_time_cached()
|
||||
while True:
|
||||
if self.get_sim_time_cached() - tstart > 10:
|
||||
raise AutoTestTimeoutException("Did not get rc change")
|
||||
m = self.mav.recv_match(type='RC_CHANNELS', blocking=True)
|
||||
if m.chan3_raw == normal_rc_throttle:
|
||||
break
|
||||
|
||||
self.progress("Set override with RC_CHANNELS_OVERRIDE")
|
||||
tstart = self.get_sim_time_cached()
|
||||
while True:
|
||||
if self.get_sim_time_cached() - tstart > 10:
|
||||
raise AutoTestTimeoutException("Did not override")
|
||||
self.progress("Sending throttle of %u" % (throttle_override,))
|
||||
self.mav.mav.rc_channels_override_send(
|
||||
1, # target system
|
||||
1, # targe component
|
||||
65535, # chan1_raw
|
||||
65535, # chan2_raw
|
||||
throttle_override, # chan3_raw
|
||||
65535, # chan4_raw
|
||||
65535, # chan5_raw
|
||||
65535, # chan6_raw
|
||||
65535, # chan7_raw
|
||||
65535) # chan8_raw
|
||||
|
||||
m = self.mav.recv_match(type='RC_CHANNELS', blocking=True)
|
||||
self.progress("chan3=%f want=%f" % (m.chan3_raw, throttle_override))
|
||||
if m.chan3_raw == throttle_override:
|
||||
break
|
||||
|
||||
self.progress("disabling override and making sure we revert to RC input in good time")
|
||||
tstart = self.get_sim_time_cached()
|
||||
while True:
|
||||
if self.get_sim_time_cached() - tstart > 0.5:
|
||||
raise AutoTestTimeoutException("Did not cancel override")
|
||||
self.progress("Sending cancel of throttle override")
|
||||
self.mav.mav.rc_channels_override_send(
|
||||
1, # target system
|
||||
1, # targe component
|
||||
65535, # chan1_raw
|
||||
65535, # chan2_raw
|
||||
0, # chan3_raw
|
||||
65535, # chan4_raw
|
||||
65535, # chan5_raw
|
||||
65535, # chan6_raw
|
||||
65535, # chan7_raw
|
||||
65535) # chan8_raw
|
||||
|
||||
m = self.mav.recv_match(type='RC_CHANNELS', blocking=True)
|
||||
self.progress("chan3=%f want=%f" % (m.chan3_raw, normal_rc_throttle))
|
||||
if m.chan3_raw == normal_rc_throttle:
|
||||
break
|
||||
|
||||
def test_rc_overrides(self):
|
||||
self.context_push()
|
||||
ex = None
|
||||
@ -922,6 +987,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
||||
|
||||
("RCOverrides", "Test RC overrides", self.test_rc_overrides),
|
||||
|
||||
("RCOverridesCancel", "Test RC overrides Cancel", self.test_rc_override_cancel),
|
||||
|
||||
("Sprayer", "Test Sprayer", self.test_sprayer),
|
||||
|
||||
("AC_Avoidance",
|
||||
|
@ -1381,21 +1381,6 @@ class AutoTestCopter(AutoTest):
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
||||
def monitor_groundspeed(self, want, tolerance=0.5, timeout=5):
|
||||
tstart = self.get_sim_time()
|
||||
while True:
|
||||
if self.get_sim_time() - tstart > timeout:
|
||||
break
|
||||
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
|
||||
if m.groundspeed > want+tolerance:
|
||||
raise NotAchievedException("Too fast (%f > %f)" %
|
||||
(m.groundspeed, want))
|
||||
if m.groundspeed < want-tolerance:
|
||||
raise NotAchievedException("Too slow (%f < %f)" %
|
||||
(m.groundspeed, want))
|
||||
self.progress("GroundSpeed OK (got=%f) (want=%f)" %
|
||||
(m.groundspeed, want))
|
||||
|
||||
def fly_rtl_speed(self):
|
||||
"""Test RTL Speed parameters"""
|
||||
rtl_speed_ms = 7
|
||||
|
@ -1562,6 +1562,21 @@ class AutoTest(ABC):
|
||||
raise NotAchievedException("home position not updated")
|
||||
return m
|
||||
|
||||
def monitor_groundspeed(self, want, tolerance=0.5, timeout=5):
|
||||
tstart = self.get_sim_time()
|
||||
while True:
|
||||
if self.get_sim_time() - tstart > timeout:
|
||||
break
|
||||
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
|
||||
if m.groundspeed > want+tolerance:
|
||||
raise NotAchievedException("Too fast (%f > %f)" %
|
||||
(m.groundspeed, want))
|
||||
if m.groundspeed < want-tolerance:
|
||||
raise NotAchievedException("Too slow (%f < %f)" %
|
||||
(m.groundspeed, want))
|
||||
self.progress("GroundSpeed OK (got=%f) (want=%f)" %
|
||||
(m.groundspeed, want))
|
||||
|
||||
def test_arm_feature(self):
|
||||
"""Common feature to test."""
|
||||
self.context_push()
|
||||
|
Loading…
Reference in New Issue
Block a user