ArdupilotMegaPlanner: Added new APPROACH flight mode and added infrastructure necessary to make it private (ie. not a user selectable mode).

This commit is contained in:
Adam M Rivera 2012-04-17 10:02:39 -05:00
parent baf8218b58
commit dcef88c3ba
7 changed files with 289 additions and 23 deletions

View File

@ -222,6 +222,8 @@
<Compile Include="Antenna\Tracker.Designer.cs">
<DependentUpon>Tracker.cs</DependentUpon>
</Compile>
<Compile Include="Attributes\DisplayTextAttribute.cs" />
<Compile Include="Attributes\PrivateAttribute.cs" />
<Compile Include="CodeGen.cs" />
<Compile Include="Controls\BackstageView\BackstageView.cs">
<SubType>UserControl</SubType>
@ -540,6 +542,7 @@
<Compile Include="Radio\Uploader.cs" />
<Compile Include="LangUtility.cs" />
<Compile Include="ThemeManager.cs" />
<Compile Include="Utilities\EnumTranslator.cs" />
<EmbeddedResource Include="Antenna\Tracker.resx">
<DependentUpon>Tracker.cs</DependentUpon>
</EmbeddedResource>

View File

@ -0,0 +1,44 @@
#region Using Statements
using System;
#endregion
namespace ArdupilotMega.Attributes
{
/// <summary>
/// Used to decorate a type or type member with display text.
/// </summary>
[AttributeUsage(AttributeTargets.All, Inherited = false, AllowMultiple = false)]
public sealed class DisplayTextAttribute : Attribute
{
private readonly string _text;
/// <summary>
/// Initializes a new instance of the <see cref="DisplayTextAttribute"/> class.
/// </summary>
/// <param name="text">The text.</param>
/// <exception cref="ArgumentException">
/// Thrown when <paramref name="text"/> is null or empty.
/// </exception>
public DisplayTextAttribute(string text)
{
if (String.IsNullOrEmpty(text))
{
throw new ArgumentException("\"text\" is required.");
}
_text = text;
}
/// <summary>
/// Gets the text.
/// </summary>
/// <value>The text.</value>
public string Text
{
get { return _text; }
}
}
}

View File

@ -0,0 +1,35 @@
#region Using Statements
using System;
#endregion
namespace ArdupilotMega.Attributes
{
[AttributeUsage(AttributeTargets.All, Inherited = false, AllowMultiple = false)]
public sealed class PrivateAttribute : Attribute
{
private readonly bool _isPrivate;
/// <summary>
/// Initializes a new instance of the <see cref="PrivateAttribute"/> class.
/// </summary>
/// <param name="isPrivate">if set to <c>true</c> [is private].</param>
public PrivateAttribute(bool isPrivate)
{
_isPrivate = isPrivate;
}
/// <summary>
/// Gets a value indicating whether this instance is private.
/// </summary>
/// <value>
/// <c>true</c> if this instance is private; otherwise, <c>false</c>.
/// </value>
public bool IsPrivate
{
get { return _isPrivate; }
}
}
}

View File

@ -8,6 +8,7 @@ using System.Windows.Forms;
using AGaugeApp;
using System.IO.Ports;
using System.Threading;
using ArdupilotMega.Attributes;
using GMap.NET;
using GMap.NET.WindowsForms;
using GMap.NET.WindowsForms.Markers;
@ -319,28 +320,48 @@ namespace ArdupilotMega
public enum ac2modes
{
[DisplayText("Stabilize")]
STABILIZE = 0, // hold level position
[DisplayText("Acro")]
ACRO = 1, // rate control
[DisplayText("Altitude Hold")]
ALT_HOLD = 2, // AUTO control
[DisplayText("Auto")]
AUTO = 3, // AUTO control
[DisplayText("Guided")]
GUIDED = 4, // AUTO control
[DisplayText("Loiter")]
LOITER = 5, // Hold a single location
[DisplayText("Return to Launch")]
RTL = 6, // AUTO control
[DisplayText("Circle")]
CIRCLE = 7,
[DisplayText("Position Hold")]
POSITION = 8,
[DisplayText("Land")]
LAND = 9, // AUTO control
OF_LOITER = 10
[Private(true)]
APPROACH = 10,
OF_LOITER = 11
}
public enum ac2ch7modes
{
[DisplayText("Do Nothing")]
CH7_DO_NOTHING = 0,
[DisplayText("Set Hover")]
CH7_SET_HOVER = 1,
[DisplayText("Flip")]
CH7_FLIP = 2,
[DisplayText("Simple Mode")]
CH7_SIMPLE_MODE = 3,
[DisplayText("Return to Launch")]
CH7_RTL = 4,
[DisplayText("Automatic Trim")]
CH7_AUTO_TRIM = 5,
[DisplayText("ADC Filter")]
CH7_ADC_FILTER = 6,
[DisplayText("Save Waypoint")]
CH7_SAVE_WP = 7
}

View File

@ -3,6 +3,7 @@ using System.Collections.Generic;
using System.Reflection;
using System.Text;
using System.ComponentModel;
using ArdupilotMega.Utilities;
using log4net;
namespace ArdupilotMega
@ -503,34 +504,37 @@ namespace ArdupilotMega
}
break;
case (byte)(100 + Common.ac2modes.STABILIZE):
mode = "Stabilize";
mode = EnumTranslator.GetDisplayText(Common.ac2modes.STABILIZE);
break;
case (byte)(100 + Common.ac2modes.ACRO):
mode = "Acro";
mode = EnumTranslator.GetDisplayText(Common.ac2modes.ACRO);
break;
case (byte)(100 + Common.ac2modes.ALT_HOLD):
mode = "Alt Hold";
mode = EnumTranslator.GetDisplayText(Common.ac2modes.ALT_HOLD);
break;
case (byte)(100 + Common.ac2modes.AUTO):
mode = "Auto";
mode = EnumTranslator.GetDisplayText(Common.ac2modes.AUTO);
break;
case (byte)(100 + Common.ac2modes.GUIDED):
mode = "Guided";
mode = EnumTranslator.GetDisplayText(Common.ac2modes.GUIDED);
break;
case (byte)(100 + Common.ac2modes.LOITER):
mode = "Loiter";
mode = EnumTranslator.GetDisplayText(Common.ac2modes.LOITER);
break;
case (byte)(100 + Common.ac2modes.RTL):
mode = "RTL";
mode = EnumTranslator.GetDisplayText(Common.ac2modes.RTL);
break;
case (byte)(100 + Common.ac2modes.CIRCLE):
mode = "Circle";
mode = EnumTranslator.GetDisplayText(Common.ac2modes.CIRCLE);
break;
case (byte)(100 + Common.ac2modes.LAND):
mode = "Land";
mode = EnumTranslator.GetDisplayText(Common.ac2modes.LAND);
break;
case (byte)(100 + Common.ac2modes.APPROACH):
mode = EnumTranslator.GetDisplayText(Common.ac2modes.APPROACH);
break;
case (byte)(100 + Common.ac2modes.POSITION):
mode = "Position";
mode = EnumTranslator.GetDisplayText(Common.ac2modes.POSITION);
break;
case (byte)ArdupilotMega.MAVLink.MAV_MODE.MAV_MODE_MANUAL:
mode = "Manual";

View File

@ -7,6 +7,7 @@ using System.Linq;
using System.Text;
using System.Windows.Forms;
using ArdupilotMega.Controls.BackstageView;
using ArdupilotMega.Utilities;
namespace ArdupilotMega.GCSViews.ConfigurationView
{
@ -165,12 +166,31 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
CMB_fmode5.Items.Clear();
CMB_fmode6.Items.Clear();
CMB_fmode1.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
CMB_fmode2.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
CMB_fmode3.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
CMB_fmode4.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
CMB_fmode5.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
CMB_fmode6.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
var flightModes = EnumTranslator.Translate<Common.apmmodes>();
CMB_fmode1.DataSource = flightModes;
CMB_fmode1.ValueMember = "Value";
CMB_fmode1.DisplayMember = "Value";
CMB_fmode2.DataSource = flightModes;
CMB_fmode2.ValueMember = "Value";
CMB_fmode2.DisplayMember = "Value";
CMB_fmode3.DataSource = flightModes;
CMB_fmode3.ValueMember = "Value";
CMB_fmode3.DisplayMember = "Value";
CMB_fmode4.DataSource = flightModes;
CMB_fmode4.ValueMember = "Value";
CMB_fmode4.DisplayMember = "Value";
CMB_fmode5.DataSource = flightModes;
CMB_fmode5.ValueMember = "Value";
CMB_fmode5.DisplayMember = "Value";
CMB_fmode6.DataSource = flightModes;
CMB_fmode6.ValueMember = "Value";
CMB_fmode6.DisplayMember = "Value";
try
{
@ -193,12 +213,31 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
CMB_fmode5.Items.Clear();
CMB_fmode6.Items.Clear();
CMB_fmode1.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
CMB_fmode2.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
CMB_fmode3.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
CMB_fmode4.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
CMB_fmode5.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
CMB_fmode6.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
var flightModes = EnumTranslator.Translate<Common.apmmodes>();
CMB_fmode1.DataSource = flightModes;
CMB_fmode1.ValueMember = "Value";
CMB_fmode1.DisplayMember = "Value";
CMB_fmode2.DataSource = flightModes;
CMB_fmode2.ValueMember = "Value";
CMB_fmode2.DisplayMember = "Value";
CMB_fmode3.DataSource = flightModes;
CMB_fmode3.ValueMember = "Value";
CMB_fmode3.DisplayMember = "Value";
CMB_fmode4.DataSource = flightModes;
CMB_fmode4.ValueMember = "Value";
CMB_fmode4.DisplayMember = "Value";
CMB_fmode5.DataSource = flightModes;
CMB_fmode5.ValueMember = "Value";
CMB_fmode5.DisplayMember = "Value";
CMB_fmode6.DataSource = flightModes;
CMB_fmode6.ValueMember = "Value";
CMB_fmode6.DisplayMember = "Value";
try
{

View File

@ -0,0 +1,120 @@
#region Using Statements
using System;
using System.Collections.Generic;
using System.Linq;
using System.Reflection;
using ArdupilotMega.Attributes;
#endregion
namespace ArdupilotMega.Utilities
{
public static class EnumTranslator
{
/// <summary>
/// Translates this instance.
/// </summary>
/// <typeparam name="T"></typeparam>
/// <returns></returns>
public static Dictionary<int, string> Translate<T>()
{
return Translate<T>(true);
}
/// <summary>
/// Translates the specified check private.
/// </summary>
/// <typeparam name="T"></typeparam>
/// <param name="checkPrivate">if set to <c>true</c> [check private].</param>
/// <returns></returns>
public static Dictionary<int, string> Translate<T>(bool checkPrivate)
{
return Translate<T>(string.Empty, checkPrivate);
}
/// <summary>
/// Translates the specified default text.
/// </summary>
/// <typeparam name="T"></typeparam>
/// <param name="defaultText">The default text.</param>
/// <param name="checkPrivate">if set to <c>true</c> [check private].</param>
/// <returns></returns>
public static Dictionary<int, string> Translate<T>(string defaultText, bool checkPrivate)
{
return Translate<T>(defaultText, checkPrivate, true);
}
/// <summary>
/// Translates the specified default text.
/// </summary>
/// <typeparam name="T"></typeparam>
/// <param name="defaultText">The default text.</param>
/// <param name="checkPrivate">if set to <c>true</c> [check private].</param>
/// <param name="sorting">if set to <c>true</c> [sorting].</param>
/// <returns></returns>
public static Dictionary<int, string> Translate<T>(string defaultText, bool checkPrivate, bool sorting)
{
var types = new Dictionary<int, string>();
var tempTypes = new Dictionary<int, string>();
if (!String.IsNullOrEmpty(defaultText)) types.Add(-1, defaultText);
foreach (FieldInfo fieldInfo in typeof(T).GetFields(BindingFlags.Static | BindingFlags.GetField | BindingFlags.Public))
{
bool add = true;
string displayText = string.Empty;
T type = (T)fieldInfo.GetValue(typeof(T));
object[] displayTextObjectArr = fieldInfo.GetCustomAttributes(typeof(DisplayTextAttribute), true);
displayText = (displayTextObjectArr.Length > 0)
? ((DisplayTextAttribute)displayTextObjectArr[0]).Text
: type.ToString();
if (checkPrivate)
{
object[] privateAttributeObjectArr = fieldInfo.GetCustomAttributes(typeof(PrivateAttribute), true);
if (privateAttributeObjectArr.Length > 0)
{
add = !((PrivateAttribute)privateAttributeObjectArr[0]).IsPrivate;
}
}
if (add)
{
tempTypes.Add(Convert.ToInt32(type), displayText);
}
}
if (sorting)
{
foreach(var x in tempTypes.OrderBy(x => x.Value).ToDictionary(x => x.Key, x => x.Value)){ types.Add(x.Key, x.Value); }
}
else
{
foreach (var x in tempTypes.ToDictionary(x => x.Key, x => x.Value)) { types.Add(x.Key, x.Value); }
}
return types;
}
/// <summary>
/// Gets the display text.
/// </summary>
/// <typeparam name="T"></typeparam>
/// <param name="value">The value.</param>
/// <returns></returns>
public static string GetDisplayText<T>(T value)
{
var displayText = string.Empty;
var fieldInfo = value.GetType().GetField(value.ToString());
if(fieldInfo != null)
{
T type = (T)fieldInfo.GetValue(typeof(T));
if(type != null)
{
object[] displayTextObjectArr = fieldInfo.GetCustomAttributes(typeof(DisplayTextAttribute), true);
displayText = (displayTextObjectArr.Length > 0)
? ((DisplayTextAttribute)displayTextObjectArr[0]).Text
: type.ToString();
}
}
return displayText;
}
}
}