mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
autotest: check new MAV_SYS_STATUS_PREARM_CHECK in wait_ready_to_arm
This commit is contained in:
parent
013b39d2a6
commit
5707d8ecc0
@ -4294,7 +4294,64 @@ class AutoTest(ABC):
|
||||
self.progress("GPS healthy")
|
||||
return
|
||||
|
||||
def wait_ready_to_arm(self, timeout=120, require_absolute=True):
|
||||
def assert_sensor_state(self, sensor, present=True, enabled=True, healthy=True):
|
||||
return self.sensor_has_state(sensor, present, enabled, healthy, do_assert=True)
|
||||
|
||||
def sensor_has_state(self, sensor, present=True, enabled=True, healthy=True, do_assert=False):
|
||||
m = self.mav.recv_match(type='SYS_STATUS', blocking=True, timeout=5)
|
||||
if m is None:
|
||||
raise NotAchievedException("Did not receive SYS_STATUS")
|
||||
# self.progress("Status: %s" % str(mavutil.dump_message_verbose(sys.stdout, m)))
|
||||
reported_present = m.onboard_control_sensors_present & sensor
|
||||
reported_enabled = m.onboard_control_sensors_enabled & sensor
|
||||
reported_healthy = m.onboard_control_sensors_health & sensor
|
||||
if present:
|
||||
if not reported_present:
|
||||
if do_assert:
|
||||
raise NotAchievedException("Sensor not present")
|
||||
return False
|
||||
else:
|
||||
if reported_present:
|
||||
if do_assert:
|
||||
raise NotAchievedException("Sensor present when it shouldn't be")
|
||||
return False
|
||||
|
||||
if enabled:
|
||||
if not reported_enabled:
|
||||
if do_assert:
|
||||
raise NotAchievedException("Sensor not enabled")
|
||||
return False
|
||||
else:
|
||||
if reported_enabled:
|
||||
if do_assert:
|
||||
raise NotAchievedException("Sensor enabled when it shouldn't be")
|
||||
return False
|
||||
|
||||
if healthy:
|
||||
if not reported_healthy:
|
||||
if do_assert:
|
||||
raise NotAchievedException("Sensor not healthy")
|
||||
return False
|
||||
else:
|
||||
if reported_healthy:
|
||||
if do_assert:
|
||||
raise NotAchievedException("Sensor healthy when it shouldn't be")
|
||||
return False
|
||||
return True
|
||||
|
||||
def wait_prearm_sys_status_healthy(self, timeout=60):
|
||||
self.do_timesync_roundtrip()
|
||||
tstart = self.get_sim_time()
|
||||
while True:
|
||||
t2 = self.get_sim_time_cached()
|
||||
if t2 - tstart > timeout:
|
||||
self.progress("Prearm bit never went true. Attempting arm to elicit reason from autopilot")
|
||||
self.arm_vehicle()
|
||||
raise AutoTestTimeoutException("Prearm bit never went true")
|
||||
if self.sensor_has_state(mavutil.mavlink.MAV_SYS_STATUS_PREARM_CHECK, True, True, True):
|
||||
break
|
||||
|
||||
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")
|
||||
start = self.get_sim_time()
|
||||
@ -4306,6 +4363,8 @@ class AutoTest(ABC):
|
||||
m = self.poll_home_position()
|
||||
if m is None:
|
||||
raise NotAchievedException("Did not receive a home position")
|
||||
if check_prearm_bit:
|
||||
self.wait_prearm_sys_status_healthy()
|
||||
self.progress("Took %u seconds to become armable" % armable_time)
|
||||
self.total_waiting_to_arm_time += armable_time
|
||||
self.waiting_to_arm_count += 1
|
||||
|
Loading…
Reference in New Issue
Block a user