autotest: handle Py2 not having ConnectionResetError built in

This commit is contained in:
Peter Barker 2021-02-12 15:13:47 +11:00 committed by Peter Barker
parent 50d80e9dc4
commit a5706a18af
2 changed files with 14 additions and 0 deletions

View File

@ -3,12 +3,17 @@
# Dive ArduSub in SITL # Dive ArduSub in SITL
from __future__ import print_function from __future__ import print_function
import os import os
import sys
import time import time
from pymavlink import mavutil from pymavlink import mavutil
from common import AutoTest from common import AutoTest
from common import NotAchievedException from common import NotAchievedException
from common import AutoTestTimeoutException
if sys.version_info[0] < 3:
ConnectionResetError = AutoTestTimeoutException
# get location of scripts # get location of scripts
testdir = os.path.dirname(os.path.realpath(__file__)) testdir = os.path.dirname(os.path.realpath(__file__))

View File

@ -91,6 +91,10 @@ class AutoTestTimeoutException(ErrorException):
pass pass
if sys.version_info[0] < 3:
ConnectionResetError = AutoTestTimeoutException
class WaitModeTimeout(AutoTestTimeoutException): class WaitModeTimeout(AutoTestTimeoutException):
"""Thrown when fails to achieve given mode change.""" """Thrown when fails to achieve given mode change."""
pass pass
@ -1559,6 +1563,11 @@ class AutoTest(ABC):
pass pass
except ConnectionResetError: except ConnectionResetError:
pass pass
except socket.error:
pass
except Exception as e:
self.progress("Got unexpected exception (%s)" % str(type(e)))
pass
# empty mav to avoid getting old timestamps: # empty mav to avoid getting old timestamps:
self.do_timesync_roundtrip(timeout_in_wallclock=True) self.do_timesync_roundtrip(timeout_in_wallclock=True)