예제 #1
0
    def close(self):
        if self.use_map:
            self.mavproxy.send("module unload map\n")
            self.mavproxy.expect("Unloaded module map")

        self.mav.close()
        util.pexpect_close(self.mavproxy)
        util.pexpect_close(self.sitl)

        valgrind_log = util.valgrind_log_filepath(binary=self.binary,
                                                  model=self.frame)
        if os.path.exists(valgrind_log):
            os.chmod(valgrind_log, 0o644)
            shutil.copy(valgrind_log,
                        self.buildlogs_path("QuadPlane-valgrind.log"))
예제 #2
0
파일: common.py 프로젝트: zkirwan/ardupilot
    def close(self):
        '''tidy up after running all tests'''
        if self.use_map:
            self.mavproxy.send("module unload map\n")
            self.mavproxy.expect("Unloaded module map")

        self.mav.close()
        util.pexpect_close(self.mavproxy)
        util.pexpect_close(self.sitl)

        valgrind_log = util.valgrind_log_filepath(binary=self.binary,
                                                  model=self.frame)
        if os.path.exists(valgrind_log):
            os.chmod(valgrind_log, 0o644)
            shutil.copy(valgrind_log,
                        self.buildlogs_path("%s-valgrind.log" % self.log_name))
예제 #3
0
    def close(self):
        """Tidy up after running all tests."""
        if self.use_map:
            self.mavproxy.send("module unload map\n")
            self.mavproxy.expect("Unloaded module map")

        self.mav.close()
        util.pexpect_close(self.mavproxy)
        util.pexpect_close(self.sitl)

        valgrind_log = util.valgrind_log_filepath(binary=self.binary,
                                                  model=self.frame)
        if os.path.exists(valgrind_log):
            os.chmod(valgrind_log, 0o644)
            shutil.copy(valgrind_log,
                        self.buildlogs_path("%s-valgrind.log" %
                                            self.log_name))
예제 #4
0
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
예제 #5
0
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
예제 #6
0
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)
    print("LOGFILE %s" % logfile)

    buildlog = util.reltopdir("../buildlogs/ArduSub-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("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()
        print("Home location: %s" % homeloc)
        if not arm_sub(mavproxy, mav):
            print("Failed to ARM")
            failed = True
        if not dive_manual(mavproxy, mav):
            print("Failed manual dive")
            failed = True
        if not dive_mission(mavproxy, mav, os.path.join(testdir, "sub_mission.txt")):
            print("Failed auto mission")
            failed = True
        if not log_download(mavproxy, mav, util.reltopdir("../buildlogs/ArduSub-log.bin")):
            print("Failed log download")
            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='sub')
    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
예제 #7
0
파일: apmrover2.py 프로젝트: xvzf/ardupilot
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')

    progress("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+)\r\n')
    logfile = mavproxy.match.group(1)
    progress("LOGFILE %s" % logfile)

    buildlog = util.reltopdir("../buildlogs/APMrover2-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("Setting up RC parameters")
        set_rc_default(mavproxy)
        set_rc(mavproxy, mav, 8, 1800)
        progress("Waiting for GPS fix")
        mav.wait_gps_fix()
        homeloc = mav.location()
        progress("Home location: %s" % homeloc)
        mavproxy.send('switch 6\n')  # Manual mode
        wait_mode(mav, 'MANUAL')
        progress("Waiting reading for arm")
        wait_ready_to_arm(mav)
        if not arm_vehicle(mavproxy, mav):
            progress("Failed to ARM")
            failed = True
        progress("#")
        progress(
            "########## Drive a square and save WPs with CH7 switch  ##########"
        )
        progress("#")
        # Drive a square in learning mode
        if not drive_mission(mavproxy, mav, os.path.join(
                testdir, "rover1.txt")):
            progress("Failed mission")
            failed = True

        if not drive_brake(mavproxy, mav):
            progress("Failed brake")
            failed = True

        if not disarm_vehicle(mavproxy, mav):
            progress("Failed to DISARM")
            failed = True

        # do not move this to be the first test.  MAVProxy's dedupe
        # function may bite you.
        progress("Getting banner")
        if not do_get_banner(mavproxy, mav):
            progress("FAILED: get banner")
            failed = True

        progress("Getting autopilot capabilities")
        if not do_get_autopilot_capabilities(mavproxy, mav):
            progress("FAILED: get capabilities")
            failed = True

        progress("Setting mode via MAV_COMMAND_DO_SET_MODE")
        if not do_set_mode_via_command_long(mavproxy, mav):
            failed = True

        if not log_download(mavproxy, mav,
                            util.reltopdir("../buildlogs/APMrover2-log.bin")):
            progress("Failed log download")
            failed = True
#        if not drive_left_circuit(mavproxy, mav):
#            progress("Failed left circuit")
#            failed = True
#        if not drive_RTL(mavproxy, mav):
#            progress("Failed RTL")
#            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='rover')
    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
예제 #8
0
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')
    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+)\r\n')
    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)
        set_rc_default(mavproxy)
        if not arm_vehicle(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
예제 #9
0
def fly_CopterAVC(binary,
                  viewerip=None,
                  use_map=False,
                  valgrind=False,
                  gdb=False,
                  frame=None,
                  params=None,
                  gdbserver=False,
                  speedup=10):
    """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)
    mavproxy = util.start_MAVProxy_SITL('ArduCopter')
    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,
                           valgrind=valgrind,
                           gdb=gdb,
                           gdbserver=gdbserver)
    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+)\r\n')
    logfile = mavproxy.match.group(1)
    progress("LOGFILE %s" % logfile)

    buildlog = util.reltopdir("../buildlogs/CopterAVC-test.tlog")
    progress("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:
        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
    failed_test_msg = "None"

    try:
        mav.wait_heartbeat()
        set_rc_default(mavproxy)
        set_rc(mavproxy, mav, 3, 1000)
        homeloc = mav.location()

        progress("Lowering rotor speed")
        set_rc(mavproxy, mav, 8, 1000)

        mavproxy.send('switch 6\n')  # stabilize mode
        wait_mode(mav, 'STABILIZE')
        wait_ready_to_arm(mav)

        # Arm
        progress("# Arm motors")
        if not arm_vehicle(mavproxy, mav):
            failed_test_msg = "arm_motors failed"
            progress(failed_test_msg)
            failed = True

        progress("Raising rotor speed")
        set_rc(mavproxy, mav, 8, 2000)

        progress("# Fly AVC mission")
        if not fly_avc_test(mavproxy, mav):
            failed_test_msg = "fly_avc_test failed"
            progress(failed_test_msg)
            failed = True
        else:
            progress("Flew AVC mission OK")

        progress("Lowering rotor speed")
        set_rc(mavproxy, mav, 8, 1000)

        # 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"
            progress(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:
        progress("FAILED: %s" % failed_test_msg)
        return False
    return True
예제 #10
0
def fly_ArduCopter(binary,
                   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 = '+'

    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('ArduCopter')
    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,
                           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+)\r\n')
    logfile = mavproxy.match.group(1)
    progress("LOGFILE %s" % logfile)

    buildlog = util.reltopdir("../buildlogs/ArduCopter-test.tlog")
    progress("buildlog=%s" % buildlog)
    copy_tlog = False
    if os.path.exists(buildlog):
        os.unlink(buildlog)
    try:
        os.link(logfile, buildlog)
    except Exception:
        progress("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:
        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
    failed_test_msg = "None"

    try:
        progress("Waiting for a heartbeat with mavlink protocol %s" %
                 mav.WIRE_PROTOCOL_VERSION)
        mav.wait_heartbeat()
        progress("Setting up RC parameters")
        set_rc_default(mavproxy)
        set_rc(mavproxy, mav, 3, 1000)
        homeloc = mav.location()

        progress("Home location: %s" % homeloc)
        mavproxy.send('switch 6\n')  # stabilize mode
        mav.wait_heartbeat()
        wait_mode(mav, 'STABILIZE')
        progress("Waiting reading for arm")
        wait_ready_to_arm(mav)

        # Arm
        progress("# Arm motors")
        if not arm_vehicle(mavproxy, mav):
            failed_test_msg = "arm_motors failed"
            progress(failed_test_msg)
            failed = True

        progress("# Takeoff")
        if not takeoff(mavproxy, mav, 10):
            failed_test_msg = "takeoff failed"
            progress(failed_test_msg)
            failed = True

        # Fly a square in Stabilize mode
        progress("#")
        progress(
            "########## Fly a square and save WPs with CH7 switch ##########")
        progress("#")
        if not fly_square(mavproxy, mav):
            failed_test_msg = "fly_square failed"
            progress(failed_test_msg)
            failed = True

        # save the stored mission to file
        progress("# Save out the CH7 mission to file")
        global num_wp
        num_wp = save_mission_to_file(mavproxy,
                                      os.path.join(testdir, "ch7_mission.txt"))
        if not num_wp:
            failed_test_msg = "save_mission_to_file failed"
            progress(failed_test_msg)
            failed = True

        # fly the stored mission
        progress("# Fly CH7 saved mission")
        if not fly_mission(
                mavproxy, mav, height_accuracy=0.5, target_altitude=10):
            failed_test_msg = "fly ch7_mission failed"
            progress(failed_test_msg)
            failed = True

        # Throttle Failsafe
        progress("#")
        progress("########## Test Failsafe ##########")
        progress("#")
        if not fly_throttle_failsafe(mavproxy, mav):
            failed_test_msg = "fly_throttle_failsafe failed"
            progress(failed_test_msg)
            failed = True

        # Takeoff
        progress("# Takeoff")
        if not takeoff(mavproxy, mav, 10):
            failed_test_msg = "takeoff failed"
            progress(failed_test_msg)
            failed = True

        # Battery failsafe
        if not fly_battery_failsafe(mavproxy, mav):
            failed_test_msg = "fly_battery_failsafe failed"
            progress(failed_test_msg)
            failed = True

        # Takeoff
        progress("# Takeoff")
        if not takeoff(mavproxy, mav, 10):
            failed_test_msg = "takeoff failed"
            progress(failed_test_msg)
            failed = True

        # Stability patch
        progress("#")
        progress("########## Test Stability Patch ##########")
        progress("#")
        if not fly_stability_patch(mavproxy, mav, 30):
            failed_test_msg = "fly_stability_patch failed"
            progress(failed_test_msg)
            failed = True

        # RTL
        progress("# RTL #")
        if not fly_RTL(mavproxy, mav):
            failed_test_msg = "fly_RTL after stab patch failed"
            progress(failed_test_msg)
            failed = True

        # Takeoff
        progress("# Takeoff")
        if not takeoff(mavproxy, mav, 10):
            failed_test_msg = "takeoff failed"
            progress(failed_test_msg)
            failed = True

        # Fence test
        progress("#")
        progress("########## Test Horizontal Fence ##########")
        progress("#")
        if not fly_fence_test(mavproxy, mav, 180):
            failed_test_msg = "fly_fence_test failed"
            progress(failed_test_msg)
            failed = True

        # Fence test
        progress("#")
        progress("########## Test Max Alt Fence ##########")
        progress("#")
        if not fly_alt_max_fence_test(mavproxy, mav, 180):
            failed_test_msg = "fly_alt_max_fence_test failed"
            progress(failed_test_msg)
            failed = True

        # Takeoff
        progress("# Takeoff")
        if not takeoff(mavproxy, mav, 10):
            failed_test_msg = "takeoff failed"
            progress(failed_test_msg)
            failed = True

        # Fly GPS Glitch Loiter test
        progress("# GPS Glitch Loiter Test")
        if not fly_gps_glitch_loiter_test(mavproxy, mav, use_map):
            failed_test_msg = "fly_gps_glitch_loiter_test failed"
            progress(failed_test_msg)
            failed = True

        # RTL after GPS Glitch Loiter test
        progress("# RTL #")
        if not fly_RTL(mavproxy, mav):
            failed_test_msg = "fly_RTL failed"
            progress(failed_test_msg)
            failed = True

        # Fly GPS Glitch test in auto mode
        progress("# GPS Glitch Auto Test")
        if not fly_gps_glitch_auto_test(mavproxy, mav, use_map):
            failed_test_msg = "fly_gps_glitch_auto_test failed"
            progress(failed_test_msg)
            failed = True

        # take-off ahead of next test
        progress("# Takeoff")
        if not takeoff(mavproxy, mav, 10):
            failed_test_msg = "takeoff failed"
            progress(failed_test_msg)
            failed = True

        # Loiter for 10 seconds
        progress("#")
        progress("########## Test Loiter for 10 seconds ##########")
        progress("#")
        if not loiter(mavproxy, mav):
            failed_test_msg = "loiter failed"
            progress(failed_test_msg)
            failed = True

        # Loiter Climb
        progress("#")
        progress("# Loiter - climb to 30m")
        progress("#")
        if not change_alt(mavproxy, mav, 30):
            failed_test_msg = "change_alt climb failed"
            progress(failed_test_msg)
            failed = True

        # Loiter Descend
        progress("#")
        progress("# Loiter - descend to 20m")
        progress("#")
        if not change_alt(mavproxy, mav, 20):
            failed_test_msg = "change_alt descend failed"
            progress(failed_test_msg)
            failed = True

        # RTL
        progress("#")
        progress("########## Test RTL ##########")
        progress("#")
        if not fly_RTL(mavproxy, mav):
            failed_test_msg = "fly_RTL after Loiter climb/descend failed"
            progress(failed_test_msg)
            failed = True

        # Takeoff
        progress("# Takeoff")
        if not takeoff(mavproxy, mav, 10):
            failed_test_msg = "takeoff failed"
            progress(failed_test_msg)
            failed = True

        # Simple mode
        progress("# Fly in SIMPLE mode")
        if not fly_simple(mavproxy, mav):
            failed_test_msg = "fly_simple failed"
            progress(failed_test_msg)
            failed = True

        # RTL
        progress("#")
        progress("########## Test RTL ##########")
        progress("#")
        if not fly_RTL(mavproxy, mav):
            failed_test_msg = "fly_RTL after simple mode failed"
            progress(failed_test_msg)
            failed = True

        # Takeoff
        progress("# Takeoff")
        if not takeoff(mavproxy, mav, 10):
            failed_test_msg = "takeoff failed"
            progress(failed_test_msg)
            failed = True

        # Fly a circle in super simple mode
        progress("# Fly a circle in SUPER SIMPLE mode")
        if not fly_super_simple(mavproxy, mav):
            failed_test_msg = "fly_super_simple failed"
            progress(failed_test_msg)
            failed = True

        # RTL
        progress("# RTL #")
        if not fly_RTL(mavproxy, mav):
            failed_test_msg = "fly_RTL after super simple mode failed"
            progress(failed_test_msg)
            failed = True

        # Takeoff
        progress("# Takeoff")
        if not takeoff(mavproxy, mav, 10):
            failed_test_msg = "takeoff failed"
            progress(failed_test_msg)
            failed = True

        # Circle mode
        progress("# Fly CIRCLE mode")
        if not fly_circle(mavproxy, mav):
            failed_test_msg = "fly_circle failed"
            progress(failed_test_msg)
            failed = True

        # RTL
        progress("#")
        progress("########## Test RTL ##########")
        progress("#")
        if not fly_RTL(mavproxy, mav):
            failed_test_msg = "fly_RTL after circle failed"
            progress(failed_test_msg)
            failed = True

        progress("# Fly copter mission")
        if not fly_auto_test(mavproxy, mav):
            failed_test_msg = "fly_auto_test failed"
            progress(failed_test_msg)
            failed = True
        else:
            progress("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"
            progress(failed_test_msg)
            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='+')
    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:
        progress("FAILED: %s" % failed_test_msg)
        return False
    return True
예제 #11
0
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')

    progress("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+)\r\n')
    logfile = mavproxy.match.group(1)
    progress("LOGFILE %s" % logfile)

    buildlog = util.reltopdir("../buildlogs/APMrover2-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("Setting up RC parameters")
        set_rc_default(mavproxy)
        set_rc(mavproxy, mav, 8, 1800)
        progress("Waiting for GPS fix")
        mav.wait_gps_fix()
        homeloc = mav.location()
        progress("Home location: %s" % homeloc)
        mavproxy.send('switch 6\n')  # Manual mode
        wait_mode(mav, 'MANUAL')
        progress("Waiting reading for arm")
        wait_ready_to_arm(mav)
        if not arm_vehicle(mavproxy, mav):
            progress("Failed to ARM")
            failed = True

        progress("#")
        progress("########## Drive an RTL mission  ##########")
        progress("#")
        # Drive a square in learning mode
        if not drive_rtl_mission(mavproxy, mav):
            progress("Failed RTL mission")
            failed = True

        progress("#")
        progress("########## Drive a square and save WPs with CH7 switch  ##########")
        progress("#")
        # Drive a square in learning mode
        if not drive_mission(mavproxy, mav, os.path.join(testdir, "rover1.txt")):
            progress("Failed mission")
            failed = True

        if not drive_brake(mavproxy, mav):
            progress("Failed brake")
            failed = True

        if not disarm_vehicle(mavproxy, mav):
            progress("Failed to DISARM")
            failed = True

        # do not move this to be the first test.  MAVProxy's dedupe
        # function may bite you.
        progress("Getting banner")
        if not do_get_banner(mavproxy, mav):
            progress("FAILED: get banner")
            failed = True

        progress("Getting autopilot capabilities")
        if not do_get_autopilot_capabilities(mavproxy, mav):
            progress("FAILED: get capabilities")
            failed = True

        progress("Setting mode via MAV_COMMAND_DO_SET_MODE")
        if not do_set_mode_via_command_long(mavproxy, mav):
            failed = True

        if not log_download(mavproxy, mav, util.reltopdir("../buildlogs/APMrover2-log.bin")):
            progress("Failed log download")
            failed = True
#        if not drive_left_circuit(mavproxy, mav):
#            progress("Failed left circuit")
#            failed = True
#        if not drive_RTL(mavproxy, mav):
#            progress("Failed RTL")
#            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='rover')
    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
예제 #12
0
def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame=None, params=None, gdbserver=False):
    """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, 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+)')
    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
예제 #13
0
def fly_CopterAVC(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame=None, params=None, gdbserver=False):
    """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, gdbserver=gdbserver)
    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
예제 #14
0
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
예제 #15
0
def drive_APMrover2(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame=None, params=None, gdbserver=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

    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=10)
    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')
    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, 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 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
    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