added octa-quad target for SITL, fixed octa motor order

This commit is contained in:
Andrew Chapman 2015-02-24 20:04:09 -08:00 committed by Randy Mackay
parent a2d5ac6805
commit e90f5375d0
2 changed files with 19 additions and 4 deletions

View File

@ -58,14 +58,25 @@ def build_motors(frame):
Motor(180, True, 2),
Motor(45, False, 3),
Motor(135, False, 4),
Motor(-45, False, 7),
Motor(-135, False, 8),
Motor(270, True, 10),
Motor(90, True, 11),
Motor(-45, False, 5),
Motor(-135, False, 6),
Motor(270, True, 7),
Motor(90, True, 8),
]
if frame == 'octax':
for i in range(8):
motors[i].angle += 22.5
elif frame in ["octa-quad"]:
motors = [
Motor( 45, False, 1),
Motor( -45, True, 2),
Motor(-135, False, 3),
Motor( 135, True, 4),
Motor( -45, False, 5),
Motor( 45, True, 6),
Motor( 135, False, 7),
Motor(-135, True, 8),
]
else:
raise RuntimeError("Unknown multicopter frame type '%s'" % frame)

View File

@ -184,6 +184,10 @@ case $FRAME in
BUILD_TARGET="sitl-octa"
EXTRA_SIM="--frame=octa"
;;
octa-quad)
BUILD_TARGET="sitl-octa-quad"
EXTRA_SIM="--frame=octa-quad"
;;
heli)
BUILD_TARGET="sitl-heli"
EXTRA_SIM="--frame=heli"