mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
autotest: add diagnostics for frsky tests
This commit is contained in:
parent
c059338386
commit
7b251b6fd4
@ -1126,7 +1126,7 @@ class FRSkySPort(FRSky):
|
|||||||
self.state = self.state_SEND_POLL
|
self.state = self.state_SEND_POLL
|
||||||
elif self.state == self.state_SEND_POLL:
|
elif self.state == self.state_SEND_POLL:
|
||||||
# this is done in check_poll
|
# this is done in check_poll
|
||||||
print("in send_poll state")
|
self.progress("in send_poll state")
|
||||||
pass
|
pass
|
||||||
else:
|
else:
|
||||||
raise ValueError("Unknown state (%s)" % self.state)
|
raise ValueError("Unknown state (%s)" % self.state)
|
||||||
@ -9152,12 +9152,12 @@ switch value'''
|
|||||||
wants_copy = copy.copy(wants)
|
wants_copy = copy.copy(wants)
|
||||||
t2 = self.get_sim_time_cached()
|
t2 = self.get_sim_time_cached()
|
||||||
if t2 - tstart > 300:
|
if t2 - tstart > 300:
|
||||||
self.progress("Failed to get frsky data")
|
self.progress("Failed to get frsky passthrough data")
|
||||||
self.progress("Counts of sensor_id polls sent:")
|
self.progress("Counts of sensor_id polls sent:")
|
||||||
frsky.dump_sensor_id_poll_counts_as_progress_messages()
|
frsky.dump_sensor_id_poll_counts_as_progress_messages()
|
||||||
self.progress("Counts of dataids received:")
|
self.progress("Counts of dataids received:")
|
||||||
frsky.dump_dataid_counts_as_progress_messages()
|
frsky.dump_dataid_counts_as_progress_messages()
|
||||||
raise AutoTestTimeoutException("Failed to get frsky data")
|
raise AutoTestTimeoutException("Failed to get frsky passthrough data")
|
||||||
frsky.update()
|
frsky.update()
|
||||||
for want in wants_copy:
|
for want in wants_copy:
|
||||||
data = frsky.get_data(want)
|
data = frsky.get_data(want)
|
||||||
@ -9681,7 +9681,12 @@ switch value'''
|
|||||||
last_wanting_print = now
|
last_wanting_print = now
|
||||||
wants_copy = copy.copy(wants)
|
wants_copy = copy.copy(wants)
|
||||||
if now - tstart > 300:
|
if now - tstart > 300:
|
||||||
raise AutoTestTimeoutException("Failed to get frsky data")
|
self.progress("Failed to get frsky passthrough data")
|
||||||
|
self.progress("Counts of sensor_id polls sent:")
|
||||||
|
frsky.dump_sensor_id_poll_counts_as_progress_messages()
|
||||||
|
self.progress("Counts of dataids received:")
|
||||||
|
frsky.dump_dataid_counts_as_progress_messages()
|
||||||
|
raise AutoTestTimeoutException("Failed to get frsky sport data")
|
||||||
frsky.update()
|
frsky.update()
|
||||||
for want in wants_copy:
|
for want in wants_copy:
|
||||||
data = frsky.get_data(want)
|
data = frsky.get_data(want)
|
||||||
@ -9713,7 +9718,7 @@ switch value'''
|
|||||||
while True:
|
while True:
|
||||||
t2 = self.get_sim_time_cached()
|
t2 = self.get_sim_time_cached()
|
||||||
if t2 - tstart > 10:
|
if t2 - tstart > 10:
|
||||||
raise AutoTestTimeoutException("Failed to get frsky data")
|
raise AutoTestTimeoutException("Failed to get frsky D data")
|
||||||
frsky.update()
|
frsky.update()
|
||||||
alt = frsky.get_data(frsky.dataid_GPS_ALT_BP)
|
alt = frsky.get_data(frsky.dataid_GPS_ALT_BP)
|
||||||
self.progress("Got alt (%s) mav=%s" % (str(alt), str(gpi_abs_alt)))
|
self.progress("Got alt (%s) mav=%s" % (str(alt), str(gpi_abs_alt)))
|
||||||
|
Loading…
Reference in New Issue
Block a user