mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
autotest: add test for HIGH_LATENCY2
This commit is contained in:
parent
207f38dfaf
commit
89c884e8f1
@ -2458,6 +2458,24 @@ class AutoTest(ABC):
|
||||
if bytes1[i] != bytes2[i]:
|
||||
raise NotAchievedException("differ at offset %u" % i)
|
||||
|
||||
def HIGH_LATENCY2(self):
|
||||
'''test sending of HIGH_LATENCY2'''
|
||||
# should not be getting HIGH_LATENCY2 by default
|
||||
m = self.mav.recv_match(type='HIGH_LATENCY2', blocking=True, timeout=2)
|
||||
if m is not None:
|
||||
raise NotAchievedException("Shouldn't be getting HIGH_LATENCY2 by default")
|
||||
m = self.poll_message("HIGH_LATENCY2")
|
||||
if (m.failure_flags & mavutil.mavlink.HL_FAILURE_FLAG_GPS) != 0:
|
||||
raise NotAchievedException("Expected GPS to be OK")
|
||||
self.assert_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS, True, True, True)
|
||||
self.set_parameter("SIM_GPS_TYPE", 0)
|
||||
self.delay_sim_time(10)
|
||||
self.assert_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS, False, False, False)
|
||||
m = self.poll_message("HIGH_LATENCY2")
|
||||
mavutil.dump_message_verbose(sys.stdout, m)
|
||||
if (m.failure_flags & mavutil.mavlink.HL_FAILURE_FLAG_GPS) == 0:
|
||||
raise NotAchievedException("Expected GPS to be failed")
|
||||
|
||||
def test_log_download(self):
|
||||
if self.is_tracker():
|
||||
# tracker starts armed, which is annoying
|
||||
|
@ -5686,6 +5686,10 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
||||
"Set modes via mavproxy switch",
|
||||
self.test_setting_modes_via_mavproxy_switch),
|
||||
|
||||
("HIGH_LATENCY2",
|
||||
"Set sending of HIGH_LATENCY2",
|
||||
self.HIGH_LATENCY2),
|
||||
|
||||
("MAVProxy_SetModeUsingMode",
|
||||
"Set modes via mavproxy mode command",
|
||||
self.test_setting_modes_via_mavproxy_mode_command),
|
||||
|
Loading…
Reference in New Issue
Block a user