autotest: add test for fetching invalid fence point

This commit is contained in:
Peter Barker 2025-02-04 15:45:39 +11:00 committed by Peter Barker
parent 26c61f527e
commit e9e419d252
2 changed files with 57 additions and 10 deletions

View File

@ -2306,6 +2306,47 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.test_gcs_fence_via_mavproxy(target_system=target_system, self.test_gcs_fence_via_mavproxy(target_system=target_system,
target_component=target_component) target_component=target_component)
def GCSFenceInvalidPoint(self):
'''Test fetch non-existant fencepoint'''
target_system = 1
target_component = 1
here = self.mav.location()
self.upload_fences_from_locations([
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [
# east
self.offset_location_ne(here, -50, 20), # bl
self.offset_location_ne(here, 50, 20), # br
self.offset_location_ne(here, 50, 40), # tr
]),
])
for i in 0, 1, 2:
self.assert_fetch_mission_item_int(target_system, target_component, i, mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
self.progress("Requesting invalid point")
self.mav.mav.mission_request_int_send(
target_system,
target_component,
3,
mavutil.mavlink.MAV_MISSION_TYPE_FENCE
)
self.context_push()
self.context_collect('MISSION_COUNT')
m = self.assert_receive_mission_ack(
mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
want_type=mavutil.mavlink.MAV_MISSION_INVALID_SEQUENCE,
)
self.delay_sim_time(0.1)
found = False
for m in self.context_collection('MISSION_COUNT'):
if m.mission_type != mavutil.mavlink.MAV_MISSION_TYPE_FENCE:
continue
if m.count != 3:
raise NotAchievedException("Unexpected count in MISSION_COUNT")
found = True
self.context_pop()
if not found:
raise NotAchievedException("Did not see correction for fencepoint count")
# explode the write_type_to_storage method # explode the write_type_to_storage method
# FIXME: test converting invalid fences / minimally valid fences / normal fences # FIXME: test converting invalid fences / minimally valid fences / normal fences
# FIXME: show that uploading smaller items take up less space # FIXME: show that uploading smaller items take up less space
@ -2533,6 +2574,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
if m.type != want_type: if m.type != want_type:
raise NotAchievedException("Expected ack type %u got %u" % raise NotAchievedException("Expected ack type %u got %u" %
(want_type, m.type)) (want_type, m.type))
return m
def assert_filepath_content(self, filepath, want): def assert_filepath_content(self, filepath, want):
with open(filepath) as f: with open(filepath) as f:
@ -7015,6 +7057,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.Offboard, self.Offboard,
self.MAVProxyParam, self.MAVProxyParam,
self.GCSFence, self.GCSFence,
self.GCSFenceInvalidPoint,
self.GCSMission, self.GCSMission,
self.GCSRally, self.GCSRally,
self.MotorTest, self.MotorTest,

View File

@ -9311,6 +9311,19 @@ Also, ignores heartbeats not from our target system'''
(mavutil.mavlink.enums["MAV_MISSION_RESULT"][m.type].name),) (mavutil.mavlink.enums["MAV_MISSION_RESULT"][m.type].name),)
self.progress("Upload of all %u items succeeded" % len(items)) self.progress("Upload of all %u items succeeded" % len(items))
def assert_fetch_mission_item_int(self, target_system, target_component, seq, mission_type):
self.mav.mav.mission_request_int_send(target_system,
target_component,
seq,
mission_type)
m = self.assert_receive_message(
'MISSION_ITEM_INT',
condition=f'MISSION_ITEM_INT.mission_type=={mission_type}',
)
if m is None:
raise NotAchievedException("Did not receive MISSION_ITEM_INT")
return m
def download_using_mission_protocol(self, mission_type, verbose=False, timeout=10): def download_using_mission_protocol(self, mission_type, verbose=False, timeout=10):
'''mavlink2 required''' '''mavlink2 required'''
target_system = 1 target_system = 1
@ -9362,16 +9375,7 @@ Also, ignores heartbeats not from our target system'''
return items return items
self.progress("Requesting item %u (remaining=%u)" % self.progress("Requesting item %u (remaining=%u)" %
(next_to_request, len(remaining_to_receive))) (next_to_request, len(remaining_to_receive)))
self.mav.mav.mission_request_int_send(target_system, m = self.assert_fetch_mission_item_int(target_system, target_component, next_to_request, mission_type)
target_component,
next_to_request,
mission_type)
m = self.mav.recv_match(type='MISSION_ITEM_INT',
blocking=True,
timeout=5,
condition='MISSION_ITEM_INT.mission_type==%u' % mission_type)
if m is None:
raise NotAchievedException("Did not receive MISSION_ITEM_INT")
if m.target_system != self.mav.source_system: if m.target_system != self.mav.source_system:
raise NotAchievedException("Wrong target system (want=%u got=%u)" % raise NotAchievedException("Wrong target system (want=%u got=%u)" %
(self.mav.source_system, m.target_system)) (self.mav.source_system, m.target_system))