Tools: setup CI test for CANBus

This commit is contained in:
bugobliterator 2020-09-30 00:24:02 +05:30 committed by Andrew Tridgell
parent 60e8d747c6
commit c72c96fa9c
5 changed files with 77 additions and 9 deletions

View File

@ -1956,6 +1956,13 @@ class AutoTestCopter(AutoTest):
self.progress("Auto mission completed: passed!")
# fly_auto_test using CAN GPS - fly mission which tests normal operation alongside CAN GPS
def fly_auto_test_using_can_gps(self):
self.set_parameter("CAN_P1_DRIVER", 1)
self.set_parameter("GPS_TYPE", 9)
self.reboot_sitl()
self.fly_auto_test()
def fly_motor_fail(self, fail_servo=0, fail_mul=0.0, holdtime=30):
"""Test flight with reduced motor efficiency"""
@ -5638,6 +5645,15 @@ class AutoTestCopter(AutoTest):
])
return ret
def testcan(self):
ret = ([
("CANGPSCopterMission",
"Fly copter mission",
self.fly_auto_test_using_can_gps),
])
return ret
def tests(self):
ret = []
ret.extend(self.tests1())
@ -5980,6 +5996,7 @@ class AutoTestCopterTests2a(AutoTestCopter):
class AutoTestCopterTests2b(AutoTestCopter):
def tests(self):
return self.tests2b()
class AutoTestCAN(AutoTestCopter):
def tests(self):
return self.testcan()

View File

@ -279,6 +279,8 @@ __bin_names = {
"QuadPlane": "arduplane",
"Sub": "ardusub",
"BalanceBot": "ardurover",
"SITLPeriphGPS" : "sitl_periph_gp.AP_Periph",
"CAN" : "arducopter",
}
@ -289,13 +291,18 @@ def binary_path(step, debug=False):
return None
if vehicle in __bin_names:
binary_name = __bin_names[vehicle]
if len(__bin_names[vehicle].split(".")) == 2:
config_name = __bin_names[vehicle].split(".")[0]
binary_name = __bin_names[vehicle].split(".")[1]
else:
config_name = 'sitl'
binary_name = __bin_names[vehicle]
else:
# cope with builds that don't have a specific binary
return None
binary = util.reltopdir(os.path.join('build',
'sitl',
config_name,
'bin',
binary_name))
if not os.path.exists(binary):
@ -338,6 +345,11 @@ tester_class_map = {
"test.Helicopter": arducopter.AutoTestHeli,
"test.Sub": ardusub.AutoTestSub,
"test.Tracker": antennatracker.AutoTestTracker,
"test.CAN": arducopter.AutoTestCAN,
}
suplementary_test_binary_map = {
"test.CAN": "sitl_periph_gps.AP_Periph",
}
def run_specific_test(step, *args, **kwargs):
@ -396,9 +408,15 @@ def run_step(step):
if step == 'build.Sub':
vehicle_binary = 'bin/ardusub'
if step == 'build.SITLPeriphGPS':
vehicle_binary = 'sitl_periph_gps.bin/AP_Periph'
if vehicle_binary is not None:
return util.build_SITL(vehicle_binary, **build_opts)
if len(vehicle_binary.split(".")) == 1:
return util.build_SITL(vehicle_binary, **build_opts)
else:
return util.build_SITL(vehicle_binary.split(".")[1], board = vehicle_binary.split(".")[0], **build_opts)
binary = binary_path(step, debug=opts.debug)
@ -406,6 +424,18 @@ def run_step(step):
vehicle = step[9:]
return get_default_params(vehicle, binary)
if step in suplementary_test_binary_map:
config_name = suplementary_test_binary_map[step].split('.')[0]
binary_name = suplementary_test_binary_map[step].split('.')[1]
supplementary_binary = util.reltopdir(os.path.join('build',
config_name,
'bin',
binary_name))
# we are running in conjunction with a supplementary app
# can't have speedup
opts.speedup = 1.0
else:
supplementary_binary = None
fly_opts = {
"viewerip": opts.viewerip,
"use_map": opts.map,
@ -419,6 +449,7 @@ def run_step(step):
"_show_test_timings": opts.show_test_timings,
"force_ahrs_type": opts.force_ahrs_type,
"logs_dir": buildlogs_dirpath(),
"sup_binary": supplementary_binary,
}
if opts.speedup is not None:
fly_opts["speedup"] = opts.speedup
@ -860,6 +891,9 @@ if __name__ == "__main__":
'defaults.Sub',
'test.Sub',
'build.SITLPeriphGPS',
'test.CAN',
'convertgpx',
]

View File

@ -1084,7 +1084,8 @@ class AutoTest(ABC):
use_map=False,
_show_test_timings=False,
logs_dir=None,
force_ahrs_type=None):
force_ahrs_type=None,
sup_binary=None):
self.start_time = time.time()
global __autotest__ # FIXME; make progress a non-staticmethod
@ -1103,6 +1104,7 @@ class AutoTest(ABC):
self.breakpoints = breakpoints
self.disable_breakpoints = disable_breakpoints
self.speedup = speedup
self.sup_binary = sup_binary
self.mavproxy = None
self.mav = None
@ -4614,6 +4616,12 @@ Also, ignores heartbeats not from our target system'''
self.progress("Starting SITL")
self.sitl = util.start_SITL(self.binary, **start_sitl_args)
self.expect_list_add(self.sitl)
if self.sup_binary is not None:
self.progress("Starting Supplementary Program")
self.sup_prog = util.start_SITL(self.sup_binary, **start_sitl_args)
self.expect_list_add(self.sup_prog)
else:
self.sup_prog = None
def sitl_is_running(self):
return self.sitl.isalive()
@ -4641,7 +4649,10 @@ Also, ignores heartbeats not from our target system'''
util.expect_setup_callback(self.mavproxy, self.expect_callback)
self.expect_list_clear()
self.expect_list_extend([self.sitl, self.mavproxy])
if self.sup_prog is not None:
self.expect_list_extend([self.sitl, self.mavproxy])
else:
self.expect_list_extend([self.sitl, self.mavproxy, self.sup_prog])
# need to wait for a heartbeat to arrive as then mavutil will
# select the correct set of messages for us to receive in

View File

@ -408,7 +408,7 @@ def start_SITL(binary,
# TODO: have a SITL-compiled ardupilot able to have its
# console on an output fd.
else:
child.expect('Waiting for connection', timeout=300)
child.expect('Waiting for ', timeout=300)
return child

View File

@ -122,7 +122,13 @@ for t in $CI_BUILD_TARGET; do
run_autotest "Copter" "build.Copter" "test.CopterTests2b"
continue
fi
if [ "$t" == "sitltest-can" ]; then
echo "Building navigator"
$waf configure --board sitl
$waf copter
run_autotest "Copter" "build.SITLPeriphGPS" "test.CAN"
continue
fi
if [ "$t" == "sitltest-plane" ]; then
run_autotest "Plane" "build.Plane" "test.Plane"
continue