Skip to content

Commit

Permalink
GCSViews: ConfigurationView: Motor test: use JSON file to add more in…
Browse files Browse the repository at this point in the history
…fromation (ArduPilot#3043)

* Include `APMotorLayout.json` in build

* GCSViews: ConfigurationView: Motor test: use JSON file to add more infromation

---------

Co-authored-by: Michael Oborne <[email protected]>
  • Loading branch information
IamPete1 and meee1 authored Oct 3, 2023
1 parent 3ea4f5e commit dedc9ef
Show file tree
Hide file tree
Showing 10 changed files with 3,080 additions and 96 deletions.
2,815 changes: 2,815 additions & 0 deletions APMotorLayout.json

Large diffs are not rendered by default.

3 changes: 3 additions & 0 deletions ExtLibs/Xamarin/Xamarin/files.resx
Original file line number Diff line number Diff line change
Expand Up @@ -145,6 +145,9 @@
<data name="FirmwareHistory" type="System.Resources.ResXFileRef, System.Windows.Forms">
<value>..\..\..\FirmwareHistory.txt;System.String, mscorlib, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;utf-8</value>
</data>
<data name="APMotorLayout" type="System.Resources.ResXFileRef, System.Windows.Forms">
<value>..\..\..\APMotorLayout.json;System.String, mscorlib, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;utf-8</value>
</data>
<data name="HighContrast" type="System.Resources.ResXFileRef, System.Windows.Forms">
<value>..\..\..\HighContrast.mpsystheme;System.String, mscorlib, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;utf-8</value>
</data>
Expand Down
46 changes: 32 additions & 14 deletions GCSViews/ConfigurationView/ConfigMotorTest.Designer.cs

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

157 changes: 118 additions & 39 deletions GCSViews/ConfigurationView/ConfigMotorTest.cs
Original file line number Diff line number Diff line change
@@ -1,9 +1,12 @@
using MissionPlanner.Controls;
using MissionPlanner.HIL;
using MissionPlanner.Utilities;
using System;
using System.Diagnostics;
using System.Drawing;
using System.Windows.Forms;
using System.Reflection;
using Newtonsoft.Json;
using System.IO;

namespace MissionPlanner.GCSViews.ConfigurationView
{
Expand All @@ -14,31 +17,35 @@ public ConfigMotorTest()
InitializeComponent();
}

/*
#if (FRAME_CONFIG == QUAD_FRAME)
MAV_TYPE_QUADROTOR,
#elif (FRAME_CONFIG == TRI_FRAME)
MAV_TYPE_TRICOPTER,
#elif (FRAME_CONFIG == HEXA_FRAME || FRAME_CONFIG == Y6_FRAME)
MAV_TYPE_HEXAROTOR,
#elif (FRAME_CONFIG == OCTA_FRAME || FRAME_CONFIG == OCTA_QUAD_FRAME)
MAV_TYPE_OCTOROTOR,
#elif (FRAME_CONFIG == HELI_FRAME)
MAV_TYPE_HELICOPTER,
#elif (FRAME_CONFIG == SINGLE_FRAME) //because mavlink did not define a singlecopter, we use a rocket
MAV_TYPE_ROCKET,
#elif (FRAME_CONFIG == COAX_FRAME) //because mavlink did not define a singlecopter, we use a rocket
MAV_TYPE_ROCKET,
#else
#error Unrecognised frame type
#endif*/
private int motormax = 0;

private struct _motors
{
public int Number { get; set; }
public int TestOrder { get; set; }
public string Rotation { get; set; }
public float Roll { get; set; }
public float Pitch { get; set; }
}
struct _layouts
{
public int Class { get; set; }
public int Type { get; set; }
public _motors[] motors { get; set; }
}
private struct JSON_motors
{
public string Version { get; set; }
public _layouts[] layouts { get; set; }
}
private _layouts motor_layout;

public void Activate()
{
var x = 20;
var y = 40;
var x = 6;
var y = 75;

var motormax = this.get_motormax();
motormax = this.get_motormax();

MyButton but;
for (var a = 1; a <= motormax; a++)
Expand All @@ -51,6 +58,25 @@ public void Activate()

groupBox1.Controls.Add(but);

if (motor_layout.motors != null)
{
foreach (var motor in motor_layout.motors)
{
if (motor.TestOrder == a)
{
var lab = new Label();
lab.Text += "Motor Number: " + motor.Number;
if (motor.Rotation != "?")
{
lab.Text += ", " + motor.Rotation;
}
lab.Location = new Point(x + 85, y + 5);
lab.Width = 150;
groupBox1.Controls.Add(lab);
}
}
}

y += 25;
}

Expand Down Expand Up @@ -99,8 +125,16 @@ private int get_motormax()
return motormax;
}

if (set_frame_class_and_type("FRAME_CLASS", "FRAME_TYPE") ||
set_frame_class_and_type("Q_FRAME_CLASS", "Q_FRAME_TYPE"))
{
if (motor_layout.motors != null)
{
return motor_layout.motors.Length;
}
}

MAVLink.MAV_TYPE type = MAVLink.MAV_TYPE.QUADROTOR;
int frame_type = 0; // + frame

if (MainV2.comPort.MAV.param.ContainsKey("Q_FRAME_CLASS"))
{
Expand All @@ -127,44 +161,31 @@ private int get_motormax()
break;
}

frame_type = (int)MainV2.comPort.MAV.param["Q_FRAME_TYPE"].Value;
}
else if (MainV2.comPort.MAV.param.ContainsKey("FRAME"))
{
type = MainV2.comPort.MAV.aptype;
frame_type = (int)MainV2.comPort.MAV.param["FRAME"].Value;
}
else if (MainV2.comPort.MAV.param.ContainsKey("FRAME_TYPE"))
{
type = MainV2.comPort.MAV.aptype;
frame_type = (int)MainV2.comPort.MAV.param["FRAME_TYPE"].Value;
}

var motors = new Motor[0];

if (type == MAVLink.MAV_TYPE.TRICOPTER)
{
motormax = 4;

motors = Motor.build_motors(MAVLink.MAV_TYPE.TRICOPTER, frame_type);
}
else if (type == MAVLink.MAV_TYPE.QUADROTOR)
{
motormax = 4;

motors = Motor.build_motors(MAVLink.MAV_TYPE.QUADROTOR, frame_type);
}
else if (type == MAVLink.MAV_TYPE.HEXAROTOR)
{
motormax = 6;

motors = Motor.build_motors(MAVLink.MAV_TYPE.HEXAROTOR, frame_type);
}
else if (type == MAVLink.MAV_TYPE.OCTOROTOR)
{
motormax = 8;

motors = Motor.build_motors(MAVLink.MAV_TYPE.OCTOROTOR, frame_type);
}
else if (type == MAVLink.MAV_TYPE.HELICOPTER)
{
Expand All @@ -178,12 +199,72 @@ private int get_motormax()
return motormax;
}

private bool set_frame_class_and_type(string class_param_name, string type_param_name)
{
if (!MainV2.comPort.MAV.param.ContainsKey(class_param_name) || !MainV2.comPort.MAV.param.ContainsKey(type_param_name))
{
return false;
}
var frame_class = (int)MainV2.comPort.MAV.param[class_param_name].Value;
var class_list = ParameterMetaDataRepository.GetParameterOptionsInt(class_param_name, MainV2.comPort.MAV.cs.firmware.ToString());
foreach (var item in class_list)
{
if (item.Key == Convert.ToInt32(frame_class))
{
FrameClass.Text = "Class: " + item.Value;
break;
}
}

var frame_type = (int)MainV2.comPort.MAV.param[type_param_name].Value;
var type_list = ParameterMetaDataRepository.GetParameterOptionsInt(type_param_name, MainV2.comPort.MAV.cs.firmware.ToString());
foreach (var item in type_list)
{
if (item.Key == Convert.ToInt32(frame_type))
{
FrameType.Text = "Type: " + item.Value;
break;
}
}

lookup_frame_layout(frame_class, frame_type);

return true;
}


private void lookup_frame_layout(int frame_class, int frame_type)
{
try
{
string file = Path.GetDirectoryName(Path.GetFullPath(Assembly.GetExecutingAssembly().Location)) + Path.DirectorySeparatorChar + "APMotorLayout.json";
using (StreamReader r = new StreamReader(file))
{
string json = r.ReadToEnd();
var all_layouts = JsonConvert.DeserializeObject<JSON_motors>(json);
if (all_layouts.Version == "AP_Motors library test ver 1.1")
{
foreach (var layout in all_layouts.layouts)
{
if ((layout.Class == frame_class) && (layout.Type == frame_type))
{
motor_layout = layout;
break;
}
}
}
}
}
catch
{
}
}

private void but_TestAll(object sender, EventArgs e)
{
int speed = (int)NUM_thr_percent.Value;
int time = (int)NUM_duration.Value;

int motormax = this.get_motormax();
for (int i = 1; i <= motormax; i++)
{
testMotor(i, speed, time);
Expand All @@ -192,7 +273,6 @@ private void but_TestAll(object sender, EventArgs e)

private void but_TestAllSeq(object sender, EventArgs e)
{
int motormax = this.get_motormax();
int speed = (int)NUM_thr_percent.Value;
int time = (int)NUM_duration.Value;

Expand All @@ -201,7 +281,6 @@ private void but_TestAllSeq(object sender, EventArgs e)

private void but_StopAll(object sender, EventArgs e)
{
int motormax = this.get_motormax();
for (int i = 1; i <= motormax; i++)
{
testMotor(i, 0, 0);
Expand Down
Loading

0 comments on commit dedc9ef

Please sign in to comment.