autotest: cope with rename of AutoTest to Testsuite

This commit is contained in:
Peter Barker 2022-02-23 23:07:15 +11:00 committed by Peter Barker
parent 00bbb61411
commit a8bd417527
13 changed files with 60 additions and 54 deletions

View File

@ -14,15 +14,15 @@ import os
from pymavlink import mavextra
from pymavlink import mavutil
from common import AutoTest
from common import NotAchievedException
import vehicle_test_suite
from vehicle_test_suite import NotAchievedException
# get location of scripts
testdir = os.path.dirname(os.path.realpath(__file__))
SITL_START_LOCATION = mavutil.location(-27.274439, 151.290064, 343, 8.7)
class AutoTestTracker(AutoTest):
class AutoTestTracker(vehicle_test_suite.TestSuite):
def log_name(self):
return "AntennaTracker"

View File

@ -20,10 +20,11 @@ from pymavlink import rotmat
from pysim import util
from pysim import vehicleinfo
from common import AutoTest
from common import NotAchievedException, AutoTestTimeoutException, PreconditionFailedException
from common import Test
from common import MAV_POS_TARGET_TYPE_MASK
import vehicle_test_suite
from vehicle_test_suite import NotAchievedException, AutoTestTimeoutException, PreconditionFailedException
from vehicle_test_suite import Test
from vehicle_test_suite import MAV_POS_TARGET_TYPE_MASK
from pymavlink.rotmat import Vector3
@ -40,7 +41,7 @@ SITL_START_LOCATION = mavutil.location(-35.362938, 149.165085, 584, 270)
# switch 6 = Stabilize
class AutoTestCopter(AutoTest):
class AutoTestCopter(vehicle_test_suite.TestSuite):
@staticmethod
def get_not_armable_mode_list():
return ["AUTO", "AUTOTUNE", "BRAKE", "CIRCLE", "FLIP", "LAND", "RTL", "SMART_RTL", "AVOID_ADSB", "FOLLOW"]
@ -9874,7 +9875,7 @@ class AutoTestCopter(AutoTest):
def tests1a(self):
'''return list of all tests'''
ret = super(AutoTestCopter, self).tests() # about 5 mins and ~20 initial tests from autotest/common.py
ret = super(AutoTestCopter, self).tests() # about 5 mins and ~20 initial tests from autotest/vehicle_test_suite.py
ret.extend([
self.NavDelayTakeoffAbsTime,
self.NavDelayAbsTime,

View File

@ -15,15 +15,17 @@ from pymavlink import quaternion
from pymavlink import mavextra
from pymavlink import mavutil
from common import AutoTest
from common import AutoTestTimeoutException
from common import NotAchievedException
from common import PreconditionFailedException
from common import WaitModeTimeout
from common import OldpymavlinkException
from common import Test
from pymavlink.rotmat import Vector3
import vehicle_test_suite
from vehicle_test_suite import AutoTestTimeoutException
from vehicle_test_suite import NotAchievedException
from vehicle_test_suite import OldpymavlinkException
from vehicle_test_suite import PreconditionFailedException
from vehicle_test_suite import Test
from vehicle_test_suite import WaitModeTimeout
from pysim import vehicleinfo
from pysim import util
@ -35,7 +37,7 @@ SITL_START_LOCATION = mavutil.location(-35.362938, 149.165085, 585, 354)
WIND = "0,180,0.2" # speed,direction,variance
class AutoTestPlane(AutoTest):
class AutoTestPlane(vehicle_test_suite.TestSuite):
@staticmethod
def get_not_armable_mode_list():
return []

View File

@ -11,9 +11,9 @@ import time
from pymavlink import mavutil
from common import AutoTest
from common import NotAchievedException
from common import AutoTestTimeoutException
import vehicle_test_suite
from vehicle_test_suite import NotAchievedException
from vehicle_test_suite import AutoTestTimeoutException
if sys.version_info[0] < 3:
ConnectionResetError = AutoTestTimeoutException
@ -33,7 +33,7 @@ class Joystick():
Lateral = 6
class AutoTestSub(AutoTest):
class AutoTestSub(vehicle_test_suite.TestSuite):
@staticmethod
def get_not_armable_mode_list():
return []

View File

@ -36,7 +36,7 @@ import examples
from pysim import util
from pymavlink.generator import mavtemplate
from common import Test
from vehicle_test_suite import Test
tester = None

View File

@ -10,9 +10,9 @@ from __future__ import print_function
import os
from rover import AutoTestRover
from common import AutoTest
from common import NotAchievedException
import vehicle_test_suite
from vehicle_test_suite import NotAchievedException
# get location of scripts
testdir = os.path.dirname(os.path.realpath(__file__))
@ -105,7 +105,7 @@ class AutoTestBalanceBot(AutoTestRover):
'''note that while AutoTestBalanceBot inherits from Rover we don't
inherit Rover's tests!'''
ret = AutoTest.tests(self)
ret = vehicle_test_suite.TestSuite.tests(self)
ret.extend([
self.DriveRTL,

View File

@ -10,7 +10,7 @@ import shutil
from pymavlink import mavutil
from common import AutoTest
from vehicle_test_suite import TestSuite
# get location of scripts
testdir = os.path.dirname(os.path.realpath(__file__))
@ -25,7 +25,7 @@ SITL_START_LOCATION = mavutil.location(-35.362938, 149.165085, 584, 0)
# switch 6 = Manual
class AutoTestBlimp(AutoTest):
class AutoTestBlimp(TestSuite):
@staticmethod
def get_not_armable_mode_list():
return []

View File

@ -5,9 +5,11 @@ AP_FLAKE8_CLEAN
'''
from __future__ import print_function
from arducopter import AutoTestCopter
from common import AutoTest
from common import NotAchievedException, AutoTestTimeoutException
import vehicle_test_suite
from vehicle_test_suite import NotAchievedException, AutoTestTimeoutException
from pymavlink import mavutil
from pysim import vehicleinfo
@ -801,7 +803,7 @@ class AutoTestHelicopter(AutoTestCopter):
def tests(self):
'''return list of all tests'''
ret = AutoTest.tests(self)
ret = vehicle_test_suite.TestSuite.tests(self)
ret.extend([
self.AVCMission,
self.RotorRunup,

View File

@ -13,9 +13,9 @@ import math
from pymavlink import mavutil
from pymavlink.rotmat import Vector3
from common import AutoTest
from common import Test
from common import AutoTestTimeoutException, NotAchievedException, PreconditionFailedException
import vehicle_test_suite
from vehicle_test_suite import Test
from vehicle_test_suite import AutoTestTimeoutException, NotAchievedException, PreconditionFailedException
import operator
@ -26,7 +26,7 @@ WIND = "0,180,0.2" # speed,direction,variance
SITL_START_LOCATION = mavutil.location(-27.274439, 151.290064, 343, 8.7)
class AutoTestQuadPlane(AutoTest):
class AutoTestQuadPlane(vehicle_test_suite.TestSuite):
@staticmethod
def get_not_armable_mode_list():

View File

@ -14,12 +14,13 @@ import os
import sys
import time
from common import AutoTest
import vehicle_test_suite
from pysim import util
from common import AutoTestTimeoutException
from common import NotAchievedException
from common import PreconditionFailedException
from vehicle_test_suite import AutoTestTimeoutException
from vehicle_test_suite import NotAchievedException
from vehicle_test_suite import PreconditionFailedException
from pymavlink import mavextra
from pymavlink import mavutil
@ -33,7 +34,7 @@ SITL_START_LOCATION = mavutil.location(40.071374969556928,
246)
class AutoTestRover(AutoTest):
class AutoTestRover(vehicle_test_suite.TestSuite):
@staticmethod
def get_not_armable_mode_list():
return ["RTL", "SMART_RTL"]

View File

@ -6,7 +6,7 @@ Run a mission in SITL
AP_FLAKE8_CLEAN
'''
import common
import vehicle_test_suite
import os
import sys
import argparse
@ -14,7 +14,7 @@ import argparse
from pysim import util
class RunMission(common.AutoTest):
class RunMission(vehicle_test_suite.TestSuite):
def __init__(self, vehicle_binary, model, mission_filepath, speedup=None, sim_rate_hz=None):
super(RunMission, self).__init__(vehicle_binary)
self.mission_filepath = mission_filepath

View File

@ -11,8 +11,8 @@ import os
from rover import AutoTestRover
from common import AutoTestTimeoutException
from common import PreconditionFailedException
from vehicle_test_suite import AutoTestTimeoutException
from vehicle_test_suite import PreconditionFailedException
# get location of scripts
testdir = os.path.dirname(os.path.realpath(__file__))

View File

@ -1482,7 +1482,7 @@ class Result(object):
return ret
class AutoTest(ABC):
class TestSuite(ABC):
"""Base abstract class.
It implements the common function for all vehicle types.
"""
@ -5937,14 +5937,14 @@ class AutoTest(ABC):
@staticmethod
def get_distance(loc1, loc2):
"""Get ground distance between two locations."""
return AutoTest.get_distance_accurate(loc1, loc2)
return TestSuite.get_distance_accurate(loc1, loc2)
# dlat = loc2.lat - loc1.lat
# try:
# dlong = loc2.lng - loc1.lng
# except AttributeError:
# dlong = loc2.lon - loc1.lon
# return math.sqrt((dlat*dlat) + (dlong*dlong)*AutoTest.longitude_scale(loc2.lat)) * 1.113195e5
# return math.sqrt((dlat*dlat) + (dlong*dlong)*TestSuite.longitude_scale(loc2.lat)) * 1.113195e5
@staticmethod
def get_distance_accurate(loc1, loc2):
@ -5981,23 +5981,23 @@ class AutoTest(ABC):
@staticmethod
def get_lat_attr(loc):
'''return any found latitude attribute from loc'''
return AutoTest.get_latlon_attr(loc, ["lat", "latitude"])
return TestSuite.get_latlon_attr(loc, ["lat", "latitude"])
@staticmethod
def get_lon_attr(loc):
'''return any found latitude attribute from loc'''
return AutoTest.get_latlon_attr(loc, ["lng", "lon", "longitude"])
return TestSuite.get_latlon_attr(loc, ["lng", "lon", "longitude"])
@staticmethod
def get_distance_int(loc1, loc2):
"""Get ground distance between two locations in the normal "int" form
- lat/lon multiplied by 1e7"""
loc1_lat = AutoTest.get_lat_attr(loc1)
loc2_lat = AutoTest.get_lat_attr(loc2)
loc1_lon = AutoTest.get_lon_attr(loc1)
loc2_lon = AutoTest.get_lon_attr(loc2)
loc1_lat = TestSuite.get_lat_attr(loc1)
loc2_lat = TestSuite.get_lat_attr(loc2)
loc1_lon = TestSuite.get_lon_attr(loc1)
loc2_lon = TestSuite.get_lon_attr(loc2)
return AutoTest.get_distance_accurate(
return TestSuite.get_distance_accurate(
mavutil.location(loc1_lat*1e-7, loc1_lon*1e-7),
mavutil.location(loc2_lat*1e-7, loc2_lon*1e-7))