mirror of https://github.com/ArduPilot/ardupilot
autotest: disable terrain during frsky passthrough test
If terrain isn't available then our expected statustext gets blatted with one which RCTelemetry library emits
This commit is contained in:
parent
aa7987a4fb
commit
3c700bdf44
|
@ -3897,9 +3897,13 @@ function'''
|
|||
"Test FrSky SPort mode",
|
||||
self.test_frsky_sport),
|
||||
|
||||
("FRSkyPassThrough",
|
||||
"Test FrSky PassThrough serial output",
|
||||
self.test_frsky_passthrough),
|
||||
("FRSkyPassThroughStatustext",
|
||||
"Test FrSky PassThrough serial output - statustext",
|
||||
self.FRSkyPassThroughStatustext),
|
||||
|
||||
("FRSkyPassThroughSensorIDs",
|
||||
"Test FrSky PassThrough serial output - sensor ids",
|
||||
self.FRSkyPassThroughSensorIDs),
|
||||
|
||||
("FRSkyMAVlite",
|
||||
"Test FrSky MAVlite serial output",
|
||||
|
|
|
@ -11027,9 +11027,16 @@ switch value'''
|
|||
self.progress(" Fulfilled")
|
||||
del wants[want]
|
||||
|
||||
def test_frsky_passthrough(self):
|
||||
self.set_parameter("SERIAL5_PROTOCOL", 10) # serial5 is FRSky passthrough
|
||||
self.set_parameter("RPM1_TYPE", 10) # enable RPM output
|
||||
def FRSkyPassThroughStatustext(self):
|
||||
'''test FRSKy protocol's telem-passthrough functionality'''
|
||||
# we disable terrain here as RCTelemetry can queue a lot of
|
||||
# statustexts if terrain tiles aren't available which can
|
||||
# happen on the autotest server.
|
||||
self.set_parameters({
|
||||
"SERIAL5_PROTOCOL": 10, # serial5 is FRSky passthrough
|
||||
"RPM1_TYPE": 10, # enable RPM output
|
||||
"TERRAIN_ENABLE": 0,
|
||||
})
|
||||
self.customise_SITL_commandline([
|
||||
"--uartF=tcp:6735" # serial5 spews to localhost:6735
|
||||
])
|
||||
|
@ -11047,6 +11054,7 @@ switch value'''
|
|||
tstart = self.get_sim_time()
|
||||
old_data = None
|
||||
text = ""
|
||||
|
||||
self.context_collect('STATUSTEXT')
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
|
||||
0, # p1
|
||||
|
@ -11112,12 +11120,22 @@ switch value'''
|
|||
raise NotAchievedException("Incorrect severity; want=%u got=%u" % (want_sev, severity))
|
||||
self.progress("Got statustext (%s)" % received_text)
|
||||
break
|
||||
self.context_stop_collecting('STATUSTEXT')
|
||||
|
||||
def FRSkyPassThroughSensorIDs(self):
|
||||
'''test FRSKy protocol's telem-passthrough functionality (sensor IDs)'''
|
||||
self.set_parameters({
|
||||
"SERIAL5_PROTOCOL": 10, # serial5 is FRSky passthrough
|
||||
"RPM1_TYPE": 10, # enable RPM output
|
||||
})
|
||||
self.customise_SITL_commandline([
|
||||
"--uartF=tcp:6735" # serial5 spews to localhost:6735
|
||||
])
|
||||
frsky = FRSkyPassThrough(("127.0.0.1", 6735),
|
||||
get_time=self.get_sim_time_cached)
|
||||
|
||||
self.wait_ready_to_arm()
|
||||
|
||||
# we need to start the engine to get some RPM readings, we do it for plane only
|
||||
self.drain_mav()
|
||||
# anything with a lambda in here needs a proper test written.
|
||||
# This, at least makes sure we're getting some of each
|
||||
# message. These are ordered according to the wfq scheduler
|
||||
|
|
Loading…
Reference in New Issue