mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 09:38:29 -04:00
autotest: add test for uploading big fence then small fence
This commit is contained in:
parent
af92c9679f
commit
6e4aa2264f
@ -4270,6 +4270,42 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||||||
target_system=target_system,
|
target_system=target_system,
|
||||||
target_component=target_component)
|
target_component=target_component)
|
||||||
|
|
||||||
|
def test_poly_fence_big_then_small(self, target_system=1, target_component=1):
|
||||||
|
here = self.mav.location()
|
||||||
|
|
||||||
|
self.roundtrip_fence_using_fencepoint_protocol([
|
||||||
|
self.offset_location_ne(here, 0, 0), # bl // return point
|
||||||
|
self.offset_location_ne(here, -50, 20), # bl
|
||||||
|
self.offset_location_ne(here, 50, 20), # br
|
||||||
|
self.offset_location_ne(here, 50, 40), # tr
|
||||||
|
self.offset_location_ne(here, -50, 40), # tl,
|
||||||
|
self.offset_location_ne(here, -50, 20), # closing point
|
||||||
|
], ordering=[1, 2, 3, 4, 5, 0])
|
||||||
|
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
|
||||||
|
if len(downloaded_items) != 5:
|
||||||
|
# that's one return point and then bl, br, tr, then tl
|
||||||
|
raise NotAchievedException("Bad number of downloaded items in original download")
|
||||||
|
|
||||||
|
self.roundtrip_fence_using_fencepoint_protocol([
|
||||||
|
self.offset_location_ne(here, 0, 0), # bl // return point
|
||||||
|
self.offset_location_ne(here, -50, 20), # bl
|
||||||
|
self.offset_location_ne(here, 50, 40), # tr
|
||||||
|
self.offset_location_ne(here, -50, 40), # tl,
|
||||||
|
self.offset_location_ne(here, -50, 20), # closing point
|
||||||
|
], ordering=[1, 2, 3, 4, 0])
|
||||||
|
|
||||||
|
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
|
||||||
|
want_count = 4
|
||||||
|
if len(downloaded_items) != want_count:
|
||||||
|
# that's one return point and then bl, tr, then tl
|
||||||
|
raise NotAchievedException("Bad number of downloaded items in second download got=%u wanted=%u" %
|
||||||
|
(len(downloaded_items), want_count))
|
||||||
|
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
|
||||||
|
if len(downloaded_items) != 4:
|
||||||
|
# that's one return point and then bl, tr, then tl
|
||||||
|
raise NotAchievedException("Bad number of downloaded items in second download (second time) got=%u want=%u" %
|
||||||
|
(len(downloaded_items), want_count))
|
||||||
|
|
||||||
def test_poly_fence_compatability(self, target_system=1, target_component=1):
|
def test_poly_fence_compatability(self, target_system=1, target_component=1):
|
||||||
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
|
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
|
||||||
target_system=target_system,
|
target_system=target_system,
|
||||||
@ -4347,6 +4383,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||||||
|
|
||||||
# self.set_parameter("SIM_SPEEDUP", 1)
|
# self.set_parameter("SIM_SPEEDUP", 1)
|
||||||
|
|
||||||
|
self.test_poly_fence_big_then_small()
|
||||||
|
|
||||||
self.test_poly_fence_compatability()
|
self.test_poly_fence_compatability()
|
||||||
|
|
||||||
self.test_fence_upload_timeouts()
|
self.test_fence_upload_timeouts()
|
||||||
|
Loading…
Reference in New Issue
Block a user