mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
autotest: tighten tolerances on beacon test
7m is actually pretty much all of the required movement for this fence test!
This commit is contained in:
parent
720bfc8dc8
commit
1cfe409189
@ -6665,18 +6665,18 @@ class AutoTestCopter(AutoTest):
|
||||
self.takeoff(10, mode="LOITER")
|
||||
self.set_rc(2, 1400)
|
||||
west_loc = mavutil.location(-35.362919, 149.165055, 0, 0)
|
||||
self.wait_location(west_loc, accuracy=7)
|
||||
self.wait_location(west_loc, accuracy=1)
|
||||
self.reach_heading_manual(0)
|
||||
north_loc = mavutil.location(-35.362881, 149.165103, 0, 0)
|
||||
self.wait_location(north_loc, accuracy=7)
|
||||
self.wait_location(north_loc, accuracy=1)
|
||||
self.set_rc(2, 1500)
|
||||
self.set_rc(1, 1600)
|
||||
east_loc = mavutil.location(-35.362986, 149.165227, 0, 0)
|
||||
self.wait_location(east_loc, accuracy=7)
|
||||
self.wait_location(east_loc, accuracy=1)
|
||||
self.set_rc(1, 1500)
|
||||
self.set_rc(2, 1600)
|
||||
south_loc = mavutil.location(-35.363025, 149.165182, 0, 0)
|
||||
self.wait_location(south_loc, accuracy=7)
|
||||
self.wait_location(south_loc, accuracy=1)
|
||||
self.set_rc(2, 1500)
|
||||
self.do_RTL()
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user