From 6c22733de61577630b6145ec73e41ed77472e805 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 20 May 2024 07:20:50 +1000 Subject: [PATCH] autotest: add polygon pre-arm tests --- Tools/autotest/rover.py | 91 +++++++++++++++++++++++++++++++++++++++++ 1 file changed, 91 insertions(+) diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 8df5e424c2be6..2b14250974e20 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -6811,6 +6811,96 @@ def MissionRetransfer(self, target_system=1, target_component=1): want_type=mavutil.mavlink.MAV_MISSION_OPERATION_CANCELLED, ) + def MissionPolyEnabledPreArm(self): + '''check Polygon porearm checks''' + self.set_parameters({ + 'FENCE_ENABLE': 1, + }) + self.progress("Ensure that we can arm if polyfence is enabled but we have no polyfence") + self.assert_parameter_value('FENCE_TYPE', 6) + self.wait_ready_to_arm() + self.reboot_sitl() + self.wait_ready_to_arm() + + self.progress("Ensure we can arm when we have an inclusion fence we are inside of") + here = self.mav.location() + self.upload_fences_from_locations( + mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, + [ + [ # over the top of the vehicle + self.offset_location_ne(here, -50, -50), # bl + self.offset_location_ne(here, -50, 50), # br + self.offset_location_ne(here, 50, 50), # tr + self.offset_location_ne(here, 50, -50), # tl, + ] + ] + ) + self.delay_sim_time(5) + self.wait_ready_to_arm() + + self.reboot_sitl() + self.wait_ready_to_arm() + + self.progress("Ensure we can't arm when we are in breacnh of a polyfence") + self.clear_fence() + + self.progress("Now create a fence we are in breach of") + here = self.mav.location() + self.upload_fences_from_locations( + mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, + [ + [ # over the top of the vehicle + self.offset_location_ne(here, 20, 20), # bl + self.offset_location_ne(here, 20, 50), # br + self.offset_location_ne(here, 50, 50), # tr + self.offset_location_ne(here, 50, 20), # tl, + ] + ] + ) + + self.assert_prearm_failure('vehicle outside fence', other_prearm_failures_fatal=False) + self.reboot_sitl() + + self.assert_prearm_failure('vehicle outside fence', other_prearm_failures_fatal=False, timeout=120) + + self.progress("Ensure we can arm when a polyfence fence is cleared when we've previously been in breach") + self.clear_fence() + self.wait_ready_to_arm() + + self.upload_fences_from_locations( + mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, + [ + [ # over the top of the vehicle + self.offset_location_ne(here, 20, 20), # bl + self.offset_location_ne(here, 20, 50), # br + self.offset_location_ne(here, 50, 50), # tr + self.offset_location_ne(here, 50, 20), # tl, + ] + ] + ) + self.reboot_sitl() + self.assert_prearm_failure('vehicle outside fence', other_prearm_failures_fatal=False, timeout=120) + self.clear_fence() + self.wait_ready_to_arm() + + self.progress("Ensure we can arm after clearing polygon fence type enabled") + self.upload_fences_from_locations( + mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, + [ + [ # over the top of the vehicle + self.offset_location_ne(here, 20, 20), # bl + self.offset_location_ne(here, 20, 50), # br + self.offset_location_ne(here, 50, 50), # tr + self.offset_location_ne(here, 50, 20), # tl, + ] + ] + ) + self.assert_prearm_failure('vehicle outside fence', other_prearm_failures_fatal=False, timeout=120) + self.set_parameter('FENCE_TYPE', 2) + self.wait_ready_to_arm() + self.set_parameter('FENCE_TYPE', 6) + self.assert_prearm_failure('vehicle outside fence', other_prearm_failures_fatal=False, timeout=120) + def tests(self): '''return list of all tests''' ret = super(AutoTestRover, self).tests() @@ -6900,6 +6990,7 @@ def tests(self): self.RTL_SPEED, self.MissionRetransfer, self.FenceFullAndPartialTransfer, + self.MissionPolyEnabledPreArm, ]) return ret