def build_all(): """Run the build_all.sh script.""" print("Running build_all.sh") if util.run_cmd(util.reltopdir('Tools/scripts/build_all.sh'), directory=util.reltopdir('.')) != 0: print("Failed build_all.sh") return False return True
def write_webresults(results_to_write): """Write webpage results.""" t = mavtemplate.MAVTemplate() for h in glob.glob(util.reltopdir('Tools/autotest/web/*.html')): html = util.loadfile(h) f = open(buildlogs_path(os.path.basename(h)), mode='w') t.write(f, html, results_to_write) f.close() for f in glob.glob(util.reltopdir('Tools/autotest/web/*.png')): shutil.copy(f, buildlogs_path(os.path.basename(f)))
def write_webresults(results_to_write): """Write webpage results.""" from pymavlink.generator import mavtemplate t = mavtemplate.MAVTemplate() for h in glob.glob(util.reltopdir('Tools/autotest/web/*.html')): html = util.loadfile(h) f = open(util.reltopdir("../buildlogs/%s" % os.path.basename(h)), mode='w') t.write(f, html, results_to_write) f.close() for f in glob.glob(util.reltopdir('Tools/autotest/web/*.png')): shutil.copy(f, util.reltopdir('../buildlogs/%s' % os.path.basename(f)))
def convert_gpx(): """Convert any tlog files to GPX and KML.""" mavlog = glob.glob(util.reltopdir("../buildlogs/*.tlog")) for m in mavlog: util.run_cmd(util.reltopdir("modules/mavlink/pymavlink/tools/mavtogpx.py") + " --nofixcheck " + m) gpx = m + '.gpx' kml = m + '.kml' util.run_cmd('gpsbabel -i gpx -f %s -o kml,units=m,floating=1,extrude=1 -F %s' % (gpx, kml), checkfail=False) util.run_cmd('zip %s.kmz %s.kml' % (m, m), checkfail=False) util.run_cmd("mavflightview.py --imagefile=%s.png %s" % (m, m)) return True
def build_devrelease(): """Run the build_devrelease.sh script.""" print("Running build_devrelease.sh") # copy the script as it changes git branch, which can change the script while running orig = util.reltopdir('Tools/scripts/build_devrelease.sh') copy = util.reltopdir('./build_devrelease.sh') shutil.copy2(orig, copy) if util.run_cmd(copy, directory=util.reltopdir('.')) != 0: print("Failed build_devrelease.sh") return False return True
def build_binaries(): """Run the build_binaries.sh script.""" print("Running build_binaries.sh") import shutil # copy the script as it changes git branch, which can change the script while running orig = util.reltopdir('Tools/scripts/build_binaries.sh') copy = util.reltopdir('./build_binaries.sh') shutil.copyfile(orig, copy) shutil.copymode(orig, copy) if util.run_cmd(copy, directory=util.reltopdir('.')) != 0: print("Failed build_binaries.sh") return False return True
def disable_option_in_config(self, var): tmpfile = util.reltopdir(self.config) + ".tmp" shutil.move(self.config, tmpfile) out_fd = open(self.config, 'w+') with open(util.reltopdir(tmpfile)) as fd: for line in fd: things_to_toggle = self.reverse_deps_for_var(var) things_to_toggle.append(var) for thing in things_to_toggle: line = re.sub( '//(#define\s+%s\s+(ENABLED|DISABLED))' % thing, "\\1", line) out_fd.write(line) out_fd.close()
def binary_path(step, debug=False): if step.find("ArduCopter") != -1: binary_name = "arducopter" elif step.find("ArduPlane") != -1: binary_name = "arduplane" elif step.find("APMrover2") != -1: binary_name = "ardurover" elif step.find("AntennaTracker") != -1: binary_name = "antennatracker" elif step.find("CopterAVC") != -1: binary_name = "arducopter-heli" elif step.find("QuadPlane") != -1: binary_name = "arduplane" else: # cope with builds that don't have a specific binary return None if debug: binary_basedir = "sitl-debug" else: binary_basedir = "sitl" binary = util.reltopdir(os.path.join('build', binary_basedir, 'bin', binary_name)) if not os.path.exists(binary): if os.path.exists(binary + ".exe"): binary += ".exe" else: raise ValueError("Binary (%s) does not exist" % (binary,)) return binary
def get_default_params(atype, binary): """Get default parameters.""" # use rover simulator so SITL is not starved of input from pymavlink import mavutil HOME = mavutil.location(40.071374969556928, -105.22978898137808, 1583.702759, 246) if binary.find("plane") != -1 or binary.find("rover") != -1: frame = "rover" else: frame = "+" home = "%f,%f,%u,%u" % (HOME.lat, HOME.lng, HOME.alt, HOME.heading) sitl = util.start_SITL(binary, wipe=True, model=frame, home=home, speedup=10, unhide_parameters=True) mavproxy = util.start_MAVProxy_SITL(atype) print("Dumping defaults") idx = mavproxy.expect(['Please Run Setup', 'Saved [0-9]+ parameters to (\S+)']) if idx == 0: # we need to restart it after eeprom erase util.pexpect_close(mavproxy) util.pexpect_close(sitl) sitl = util.start_SITL(binary, model=frame, home=home, speedup=10) mavproxy = util.start_MAVProxy_SITL(atype) idx = mavproxy.expect('Saved [0-9]+ parameters to (\S+)') parmfile = mavproxy.match.group(1) dest = util.reltopdir('../buildlogs/%s-defaults.parm' % atype) shutil.copy(parmfile, dest) util.pexpect_close(mavproxy) util.pexpect_close(sitl) print("Saved defaults for %s to %s" % (atype, dest)) return True
def binary_path(step, debug=False): try: vehicle = step.split(".")[1] except Exception: return None if vehicle in __bin_names: binary_name = __bin_names[vehicle] else: # cope with builds that don't have a specific binary return None if debug: binary_basedir = "sitl-debug" else: binary_basedir = "sitl" binary = util.reltopdir(os.path.join('build', binary_basedir, 'bin', binary_name)) if not os.path.exists(binary): if os.path.exists(binary + ".exe"): binary += ".exe" else: raise ValueError("Binary (%s) does not exist" % (binary,)) return binary
def build_parameters(): """Run the param_parse.py script.""" print("Running param_parse.py") if util.run_cmd(util.reltopdir('Tools/autotest/param_metadata/param_parse.py'), directory=util.reltopdir('.')) != 0: print("Failed param_parse.py") return False return True
def check_logs(step): """Check for log files from a step.""" print("check step: ", step) if step.startswith('fly.'): vehicle = step[4:] elif step.startswith('drive.'): vehicle = step[6:] else: return logs = glob.glob("logs/*.BIN") for log in logs: bname = os.path.basename(log) newname = buildlogs_path("%s-%s" % (vehicle, bname)) print("Renaming %s to %s" % (log, newname)) shutil.move(log, newname) corefile = "core" if os.path.exists(corefile): newname = buildlogs_path("%s.core" % vehicle) print("Renaming %s to %s" % (corefile, newname)) shutil.move(corefile, newname) try: util.run_cmd('/bin/cp build/sitl/bin/* %s' % buildlogs_dirpath(), directory=util.reltopdir('.')) except Exception: print("Unable to save binary")
def build_works(self): self.progress("Building") autotest = util.reltopdir("Tools/autotest/autotest.py") try: ret = util.run_cmd([autotest, self.autotest_build]) except subprocess.CalledProcessError: return False return ret == 0
def build_binaries(): """Run the build_binaries.py script.""" print("Running build_binaries.py") # copy the script as it changes git branch, which can change the script while running orig = util.reltopdir('Tools/scripts/build_binaries.py') copy = util.reltopdir('./build_binaries.py') shutil.copy2(orig, copy) # also copy generate_manifest library: orig_gm = util.reltopdir('Tools/scripts/generate_manifest.py') copy_gm = util.reltopdir('./generate_manifest.py') shutil.copy2(orig_gm, copy_gm) if util.run_cmd(copy, directory=util.reltopdir('.')) != 0: print("Failed build_binaries.py") return False return True
def __init__(self): self.date = time.asctime() self.githash = util.run_cmd('git rev-parse HEAD', output=True, directory=util.reltopdir('.')).strip() self.tests = [] self.files = [] self.images = []
def build_parameters(): """Run the param_parse.py script.""" print("Running param_parse.py") for vehicle in 'ArduPlane', 'ArduCopter', 'ArduSub', 'APMrover2', 'AntennaTracker': if util.run_cmd([util.reltopdir('Tools/autotest/param_metadata/param_parse.py'), '--vehicle', vehicle], directory=util.reltopdir('.')) != 0: print("Failed param_parse.py (%s)" % vehicle) return False return True
def get_config_variables(self): ret = [] with open(util.reltopdir(self.config)) as fd: for line in fd: match = re.match('//#define ([A-Z_]+)\s+(ENABLED|DISABLED)', line) if match is not None: ret.append(match.group(1)) return ret
def build_parameters(): """Run the param_parse.py script.""" print("Running param_parse.py") for vehicle in all_vehicles(): if util.run_cmd([param_parse_filepath(), '--vehicle', vehicle], directory=util.reltopdir('.')) != 0: print("Failed param_parse.py (%s)" % vehicle) return False return True
def get_config_variables(self): ret = [] r = '//#define ([A-Z_]+)\s+(ENABLED|DISABLED!HAL_MINIMIZE_FEATURES)' with open(util.reltopdir(self.config)) as fd: for line in fd: print("line: %s" % line) match = re.match(r, line) if match is not None: ret.append(match.group(1)) return ret
def check_logs(step): """Check for log files from a step.""" print("check step: ", step) if step.startswith('fly.'): vehicle = step[4:] elif step.startswith('drive.'): vehicle = step[6:] else: return logs = glob.glob("logs/*.BIN") for log in logs: bname = os.path.basename(log) newname = util.reltopdir("../buildlogs/%s-%s" % (vehicle, bname)) print("Renaming %s to %s" % (log, newname)) os.rename(log, newname) corefile = "core" if os.path.exists(corefile): newname = util.reltopdir("../buildlogs/%s.core" % vehicle) print("Renaming %s to %s" % (corefile, newname)) os.rename(corefile, newname) util.run_cmd('/bin/cp A*/A*.elf ../buildlogs', directory=util.reltopdir('.'))
def get_config_variables(self): ret = [] r = (' *# *define +([A-Z_]+)\s+' '(ENABLED|DISABLED|!HAL_MINIMIZE_FEATURES)') with open(util.reltopdir(self.config)) as fd: for line in fd: match = re.match(r, line) if match is None: continue if match.group(1) in ("ENABLE", "DISABLE", "!HAL_MINIMIZE_FEATURES"): continue ret.append( (match.group(1), match.group(2) )) return set(ret)
def run_unit_tests(): binary_dir = util.reltopdir(os.path.join('build', 'linux', 'tests', )) tests = glob.glob("%s/*" % binary_dir) success = True for test in tests: try: run_unit_test(test) except Exception as e: print("Exception running (%s): %s" % (test, e.message)) success = False return success
def disable_option_in_config(self, var): tmpfile = util.reltopdir(self.config) + ".tmp" shutil.move(self.config, tmpfile) with open(self.config, 'w+') as out_fd: with open(util.reltopdir(tmpfile)) as fd: did_enable = False for line in fd: regex = ' *# *define +%s\s+(ENABLED|DISABLED|!HAL_MINIMIZE_FEATURES)' % (var[0],) match = re.match(regex, line) if match is not None: if (match.group(1) in ["ENABLED", "!HAL_MINIMIZE_FEATURES"]): fnoo = "DISABLED" else: fnoo = "ENABLED" did_enable = True line = "#define %s %s\n" % (var[0], fnoo) out_fd.write(line) # turn dependencies on or off: tmpfile = util.reltopdir(self.config) + ".tmp-deps" shutil.move(self.config, tmpfile) with open(self.config, 'w+') as out_fd: with open(util.reltopdir(tmpfile)) as fd: for line in fd: things_to_toggle = self.reverse_deps_for_var(var[0]) for thing in things_to_toggle: regex = ' *# *define +%s\s+(ENABLED|DISABLED|!HAL_MINIMIZE_FEATURES)' % thing match = re.match(regex, line) if match is not None: if did_enable: fnoo = "ENABLED" else: fnoo = "DISABLED" line = "#define %s %s\n" % (thing, fnoo) out_fd.write(line)
def run_examples(debug=False, valgrind=False, gdb=False): dirpath = util.reltopdir(os.path.join('build', 'linux', 'examples')) skip = { "BARO_generic": "Most linux computers don't have baros...", } for afile in os.listdir(dirpath): if afile in skip: print("Skipping %s: %s" % (afile, skip[afile])) continue filepath = os.path.join(dirpath, afile) if not os.path.isfile(filepath): continue run_example(filepath, valgrind=valgrind, gdb=gdb) return True
def convert_gpx(): """Convert any tlog files to GPX and KML.""" mavlog = glob.glob(buildlogs_path("*.tlog")) passed = True for m in mavlog: util.run_cmd(util.reltopdir("modules/mavlink/pymavlink/tools/mavtogpx.py") + " --nofixcheck " + m) gpx = m + '.gpx' kml = m + '.kml' try: util.run_cmd('gpsbabel -i gpx -f %s -o kml,units=m,floating=1,extrude=1 -F %s' % (gpx, kml)) except CalledProcessError as e: passed = False try: util.run_cmd('zip %s.kmz %s.kml' % (m, m)) except CalledProcessError as e: passed = False util.run_cmd("mavflightview.py --imagefile=%s.png %s" % (m, m)) return passed
def generate_badge(self): """ Gets the badge template, populates and saves the result to buildlogs path. """ passed_tests = len([t for t in self.tests if "PASSED" in t.result]) total_tests = len(self.tests) badge_color = "#4c1" if passed_tests == total_tests else "#e05d44" badge_text = "{0}/{1}".format(passed_tests, total_tests) # Text length so it is not stretched by svg text_length = len(badge_text) * 70 # Load template file template_path = 'Tools/autotest/web/autotest-badge-template.svg' with open(util.reltopdir(template_path), "r") as f: template = f.read() # Add our results to the template badge = template.format(color=badge_color, text=badge_text, text_length=text_length) with open(buildlogs_path("autotest-badge.svg"), "w") as f: f.write(badge)
def drive_APMrover2(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame=None, params=None, gdbserver=False, speedup=10): """Drive APMrover2 in SITL. you can pass viewerip as an IP address to optionally send fg and mavproxy packets too for local viewing of the mission in real time """ global homeloc if frame is None: frame = 'rover' options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --streamrate=10' if viewerip: options += " --out=%s:14550" % viewerip if use_map: options += ' --map' home = "%f,%f,%u,%u" % (HOME.lat, HOME.lng, HOME.alt, HOME.heading) sitl = util.start_SITL(binary, wipe=True, model=frame, home=home, speedup=speedup) mavproxy = util.start_MAVProxy_SITL('APMrover2', options=options) print("WAITING FOR PARAMETERS") mavproxy.expect('Received [0-9]+ parameters') # setup test parameters if params is None: params = vinfo.options["APMrover2"]["frames"][frame][ "default_params_filename"] if not isinstance(params, list): params = [params] for x in params: mavproxy.send("param load %s\n" % os.path.join(testdir, x)) mavproxy.expect('Loaded [0-9]+ parameters') set_parameter(mavproxy, 'LOG_REPLAY', 1) set_parameter(mavproxy, 'LOG_DISARMED', 1) # restart with new parms util.pexpect_close(mavproxy) util.pexpect_close(sitl) sitl = util.start_SITL(binary, model='rover', home=home, speedup=speedup, valgrind=valgrind, gdb=gdb, gdbserver=gdbserver) mavproxy = util.start_MAVProxy_SITL('APMrover2', options=options) mavproxy.expect('Telemetry log: (\S+)') logfile = mavproxy.match.group(1) print("LOGFILE %s" % logfile) buildlog = util.reltopdir("../buildlogs/APMrover2-test.tlog") print("buildlog=%s" % buildlog) if os.path.exists(buildlog): os.unlink(buildlog) try: os.link(logfile, buildlog) except Exception: pass mavproxy.expect('Received [0-9]+ parameters') util.expect_setup_callback(mavproxy, expect_callback) expect_list_clear() expect_list_extend([sitl, mavproxy]) print("Started simulator") # get a mavlink connection going try: mav = mavutil.mavlink_connection('127.0.0.1:19550', robust_parsing=True) except Exception as msg: print("Failed to start mavlink connection on 127.0.0.1:19550" % msg) raise mav.message_hooks.append(message_hook) mav.idle_hooks.append(idle_hook) failed = False e = 'None' try: print("Waiting for a heartbeat with mavlink protocol %s" % mav.WIRE_PROTOCOL_VERSION) mav.wait_heartbeat() print("Setting up RC parameters") setup_rc(mavproxy) print("Waiting for GPS fix") mav.wait_gps_fix() homeloc = mav.location() print("Home location: %s" % homeloc) if not arm_rover(mavproxy, mav): print("Failed to ARM") failed = True if not drive_mission(mavproxy, mav, os.path.join( testdir, "rover1.txt")): print("Failed mission") failed = True if not drive_brake(mavproxy, mav): print("Failed brake") failed = True if not disarm_rover(mavproxy, mav): print("Failed to DISARM") failed = True if not log_download(mavproxy, mav, util.reltopdir("../buildlogs/APMrover2-log.bin")): print("Failed log download") failed = True # if not drive_left_circuit(mavproxy, mav): # print("Failed left circuit") # failed = True # if not drive_RTL(mavproxy, mav): # print("Failed RTL") # failed = True # do not move this to be the first test. MAVProxy's dedupe # function may bite you. print("Getting banner") if not do_get_banner(mavproxy, mav): print("FAILED: get banner") failed = True print("Getting autopilot capabilities") if not do_get_autopilot_capabilities(mavproxy, mav): print("FAILED: get capabilities") failed = True print("Setting mode via MAV_COMMAND_DO_SET_MODE") if not do_set_mode_via_command_long(mavproxy, mav): failed = True except pexpect.TIMEOUT as e: print("Failed with timeout") failed = True mav.close() util.pexpect_close(mavproxy) util.pexpect_close(sitl) valgrind_log = util.valgrind_log_filepath(binary=binary, model='rover') if os.path.exists(valgrind_log): os.chmod(valgrind_log, 0o644) shutil.copy(valgrind_log, util.reltopdir("../buildlogs/APMrover2-valgrind.log")) if failed: print("FAILED: %s" % e) return False return True
def build_all_filepath(): """Get build_all.sh path.""" return util.reltopdir('Tools/scripts/build_all.sh')
def buildlogs_dirpath(): return os.getenv("BUILDLOGS", util.reltopdir("../buildlogs"))
def init(self): if self.frame is None: self.frame = 'vectored' if self.viewerip: self.options += " --out=%s:14550" % self.viewerip if self.use_map: self.options += ' --map' self.sitl = util.start_SITL(self.binary, wipe=True, model=self.frame, home=self.home, speedup=self.speedup_default) self.mavproxy = util.start_MAVProxy_SITL('ArduSub') self.progress("WAITING FOR PARAMETERS") self.mavproxy.expect('Received [0-9]+ parameters') # setup test parameters vinfo = vehicleinfo.VehicleInfo() if self.params is None: frames = vinfo.options["ArduSub"]["frames"] self.params = frames[self.frame]["default_params_filename"] if not isinstance(self.params, list): self.params = [self.params] for x in self.params: self.mavproxy.send("param load %s\n" % os.path.join(testdir, x)) self.mavproxy.expect('Loaded [0-9]+ parameters') self.set_parameter('LOG_REPLAY', 1) self.set_parameter('LOG_DISARMED', 1) self.progress("RELOADING SITL WITH NEW PARAMETERS") # restart with new parms util.pexpect_close(self.mavproxy) util.pexpect_close(self.sitl) self.sitl = util.start_SITL(self.binary, model=self.frame, home=self.home, speedup=self.speedup, valgrind=self.valgrind, gdb=self.gdb, gdbserver=self.gdbserver) self.mavproxy = util.start_MAVProxy_SITL('ArduSub', options=self.options) self.mavproxy.expect('Telemetry log: (\S+)') logfile = self.mavproxy.match.group(1) self.progress("LOGFILE %s" % logfile) buildlog = util.reltopdir("../buildlogs/ArduSub-test.tlog") self.progress("buildlog=%s" % buildlog) if os.path.exists(buildlog): os.unlink(buildlog) try: os.link(logfile, buildlog) except Exception: pass self.mavproxy.expect('Received [0-9]+ parameters') util.expect_setup_callback(self.mavproxy, self.expect_callback) self.expect_list_clear() self.expect_list_extend([self.sitl, self.mavproxy]) self.progress("Started simulator") # get a mavlink connection going connection_string = '127.0.0.1:19550' try: self.mav = mavutil.mavlink_connection(connection_string, robust_parsing=True) except Exception as msg: self.progress("Failed to start mavlink connection on %s: %s" % (connection_string, msg,)) raise self.mav.message_hooks.append(self.message_hook) self.mav.idle_hooks.append(self.idle_hook) self.hasInit = True self.progress("Ready to start testing!")
def drive_APMrover2(binary, viewerip=None, use_map=False, valgrind=False, gdb=False): """Drive APMrover2 in SITL. you can pass viewerip as an IP address to optionally send fg and mavproxy packets too for local viewing of the mission in real time """ global homeloc options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --streamrate=10' if viewerip: options += " --out=%s:14550" % viewerip if use_map: options += ' --map' home = "%f,%f,%u,%u" % (HOME.lat, HOME.lng, HOME.alt, HOME.heading) sitl = util.start_SITL(binary, wipe=True, model='rover', home=home, speedup=10) mavproxy = util.start_MAVProxy_SITL('APMrover2', options=options) print("WAITING FOR PARAMETERS") mavproxy.expect('Received [0-9]+ parameters') # setup test parameters mavproxy.send("param load %s/default_params/rover.parm\n" % testdir) mavproxy.expect('Loaded [0-9]+ parameters') mavproxy.send("param set LOG_REPLAY 1\n") mavproxy.send("param set LOG_DISARMED 1\n") time.sleep(3) # restart with new parms util.pexpect_close(mavproxy) util.pexpect_close(sitl) sitl = util.start_SITL(binary, model='rover', home=home, speedup=10, valgrind=valgrind, gdb=gdb) mavproxy = util.start_MAVProxy_SITL('APMrover2', options=options) mavproxy.expect('Telemetry log: (\S+)') logfile = mavproxy.match.group(1) print("LOGFILE %s" % logfile) buildlog = util.reltopdir("../buildlogs/APMrover2-test.tlog") print("buildlog=%s" % buildlog) if os.path.exists(buildlog): os.unlink(buildlog) try: os.link(logfile, buildlog) except Exception: pass mavproxy.expect('Received [0-9]+ parameters') util.expect_setup_callback(mavproxy, expect_callback) expect_list_clear() expect_list_extend([sitl, mavproxy]) print("Started simulator") # get a mavlink connection going try: mav = mavutil.mavlink_connection('127.0.0.1:19550', robust_parsing=True) except Exception as msg: print("Failed to start mavlink connection on 127.0.0.1:19550" % msg) raise mav.message_hooks.append(message_hook) mav.idle_hooks.append(idle_hook) failed = False e = 'None' try: print("Waiting for a heartbeat with mavlink protocol %s" % mav.WIRE_PROTOCOL_VERSION) mav.wait_heartbeat() print("Setting up RC parameters") setup_rc(mavproxy) print("Waiting for GPS fix") mav.wait_gps_fix() homeloc = mav.location() print("Home location: %s" % homeloc) if not arm_rover(mavproxy, mav): print("Failed to ARM") failed = True if not drive_mission(mavproxy, mav, os.path.join( testdir, "rover1.txt")): print("Failed mission") failed = True if not log_download(mavproxy, mav, util.reltopdir("../buildlogs/APMrover2-log.bin")): print("Failed log download") failed = True # if not drive_left_circuit(mavproxy, mav): # print("Failed left circuit") # failed = True # if not drive_RTL(mavproxy, mav): # print("Failed RTL") # failed = True except pexpect.TIMEOUT as e: print("Failed with timeout") failed = True mav.close() util.pexpect_close(mavproxy) util.pexpect_close(sitl) valgrind_log = util.valgrind_log_filepath(binary=binary, model='rover') if os.path.exists(valgrind_log): os.chmod(valgrind_log, 0o644) shutil.copy(valgrind_log, util.reltopdir("../buildlogs/APMrover2-valgrind.log")) if failed: print("FAILED: %s" % e) return False return True
def build_all_filepath(): return util.reltopdir('Tools/scripts/build_all.sh')
def dive_ArduSub(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, gdbserver=False, speedup=10): """Dive ArduSub in SITL. you can pass viewerip as an IP address to optionally send fg and mavproxy packets too for local viewing of the mission in real time """ options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --streamrate=10' if viewerip: options += " --out=%s:14550" % viewerip if use_map: options += ' --map' home = "%f,%f,%u,%u" % (HOME.lat, HOME.lng, HOME.alt, HOME.heading) sitl = util.start_SITL(binary, model='vectored', wipe=True, home=home, speedup=speedup) mavproxy = util.start_MAVProxy_SITL('ArduSub', options=options) mavproxy.expect('Received [0-9]+ parameters') # setup test parameters mavproxy.send("param load %s/default_params/sub.parm\n" % testdir) mavproxy.expect('Loaded [0-9]+ parameters') mavproxy.send('param set FS_GCS_ENABLE 0\n') mavproxy.send("param set LOG_REPLAY 1\n") mavproxy.send("param set LOG_DISARMED 1\n") time.sleep(3) # reboot with new parameters util.pexpect_close(mavproxy) util.pexpect_close(sitl) sitl = util.start_SITL(binary, model='vectored', home=home, speedup=speedup, valgrind=valgrind, gdb=gdb, gdbserver=gdbserver) mavproxy = util.start_MAVProxy_SITL('ArduSub', options=options) mavproxy.expect('Telemetry log: (\S+)') logfile = mavproxy.match.group(1) progress("LOGFILE %s" % logfile) buildlog = util.reltopdir("../buildlogs/ArduSub-test.tlog") progress("buildlog=%s" % buildlog) if os.path.exists(buildlog): os.unlink(buildlog) try: os.link(logfile, buildlog) except Exception: pass mavproxy.expect('Received [0-9]+ parameters') util.expect_setup_callback(mavproxy, expect_callback) expect_list_clear() expect_list_extend([sitl, mavproxy]) progress("Started simulator") # get a mavlink connection going try: mav = mavutil.mavlink_connection('127.0.0.1:19550', robust_parsing=True) except Exception as msg: progress("Failed to start mavlink connection on 127.0.0.1:19550" % msg) raise mav.message_hooks.append(message_hook) mav.idle_hooks.append(idle_hook) failed = False e = 'None' try: progress("Waiting for a heartbeat with mavlink protocol %s" % mav.WIRE_PROTOCOL_VERSION) mav.wait_heartbeat() progress("Waiting for GPS fix") mav.wait_gps_fix() # wait for EKF and GPS checks to pass mavproxy.expect('IMU0 is using GPS') homeloc = mav.location() progress("Home location: %s" % homeloc) if not arm_sub(mavproxy, mav): progress("Failed to ARM") failed = True if not dive_manual(mavproxy, mav): progress("Failed manual dive") failed = True if not dive_mission(mavproxy, mav, os.path.join(testdir, "sub_mission.txt")): progress("Failed auto mission") failed = True if not log_download(mavproxy, mav, util.reltopdir("../buildlogs/ArduSub-log.bin")): progress("Failed log download") failed = True except pexpect.TIMEOUT as e: progress("Failed with timeout") failed = True mav.close() util.pexpect_close(mavproxy) util.pexpect_close(sitl) valgrind_log = util.valgrind_log_filepath(binary=binary, model='sub') if os.path.exists(valgrind_log): os.chmod(valgrind_log, 0o644) shutil.copy(valgrind_log, util.reltopdir("../buildlogs/APMrover2-valgrind.log")) if failed: progress("FAILED: %s" % e) return False return True
def mavtogpx_filepath(): """Get mavtogpx script path.""" return util.reltopdir("modules/mavlink/pymavlink/tools/mavtogpx.py")
def buildlogs_dirpath(): """Return BUILDLOGS directory path.""" return os.getenv("BUILDLOGS", util.reltopdir("../buildlogs"))
import os import shutil import signal import sys import time import traceback import apmrover2 import arducopter import arduplane import quadplane from pysim import util os.environ['PYTHONUNBUFFERED'] = '1' os.putenv('TMPDIR', util.reltopdir('tmp')) def get_default_params(atype, binary): """Get default parameters.""" # use rover simulator so SITL is not starved of input from pymavlink import mavutil HOME = mavutil.location(40.071374969556928, -105.22978898137808, 1583.702759, 246) if binary.find("plane") != -1 or binary.find("rover") != -1: frame = "rover" else: frame = "+" home = "%f,%f,%u,%u" % (HOME.lat, HOME.lng, HOME.alt, HOME.heading)
def fly_CopterAVC(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame=None, params=None): """Fly ArduCopter in SITL for AVC2013 mission.""" global homeloc if frame is None: frame = 'heli' home = "%f,%f,%u,%u" % (AVCHOME.lat, AVCHOME.lng, AVCHOME.alt, AVCHOME.heading) sitl = util.start_SITL(binary, wipe=True, model=frame, home=home, speedup=speedup_default) mavproxy = util.start_MAVProxy_SITL( 'ArduCopter', options='--sitl=127.0.0.1:5501 --out=127.0.0.1:19550') mavproxy.expect('Received [0-9]+ parameters') # setup test parameters if params is None: params = vinfo.options["ArduCopter"]["frames"][frame][ "default_params_filename"] if not isinstance(params, list): params = [params] for x in params: mavproxy.send("param load %s\n" % os.path.join(testdir, x)) mavproxy.expect('Loaded [0-9]+ parameters') mavproxy.send("param set LOG_REPLAY 1\n") mavproxy.send("param set LOG_DISARMED 1\n") time.sleep(3) # reboot with new parameters util.pexpect_close(mavproxy) util.pexpect_close(sitl) sitl = util.start_SITL(binary, model='heli', home=home, speedup=speedup_default, valgrind=valgrind, gdb=gdb) options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --streamrate=5' if viewerip: options += ' --out=%s:14550' % viewerip if use_map: options += ' --map' mavproxy = util.start_MAVProxy_SITL('ArduCopter', options=options) mavproxy.expect('Telemetry log: (\S+)') logfile = mavproxy.match.group(1) print("LOGFILE %s" % logfile) buildlog = util.reltopdir("../buildlogs/CopterAVC-test.tlog") print("buildlog=%s" % buildlog) if os.path.exists(buildlog): os.unlink(buildlog) try: os.link(logfile, buildlog) except Exception: pass # the received parameters can come before or after the ready to fly message mavproxy.expect(['Received [0-9]+ parameters', 'Ready to FLY']) mavproxy.expect(['Received [0-9]+ parameters', 'Ready to FLY']) util.expect_setup_callback(mavproxy, expect_callback) expect_list_clear() expect_list_extend([sitl, mavproxy]) if use_map: mavproxy.send('map icon 40.072467969730496 -105.2314389590174\n') mavproxy.send('map icon 40.072600990533829 -105.23146100342274\n') # get a mavlink connection going try: mav = mavutil.mavlink_connection('127.0.0.1:19550', robust_parsing=True) except Exception as msg: print("Failed to start mavlink connection on 127.0.0.1:19550" % msg) raise mav.message_hooks.append(message_hook) mav.idle_hooks.append(idle_hook) failed = False failed_test_msg = "None" try: mav.wait_heartbeat() setup_rc(mavproxy) homeloc = mav.location() print("Lowering rotor speed") mavproxy.send('rc 8 1000\n') wait_ready_to_arm(mavproxy) # Arm print("# Arm motors") if not arm_motors(mavproxy, mav): failed_test_msg = "arm_motors failed" print(failed_test_msg) failed = True print("Raising rotor speed") mavproxy.send('rc 8 2000\n') print("# Fly AVC mission") if not fly_avc_test(mavproxy, mav): failed_test_msg = "fly_avc_test failed" print(failed_test_msg) failed = True else: print("Flew AVC mission OK") print("Lowering rotor speed") mavproxy.send('rc 8 1000\n') # mission includes disarm at end so should be ok to download logs now if not log_download(mavproxy, mav, util.reltopdir("../buildlogs/CopterAVC-log.bin")): failed_test_msg = "log_download failed" print(failed_test_msg) failed = True except pexpect.TIMEOUT as failed_test_msg: failed_test_msg = "Timeout" failed = True mav.close() util.pexpect_close(mavproxy) util.pexpect_close(sitl) valgrind_log = util.valgrind_log_filepath(binary=binary, model='heli') if os.path.exists(valgrind_log): os.chmod(valgrind_log, 0o644) shutil.copy(valgrind_log, util.reltopdir("../buildlogs/Helicopter-valgrind.log")) if failed: print("FAILED: %s" % failed_test_msg) return False return True
def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame=None, params=None): """Fly ArduCopter in SITL. you can pass viewerip as an IP address to optionally send fg and mavproxy packets too for local viewing of the flight in real time """ global homeloc if frame is None: frame = '+' home = "%f,%f,%u,%u" % (HOME.lat, HOME.lng, HOME.alt, HOME.heading) sitl = util.start_SITL(binary, wipe=True, model=frame, home=home, speedup=speedup_default) mavproxy = util.start_MAVProxy_SITL( 'ArduCopter', options='--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter') mavproxy.expect('Received [0-9]+ parameters') # setup test parameters if params is None: params = vinfo.options["ArduCopter"]["frames"][frame][ "default_params_filename"] if not isinstance(params, list): params = [params] for x in params: mavproxy.send("param load %s\n" % os.path.join(testdir, x)) mavproxy.expect('Loaded [0-9]+ parameters') mavproxy.send("param set LOG_REPLAY 1\n") mavproxy.send("param set LOG_DISARMED 1\n") time.sleep(3) # reboot with new parameters util.pexpect_close(mavproxy) util.pexpect_close(sitl) sitl = util.start_SITL(binary, model=frame, home=home, speedup=speedup_default, valgrind=valgrind, gdb=gdb) options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=5' if viewerip: options += ' --out=%s:14550' % viewerip if use_map: options += ' --map' mavproxy = util.start_MAVProxy_SITL('ArduCopter', options=options) mavproxy.expect('Telemetry log: (\S+)') logfile = mavproxy.match.group(1) print("LOGFILE %s" % logfile) buildlog = util.reltopdir("../buildlogs/ArduCopter-test.tlog") print("buildlog=%s" % buildlog) copy_tlog = False if os.path.exists(buildlog): os.unlink(buildlog) try: os.link(logfile, buildlog) except Exception: print("WARN: Failed to create symlink: " + logfile + " => " + buildlog + ", Will copy tlog manually to target location") copy_tlog = True # the received parameters can come before or after the ready to fly message mavproxy.expect(['Received [0-9]+ parameters', 'Ready to FLY']) mavproxy.expect(['Received [0-9]+ parameters', 'Ready to FLY']) util.expect_setup_callback(mavproxy, expect_callback) expect_list_clear() expect_list_extend([sitl, mavproxy]) # get a mavlink connection going try: mav = mavutil.mavlink_connection('127.0.0.1:19550', robust_parsing=True) except Exception as msg: print("Failed to start mavlink connection on 127.0.0.1:19550" % msg) raise mav.message_hooks.append(message_hook) mav.idle_hooks.append(idle_hook) failed = False failed_test_msg = "None" try: mav.wait_heartbeat() setup_rc(mavproxy) homeloc = mav.location() wait_ready_to_arm(mavproxy) # Arm print("# Arm motors") if not arm_motors(mavproxy, mav): failed_test_msg = "arm_motors failed" print(failed_test_msg) failed = True print("# Takeoff") if not takeoff(mavproxy, mav, 10): failed_test_msg = "takeoff failed" print(failed_test_msg) failed = True # Fly a square in Stabilize mode print("#") print( "########## Fly a square and save WPs with CH7 switch ##########") print("#") if not fly_square(mavproxy, mav): failed_test_msg = "fly_square failed" print(failed_test_msg) failed = True # save the stored mission to file print("# Save out the CH7 mission to file") if not save_mission_to_file(mavproxy, mav, os.path.join(testdir, "ch7_mission.txt")): failed_test_msg = "save_mission_to_file failed" print(failed_test_msg) failed = True # fly the stored mission print("# Fly CH7 saved mission") if not fly_mission( mavproxy, mav, height_accuracy=0.5, target_altitude=10): failed_test_msg = "fly ch7_mission failed" print(failed_test_msg) failed = True # Throttle Failsafe print("#") print("########## Test Failsafe ##########") print("#") if not fly_throttle_failsafe(mavproxy, mav): failed_test_msg = "fly_throttle_failsafe failed" print(failed_test_msg) failed = True # Takeoff print("# Takeoff") if not takeoff(mavproxy, mav, 10): failed_test_msg = "takeoff failed" print(failed_test_msg) failed = True # Battery failsafe if not fly_battery_failsafe(mavproxy, mav): failed_test_msg = "fly_battery_failsafe failed" print(failed_test_msg) failed = True # Takeoff print("# Takeoff") if not takeoff(mavproxy, mav, 10): failed_test_msg = "takeoff failed" print(failed_test_msg) failed = True # Stability patch print("#") print("########## Test Stability Patch ##########") print("#") if not fly_stability_patch(mavproxy, mav, 30): failed_test_msg = "fly_stability_patch failed" print(failed_test_msg) failed = True # RTL print("# RTL #") if not fly_RTL(mavproxy, mav): failed_test_msg = "fly_RTL after stab patch failed" print(failed_test_msg) failed = True # Takeoff print("# Takeoff") if not takeoff(mavproxy, mav, 10): failed_test_msg = "takeoff failed" print(failed_test_msg) failed = True # Fence test print("#") print("########## Test Horizontal Fence ##########") print("#") if not fly_fence_test(mavproxy, mav, 180): failed_test_msg = "fly_fence_test failed" print(failed_test_msg) failed = True # Takeoff print("# Takeoff") if not takeoff(mavproxy, mav, 10): failed_test_msg = "takeoff failed" print(failed_test_msg) failed = True # Fly GPS Glitch Loiter test print("# GPS Glitch Loiter Test") if not fly_gps_glitch_loiter_test(mavproxy, mav, use_map): failed_test_msg = "fly_gps_glitch_loiter_test failed" print(failed_test_msg) failed = True # RTL after GPS Glitch Loiter test print("# RTL #") if not fly_RTL(mavproxy, mav): failed_test_msg = "fly_RTL failed" print(failed_test_msg) failed = True # Fly GPS Glitch test in auto mode print("# GPS Glitch Auto Test") if not fly_gps_glitch_auto_test(mavproxy, mav, use_map): failed_test_msg = "fly_gps_glitch_auto_test failed" print(failed_test_msg) failed = True # take-off ahead of next test print("# Takeoff") if not takeoff(mavproxy, mav, 10): failed_test_msg = "takeoff failed" print(failed_test_msg) failed = True # Loiter for 10 seconds print("#") print("########## Test Loiter for 10 seconds ##########") print("#") if not loiter(mavproxy, mav): failed_test_msg = "loiter failed" print(failed_test_msg) failed = True # Loiter Climb print("#") print("# Loiter - climb to 30m") print("#") if not change_alt(mavproxy, mav, 30): failed_test_msg = "change_alt climb failed" print(failed_test_msg) failed = True # Loiter Descend print("#") print("# Loiter - descend to 20m") print("#") if not change_alt(mavproxy, mav, 20): failed_test_msg = "change_alt descend failed" print(failed_test_msg) failed = True # RTL print("#") print("########## Test RTL ##########") print("#") if not fly_RTL(mavproxy, mav): failed_test_msg = "fly_RTL after Loiter climb/descend failed" print(failed_test_msg) failed = True # Takeoff print("# Takeoff") if not takeoff(mavproxy, mav, 10): failed_test_msg = "takeoff failed" print(failed_test_msg) failed = True # Simple mode print("# Fly in SIMPLE mode") if not fly_simple(mavproxy, mav): failed_test_msg = "fly_simple failed" print(failed_test_msg) failed = True # RTL print("#") print("########## Test RTL ##########") print("#") if not fly_RTL(mavproxy, mav): failed_test_msg = "fly_RTL after simple mode failed" print(failed_test_msg) failed = True # Takeoff print("# Takeoff") if not takeoff(mavproxy, mav, 10): failed_test_msg = "takeoff failed" print(failed_test_msg) failed = True # Fly a circle in super simple mode print("# Fly a circle in SUPER SIMPLE mode") if not fly_super_simple(mavproxy, mav): failed_test_msg = "fly_super_simple failed" print(failed_test_msg) failed = True # RTL print("# RTL #") if not fly_RTL(mavproxy, mav): failed_test_msg = "fly_RTL after super simple mode failed" print(failed_test_msg) failed = True # Takeoff print("# Takeoff") if not takeoff(mavproxy, mav, 10): failed_test_msg = "takeoff failed" print(failed_test_msg) failed = True # Circle mode print("# Fly CIRCLE mode") if not fly_circle(mavproxy, mav): failed_test_msg = "fly_circle failed" print(failed_test_msg) failed = True # RTL print("#") print("########## Test RTL ##########") print("#") if not fly_RTL(mavproxy, mav): failed_test_msg = "fly_RTL after circle failed" print(failed_test_msg) failed = True print("# Fly copter mission") if not fly_auto_test(mavproxy, mav): failed_test_msg = "fly_auto_test failed" print(failed_test_msg) failed = True else: print("Flew copter mission OK") # wait for disarm mav.motors_disarmed_wait() if not log_download(mavproxy, mav, util.reltopdir("../buildlogs/ArduCopter-log.bin")): failed_test_msg = "log_download failed" print(failed_test_msg) failed = True except pexpect.TIMEOUT as failed_test_msg: failed_test_msg = "Timeout" failed = True mav.close() util.pexpect_close(mavproxy) util.pexpect_close(sitl) valgrind_log = util.valgrind_log_filepath(binary=binary, model='+') if os.path.exists(valgrind_log): os.chmod(valgrind_log, 0o644) shutil.copy(valgrind_log, util.reltopdir("../buildlogs/ArduCopter-valgrind.log")) # [2014/05/07] FC Because I'm doing a cross machine build (source is on host, build is on guest VM) I cannot hard link # This flag tells me that I need to copy the data out if copy_tlog: shutil.copy(logfile, buildlog) if failed: print("FAILED: %s" % failed_test_msg) return False return True
(desc, exception, debug_filename)) print("FAILED %u tests: %s" % (len(failed), failed)) util.pexpect_close_all() write_fullresults() return passed if __name__ == "__main__": ''' main program ''' os.environ['PYTHONUNBUFFERED'] = '1' os.putenv('TMPDIR', util.reltopdir('tmp')) parser = optparse.OptionParser("autotest") parser.add_option("--skip", type='string', default='', help='list of steps to skip (comma separated)') parser.add_option("--list", action='store_true', default=False, help='list the available steps') parser.add_option("--viewerip", default=None, help='IP address to send MAVLink and fg packets to') parser.add_option("--map", action='store_true',
def backup_config_filepath(self): return util.reltopdir(self.config) + ".backup"
def param_parse_filepath(): return util.reltopdir('Tools/autotest/param_metadata/param_parse.py')
def fly_QuadPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, gdbserver=False, speedup=10): """Fly QuadPlane in SITL. you can pass viewerip as an IP address to optionally send fg and mavproxy packets too for local viewing of the flight in real time. """ global homeloc options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --streamrate=10' if viewerip: options += " --out=%s:14550" % viewerip if use_map: options += ' --map' sitl = util.start_SITL(binary, model='quadplane', wipe=True, home=HOME_LOCATION, speedup=speedup, defaults_file=os.path.join( testdir, 'default_params/quadplane.parm'), valgrind=valgrind, gdb=gdb, gdbserver=gdbserver) mavproxy = util.start_MAVProxy_SITL('QuadPlane', options=options) mavproxy.expect('Telemetry log: (\S+)') logfile = mavproxy.match.group(1) progress("LOGFILE %s" % logfile) buildlog = util.reltopdir("../buildlogs/QuadPlane-test.tlog") progress("buildlog=%s" % buildlog) if os.path.exists(buildlog): os.unlink(buildlog) try: os.link(logfile, buildlog) except Exception: pass util.expect_setup_callback(mavproxy, expect_callback) mavproxy.expect('Received [0-9]+ parameters') expect_list_clear() expect_list_extend([sitl, mavproxy]) progress("Started simulator") # get a mavlink connection going try: mav = mavutil.mavlink_connection('127.0.0.1:19550', robust_parsing=True) except Exception as msg: progress("Failed to start mavlink connection on 127.0.0.1:19550" % msg) raise mav.message_hooks.append(message_hook) mav.idle_hooks.append(idle_hook) failed = False e = 'None' try: progress("Waiting for a heartbeat with mavlink protocol %s" % mav.WIRE_PROTOCOL_VERSION) mav.wait_heartbeat() progress("Waiting for GPS fix") mav.recv_match(condition='VFR_HUD.alt>10', blocking=True) mav.wait_gps_fix() while mav.location().alt < 10: mav.wait_gps_fix() homeloc = mav.location() progress("Home location: %s" % homeloc) # wait for EKF and GPS checks to pass wait_seconds(mav, 30) mavproxy.send('arm throttle\n') mavproxy.expect('ARMED') if not fly_mission( mavproxy, mav, os.path.join(testdir, "ArduPlane-Missions/Dalby-OBC2016.txt"), os.path.join(testdir, "ArduPlane-Missions/Dalby-OBC2016-fence.txt")): progress("Failed mission") failed = True except pexpect.TIMEOUT as e: progress("Failed with timeout") failed = True mav.close() util.pexpect_close(mavproxy) util.pexpect_close(sitl) valgrind_log = util.valgrind_log_filepath(binary=binary, model='quadplane') if os.path.exists(valgrind_log): os.chmod(valgrind_log, 0o644) shutil.copy(valgrind_log, util.reltopdir("../buildlogs/QuadPlane-valgrind.log")) if failed: progress("FAILED: %s" % e) return False return True
def mavtogpx_filepath(): return util.reltopdir("modules/mavlink/pymavlink/tools/mavtogpx.py")
results.add(step, '<span class="failed-text">FAILED</span>', time.time() - t1) check_logs(step) if not passed: print("FAILED %u tests: %s" % (len(failed), failed)) util.pexpect_close_all() write_fullresults() return passed if __name__ == "__main__": ############## main program ############# os.environ['PYTHONUNBUFFERED'] = '1' os.putenv('TMPDIR', util.reltopdir('tmp')) parser = optparse.OptionParser("autotest") parser.add_option("--skip", type='string', default='', help='list of steps to skip (comma separated)') parser.add_option("--list", action='store_true', default=False, help='list the available steps') parser.add_option("--viewerip", default=None, help='IP address to send MAVLink and fg packets to') parser.add_option("--map", action='store_true', default=False, help='show map') parser.add_option("--experimental", default=False, action='store_true', help='enable experimental tests') parser.add_option("--timeout", default=3000, type='int', help='maximum runtime in seconds') parser.add_option("--frame", type='string', default=None, help='specify frame type') group_build = optparse.OptionGroup(parser, "Build options") group_build.add_option("--no-configure", default=False, action='store_true', help='do not configure before building', dest="no_configure") group_build.add_option("-j", default=None, type='int', help='build CPUs') group_build.add_option("--no-clean", default=False,
def param_parse_filepath(): """Get param_parse.py script path.""" return util.reltopdir('Tools/autotest/param_metadata/param_parse.py')
def fly_ArduPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=False): """Fly ArduPlane in SITL. you can pass viewerip as an IP address to optionally send fg and mavproxy packets too for local viewing of the flight in real time """ global homeloc options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --streamrate=10' if viewerip: options += " --out=%s:14550" % viewerip if use_map: options += ' --map' sitl = util.start_SITL(binary, model='plane-elevrev', home=HOME_LOCATION, speedup=10, valgrind=valgrind, gdb=gdb, defaults_file=os.path.join( testdir, 'default_params/plane-jsbsim.parm')) mavproxy = util.start_MAVProxy_SITL('ArduPlane', options=options) mavproxy.expect('Telemetry log: (\S+)') logfile = mavproxy.match.group(1) print("LOGFILE %s" % logfile) buildlog = util.reltopdir("../buildlogs/ArduPlane-test.tlog") print("buildlog=%s" % buildlog) if os.path.exists(buildlog): os.unlink(buildlog) try: os.link(logfile, buildlog) except Exception: pass util.expect_setup_callback(mavproxy, expect_callback) mavproxy.expect('Received [0-9]+ parameters') expect_list_clear() expect_list_extend([sitl, mavproxy]) print("Started simulator") # get a mavlink connection going try: mav = mavutil.mavlink_connection('127.0.0.1:19550', robust_parsing=True) except Exception as msg: print("Failed to start mavlink connection on 127.0.0.1:19550" % msg) raise mav.message_hooks.append(message_hook) mav.idle_hooks.append(idle_hook) failed = False fail_list = [] e = 'None' try: print("Waiting for a heartbeat with mavlink protocol %s" % mav.WIRE_PROTOCOL_VERSION) mav.wait_heartbeat() print("Setting up RC parameters") setup_rc(mavproxy) print("Waiting for GPS fix") mav.recv_match(condition='VFR_HUD.alt>10', blocking=True) mav.wait_gps_fix() while mav.location().alt < 10: mav.wait_gps_fix() homeloc = mav.location() print("Home location: %s" % homeloc) if not takeoff(mavproxy, mav): print("Failed takeoff") failed = True fail_list.append("takeoff") if not fly_left_circuit(mavproxy, mav): print("Failed left circuit") failed = True fail_list.append("left_circuit") if not axial_left_roll(mavproxy, mav, 1): print("Failed left roll") failed = True fail_list.append("left_roll") if not inside_loop(mavproxy, mav): print("Failed inside loop") failed = True fail_list.append("inside_loop") if not test_stabilize(mavproxy, mav): print("Failed stabilize test") failed = True fail_list.append("stabilize") if not test_acro(mavproxy, mav): print("Failed ACRO test") failed = True fail_list.append("acro") if not test_FBWB(mavproxy, mav): print("Failed FBWB test") failed = True fail_list.append("fbwb") if not test_FBWB(mavproxy, mav, mode='CRUISE'): print("Failed CRUISE test") failed = True fail_list.append("cruise") if not fly_RTL(mavproxy, mav): print("Failed RTL") failed = True fail_list.append("RTL") if not fly_LOITER(mavproxy, mav): print("Failed LOITER") failed = True fail_list.append("LOITER") if not fly_CIRCLE(mavproxy, mav): print("Failed CIRCLE") failed = True fail_list.append("LOITER") if not fly_mission(mavproxy, mav, os.path.join(testdir, "ap1.txt"), height_accuracy=10, target_altitude=homeloc.alt + 100): print("Failed mission") failed = True fail_list.append("mission") if not log_download(mavproxy, mav, util.reltopdir("../buildlogs/ArduPlane-log.bin")): print("Failed log download") failed = True fail_list.append("log_download") except pexpect.TIMEOUT as e: print("Failed with timeout") failed = True fail_list.append("timeout") mav.close() util.pexpect_close(mavproxy) util.pexpect_close(sitl) valgrind_log = util.valgrind_log_filepath(binary=binary, model='plane-elevrev') if os.path.exists(valgrind_log): os.chmod(valgrind_log, 0o644) shutil.copy(valgrind_log, util.reltopdir("../buildlogs/ArduPlane-valgrind.log")) if failed: print("FAILED: %s" % e, fail_list) return False return True
def fly_QuadPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=False): """Fly QuadPlane in SITL. you can pass viewerip as an IP address to optionally send fg and mavproxy packets too for local viewing of the flight in real time. """ global homeloc options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --streamrate=10' if viewerip: options += " --out=%s:14550" % viewerip if use_map: options += ' --map' sitl = util.start_SITL(binary, model='quadplane', wipe=True, home=HOME_LOCATION, speedup=10, defaults_file=os.path.join(testdir, 'default_params/quadplane.parm'), valgrind=valgrind, gdb=gdb) mavproxy = util.start_MAVProxy_SITL('QuadPlane', options=options) mavproxy.expect('Telemetry log: (\S+)') logfile = mavproxy.match.group(1) print("LOGFILE %s" % logfile) buildlog = util.reltopdir("../buildlogs/QuadPlane-test.tlog") print("buildlog=%s" % buildlog) if os.path.exists(buildlog): os.unlink(buildlog) try: os.link(logfile, buildlog) except Exception: pass util.expect_setup_callback(mavproxy, expect_callback) mavproxy.expect('Received [0-9]+ parameters') expect_list_clear() expect_list_extend([sitl, mavproxy]) print("Started simulator") # get a mavlink connection going try: mav = mavutil.mavlink_connection('127.0.0.1:19550', robust_parsing=True) except Exception as msg: print("Failed to start mavlink connection on 127.0.0.1:19550" % msg) raise mav.message_hooks.append(message_hook) mav.idle_hooks.append(idle_hook) failed = False e = 'None' try: print("Waiting for a heartbeat with mavlink protocol %s" % mav.WIRE_PROTOCOL_VERSION) mav.wait_heartbeat() print("Waiting for GPS fix") mav.recv_match(condition='VFR_HUD.alt>10', blocking=True) mav.wait_gps_fix() while mav.location().alt < 10: mav.wait_gps_fix() homeloc = mav.location() print("Home location: %s" % homeloc) # wait for EKF and GPS checks to pass wait_seconds(mav, 30) mavproxy.send('arm throttle\n') mavproxy.expect('ARMED') if not fly_mission(mavproxy, mav, os.path.join(testdir, "ArduPlane-Missions/Dalby-OBC2016.txt"), os.path.join(testdir, "ArduPlane-Missions/Dalby-OBC2016-fence.txt")): print("Failed mission") failed = True except pexpect.TIMEOUT as e: print("Failed with timeout") failed = True mav.close() util.pexpect_close(mavproxy) util.pexpect_close(sitl) valgrind_log = util.valgrind_log_filepath(binary=binary, model='quadplane') if os.path.exists(valgrind_log): os.chmod(valgrind_log, 0o644) shutil.copy(valgrind_log, util.reltopdir("../buildlogs/QuadPlane-valgrind.log")) if failed: print("FAILED: %s" % e) return False return True
def run_step(step): """Run one step.""" # remove old logs util.run_cmd('/bin/rm -f logs/*.BIN logs/LASTLOG.TXT') if step == "prerequisites": return test_prerequisites() build_opts = { "j": opts.j, "debug": opts.debug, "clean": not opts.no_clean, "configure": not opts.no_configure, "math_check_indexes": opts.math_check_indexes, "ekf_single": opts.ekf_single, "postype_single": opts.postype_single, "extra_configure_args": opts.waf_configure_args, "coverage": opts.coverage, "sitl_32bit" : opts.sitl_32bit, } if opts.Werror: build_opts['extra_configure_args'].append("--Werror") vehicle_binary = None if step == 'build.Plane': vehicle_binary = 'bin/arduplane' if step == 'build.Rover': vehicle_binary = 'bin/ardurover' if step == 'build.Copter': vehicle_binary = 'bin/arducopter' if step == 'build.Blimp': vehicle_binary = 'bin/blimp' if step == 'build.Tracker': vehicle_binary = 'bin/antennatracker' if step == 'build.Helicopter': vehicle_binary = 'bin/arducopter-heli' if step == 'build.Sub': vehicle_binary = 'bin/ardusub' if step == 'build.SITLPeriphGPS': vehicle_binary = 'sitl_periph_gps.bin/AP_Periph' if step == 'build.Replay': return util.build_replay(board='SITL') if vehicle_binary is not None: 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) if step.startswith("defaults"): vehicle = step[9:] return get_default_params(vehicle, binary) supplementary_binaries = [] if step in suplementary_test_binary_map: for supplementary_test_binary in suplementary_test_binary_map[step]: config_name = supplementary_test_binary.split('.')[0] binary_name = supplementary_test_binary.split('.')[1] instance_num = 0 if len(supplementary_test_binary.split('.')) >= 3: instance_num = int(supplementary_test_binary.split('.')[2]) supplementary_binaries.append([util.reltopdir(os.path.join('build', config_name, 'bin', binary_name)), '-I {}'.format(instance_num)]) # we are running in conjunction with a supplementary app # can't have speedup opts.speedup = 1.0 else: supplementary_binaries = [] fly_opts = { "viewerip": opts.viewerip, "use_map": opts.map, "valgrind": opts.valgrind, "callgrind": opts.callgrind, "gdb": opts.gdb, "gdb_no_tui": opts.gdb_no_tui, "lldb": opts.lldb, "gdbserver": opts.gdbserver, "breakpoints": opts.breakpoint, "disable_breakpoints": opts.disable_breakpoints, "frame": opts.frame, "_show_test_timings": opts.show_test_timings, "force_ahrs_type": opts.force_ahrs_type, "replay": opts.replay, "logs_dir": buildlogs_dirpath(), "sup_binaries": supplementary_binaries, "reset_after_every_test": opts.reset_after_every_test, } if opts.speedup is not None: fly_opts["speedup"] = opts.speedup # handle "test.Copter" etc: if step in tester_class_map: # create an instance of the tester class: global tester tester = tester_class_map[step](binary, **fly_opts) # run the test and return its result and the tester itself return (tester.autotest(), tester) # handle "test.Copter.CPUFailsafe" etc: specific_test_to_run = find_specific_test_to_run(step) if specific_test_to_run is not None: return run_specific_test(specific_test_to_run, binary, **fly_opts) if step == 'build.All': return build_all() if step == 'build.Binaries': return build_binaries() if step == 'build.examples': return build_examples(**build_opts) if step == 'run.examples': return examples.run_examples(debug=opts.debug, valgrind=False, gdb=False) if step == 'build.Parameters': return build_parameters() if step == 'convertgpx': return convert_gpx() if step == 'build.unit_tests': return build_unit_tests(**build_opts) if step == 'run.unit_tests': return run_unit_tests() if step == 'clang-scan-build': return run_clang_scan_build() raise RuntimeError("Unknown step %s" % step)
def test_prerequisites(): """Check we have the right directories and tools to run tests.""" print("Testing prerequisites") util.mkdir_p(util.reltopdir('../buildlogs')) return True
def addglob(self, name, pattern): """Add a set of files.""" for f in glob.glob(util.reltopdir('../buildlogs/%s' % pattern)): self.addfile(name, os.path.basename(f))
def addglobimage(self, name, pattern): """Add a set of images.""" import glob for f in glob.glob(util.reltopdir('../buildlogs/%s' % pattern)): self.addimage(name, os.path.basename(f))
def run_step(step): """Run one step.""" # remove old logs util.run_cmd('/bin/rm -f logs/*.BIN logs/LASTLOG.TXT') if step == "prerequisites": return test_prerequisites() build_opts = { "j": opts.j, "debug": opts.debug, "clean": not opts.no_clean, "configure": not opts.no_configure, "math_check_indexes": opts.math_check_indexes, "extra_configure_args": opts.waf_configure_args, } if opts.Werror: build_opts['extra_configure_args'].append("--Werror") vehicle_binary = None if step == 'build.Plane': vehicle_binary = 'bin/arduplane' if step == 'build.Rover': vehicle_binary = 'bin/ardurover' if step == 'build.Copter': vehicle_binary = 'bin/arducopter' if step == 'build.Tracker': vehicle_binary = 'bin/antennatracker' if step == 'build.Helicopter': vehicle_binary = 'bin/arducopter-heli' if step == 'build.Sub': vehicle_binary = 'bin/ardusub' if step == 'build.SITLPeriphGPS': vehicle_binary = 'sitl_periph_gps.bin/AP_Periph' if step == 'build.Replay': return util.build_SITL('tools/Replay', clean=False, configure=False) if vehicle_binary is not None: 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) if step.startswith("defaults"): 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, "valgrind": opts.valgrind, "gdb": opts.gdb, "lldb": opts.lldb, "gdbserver": opts.gdbserver, "breakpoints": opts.breakpoint, "disable_breakpoints": opts.disable_breakpoints, "frame": opts.frame, "_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 # handle "test.Copter" etc: if step in tester_class_map: t = tester_class_map[step](binary, **fly_opts) return (t.autotest(), t) specific_test_to_run = find_specific_test_to_run(step) if specific_test_to_run is not None: return run_specific_test(specific_test_to_run, binary, **fly_opts) if step == 'build.All': return build_all() if step == 'build.Binaries': return build_binaries() if step == 'build.examples': return build_examples() if step == 'run.examples': return examples.run_examples(debug=opts.debug, valgrind=False, gdb=False) if step == 'build.Parameters': return build_parameters() if step == 'convertgpx': return convert_gpx() if step == 'build.unit_tests': return build_unit_tests() if step == 'run.unit_tests': return run_unit_tests() if step == 'clang-scan-build': return run_clang_scan_build() raise RuntimeError("Unknown step %s" % step)
def fly_ArduPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, gdbserver=False): """Fly ArduPlane in SITL. you can pass viewerip as an IP address to optionally send fg and mavproxy packets too for local viewing of the flight in real time """ global homeloc options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --streamrate=10' if viewerip: options += " --out=%s:14550" % viewerip if use_map: options += ' --map' sitl = util.start_SITL(binary, model='plane-elevrev', home=HOME_LOCATION, speedup=10, valgrind=valgrind, gdb=gdb, gdbserver=gdbserver, defaults_file=os.path.join(testdir, 'default_params/plane-jsbsim.parm')) mavproxy = util.start_MAVProxy_SITL('ArduPlane', options=options) mavproxy.expect('Telemetry log: (\S+)') logfile = mavproxy.match.group(1) print("LOGFILE %s" % logfile) buildlog = util.reltopdir("../buildlogs/ArduPlane-test.tlog") print("buildlog=%s" % buildlog) if os.path.exists(buildlog): os.unlink(buildlog) try: os.link(logfile, buildlog) except Exception: pass util.expect_setup_callback(mavproxy, expect_callback) mavproxy.expect('Received [0-9]+ parameters') expect_list_clear() expect_list_extend([sitl, mavproxy]) print("Started simulator") # get a mavlink connection going try: mav = mavutil.mavlink_connection('127.0.0.1:19550', robust_parsing=True) except Exception as msg: print("Failed to start mavlink connection on 127.0.0.1:19550" % msg) raise mav.message_hooks.append(message_hook) mav.idle_hooks.append(idle_hook) failed = False fail_list = [] e = 'None' try: print("Waiting for a heartbeat with mavlink protocol %s" % mav.WIRE_PROTOCOL_VERSION) mav.wait_heartbeat() print("Setting up RC parameters") setup_rc(mavproxy) print("Waiting for GPS fix") mav.recv_match(condition='VFR_HUD.alt>10', blocking=True) mav.wait_gps_fix() while mav.location().alt < 10: mav.wait_gps_fix() homeloc = mav.location() print("Home location: %s" % homeloc) if not takeoff(mavproxy, mav): print("Failed takeoff") failed = True fail_list.append("takeoff") if not fly_left_circuit(mavproxy, mav): print("Failed left circuit") failed = True fail_list.append("left_circuit") if not axial_left_roll(mavproxy, mav, 1): print("Failed left roll") failed = True fail_list.append("left_roll") if not inside_loop(mavproxy, mav): print("Failed inside loop") failed = True fail_list.append("inside_loop") if not test_stabilize(mavproxy, mav): print("Failed stabilize test") failed = True fail_list.append("stabilize") if not test_acro(mavproxy, mav): print("Failed ACRO test") failed = True fail_list.append("acro") if not test_FBWB(mavproxy, mav): print("Failed FBWB test") failed = True fail_list.append("fbwb") if not test_FBWB(mavproxy, mav, mode='CRUISE'): print("Failed CRUISE test") failed = True fail_list.append("cruise") if not fly_RTL(mavproxy, mav): print("Failed RTL") failed = True fail_list.append("RTL") if not fly_LOITER(mavproxy, mav): print("Failed LOITER") failed = True fail_list.append("LOITER") if not fly_CIRCLE(mavproxy, mav): print("Failed CIRCLE") failed = True fail_list.append("LOITER") if not fly_mission(mavproxy, mav, os.path.join(testdir, "ap1.txt"), height_accuracy = 10, target_altitude=homeloc.alt+100): print("Failed mission") failed = True fail_list.append("mission") if not log_download(mavproxy, mav, util.reltopdir("../buildlogs/ArduPlane-log.bin")): print("Failed log download") failed = True fail_list.append("log_download") except pexpect.TIMEOUT as e: print("Failed with timeout") failed = True fail_list.append("timeout") mav.close() util.pexpect_close(mavproxy) util.pexpect_close(sitl) valgrind_log = util.valgrind_log_filepath(binary=binary, model='plane-elevrev') if os.path.exists(valgrind_log): os.chmod(valgrind_log, 0o644) shutil.copy(valgrind_log, util.reltopdir("../buildlogs/ArduPlane-valgrind.log")) if failed: print("FAILED: %s" % e, fail_list) return False return True
def fly_Falcon(binary, filepath, viewerip=None, use_map=False, valgrind=False, gdb=False, frame=None, params=None, gdbserver=False, speedup=10): """Fly ArduCopter in SITL. you can pass viewerip as an IP address to optionally send fg and mavproxy packets too for local viewing of the flight in real time """ global homeloc if frame is None: frame = '+' print("# ########################### enter fly_falcon..") home = "%f,%f,%u,%u" % (HOME.lat, HOME.lng, HOME.alt, HOME.heading) sitl = util.start_SITL(binary, model=frame, home=home, speedup=speedup, valgrind=valgrind, gdb=gdb, gdbserver=gdbserver) options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=5' if viewerip: options += ' --out=%s:14550' % viewerip if use_map: options += ' --map' mavproxy = util.start_MAVProxy_SITL('ArduCopter', options=options) mavproxy.expect('Telemetry log: (\S+)') ardulogfile = mavproxy.match.group(1) logfile_path,logfile_name = os.path.split(ardulogfile) logfile = os.path.join(logfile_path, "falconlog.tlog") print("LOGFILE PATH %s" % logfile) buildlog = util.reltopdir("../buildlogs/FalconCopter-test.tlog") print("buildlog=%s" % buildlog) copy_tlog = False if os.path.exists(buildlog): os.unlink(buildlog) try: os.link(logfile, buildlog) except Exception: print("WARN: Failed to create symlink: " + logfile + " => " + buildlog + ", Will copy tlog manually to target location") copy_tlog = True # the received parameters can come before or after the ready to fly message mavproxy.expect(['Received [0-9]+ parameters', 'Ready to FLY']) mavproxy.expect(['Received [0-9]+ parameters', 'Ready to FLY']) util.expect_setup_callback(mavproxy, expect_callback) expect_list_clear() expect_list_extend([sitl, mavproxy]) # get a mavlink connection going try: mav = mavutil.mavlink_connection('127.0.0.1:19550', robust_parsing=True) except Exception as msg: print("Failed to start mavlink connection on 127.0.0.1:19550" % msg) raise mav.message_hooks.append(message_hook) mav.idle_hooks.append(idle_hook) failed = False failed_test_msg = "None" # Enable MAVProxy debugging mavproxy.send("set moddebug 3\n") try: # Falcon test print("######## Fly falcon mission now") # time.sleep(3) if not fly_falcon_test(mavproxy, mav, filepath): failed_test_msg = "fly_falcon_test failed" print(failed_test_msg) failed = True else: print("fly_falcon_test OK") except pexpect.TIMEOUT as failed_test_msg: failed_test_msg = "Timeout" failed = True mav.close() util.pexpect_close(mavproxy) util.pexpect_close(sitl) # valgrind_log = util.valgrind_log_filepath(binary=binary, model='+') # if os.path.exists(valgrind_log): # os.chmod(valgrind_log, 0o644) # shutil.copy(valgrind_log, util.reltopdir("../buildlogs/ArduCopter-valgrind.log")) # [2014/05/07] FC Because I'm doing a cross machine build (source is on host, build is on guest VM) I cannot hard link # This flag tells me that I need to copy the data out if copy_tlog: shutil.copy(logfile, buildlog) if failed: print("FAILED: %s" % failed_test_msg) return False return True