This commit is contained in:
Jason Short 2011-11-09 22:56:52 -08:00
commit 8ad94b9993
5 changed files with 180 additions and 148 deletions

View File

@ -1171,7 +1171,7 @@ static void read_AHRS(void)
{ {
// Perform IMU calculations and get attitude info // Perform IMU calculations and get attitude info
//----------------------------------------------- //-----------------------------------------------
#if HIL_MODE == HIL_MODE_SENSORS #if HIL_MODE != HIL_MODE_DISABLED
// update hil before dcm update // update hil before dcm update
gcs_update(); gcs_update();
#endif #endif

View File

@ -91,6 +91,7 @@ def arm_motors(mavproxy):
mavproxy.expect('APM: ARMING MOTORS') mavproxy.expect('APM: ARMING MOTORS')
mavproxy.send('rc 4 1500\n') mavproxy.send('rc 4 1500\n')
print("MOTORS ARMED OK") print("MOTORS ARMED OK")
return True
def disarm_motors(mavproxy): def disarm_motors(mavproxy):
'''disarm motors''' '''disarm motors'''
@ -101,6 +102,7 @@ def disarm_motors(mavproxy):
mavproxy.expect('APM: DISARMING MOTORS') mavproxy.expect('APM: DISARMING MOTORS')
mavproxy.send('rc 4 1500\n') mavproxy.send('rc 4 1500\n')
print("MOTORS DISARMED OK") print("MOTORS DISARMED OK")
return True
def takeoff(mavproxy, mav): def takeoff(mavproxy, mav):
@ -110,6 +112,7 @@ def takeoff(mavproxy, mav):
mavproxy.send('rc 3 1500\n') mavproxy.send('rc 3 1500\n')
wait_altitude(mav, 30, 40) wait_altitude(mav, 30, 40)
print("TAKEOFF COMPLETE") print("TAKEOFF COMPLETE")
return True
def loiter(mavproxy, mav, maxaltchange=10, holdtime=10, timeout=60): def loiter(mavproxy, mav, maxaltchange=10, holdtime=10, timeout=60):
@ -162,16 +165,18 @@ def wait_distance(mav, distance, accuracy=5, timeout=30):
return False return False
def wait_location(mav, loc, accuracy=5, timeout=30, height_accuracy=-1): def wait_location(mav, loc, accuracy=5, timeout=30, target_altitude=None, height_accuracy=-1):
'''wait for arrival at a location''' '''wait for arrival at a location'''
tstart = time.time() tstart = time.time()
if target_altitude is None:
target_altitude = loc.alt
while time.time() < tstart + timeout: while time.time() < tstart + timeout:
m = mav.recv_match(type='GPS_RAW', blocking=True) m = mav.recv_match(type='GPS_RAW', blocking=True)
pos = current_location(mav) pos = current_location(mav)
delta = get_distance(loc, pos) delta = get_distance(loc, pos)
print("Distance %.2f meters" % delta) print("Distance %.2f meters" % delta)
if delta <= accuracy: if delta <= accuracy:
if height_accuracy != -1 and math.fabs(pos.alt - loc.alt) > height_accuracy: if height_accuracy != -1 and math.fabs(pos.alt - target_altitude) > height_accuracy:
continue continue
print("Reached location (%.2f meters)" % delta) print("Reached location (%.2f meters)" % delta)
return True return True
@ -184,6 +189,7 @@ def fly_square(mavproxy, mav, side=50, timeout=120):
mavproxy.send('switch 6\n') mavproxy.send('switch 6\n')
mavproxy.expect('STABILIZE>') mavproxy.expect('STABILIZE>')
tstart = time.time() tstart = time.time()
failed = False
mavproxy.send('rc 3 1430\n') mavproxy.send('rc 3 1430\n')
mavproxy.send('rc 4 1610\n') mavproxy.send('rc 4 1610\n')
if not wait_heading(mav, 0): if not wait_heading(mav, 0):
@ -192,24 +198,28 @@ def fly_square(mavproxy, mav, side=50, timeout=120):
print("Going north %u meters" % side) print("Going north %u meters" % side)
mavproxy.send('rc 2 1390\n') mavproxy.send('rc 2 1390\n')
ok = wait_distance(mav, side) if not wait_distance(mav, side):
failed = True
mavproxy.send('rc 2 1500\n') mavproxy.send('rc 2 1500\n')
print("Going east %u meters" % side) print("Going east %u meters" % side)
mavproxy.send('rc 1 1610\n') mavproxy.send('rc 1 1610\n')
ok = wait_distance(mav, side) if not wait_distance(mav, side):
failed = True
mavproxy.send('rc 1 1500\n') mavproxy.send('rc 1 1500\n')
print("Going south %u meters" % side) print("Going south %u meters" % side)
mavproxy.send('rc 2 1610\n') mavproxy.send('rc 2 1610\n')
ok = wait_distance(mav, side) if not wait_distance(mav, side):
failed = True
mavproxy.send('rc 2 1500\n') mavproxy.send('rc 2 1500\n')
print("Going west %u meters" % side) print("Going west %u meters" % side)
mavproxy.send('rc 1 1390\n') mavproxy.send('rc 1 1390\n')
ok = wait_distance(mav, side) if not wait_distance(mav, side):
failed = True
mavproxy.send('rc 1 1500\n') mavproxy.send('rc 1 1500\n')
return ok return not failed
@ -238,7 +248,7 @@ def land(mavproxy, mav, timeout=60):
return False return False
def fly_mission(mavproxy, mav, filename, height_accuracy=-1): def fly_mission(mavproxy, mav, filename, height_accuracy=-1, target_altitude=None):
'''fly a mission from a file''' '''fly a mission from a file'''
global homeloc global homeloc
mavproxy.send('wp load %s\n' % filename) mavproxy.send('wp load %s\n' % filename)
@ -247,8 +257,11 @@ def fly_mission(mavproxy, mav, filename, height_accuracy=-1):
mavproxy.expect('Requesting [0-9]+ waypoints') mavproxy.expect('Requesting [0-9]+ waypoints')
mavproxy.send('switch 1\n') # auto mode mavproxy.send('switch 1\n') # auto mode
mavproxy.expect('AUTO>') mavproxy.expect('AUTO>')
wait_distance(mav, 30, timeout=120) if not wait_distance(mav, 30, timeout=120):
wait_location(mav, homeloc, timeout=600, height_accuracy=height_accuracy) return False
if not wait_location(mav, homeloc, timeout=600, target_altitude=target_altitude, height_accuracy=height_accuracy):
return False
return True
def setup_rc(mavproxy): def setup_rc(mavproxy):
@ -301,7 +314,7 @@ def fly_ArduCopter():
util.expect_setup_callback(mavproxy, expect_callback) util.expect_setup_callback(mavproxy, expect_callback)
# start hil_quad.py # start hil_quad.py
hquad = pexpect.spawn(util.reltopdir('../HILTest/hil_quad.py') + ' --fgout=192.168.2.15:9123 --home=%s' % HOME_LOCATION, hquad = pexpect.spawn(util.reltopdir('../HILTest/hil_quad.py') + ' --fgout=192.168.2.15:9123 --fgrate=200 --home=%s' % HOME_LOCATION,
logfile=sys.stdout, timeout=10) logfile=sys.stdout, timeout=10)
util.pexpect_autoclose(hquad) util.pexpect_autoclose(hquad)
hquad.expect('Starting at') hquad.expect('Starting at')
@ -322,15 +335,23 @@ def fly_ArduCopter():
mav.recv_match(type='GPS_RAW', blocking=True) mav.recv_match(type='GPS_RAW', blocking=True)
setup_rc(mavproxy) setup_rc(mavproxy)
homeloc = current_location(mav) homeloc = current_location(mav)
arm_motors(mavproxy) if not arm_motors(mavproxy):
takeoff(mavproxy, mav) failed = True
fly_square(mavproxy, mav) if not takeoff(mavproxy, mav):
loiter(mavproxy, mav) failed = True
land(mavproxy, mav) if not fly_square(mavproxy, mav):
failed = True
if not loiter(mavproxy, mav):
failed = True
if not land(mavproxy, mav):
failed = True
#fly_mission(mavproxy, mav, os.path.join(testdir, "mission_ttt.txt"), height_accuracy=0.2) #fly_mission(mavproxy, mav, os.path.join(testdir, "mission_ttt.txt"), height_accuracy=0.2)
fly_mission(mavproxy, mav, os.path.join(testdir, "mission1.txt"), height_accuracy = 0.2) if not fly_mission(mavproxy, mav, os.path.join(testdir, "mission1.txt"), height_accuracy = 0.5, target_altitude=10):
land(mavproxy, mav) failed = True
disarm_motors(mavproxy) if not land(mavproxy, mav):
failed = True
if not disarm_motors(mavproxy):
failed = True
except pexpect.TIMEOUT, e: except pexpect.TIMEOUT, e:
failed = True failed = True

View File

@ -222,16 +222,16 @@ def run_tests(steps):
print(">>>> FAILED STEP: %s at %s" % (step, time.asctime())) print(">>>> FAILED STEP: %s at %s" % (step, time.asctime()))
passed = False passed = False
failed.append(step) failed.append(step)
results.add(step, "FAILED", time.time() - t1) results.add(step, '<span class="failed-text">FAILED</span>', time.time() - t1)
continue continue
except Exception, msg: except Exception, msg:
passed = False passed = False
failed.append(step) failed.append(step)
print(">>>> FAILED STEP: %s at %s (%s)" % (step, time.asctime(), msg)) print(">>>> FAILED STEP: %s at %s (%s)" % (step, time.asctime(), msg))
traceback.print_exc(file=sys.stdout) traceback.print_exc(file=sys.stdout)
results.add(step, "FAILED", time.time() - t1) results.add(step, '<span class="failed-text">FAILED</span>', time.time() - t1)
pass pass
results.add(step, "PASSED", time.time() - t1) results.add(step, '<span class="passed-text">PASSED</span>', time.time() - t1)
print(">>>> PASSED STEP: %s at %s" % (step, time.asctime())) print(">>>> PASSED STEP: %s at %s" % (step, time.asctime()))
if not passed: if not passed:
print("FAILED %u tests: %s" % (len(failed), failed)) print("FAILED %u tests: %s" % (len(failed), failed))
@ -244,9 +244,11 @@ def run_tests(steps):
results.addfile('ArduPlane build log', 'ArduPlane.txt') results.addfile('ArduPlane build log', 'ArduPlane.txt')
results.addfile('ArduPlane code size', 'ArduPlane.sizes.txt') results.addfile('ArduPlane code size', 'ArduPlane.sizes.txt')
results.addfile('ArduPlane stack sizes', 'ArduPlane.framesizes.txt') results.addfile('ArduPlane stack sizes', 'ArduPlane.framesizes.txt')
results.addfile('ArduPlane defaults', 'ArduPlane.defaults.txt')
results.addfile('ArduCopter build log', 'ArduCopter.txt') results.addfile('ArduCopter build log', 'ArduCopter.txt')
results.addfile('ArduCopter code size', 'ArduCopter.sizes.txt') results.addfile('ArduCopter code size', 'ArduCopter.sizes.txt')
results.addfile('ArduCopter stack sizes', 'ArduCopter.framesizes.txt') results.addfile('ArduCopter stack sizes', 'ArduCopter.framesizes.txt')
results.addfile('ArduCopter defaults', 'ArduCopter.defaults.txt')
write_webresults(results) write_webresults(results)

View File

@ -106,11 +106,12 @@ def start_SIL(atype, valgrind=False, wipe=False, CLI=False):
return ret return ret
def start_MAVProxy_SIL(atype, aircraft=None, setup=False, master='tcp:127.0.0.1:5760', def start_MAVProxy_SIL(atype, aircraft=None, setup=False, master='tcp:127.0.0.1:5760',
fgrate=200,
options=None, logfile=sys.stdout): options=None, logfile=sys.stdout):
'''launch mavproxy connected to a SIL instance''' '''launch mavproxy connected to a SIL instance'''
global close_list global close_list
MAVPROXY = reltopdir('../MAVProxy/mavproxy.py') MAVPROXY = reltopdir('../MAVProxy/mavproxy.py')
cmd = MAVPROXY + ' --master=%s' % master cmd = MAVPROXY + ' --master=%s --fgrate=%u' % (master, fgrate)
if setup: if setup:
cmd += ' --setup' cmd += ' --setup'
if aircraft is None: if aircraft is None:

View File

@ -1,124 +1,132 @@
@charset "utf-8"; @charset "utf-8";
/* CSS Document */ /* CSS Document */
/* Background-Styles */ /* Background-Styles */
html { html {
overflow-y: scroll; overflow-y: scroll;
} }
body { body {
font-family:Helvetica; font-family:Helvetica;
margin:0px; margin:0px;
padding:0px; padding:0px;
background-color: #fff; background-color: #fff;
background-image: url(images/bg.png); background-image: url(images/bg.png);
} }
#logo { #logo {
background-image:url(images/logo.png); background-image:url(images/logo.png);
background-repeat:no-repeat; background-repeat:no-repeat;
height: 120px; height: 120px;
width: 420px; width: 420px;
-moz-box-shadow: 2px 2px 5px #888; -moz-box-shadow: 2px 2px 5px #888;
-webkit-box-shadow: 2px 2px 5px #888; -webkit-box-shadow: 2px 2px 5px #888;
box-shadow: 2px 2px 5px #888; box-shadow: 2px 2px 5px #888;
background-color: #000; background-color: #000;
} }
h2 { h2 {
text-shadow: #ccc 0px 1px 0px; text-shadow: #ccc 0px 1px 0px;
text-decoration:none; text-decoration:none;
color:#D14836; color:#D14836;
padding-top: 0px; padding-top: 0px;
padding-right: 5px; padding-right: 5px;
padding-bottom: 5px; padding-bottom: 5px;
padding-left: 5px; padding-left: 5px;
} }
#git { #git {
background-color: #FFF; background-color: #FFF;
font-size: 15px; font-size: 15px;
display: auto; display: auto;
padding: 10px; padding: 10px;
border: 1px solid #CCC; border: 1px solid #CCC;
position: relative; position: relative;
-moz-box-shadow: 2px 2px 5px #888; -moz-box-shadow: 2px 2px 5px #888;
-webkit-box-shadow: 2px 2px 5px #888; -webkit-box-shadow: 2px 2px 5px #888;
box-shadow: 2px 2px 5px #888; box-shadow: 2px 2px 5px #888;
} }
#git a { #git a {
color:#00F; color:#00F;
font-weight: normal; font-weight: normal;
} }
#git a:hover { #git a:hover {
color:#D14836; color:#D14836;
} }
.passed-text {
#main { color:green;
padding-top:0px; }
min-width: 420px;
margin-top: 0; .failed-text {
margin-right: auto; color:red;
margin-bottom: 0; }
margin-left: auto;
padding-right: 20px;
padding-bottom: 50px; #main {
padding-left: 20px; padding-top:0px;
} min-width: 420px;
margin-top: 0;
ul#testresults { margin-right: auto;
background-color: #FFF; margin-bottom: 0;
display: block; margin-left: auto;
padding: 10px; padding-right: 20px;
border: 1px solid #CCC; padding-bottom: 50px;
list-style-type: none; padding-left: 20px;
position: relative; }
-moz-box-shadow: 2px 2px 5px #888;
-webkit-box-shadow: 2px 2px 5px #888; ul#testresults {
box-shadow: 2px 2px 5px #888; background-color: #FFF;
} display: block;
padding: 10px;
ul#testresults li { border: 1px solid #CCC;
list-style-type: none; list-style-type: none;
display: block; position: relative;
background-color: #eef1f1; -moz-box-shadow: 2px 2px 5px #888;
margin: 5px; -webkit-box-shadow: 2px 2px 5px #888;
padding: 5px; box-shadow: 2px 2px 5px #888;
} }
ul#testlogs { ul#testresults li {
background-color: #FFF; list-style-type: none;
display: block; display: block;
padding: 10px; background-color: #eef1f1;
border: 1px solid #CCC; margin: 5px;
list-style-type: none; padding: 5px;
position: relative; }
-moz-box-shadow: 2px 2px 5px #888;
-webkit-box-shadow: 2px 2px 5px #888; ul#testlogs {
box-shadow: 2px 2px 5px #888; background-color: #FFF;
} display: block;
padding: 10px;
ul#testlogs li { border: 1px solid #CCC;
text-decoration:none; list-style-type: none;
list-style-type: none; position: relative;
display: block; -moz-box-shadow: 2px 2px 5px #888;
background-color: #eef1f1; -webkit-box-shadow: 2px 2px 5px #888;
margin: 5px; box-shadow: 2px 2px 5px #888;
padding: 5px; }
font-size: 15px;
} ul#testlogs li {
text-decoration:none;
list-style-type: none;
ul#testlogs li a { display: block;
text-decoration:none; background-color: #eef1f1;
color:#8aa19c; margin: 5px;
font-weight: bold; padding: 5px;
font-size: 12px; font-size: 15px;
} }
ul#testlogs li a:hover {
color:#D14836; ul#testlogs li a {
} text-decoration:none;
color:#8aa19c;
font-weight: bold;
font-size: 12px;
}
ul#testlogs li a:hover {
color:#D14836;
}