mirror of https://github.com/ArduPilot/ardupilot
Merge branch 'master' of https://code.google.com/p/ardupilot-mega
This commit is contained in:
commit
8ad94b9993
|
@ -1171,7 +1171,7 @@ static void read_AHRS(void)
|
|||
{
|
||||
// Perform IMU calculations and get attitude info
|
||||
//-----------------------------------------------
|
||||
#if HIL_MODE == HIL_MODE_SENSORS
|
||||
#if HIL_MODE != HIL_MODE_DISABLED
|
||||
// update hil before dcm update
|
||||
gcs_update();
|
||||
#endif
|
||||
|
|
|
@ -91,6 +91,7 @@ def arm_motors(mavproxy):
|
|||
mavproxy.expect('APM: ARMING MOTORS')
|
||||
mavproxy.send('rc 4 1500\n')
|
||||
print("MOTORS ARMED OK")
|
||||
return True
|
||||
|
||||
def disarm_motors(mavproxy):
|
||||
'''disarm motors'''
|
||||
|
@ -101,6 +102,7 @@ def disarm_motors(mavproxy):
|
|||
mavproxy.expect('APM: DISARMING MOTORS')
|
||||
mavproxy.send('rc 4 1500\n')
|
||||
print("MOTORS DISARMED OK")
|
||||
return True
|
||||
|
||||
|
||||
def takeoff(mavproxy, mav):
|
||||
|
@ -110,6 +112,7 @@ def takeoff(mavproxy, mav):
|
|||
mavproxy.send('rc 3 1500\n')
|
||||
wait_altitude(mav, 30, 40)
|
||||
print("TAKEOFF COMPLETE")
|
||||
return True
|
||||
|
||||
|
||||
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
|
||||
|
||||
|
||||
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'''
|
||||
tstart = time.time()
|
||||
if target_altitude is None:
|
||||
target_altitude = loc.alt
|
||||
while time.time() < tstart + timeout:
|
||||
m = mav.recv_match(type='GPS_RAW', blocking=True)
|
||||
pos = current_location(mav)
|
||||
delta = get_distance(loc, pos)
|
||||
print("Distance %.2f meters" % delta)
|
||||
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
|
||||
print("Reached location (%.2f meters)" % delta)
|
||||
return True
|
||||
|
@ -184,6 +189,7 @@ def fly_square(mavproxy, mav, side=50, timeout=120):
|
|||
mavproxy.send('switch 6\n')
|
||||
mavproxy.expect('STABILIZE>')
|
||||
tstart = time.time()
|
||||
failed = False
|
||||
mavproxy.send('rc 3 1430\n')
|
||||
mavproxy.send('rc 4 1610\n')
|
||||
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)
|
||||
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')
|
||||
|
||||
print("Going east %u meters" % side)
|
||||
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')
|
||||
|
||||
print("Going south %u meters" % side)
|
||||
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')
|
||||
|
||||
print("Going west %u meters" % side)
|
||||
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')
|
||||
return ok
|
||||
return not failed
|
||||
|
||||
|
||||
|
||||
|
@ -238,7 +248,7 @@ def land(mavproxy, mav, timeout=60):
|
|||
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'''
|
||||
global homeloc
|
||||
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.send('switch 1\n') # auto mode
|
||||
mavproxy.expect('AUTO>')
|
||||
wait_distance(mav, 30, timeout=120)
|
||||
wait_location(mav, homeloc, timeout=600, height_accuracy=height_accuracy)
|
||||
if not wait_distance(mav, 30, timeout=120):
|
||||
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):
|
||||
|
@ -301,7 +314,7 @@ def fly_ArduCopter():
|
|||
util.expect_setup_callback(mavproxy, expect_callback)
|
||||
|
||||
# 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)
|
||||
util.pexpect_autoclose(hquad)
|
||||
hquad.expect('Starting at')
|
||||
|
@ -322,15 +335,23 @@ def fly_ArduCopter():
|
|||
mav.recv_match(type='GPS_RAW', blocking=True)
|
||||
setup_rc(mavproxy)
|
||||
homeloc = current_location(mav)
|
||||
arm_motors(mavproxy)
|
||||
takeoff(mavproxy, mav)
|
||||
fly_square(mavproxy, mav)
|
||||
loiter(mavproxy, mav)
|
||||
land(mavproxy, mav)
|
||||
if not arm_motors(mavproxy):
|
||||
failed = True
|
||||
if not takeoff(mavproxy, mav):
|
||||
failed = True
|
||||
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, "mission1.txt"), height_accuracy = 0.2)
|
||||
land(mavproxy, mav)
|
||||
disarm_motors(mavproxy)
|
||||
if not fly_mission(mavproxy, mav, os.path.join(testdir, "mission1.txt"), height_accuracy = 0.5, target_altitude=10):
|
||||
failed = True
|
||||
if not land(mavproxy, mav):
|
||||
failed = True
|
||||
if not disarm_motors(mavproxy):
|
||||
failed = True
|
||||
except pexpect.TIMEOUT, e:
|
||||
failed = True
|
||||
|
||||
|
|
|
@ -222,16 +222,16 @@ def run_tests(steps):
|
|||
print(">>>> FAILED STEP: %s at %s" % (step, time.asctime()))
|
||||
passed = False
|
||||
failed.append(step)
|
||||
results.add(step, "FAILED", time.time() - t1)
|
||||
results.add(step, '<span class="failed-text">FAILED</span>', time.time() - t1)
|
||||
continue
|
||||
except Exception, msg:
|
||||
passed = False
|
||||
failed.append(step)
|
||||
print(">>>> FAILED STEP: %s at %s (%s)" % (step, time.asctime(), msg))
|
||||
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
|
||||
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()))
|
||||
if not passed:
|
||||
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 code size', 'ArduPlane.sizes.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 code size', 'ArduCopter.sizes.txt')
|
||||
results.addfile('ArduCopter stack sizes', 'ArduCopter.framesizes.txt')
|
||||
results.addfile('ArduCopter defaults', 'ArduCopter.defaults.txt')
|
||||
|
||||
write_webresults(results)
|
||||
|
||||
|
|
|
@ -106,11 +106,12 @@ def start_SIL(atype, valgrind=False, wipe=False, CLI=False):
|
|||
return ret
|
||||
|
||||
def start_MAVProxy_SIL(atype, aircraft=None, setup=False, master='tcp:127.0.0.1:5760',
|
||||
fgrate=200,
|
||||
options=None, logfile=sys.stdout):
|
||||
'''launch mavproxy connected to a SIL instance'''
|
||||
global close_list
|
||||
MAVPROXY = reltopdir('../MAVProxy/mavproxy.py')
|
||||
cmd = MAVPROXY + ' --master=%s' % master
|
||||
cmd = MAVPROXY + ' --master=%s --fgrate=%u' % (master, fgrate)
|
||||
if setup:
|
||||
cmd += ' --setup'
|
||||
if aircraft is None:
|
||||
|
|
|
@ -56,6 +56,14 @@ h2 {
|
|||
color:#D14836;
|
||||
}
|
||||
|
||||
.passed-text {
|
||||
color:green;
|
||||
}
|
||||
|
||||
.failed-text {
|
||||
color:red;
|
||||
}
|
||||
|
||||
|
||||
#main {
|
||||
padding-top:0px;
|
||||
|
|
Loading…
Reference in New Issue