{ "Version": "AP_Motors library test ver 1.1", "layouts": [ { "Class": 1, "Type": 0, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": -0.0000 }, { "Number": 2, "TestOrder": 4, "Rotation": "CCW", "Roll": 0.5000, "Pitch": -0.0000 }, { "Number": 3, "TestOrder": 1, "Rotation": "CW", "Roll": -0.0000, "Pitch": 0.5000 }, { "Number": 4, "TestOrder": 3, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 } ] }, { "Class": 1, "Type": 1, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.5000, "Pitch": -0.5000 }, { "Number": 3, "TestOrder": 4, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.5000 }, { "Number": 4, "TestOrder": 2, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.5000 } ] }, { "Class": 1, "Type": 2, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.5000, "Pitch": -0.5000 }, { "Number": 3, "TestOrder": 4, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.5000 }, { "Number": 4, "TestOrder": 2, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.5000 } ] }, { "Class": 1, "Type": 3, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 3, "Rotation": "CW", "Roll": 0.5000, "Pitch": -0.5000 }, { "Number": 3, "TestOrder": 4, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.5000 }, { "Number": 4, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": -0.5000 } ] }, { "Class": 1, "Type": 6, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.0000 }, { "Number": 2, "TestOrder": 4, "Rotation": "CW", "Roll": 0.5000, "Pitch": -0.0000 }, { "Number": 3, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.0000, "Pitch": 0.5000 }, { "Number": 4, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.0000, "Pitch": -0.5000 } ] }, { "Class": 1, "Type": 12, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.5000 }, { "Number": 2, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 3, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.5000, "Pitch": -0.5000 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.5000 } ] }, { "Class": 1, "Type": 13, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 4, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.5000 }, { "Number": 3, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.5000, "Pitch": -0.5000 }, { "Number": 4, "TestOrder": 2, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.5000 } ] }, { "Class": 1, "Type": 14, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 2, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.5000 }, { "Number": 3, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.5000, "Pitch": -0.5000 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.5000 } ] }, { "Class": 1, "Type": 16, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "?", "Roll": -0.5000, "Pitch": -0.0000 }, { "Number": 2, "TestOrder": 4, "Rotation": "?", "Roll": 0.5000, "Pitch": -0.0000 }, { "Number": 3, "TestOrder": 1, "Rotation": "?", "Roll": -0.0000, "Pitch": 0.5000 }, { "Number": 4, "TestOrder": 3, "Rotation": "?", "Roll": 0.0000, "Pitch": -0.5000 } ] }, { "Class": 1, "Type": 17, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "?", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 3, "Rotation": "?", "Roll": 0.5000, "Pitch": -0.5000 }, { "Number": 3, "TestOrder": 4, "Rotation": "?", "Roll": 0.5000, "Pitch": 0.5000 }, { "Number": 4, "TestOrder": 2, "Rotation": "?", "Roll": -0.5000, "Pitch": -0.5000 } ] }, { "Class": 1, "Type": 18, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": -0.5000 }, { "Number": 2, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 3, "TestOrder": 3, "Rotation": "CW", "Roll": 0.5000, "Pitch": -0.5000 }, { "Number": 4, "TestOrder": 4, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.5000 } ] }, { "Class": 2, "Type": 0, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CW", "Roll": -0.0000, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 4, "Rotation": "CCW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 3, "TestOrder": 5, "Rotation": "CW", "Roll": 0.5000, "Pitch": -0.2500 }, { "Number": 4, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.2500 }, { "Number": 5, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.2500 }, { "Number": 6, "TestOrder": 3, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.2500 } ] }, { "Class": 2, "Type": 1, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.0000 }, { "Number": 2, "TestOrder": 5, "Rotation": "CCW", "Roll": 0.5000, "Pitch": -0.0000 }, { "Number": 3, "TestOrder": 6, "Rotation": "CW", "Roll": 0.2500, "Pitch": 0.5000 }, { "Number": 4, "TestOrder": 3, "Rotation": "CCW", "Roll": -0.2500, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.2500, "Pitch": 0.5000 }, { "Number": 6, "TestOrder": 4, "Rotation": "CW", "Roll": 0.2500, "Pitch": -0.5000 } ] }, { "Class": 2, "Type": 3, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.0000 }, { "Number": 2, "TestOrder": 5, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.0000 }, { "Number": 3, "TestOrder": 6, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.5000 }, { "Number": 4, "TestOrder": 3, "Rotation": "CCW", "Roll": -0.5000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 6, "TestOrder": 4, "Rotation": "CW", "Roll": 0.5000, "Pitch": -0.5000 } ] }, { "Class": 2, "Type": 13, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.2500, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 6, "Rotation": "CW", "Roll": 0.2500, "Pitch": 0.5000 }, { "Number": 3, "TestOrder": 5, "Rotation": "CCW", "Roll": 0.5000, "Pitch": -0.0000 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": 0.2500, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 3, "Rotation": "CCW", "Roll": -0.2500, "Pitch": -0.5000 }, { "Number": 6, "TestOrder": 2, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.0000 } ] }, { "Class": 2, "Type": 14, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.2500, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 2, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.0000 }, { "Number": 3, "TestOrder": 3, "Rotation": "CCW", "Roll": -0.2500, "Pitch": -0.5000 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": 0.2500, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 5, "Rotation": "CCW", "Roll": 0.5000, "Pitch": -0.0000 }, { "Number": 6, "TestOrder": 6, "Rotation": "CW", "Roll": 0.2500, "Pitch": 0.5000 } ] }, { "Class": 3, "Type": 0, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CW", "Roll": -0.0000, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 5, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 3, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.3535, "Pitch": 0.3535 }, { "Number": 4, "TestOrder": 4, "Rotation": "CCW", "Roll": -0.3535, "Pitch": -0.3535 }, { "Number": 5, "TestOrder": 8, "Rotation": "CCW", "Roll": 0.3535, "Pitch": 0.3535 }, { "Number": 6, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.3535, "Pitch": -0.3535 }, { "Number": 7, "TestOrder": 7, "Rotation": "CW", "Roll": 0.5000, "Pitch": -0.0000 }, { "Number": 8, "TestOrder": 3, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.0000 } ] }, { "Class": 3, "Type": 1, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CW", "Roll": -0.2071, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 5, "Rotation": "CW", "Roll": 0.2071, "Pitch": -0.5000 }, { "Number": 3, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.2071 }, { "Number": 4, "TestOrder": 4, "Rotation": "CCW", "Roll": -0.2071, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 8, "Rotation": "CCW", "Roll": 0.2071, "Pitch": 0.5000 }, { "Number": 6, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": -0.2071 }, { "Number": 7, "TestOrder": 7, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.2071 }, { "Number": 8, "TestOrder": 3, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.2071 } ] }, { "Class": 3, "Type": 2, "motors": [ { "Number": 1, "TestOrder": 7, "Rotation": "CW", "Roll": 0.4150, "Pitch": 0.1700 }, { "Number": 2, "TestOrder": 3, "Rotation": "CW", "Roll": -0.3350, "Pitch": -0.1600 }, { "Number": 3, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.3350, "Pitch": -0.1600 }, { "Number": 4, "TestOrder": 4, "Rotation": "CCW", "Roll": -0.2500, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 8, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.5000 }, { "Number": 6, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.4150, "Pitch": 0.1700 }, { "Number": 7, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 8, "TestOrder": 5, "Rotation": "CW", "Roll": 0.2500, "Pitch": -0.5000 } ] }, { "Class": 3, "Type": 3, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 5, "Rotation": "CW", "Roll": 0.5000, "Pitch": -0.5000 }, { "Number": 3, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.1665 }, { "Number": 4, "TestOrder": 4, "Rotation": "CCW", "Roll": -0.5000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 8, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.5000 }, { "Number": 6, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": -0.1665 }, { "Number": 7, "TestOrder": 7, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.1665 }, { "Number": 8, "TestOrder": 3, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.1665 } ] }, { "Class": 3, "Type": 13, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.2071, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 8, "Rotation": "CW", "Roll": 0.2071, "Pitch": 0.5000 }, { "Number": 3, "TestOrder": 7, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.2071 }, { "Number": 4, "TestOrder": 6, "Rotation": "CW", "Roll": 0.5000, "Pitch": -0.2071 }, { "Number": 5, "TestOrder": 5, "Rotation": "CCW", "Roll": 0.2071, "Pitch": -0.5000 }, { "Number": 6, "TestOrder": 4, "Rotation": "CW", "Roll": -0.2071, "Pitch": -0.5000 }, { "Number": 7, "TestOrder": 3, "Rotation": "CCW", "Roll": -0.5000, "Pitch": -0.2071 }, { "Number": 8, "TestOrder": 2, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.2071 } ] }, { "Class": 3, "Type": 14, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.2071, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 2, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.2071 }, { "Number": 3, "TestOrder": 3, "Rotation": "CCW", "Roll": -0.5000, "Pitch": -0.2071 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": -0.2071, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 5, "Rotation": "CCW", "Roll": 0.2071, "Pitch": -0.5000 }, { "Number": 6, "TestOrder": 6, "Rotation": "CW", "Roll": 0.5000, "Pitch": -0.2071 }, { "Number": 7, "TestOrder": 7, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.2071 }, { "Number": 8, "TestOrder": 8, "Rotation": "CW", "Roll": 0.2071, "Pitch": 0.5000 } ] }, { "Class": 3, "Type": 15, "motors": [ { "Number": 1, "TestOrder": 5, "Rotation": "CW", "Roll": 0.1665, "Pitch": -0.5000 }, { "Number": 2, "TestOrder": 1, "Rotation": "CW", "Roll": -0.1665, "Pitch": 0.5000 }, { "Number": 3, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": -0.5000 }, { "Number": 4, "TestOrder": 8, "Rotation": "CCW", "Roll": 0.1665, "Pitch": 0.5000 }, { "Number": 5, "TestOrder": 4, "Rotation": "CCW", "Roll": -0.1665, "Pitch": -0.5000 }, { "Number": 6, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 7, "TestOrder": 3, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.5000 }, { "Number": 8, "TestOrder": 7, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.5000 } ] }, { "Class": 4, "Type": 0, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.0000, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 7, "Rotation": "CW", "Roll": 0.5000, "Pitch": -0.0000 }, { "Number": 3, "TestOrder": 5, "Rotation": "CCW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 4, "TestOrder": 3, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.0000 }, { "Number": 5, "TestOrder": 8, "Rotation": "CCW", "Roll": 0.5000, "Pitch": -0.0000 }, { "Number": 6, "TestOrder": 2, "Rotation": "CW", "Roll": -0.0000, "Pitch": 0.5000 }, { "Number": 7, "TestOrder": 4, "Rotation": "CCW", "Roll": -0.5000, "Pitch": -0.0000 }, { "Number": 8, "TestOrder": 6, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 } ] }, { "Class": 4, "Type": 1, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 7, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.5000 }, { "Number": 3, "TestOrder": 5, "Rotation": "CCW", "Roll": 0.5000, "Pitch": -0.5000 }, { "Number": 4, "TestOrder": 3, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 8, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.5000 }, { "Number": 6, "TestOrder": 2, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 7, "TestOrder": 4, "Rotation": "CCW", "Roll": -0.5000, "Pitch": -0.5000 }, { "Number": 8, "TestOrder": 6, "Rotation": "CW", "Roll": 0.5000, "Pitch": -0.5000 } ] }, { "Class": 4, "Type": 2, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 7, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.5000 }, { "Number": 3, "TestOrder": 5, "Rotation": "CCW", "Roll": 0.5000, "Pitch": -0.5000 }, { "Number": 4, "TestOrder": 3, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 8, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.5000 }, { "Number": 6, "TestOrder": 2, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 7, "TestOrder": 4, "Rotation": "CCW", "Roll": -0.5000, "Pitch": -0.5000 }, { "Number": 8, "TestOrder": 6, "Rotation": "CW", "Roll": 0.5000, "Pitch": -0.5000 } ] }, { "Class": 4, "Type": 3, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 7, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.5000 }, { "Number": 3, "TestOrder": 5, "Rotation": "CW", "Roll": 0.5000, "Pitch": -0.5000 }, { "Number": 4, "TestOrder": 3, "Rotation": "CCW", "Roll": -0.5000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 8, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.5000 }, { "Number": 6, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 7, "TestOrder": 4, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.5000 }, { "Number": 8, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": -0.5000 } ] }, { "Class": 4, "Type": 12, "motors": [ { "Number": 1, "TestOrder": 3, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.5000 }, { "Number": 2, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 3, "TestOrder": 5, "Rotation": "CCW", "Roll": 0.5000, "Pitch": -0.5000 }, { "Number": 4, "TestOrder": 7, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.5000 }, { "Number": 5, "TestOrder": 4, "Rotation": "CCW", "Roll": -0.5000, "Pitch": -0.5000 }, { "Number": 6, "TestOrder": 2, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 7, "TestOrder": 6, "Rotation": "CW", "Roll": 0.5000, "Pitch": -0.5000 }, { "Number": 8, "TestOrder": 8, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.5000 } ] }, { "Class": 4, "Type": 14, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 2, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 3, "TestOrder": 3, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.5000 }, { "Number": 4, "TestOrder": 4, "Rotation": "CCW", "Roll": -0.5000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 5, "Rotation": "CCW", "Roll": 0.5000, "Pitch": -0.5000 }, { "Number": 6, "TestOrder": 6, "Rotation": "CW", "Roll": 0.5000, "Pitch": -0.5000 }, { "Number": 7, "TestOrder": 7, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.5000 }, { "Number": 8, "TestOrder": 8, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.5000 } ] }, { "Class": 4, "Type": 18, "motors": [ { "Number": 1, "TestOrder": 3, "Rotation": "CCW", "Roll": -0.5000, "Pitch": -0.5000 }, { "Number": 2, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 3, "TestOrder": 5, "Rotation": "CW", "Roll": 0.5000, "Pitch": -0.5000 }, { "Number": 4, "TestOrder": 7, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.5000 }, { "Number": 5, "TestOrder": 4, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.5000 }, { "Number": 6, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.5000 }, { "Number": 7, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": -0.5000 }, { "Number": 8, "TestOrder": 8, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.5000 } ] }, { "Class": 5, "Type": 0, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 2, "TestOrder": 5, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 3, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 6, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.0000, "Pitch": -0.5000 } ] }, { "Class": 5, "Type": 1, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 2, "TestOrder": 5, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 3, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 6, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.0000, "Pitch": -0.5000 } ] }, { "Class": 5, "Type": 2, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 2, "TestOrder": 5, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 3, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 6, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.0000, "Pitch": -0.5000 } ] }, { "Class": 5, "Type": 3, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 2, "TestOrder": 5, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 3, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 6, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.0000, "Pitch": -0.5000 } ] }, { "Class": 5, "Type": 6, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 2, "TestOrder": 5, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 3, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 6, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.0000, "Pitch": -0.5000 } ] }, { "Class": 5, "Type": 7, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 2, "TestOrder": 5, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 3, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 6, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.0000, "Pitch": -0.5000 } ] }, { "Class": 5, "Type": 8, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 2, "TestOrder": 5, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 3, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 6, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.0000, "Pitch": -0.5000 } ] }, { "Class": 5, "Type": 9, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 2, "TestOrder": 5, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 3, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 6, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.0000, "Pitch": -0.5000 } ] }, { "Class": 5, "Type": 10, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.2500 }, { "Number": 2, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.2500 }, { "Number": 3, "TestOrder": 3, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 4, "TestOrder": 4, "Rotation": "CCW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 5, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.2500 }, { "Number": 6, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.2500 } ] }, { "Class": 5, "Type": 11, "motors": [ { "Number": 1, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 2, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.2500 }, { "Number": 3, "TestOrder": 5, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.2500 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 2, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.2500 }, { "Number": 6, "TestOrder": 6, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.2500 } ] }, { "Class": 5, "Type": 12, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 2, "TestOrder": 5, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 3, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 6, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.0000, "Pitch": -0.5000 } ] }, { "Class": 5, "Type": 13, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 2, "TestOrder": 5, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 3, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 6, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.0000, "Pitch": -0.5000 } ] }, { "Class": 5, "Type": 14, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 2, "TestOrder": 5, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 3, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 6, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.0000, "Pitch": -0.5000 } ] }, { "Class": 5, "Type": 15, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 2, "TestOrder": 5, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 3, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 6, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.0000, "Pitch": -0.5000 } ] }, { "Class": 5, "Type": 16, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 2, "TestOrder": 5, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 3, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 6, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.0000, "Pitch": -0.5000 } ] }, { "Class": 5, "Type": 17, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 2, "TestOrder": 5, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 3, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 6, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.0000, "Pitch": -0.5000 } ] }, { "Class": 5, "Type": 18, "motors": [ { "Number": 1, "TestOrder": 2, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 2, "TestOrder": 5, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 3, "TestOrder": 6, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.2498 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 5, "TestOrder": 1, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.2498 }, { "Number": 6, "TestOrder": 3, "Rotation": "CCW", "Roll": 0.0000, "Pitch": -0.5000 } ] }, { "Class": 12, "Type": 0, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.0000, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 2, "Rotation": "CW", "Roll": -0.0000, "Pitch": 0.5000 }, { "Number": 3, "TestOrder": 3, "Rotation": "CW", "Roll": -0.5000, "Pitch": 0.2500 }, { "Number": 4, "TestOrder": 4, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.2500 }, { "Number": 5, "TestOrder": 5, "Rotation": "CCW", "Roll": -0.5000, "Pitch": -0.2500 }, { "Number": 6, "TestOrder": 6, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.2500 }, { "Number": 7, "TestOrder": 7, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 8, "TestOrder": 8, "Rotation": "CCW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 9, "TestOrder": 9, "Rotation": "CCW", "Roll": 0.5000, "Pitch": -0.2500 }, { "Number": 10, "TestOrder": 10, "Rotation": "CW", "Roll": 0.5000, "Pitch": -0.2500 }, { "Number": 11, "TestOrder": 11, "Rotation": "CW", "Roll": 0.5000, "Pitch": 0.2500 }, { "Number": 12, "TestOrder": 12, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.2500 } ] }, { "Class": 12, "Type": 1, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.2500, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 2, "Rotation": "CW", "Roll": -0.2500, "Pitch": 0.5000 }, { "Number": 3, "TestOrder": 3, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.0000 }, { "Number": 4, "TestOrder": 4, "Rotation": "CCW", "Roll": -0.5000, "Pitch": -0.0000 }, { "Number": 5, "TestOrder": 5, "Rotation": "CCW", "Roll": -0.2500, "Pitch": -0.5000 }, { "Number": 6, "TestOrder": 6, "Rotation": "CW", "Roll": -0.2500, "Pitch": -0.5000 }, { "Number": 7, "TestOrder": 7, "Rotation": "CW", "Roll": 0.2500, "Pitch": -0.5000 }, { "Number": 8, "TestOrder": 8, "Rotation": "CCW", "Roll": 0.2500, "Pitch": -0.5000 }, { "Number": 9, "TestOrder": 9, "Rotation": "CCW", "Roll": 0.5000, "Pitch": -0.0000 }, { "Number": 10, "TestOrder": 10, "Rotation": "CW", "Roll": 0.5000, "Pitch": -0.0000 }, { "Number": 11, "TestOrder": 11, "Rotation": "CW", "Roll": 0.2500, "Pitch": 0.5000 }, { "Number": 12, "TestOrder": 12, "Rotation": "CCW", "Roll": 0.2500, "Pitch": 0.5000 } ] }, { "Class": 14, "Type": 0, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.0000, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 2, "Rotation": "CW", "Roll": -0.3090, "Pitch": 0.4045 }, { "Number": 3, "TestOrder": 3, "Rotation": "CCW", "Roll": -0.5000, "Pitch": 0.1545 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": -0.5000, "Pitch": -0.1545 }, { "Number": 5, "TestOrder": 5, "Rotation": "CCW", "Roll": -0.3090, "Pitch": -0.4045 }, { "Number": 6, "TestOrder": 6, "Rotation": "CW", "Roll": 0.0000, "Pitch": -0.5000 }, { "Number": 7, "TestOrder": 7, "Rotation": "CCW", "Roll": 0.3090, "Pitch": -0.4045 }, { "Number": 8, "TestOrder": 8, "Rotation": "CW", "Roll": 0.5000, "Pitch": -0.1545 }, { "Number": 9, "TestOrder": 9, "Rotation": "CCW", "Roll": 0.5000, "Pitch": 0.1545 }, { "Number": 10, "TestOrder": 10, "Rotation": "CW", "Roll": 0.3090, "Pitch": 0.4045 } ] }, { "Class": 14, "Type": 1, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.1545, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 2, "Rotation": "CW", "Roll": -0.4045, "Pitch": 0.3090 }, { "Number": 3, "TestOrder": 3, "Rotation": "CCW", "Roll": -0.5000, "Pitch": -0.0000 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": -0.4045, "Pitch": -0.3090 }, { "Number": 5, "TestOrder": 5, "Rotation": "CCW", "Roll": -0.1545, "Pitch": -0.5000 }, { "Number": 6, "TestOrder": 6, "Rotation": "CW", "Roll": 0.1545, "Pitch": -0.5000 }, { "Number": 7, "TestOrder": 7, "Rotation": "CCW", "Roll": 0.4045, "Pitch": -0.3090 }, { "Number": 8, "TestOrder": 8, "Rotation": "CW", "Roll": 0.5000, "Pitch": -0.0000 }, { "Number": 9, "TestOrder": 9, "Rotation": "CCW", "Roll": 0.4045, "Pitch": 0.3090 }, { "Number": 10, "TestOrder": 10, "Rotation": "CW", "Roll": 0.1545, "Pitch": 0.5000 } ] }, { "Class": 14, "Type": 14, "motors": [ { "Number": 1, "TestOrder": 1, "Rotation": "CCW", "Roll": -0.1545, "Pitch": 0.5000 }, { "Number": 2, "TestOrder": 2, "Rotation": "CW", "Roll": -0.4045, "Pitch": 0.3090 }, { "Number": 3, "TestOrder": 3, "Rotation": "CCW", "Roll": -0.5000, "Pitch": -0.0000 }, { "Number": 4, "TestOrder": 4, "Rotation": "CW", "Roll": -0.4045, "Pitch": -0.3090 }, { "Number": 5, "TestOrder": 5, "Rotation": "CCW", "Roll": -0.1545, "Pitch": -0.5000 }, { "Number": 6, "TestOrder": 6, "Rotation": "CW", "Roll": 0.1545, "Pitch": -0.5000 }, { "Number": 7, "TestOrder": 7, "Rotation": "CCW", "Roll": 0.4045, "Pitch": -0.3090 }, { "Number": 8, "TestOrder": 8, "Rotation": "CW", "Roll": 0.5000, "Pitch": -0.0000 }, { "Number": 9, "TestOrder": 9, "Rotation": "CCW", "Roll": 0.4045, "Pitch": 0.3090 }, { "Number": 10, "TestOrder": 10, "Rotation": "CW", "Roll": 0.1545, "Pitch": 0.5000 } ] } ] }