diff --git a/mavutil.py b/mavutil.py index 8ecfc1f15e2fdc2217f51e7f5deb428c6a8e24f4..ef8f1002991602760013812cad517c332f44ad3f 100644 --- a/mavutil.py +++ b/mavutil.py @@ -1211,7 +1211,6 @@ class mavtcp(mavfile): mavfile.__init__(self, self.port.fileno(), "tcp:" + device, source_system=source_system, source_component=source_component, use_native=use_native) def do_connect(self): - self.port = socket.socket(socket.AF_INET, socket.SOCK_STREAM) retries = self.retries if retries <= 0: # try to connect at least once: @@ -1219,6 +1218,7 @@ class mavtcp(mavfile): while retries >= 0: retries -= 1 try: + self.port = socket.socket(socket.AF_INET, socket.SOCK_STREAM) self.port.connect(self.destination_addr) break except Exception as e: