Skip to content

Commit 345f1f2

Browse files
committed
autotest: fix FenceMargin test
1 parent af65924 commit 345f1f2

File tree

1 file changed

+2
-1
lines changed

1 file changed

+2
-1
lines changed

Tools/autotest/arducopter.py

+2-1
Original file line numberDiff line numberDiff line change
@@ -1929,7 +1929,8 @@ def FenceMargin(self, timeout=180):
19291929
# 110m polyfence
19301930
home_loc = self.mav.location()
19311931
radius = self.get_parameter("FENCE_RADIUS")
1932-
self.mavproxy.send("map circle %f %f %f green\n" % (home_loc.lat, home_loc.lng, radius))
1932+
if self.use_map and self.mavproxy is not None:
1933+
self.mavproxy.send("map circle %f %f %f green\n" % (home_loc.lat, home_loc.lng, radius))
19331934

19341935
locs = [
19351936
self.offset_location_ne(home_loc, -110, -110),

0 commit comments

Comments
 (0)