mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
autotest: move assert_prearm_failure up
This commit is contained in:
parent
e5a8695640
commit
474c42f9d3
@ -1230,45 +1230,6 @@ class AutoTestCopter(AutoTest):
|
||||
self.fly_fence_avoid_test_radius_check(avoid_behave=1, timeout=timeout)
|
||||
self.fly_fence_avoid_test_radius_check(avoid_behave=0, timeout=timeout)
|
||||
|
||||
def assert_prearm_failure(self, expected_statustext, timeout=5, ignore_prearm_failures=[]):
|
||||
seen_statustext = False
|
||||
seen_command_ack = False
|
||||
|
||||
self.drain_mav()
|
||||
tstart = self.get_sim_time_cached()
|
||||
arm_last_send = 0
|
||||
while True:
|
||||
if seen_command_ack and seen_statustext:
|
||||
break
|
||||
now = self.get_sim_time_cached()
|
||||
if now - tstart > timeout:
|
||||
raise NotAchievedException(
|
||||
"Did not see failure-to-arm messages (statustext=%s command_ack=%s" %
|
||||
(seen_statustext, seen_command_ack))
|
||||
if now - arm_last_send > 1:
|
||||
arm_last_send = now
|
||||
self.send_mavlink_arm_command()
|
||||
m = self.mav.recv_match(blocking=True, timeout=1)
|
||||
if m is None:
|
||||
continue
|
||||
if m.get_type() == "STATUSTEXT":
|
||||
if expected_statustext in m.text:
|
||||
self.progress("Got: %s" % str(m))
|
||||
seen_statustext = True
|
||||
elif "PreArm" in m.text and m.text[8:] not in ignore_prearm_failures:
|
||||
self.progress("Got: %s" % str(m))
|
||||
raise NotAchievedException("Unexpected prearm failure (%s)" % m.text)
|
||||
|
||||
if m.get_type() == "COMMAND_ACK":
|
||||
print("Got: %s" % str(m))
|
||||
if m.command == mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM:
|
||||
if m.result != 4:
|
||||
raise NotAchievedException("command-ack says we didn't fail to arm")
|
||||
self.progress("Got: %s" % str(m))
|
||||
seen_command_ack = True
|
||||
if self.mav.motors_armed():
|
||||
raise NotAchievedException("Armed when we shouldn't have")
|
||||
|
||||
# fly_fence_test - fly east until you hit the horizontal circular fence
|
||||
def fly_fence_test(self, timeout=180):
|
||||
# enable fence, disable avoidance
|
||||
|
@ -6078,6 +6078,45 @@ class AutoTest(ABC):
|
||||
if m is not None:
|
||||
raise NotAchievedException("Fence status received unexpectedly")
|
||||
|
||||
def assert_prearm_failure(self, expected_statustext, timeout=5, ignore_prearm_failures=[]):
|
||||
seen_statustext = False
|
||||
seen_command_ack = False
|
||||
|
||||
self.drain_mav()
|
||||
tstart = self.get_sim_time_cached()
|
||||
arm_last_send = 0
|
||||
while True:
|
||||
if seen_command_ack and seen_statustext:
|
||||
break
|
||||
now = self.get_sim_time_cached()
|
||||
if now - tstart > timeout:
|
||||
raise NotAchievedException(
|
||||
"Did not see failure-to-arm messages (statustext=%s command_ack=%s" %
|
||||
(seen_statustext, seen_command_ack))
|
||||
if now - arm_last_send > 1:
|
||||
arm_last_send = now
|
||||
self.send_mavlink_arm_command()
|
||||
m = self.mav.recv_match(blocking=True, timeout=1)
|
||||
if m is None:
|
||||
continue
|
||||
if m.get_type() == "STATUSTEXT":
|
||||
if expected_statustext in m.text:
|
||||
self.progress("Got: %s" % str(m))
|
||||
seen_statustext = True
|
||||
elif "PreArm" in m.text and m.text[8:] not in ignore_prearm_failures:
|
||||
self.progress("Got: %s" % str(m))
|
||||
raise NotAchievedException("Unexpected prearm failure (%s)" % m.text)
|
||||
|
||||
if m.get_type() == "COMMAND_ACK":
|
||||
print("Got: %s" % str(m))
|
||||
if m.command == mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM:
|
||||
if m.result != 4:
|
||||
raise NotAchievedException("command-ack says we didn't fail to arm")
|
||||
self.progress("Got: %s" % str(m))
|
||||
seen_command_ack = True
|
||||
if self.mav.motors_armed():
|
||||
raise NotAchievedException("Armed when we shouldn't have")
|
||||
|
||||
def wait_ready_to_arm(self, timeout=120, require_absolute=True, check_prearm_bit=True):
|
||||
# wait for EKF checks to pass
|
||||
self.progress("Waiting for ready to arm")
|
||||
|
Loading…
Reference in New Issue
Block a user