From ce6468c6ee273b412d8c2082f6fb236d6543b503 Mon Sep 17 00:00:00 2001 From: Bob Long Date: Fri, 1 Dec 2023 00:00:36 +1100 Subject: [PATCH] ConfigMotorTest: support Tri frames --- APMotorLayout.json | 858 +++++++++++++++++- GCSViews/ConfigurationView/ConfigMotorTest.cs | 2 +- 2 files changed, 858 insertions(+), 2 deletions(-) diff --git a/APMotorLayout.json b/APMotorLayout.json index 95ef1cae0d..df8803390f 100644 --- a/APMotorLayout.json +++ b/APMotorLayout.json @@ -1,5 +1,5 @@ { - "Version": "AP_Motors library test ver 1.1", + "Version": "AP_Motors library test ver 1.2", "layouts": [ { "Class": 1, @@ -145,6 +145,78 @@ } ] }, + { + "Class": 1, + "ClassName": "QUAD", + "Type": 4, + "TypeName": "VTAIL", + "motors": [ + { + "Number": 1, + "TestOrder": 1, + "Rotation": "?", + "Roll": -0.5000, + "Pitch": 0.2660 + }, + { + "Number": 2, + "TestOrder": 3, + "Rotation": "CW", + "Roll": -0.0000, + "Pitch": -0.5000 + }, + { + "Number": 3, + "TestOrder": 4, + "Rotation": "?", + "Roll": 0.5000, + "Pitch": 0.2660 + }, + { + "Number": 4, + "TestOrder": 2, + "Rotation": "CCW", + "Roll": -0.0000, + "Pitch": -0.5000 + } + ] + }, + { + "Class": 1, + "ClassName": "QUAD", + "Type": 5, + "TypeName": "ATAIL", + "motors": [ + { + "Number": 1, + "TestOrder": 1, + "Rotation": "?", + "Roll": -0.5000, + "Pitch": 0.2660 + }, + { + "Number": 2, + "TestOrder": 3, + "Rotation": "CCW", + "Roll": -0.0000, + "Pitch": -0.5000 + }, + { + "Number": 3, + "TestOrder": 4, + "Rotation": "?", + "Roll": 0.5000, + "Pitch": 0.2660 + }, + { + "Number": 4, + "TestOrder": 2, + "Rotation": "CW", + "Roll": -0.0000, + "Pitch": -0.5000 + } + ] + }, { "Class": 1, "ClassName": "QUAD", @@ -1743,6 +1815,106 @@ } ] }, + { + "Class": 5, + "ClassName": "Y6", + "Type": 4, + "TypeName": "default", + "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, + "ClassName": "Y6", + "Type": 5, + "TypeName": "default", + "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, "ClassName": "Y6", @@ -2393,6 +2565,690 @@ } ] }, + { + "Class": 7, + "ClassName": "TRI", + "Type": 0, + "TypeName": "default", + "motors": [ + { + "Number": 1, + "TestOrder": 1, + "Rotation": "?", + "Roll": -1.0000, + "Pitch": 0.5000 + }, + { + "Number": 2, + "TestOrder": 2, + "Rotation": "?", + "Roll": 1.0000, + "Pitch": 0.5000 + }, + { + "Number": 4, + "TestOrder": 4, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": -1.0000 + }, + { + "Number": 7, + "TestOrder": 3, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": 0.0000 + } + ] + }, + { + "Class": 7, + "ClassName": "TRI", + "Type": 1, + "TypeName": "default", + "motors": [ + { + "Number": 1, + "TestOrder": 1, + "Rotation": "?", + "Roll": -1.0000, + "Pitch": 0.5000 + }, + { + "Number": 2, + "TestOrder": 2, + "Rotation": "?", + "Roll": 1.0000, + "Pitch": 0.5000 + }, + { + "Number": 4, + "TestOrder": 4, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": -1.0000 + }, + { + "Number": 7, + "TestOrder": 3, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": 0.0000 + } + ] + }, + { + "Class": 7, + "ClassName": "TRI", + "Type": 2, + "TypeName": "default", + "motors": [ + { + "Number": 1, + "TestOrder": 1, + "Rotation": "?", + "Roll": -1.0000, + "Pitch": 0.5000 + }, + { + "Number": 2, + "TestOrder": 2, + "Rotation": "?", + "Roll": 1.0000, + "Pitch": 0.5000 + }, + { + "Number": 4, + "TestOrder": 4, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": -1.0000 + }, + { + "Number": 7, + "TestOrder": 3, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": 0.0000 + } + ] + }, + { + "Class": 7, + "ClassName": "TRI", + "Type": 3, + "TypeName": "default", + "motors": [ + { + "Number": 1, + "TestOrder": 1, + "Rotation": "?", + "Roll": -1.0000, + "Pitch": 0.5000 + }, + { + "Number": 2, + "TestOrder": 2, + "Rotation": "?", + "Roll": 1.0000, + "Pitch": 0.5000 + }, + { + "Number": 4, + "TestOrder": 4, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": -1.0000 + }, + { + "Number": 7, + "TestOrder": 3, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": 0.0000 + } + ] + }, + { + "Class": 7, + "ClassName": "TRI", + "Type": 4, + "TypeName": "default", + "motors": [ + { + "Number": 1, + "TestOrder": 1, + "Rotation": "?", + "Roll": -1.0000, + "Pitch": 0.5000 + }, + { + "Number": 2, + "TestOrder": 2, + "Rotation": "?", + "Roll": 1.0000, + "Pitch": 0.5000 + }, + { + "Number": 4, + "TestOrder": 4, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": -1.0000 + }, + { + "Number": 7, + "TestOrder": 3, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": 0.0000 + } + ] + }, + { + "Class": 7, + "ClassName": "TRI", + "Type": 5, + "TypeName": "default", + "motors": [ + { + "Number": 1, + "TestOrder": 1, + "Rotation": "?", + "Roll": -1.0000, + "Pitch": 0.5000 + }, + { + "Number": 2, + "TestOrder": 2, + "Rotation": "?", + "Roll": 1.0000, + "Pitch": 0.5000 + }, + { + "Number": 4, + "TestOrder": 4, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": -1.0000 + }, + { + "Number": 7, + "TestOrder": 3, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": 0.0000 + } + ] + }, + { + "Class": 7, + "ClassName": "TRI", + "Type": 6, + "TypeName": "default", + "motors": [ + { + "Number": 1, + "TestOrder": 1, + "Rotation": "?", + "Roll": -1.0000, + "Pitch": 0.5000 + }, + { + "Number": 2, + "TestOrder": 2, + "Rotation": "?", + "Roll": 1.0000, + "Pitch": 0.5000 + }, + { + "Number": 4, + "TestOrder": 4, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": -1.0000 + }, + { + "Number": 7, + "TestOrder": 3, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": 0.0000 + } + ] + }, + { + "Class": 7, + "ClassName": "TRI", + "Type": 7, + "TypeName": "default", + "motors": [ + { + "Number": 1, + "TestOrder": 1, + "Rotation": "?", + "Roll": -1.0000, + "Pitch": 0.5000 + }, + { + "Number": 2, + "TestOrder": 2, + "Rotation": "?", + "Roll": 1.0000, + "Pitch": 0.5000 + }, + { + "Number": 4, + "TestOrder": 4, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": -1.0000 + }, + { + "Number": 7, + "TestOrder": 3, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": 0.0000 + } + ] + }, + { + "Class": 7, + "ClassName": "TRI", + "Type": 8, + "TypeName": "default", + "motors": [ + { + "Number": 1, + "TestOrder": 1, + "Rotation": "?", + "Roll": -1.0000, + "Pitch": 0.5000 + }, + { + "Number": 2, + "TestOrder": 2, + "Rotation": "?", + "Roll": 1.0000, + "Pitch": 0.5000 + }, + { + "Number": 4, + "TestOrder": 4, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": -1.0000 + }, + { + "Number": 7, + "TestOrder": 3, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": 0.0000 + } + ] + }, + { + "Class": 7, + "ClassName": "TRI", + "Type": 9, + "TypeName": "default", + "motors": [ + { + "Number": 1, + "TestOrder": 1, + "Rotation": "?", + "Roll": -1.0000, + "Pitch": 0.5000 + }, + { + "Number": 2, + "TestOrder": 2, + "Rotation": "?", + "Roll": 1.0000, + "Pitch": 0.5000 + }, + { + "Number": 4, + "TestOrder": 4, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": -1.0000 + }, + { + "Number": 7, + "TestOrder": 3, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": 0.0000 + } + ] + }, + { + "Class": 7, + "ClassName": "TRI", + "Type": 10, + "TypeName": "default", + "motors": [ + { + "Number": 1, + "TestOrder": 1, + "Rotation": "?", + "Roll": -1.0000, + "Pitch": 0.5000 + }, + { + "Number": 2, + "TestOrder": 2, + "Rotation": "?", + "Roll": 1.0000, + "Pitch": 0.5000 + }, + { + "Number": 4, + "TestOrder": 4, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": -1.0000 + }, + { + "Number": 7, + "TestOrder": 3, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": 0.0000 + } + ] + }, + { + "Class": 7, + "ClassName": "TRI", + "Type": 11, + "TypeName": "default", + "motors": [ + { + "Number": 1, + "TestOrder": 1, + "Rotation": "?", + "Roll": -1.0000, + "Pitch": 0.5000 + }, + { + "Number": 2, + "TestOrder": 2, + "Rotation": "?", + "Roll": 1.0000, + "Pitch": 0.5000 + }, + { + "Number": 4, + "TestOrder": 4, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": -1.0000 + }, + { + "Number": 7, + "TestOrder": 3, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": 0.0000 + } + ] + }, + { + "Class": 7, + "ClassName": "TRI", + "Type": 12, + "TypeName": "default", + "motors": [ + { + "Number": 1, + "TestOrder": 1, + "Rotation": "?", + "Roll": -1.0000, + "Pitch": 0.5000 + }, + { + "Number": 2, + "TestOrder": 2, + "Rotation": "?", + "Roll": 1.0000, + "Pitch": 0.5000 + }, + { + "Number": 4, + "TestOrder": 4, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": -1.0000 + }, + { + "Number": 7, + "TestOrder": 3, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": 0.0000 + } + ] + }, + { + "Class": 7, + "ClassName": "TRI", + "Type": 13, + "TypeName": "default", + "motors": [ + { + "Number": 1, + "TestOrder": 1, + "Rotation": "?", + "Roll": -1.0000, + "Pitch": 0.5000 + }, + { + "Number": 2, + "TestOrder": 2, + "Rotation": "?", + "Roll": 1.0000, + "Pitch": 0.5000 + }, + { + "Number": 4, + "TestOrder": 4, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": -1.0000 + }, + { + "Number": 7, + "TestOrder": 3, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": 0.0000 + } + ] + }, + { + "Class": 7, + "ClassName": "TRI", + "Type": 14, + "TypeName": "default", + "motors": [ + { + "Number": 1, + "TestOrder": 1, + "Rotation": "?", + "Roll": -1.0000, + "Pitch": 0.5000 + }, + { + "Number": 2, + "TestOrder": 2, + "Rotation": "?", + "Roll": 1.0000, + "Pitch": 0.5000 + }, + { + "Number": 4, + "TestOrder": 4, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": -1.0000 + }, + { + "Number": 7, + "TestOrder": 3, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": 0.0000 + } + ] + }, + { + "Class": 7, + "ClassName": "TRI", + "Type": 15, + "TypeName": "default", + "motors": [ + { + "Number": 1, + "TestOrder": 1, + "Rotation": "?", + "Roll": -1.0000, + "Pitch": 0.5000 + }, + { + "Number": 2, + "TestOrder": 2, + "Rotation": "?", + "Roll": 1.0000, + "Pitch": 0.5000 + }, + { + "Number": 4, + "TestOrder": 4, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": -1.0000 + }, + { + "Number": 7, + "TestOrder": 3, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": 0.0000 + } + ] + }, + { + "Class": 7, + "ClassName": "TRI", + "Type": 16, + "TypeName": "default", + "motors": [ + { + "Number": 1, + "TestOrder": 1, + "Rotation": "?", + "Roll": -1.0000, + "Pitch": 0.5000 + }, + { + "Number": 2, + "TestOrder": 2, + "Rotation": "?", + "Roll": 1.0000, + "Pitch": 0.5000 + }, + { + "Number": 4, + "TestOrder": 4, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": -1.0000 + }, + { + "Number": 7, + "TestOrder": 3, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": 0.0000 + } + ] + }, + { + "Class": 7, + "ClassName": "TRI", + "Type": 17, + "TypeName": "default", + "motors": [ + { + "Number": 1, + "TestOrder": 1, + "Rotation": "?", + "Roll": -1.0000, + "Pitch": 0.5000 + }, + { + "Number": 2, + "TestOrder": 2, + "Rotation": "?", + "Roll": 1.0000, + "Pitch": 0.5000 + }, + { + "Number": 4, + "TestOrder": 4, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": -1.0000 + }, + { + "Number": 7, + "TestOrder": 3, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": 0.0000 + } + ] + }, + { + "Class": 7, + "ClassName": "TRI", + "Type": 18, + "TypeName": "default", + "motors": [ + { + "Number": 1, + "TestOrder": 1, + "Rotation": "?", + "Roll": -1.0000, + "Pitch": 0.5000 + }, + { + "Number": 2, + "TestOrder": 2, + "Rotation": "?", + "Roll": 1.0000, + "Pitch": 0.5000 + }, + { + "Number": 4, + "TestOrder": 4, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": -1.0000 + }, + { + "Number": 7, + "TestOrder": 3, + "Rotation": "?", + "Roll": 0.0000, + "Pitch": 0.0000 + } + ] + }, { "Class": 12, "ClassName": "DODECAHEXA", diff --git a/GCSViews/ConfigurationView/ConfigMotorTest.cs b/GCSViews/ConfigurationView/ConfigMotorTest.cs index ed4e206c98..f2b697de41 100644 --- a/GCSViews/ConfigurationView/ConfigMotorTest.cs +++ b/GCSViews/ConfigurationView/ConfigMotorTest.cs @@ -242,7 +242,7 @@ private void lookup_frame_layout(int frame_class, int frame_type) { string json = r.ReadToEnd(); var all_layouts = JsonConvert.DeserializeObject(json); - if (all_layouts.Version == "AP_Motors library test ver 1.1") + if (all_layouts.Version == "AP_Motors library test ver 1.2") { foreach (var layout in all_layouts.layouts) {