mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
autotest: change to an octa frame for autotest
this will be a useful experiment
This commit is contained in:
parent
efa649e51a
commit
64b541037e
@ -7,7 +7,8 @@ import mavutil, mavwp, random
|
|||||||
# get location of scripts
|
# get location of scripts
|
||||||
testdir=os.path.dirname(os.path.realpath(__file__))
|
testdir=os.path.dirname(os.path.realpath(__file__))
|
||||||
|
|
||||||
|
FRAME='octa'
|
||||||
|
TARGET='sitl-octa'
|
||||||
HOME=location(-35.362938,149.165085,584,270)
|
HOME=location(-35.362938,149.165085,584,270)
|
||||||
|
|
||||||
homeloc = None
|
homeloc = None
|
||||||
@ -280,8 +281,11 @@ def fly_ArduCopter(viewerip=None):
|
|||||||
'''
|
'''
|
||||||
global homeloc
|
global homeloc
|
||||||
|
|
||||||
sim_cmd = util.reltopdir('Tools/autotest/pysim/sim_multicopter.py') + ' --rate=400 --home=%f,%f,%u,%u' % (
|
if TARGET != 'sitl':
|
||||||
HOME.lat, HOME.lng, HOME.alt, HOME.heading)
|
util.build_SIL('ArduCopter', target=TARGET)
|
||||||
|
|
||||||
|
sim_cmd = util.reltopdir('Tools/autotest/pysim/sim_multicopter.py') + ' --frame=%s --rate=400 --home=%f,%f,%u,%u' % (
|
||||||
|
FRAME, HOME.lat, HOME.lng, HOME.alt, HOME.heading)
|
||||||
sim_cmd += ' --wind=6,45,.3'
|
sim_cmd += ' --wind=6,45,.3'
|
||||||
if viewerip:
|
if viewerip:
|
||||||
sim_cmd += ' --fgout=%s:5503' % viewerip
|
sim_cmd += ' --fgout=%s:5503' % viewerip
|
||||||
|
@ -139,9 +139,9 @@ def deltree(path):
|
|||||||
|
|
||||||
|
|
||||||
|
|
||||||
def build_SIL(atype):
|
def build_SIL(atype, target='sitl'):
|
||||||
'''build desktop SIL'''
|
'''build desktop SIL'''
|
||||||
run_cmd("make clean sitl",
|
run_cmd("make clean %s" % target,
|
||||||
dir=reltopdir(atype),
|
dir=reltopdir(atype),
|
||||||
checkfail=True)
|
checkfail=True)
|
||||||
return True
|
return True
|
||||||
|
Loading…
Reference in New Issue
Block a user