mirror of https://github.com/ArduPilot/ardupilot
pysim: support octax
This commit is contained in:
parent
b9b0aa4a81
commit
9833636500
|
@ -50,7 +50,7 @@ def build_motors(frame):
|
||||||
Motor(270, False, 2),
|
Motor(270, False, 2),
|
||||||
Motor(330, True, 3),
|
Motor(330, True, 3),
|
||||||
]
|
]
|
||||||
elif frame in ["octa", "octa+"]:
|
elif frame in ["octa", "octa+", "octax" ]:
|
||||||
motors = [
|
motors = [
|
||||||
Motor(0, True, 1),
|
Motor(0, True, 1),
|
||||||
Motor(180, True, 2),
|
Motor(180, True, 2),
|
||||||
|
@ -61,6 +61,9 @@ def build_motors(frame):
|
||||||
Motor(270, True, 10),
|
Motor(270, True, 10),
|
||||||
Motor(90, True, 11),
|
Motor(90, True, 11),
|
||||||
]
|
]
|
||||||
|
if frame == 'octax':
|
||||||
|
for i in range(8):
|
||||||
|
motors[i].angle += 22.5
|
||||||
else:
|
else:
|
||||||
raise RuntimeError("Unknown multicopter frame type '%s'" % frame)
|
raise RuntimeError("Unknown multicopter frame type '%s'" % frame)
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue