autotest: set SYSID_MYGCS in tests which need it

This was still relying on heartbeats coming from MAVProxy.  As speedup
increased those heartbeats may not come fast enough - and they really
should be coming from autotest as that's who's doing the commanding.

autotest: set SYSID_MYGCS in AFS test

autotest: set SYSID_MYGCS before setGCSfailsafe
This commit is contained in:
Peter Barker 2021-03-06 11:02:35 +11:00 committed by Peter Barker
parent 216140b58d
commit da52e5d08c
2 changed files with 2 additions and 0 deletions

View File

@ -651,6 +651,7 @@ class AutoTestCopter(AutoTest):
# Trigger an RC failure in guided mode with the option enabled
# to continue in guided. Verify no failsafe action takes place
self.start_subtest("Radio failsafe with option to continue in guided mode: FS_THR_ENABLE=1 & FS_OPTIONS=4")
self.set_parameter("SYSID_MYGCS", self.mav.source_system)
self.setGCSfailsafe(1)
self.set_parameter('FS_THR_ENABLE', 1)
self.set_parameter('FS_OPTIONS', 4)

View File

@ -8729,6 +8729,7 @@ switch value'''
self.drain_mav()
self.assert_no_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION)
self.set_parameter("AFS_ENABLE", 1)
self.set_parameter("SYSID_MYGCS", self.mav.source_system)
self.drain_mav()
self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION)
self.set_parameter("AFS_TERM_ACTION", 42)