Tools: autotest: move balancebot to new tests structure

This commit is contained in:
Peter Barker 2018-12-15 18:43:20 +11:00 committed by Andrew Tridgell
parent e420f62b62
commit 7aa1d51585
4 changed files with 47 additions and 46 deletions

View File

@ -949,6 +949,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
def set_rc_default(self):
super(AutoTestRover, self).set_rc_default()
self.set_rc(3, 1000)
self.set_rc(8, 1800)
def default_mode(self):

View File

@ -265,7 +265,8 @@ __bin_names = {
"CopterAVC": "arducopter-heli",
"QuadPlane": "arduplane",
"ArduSub": "ardusub",
"balancebot": "ardurover"
"balancebot": "ardurover",
"BalanceBot": "ardurover",
}
@ -317,6 +318,7 @@ def run_specific_test(step, *args, **kwargs):
"fly.ArduCopter": arducopter.AutoTestCopter,
"fly.ArduPlane": arduplane.AutoTestPlane,
"drive.APMrover2": apmrover2.AutoTestRover,
"drive.BalanceBot": balancebot.AutoTestBalanceBot,
}
tester_class = tester_class_map[testname]
tester = tester_class(*args, **kwargs)

View File

@ -7,6 +7,7 @@ import os
import pexpect
from apmrover2 import AutoTestRover
from common import AutoTest
from pymavlink import mavutil
@ -38,65 +39,62 @@ class AutoTestBalanceBot(AutoTestRover):
params,
gdbserver,
**kwargs)
self.log_name = "BalanceBot"
def vehicleinfo_key(self):
return "APMrover2"
def init(self):
if self.frame is None:
self.frame = 'balancebot'
super(AutoTestBalanceBot, self).init()
def drive_mission_balancebot1(self):
self.drive_mission(os.path.join(testdir, "balancebot1.txt"))
def test_do_set_mode_via_command_long(self):
self.do_set_mode_via_command_long("HOLD")
self.do_set_mode_via_command_long("MANUAL")
def autotest(self):
"""Autotest APMrover2 in SITL."""
self.check_test_syntax(test_file=os.path.realpath(__file__))
if not self.hasInit:
self.init()
self.progress("Started simulator")
def set_rc_default(self):
super(AutoTestBalanceBot, self).set_rc_default()
self.set_rc(3, 1500)
self.fail_list = []
try:
self.progress("Waiting for a heartbeat with mavlink protocol %s" %
self.mav.WIRE_PROTOCOL_VERSION)
self.mav.wait_heartbeat()
self.progress("Setting up RC parameters")
self.set_rc_default()
self.set_rc(8, 1800)
self.progress("Waiting for GPS fix")
self.mav.wait_gps_fix()
self.homeloc = self.mav.location()
self.progress("Home location: %s" % self.homeloc)
self.mavproxy.send('switch 6\n') # Manual mode
self.wait_mode('MANUAL')
def tests(self):
'''return list of all tests'''
self.run_test("Drive an RTL Mission", self.drive_rtl_mission)
'''note that while AutoTestBalanceBot inherits from Rover we don't
inherit Rover's tests!'''
ret = AutoTest.tests(self)
self.run_test("Drive Mission %s" % "balancebot1.txt",
self.drive_mission_balancebot1)
ret.extend([
self.run_test("Get Banner", self.do_get_banner)
("DriveRTL",
"Drive an RTL Mission",
self.drive_rtl_mission),
self.run_test("Get Capabilities",
self.do_get_autopilot_capabilities)
("DriveMission",
"Drive Mission %s" % "balancebot1.txt",
lambda: self.drive_mission("balancebot1.txt")),
self.run_test("Set mode via MAV_COMMAND_DO_SET_MODE",
lambda: self.do_set_mode_via_command_long("HOLD"))
("GetBanner", "Get Banner", self.do_get_banner),
self.run_test("Test ServoRelayEvents",
self.test_servorelayevents)
("GetCapabilities",
"Get Capabilities",
self.do_get_autopilot_capabilities),
self.run_test("Download logs", lambda:
self.log_download(
self.buildlogs_path("APMrover2-log.bin"),
upload_logs=len(self.fail_list)>0))
("DO_SET_MODE",
"Set mode via MAV_COMMAND_DO_SET_MODE",
self.test_do_set_mode_via_command_long),
except pexpect.TIMEOUT:
self.progress("Failed with timeout")
self.fail_list.append(("*timeout*", None))
("ServoRelayEvents",
"Test ServoRelayEvents",
self.test_servorelayevents),
self.close()
("DownLoadLogs", "Download logs", lambda:
self.log_download(
self.buildlogs_path("APMrover2-log.bin"),
upload_logs=len(self.fail_list) > 0)),
])
return ret
def default_mode(self):
return 'MANUAL'
if len(self.fail_list):
self.progress("FAILED STEPS: %s" % self.fail_list)
return False
return True

View File

@ -525,6 +525,7 @@ class AutoTest(ABC):
def load_mission(self, filename):
"""Load a mission from a file to flight controller."""
self.progress("Loading mission (%s)" % filename)
path = os.path.join(self.mission_directory(), filename)
tstart = self.get_sim_time_cached()
while True:
@ -1928,7 +1929,6 @@ class AutoTest(ABC):
self.wait_heartbeat()
self.progress("Setting up RC parameters")
self.set_rc_default()
self.set_rc(3, 1000)
for test in tests:
(name, desc, func) = test