autotest: add explicit test for MAV_CMD_GET_HOME_POSITION

This commit is contained in:
Peter Barker 2023-10-17 12:52:04 +11:00 committed by Andrew Tridgell
parent 1ae842e4ed
commit e8be3a4e21
2 changed files with 27 additions and 3 deletions

View File

@ -4299,9 +4299,17 @@ class AutoTest(ABC):
mav=None,
condition=None,
delay_fn=None,
instance=None):
instance=None,
check_context=False):
if mav is None:
mav = self.mav
if check_context:
collection = self.context_collection(type)
if len(collection) > 0:
# return the most-recently-received message:
return collection[-1]
m = None
tstart = time.time() # timeout in wallclock
while True:
@ -4311,8 +4319,10 @@ class AutoTest(ABC):
continue
if m is not None:
break
if time.time() - tstart > timeout:
raise NotAchievedException("Did not get %s" % type)
elapsed_time = time.time() - tstart
if elapsed_time > timeout:
raise NotAchievedException("Did not get %s after %s seconds" %
(type, elapsed_time))
if delay_fn is not None:
delay_fn()
if verbose:

View File

@ -6550,6 +6550,19 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.do_RTL()
self.disarm_vehicle()
def _MAV_CMD_GET_HOME_POSITION(self, run_cmd):
'''test handling of mavlink command MAV_CMD_GET_HOME_POSITION'''
self.context_collect('HOME_POSITION')
run_cmd(mavutil.mavlink.MAV_CMD_GET_HOME_POSITION)
self.assert_receive_message('HOME_POSITION', check_context=True)
def MAV_CMD_GET_HOME_POSITION(self):
'''test handling of mavlink command MAV_CMD_GET_HOME_POSITION'''
self.change_mode('LOITER')
self.wait_ready_to_arm()
self._MAV_CMD_GET_HOME_POSITION(self.run_cmd)
self._MAV_CMD_GET_HOME_POSITION(self.run_cmd_int)
def tests(self):
'''return list of all tests'''
ret = super(AutoTestRover, self).tests()
@ -6631,6 +6644,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.NoArmWithoutMissionItems,
self.CompassPrearms,
self.MAV_CMD_DO_SET_REVERSE,
self.MAV_CMD_GET_HOME_POSITION,
])
return ret