mirror of https://github.com/ArduPilot/ardupilot
APM Planner - code only
add yaw to config screen. intergrate adams changes this will force an update, but not the main exe
This commit is contained in:
parent
054aacbdf3
commit
c6d91a5b25
|
@ -101,6 +101,70 @@ Too high = slow wobbles
|
||||||
<STEP>0.001</STEP>
|
<STEP>0.001</STEP>
|
||||||
</FIELD>
|
</FIELD>
|
||||||
</FIELDS>
|
</FIELDS>
|
||||||
|
|
||||||
|
<SUBHEAD>Yaw Angular Rate Control:</SUBHEAD>
|
||||||
|
<DESC>How much throttle is applied to rotate the copter at the desired speed.
|
||||||
|
</DESC>
|
||||||
|
<FIELDS>
|
||||||
|
<FIELD>
|
||||||
|
<NAME>P</NAME>
|
||||||
|
<PARAMNAME>RATE_YAW_P</PARAMNAME>
|
||||||
|
<RANGEMIN>0.001</RANGEMIN>
|
||||||
|
<RANGEMAX>5</RANGEMAX>
|
||||||
|
<STEP>0.001</STEP>
|
||||||
|
</FIELD>
|
||||||
|
<FIELD>
|
||||||
|
<NAME>I</NAME>
|
||||||
|
<PARAMNAME>RATE_YAW_I</PARAMNAME>
|
||||||
|
<RANGEMIN>0</RANGEMIN>
|
||||||
|
<RANGEMAX>5</RANGEMAX>
|
||||||
|
<STEP>0.001</STEP>
|
||||||
|
</FIELD>
|
||||||
|
<FIELD>
|
||||||
|
<NAME>D</NAME>
|
||||||
|
<PARAMNAME>RATE_YAW_D</PARAMNAME>
|
||||||
|
<RANGEMIN>0</RANGEMIN>
|
||||||
|
<RANGEMAX>5</RANGEMAX>
|
||||||
|
<STEP>0.001</STEP>
|
||||||
|
</FIELD>
|
||||||
|
<FIELD>
|
||||||
|
<NAME>IMAX</NAME>
|
||||||
|
<PARAMNAME>RATE_YAW_IMAX</PARAMNAME>
|
||||||
|
<RANGEMIN>0</RANGEMIN>
|
||||||
|
<RANGEMAX>50</RANGEMAX>
|
||||||
|
<STEP>1</STEP>
|
||||||
|
</FIELD>
|
||||||
|
</FIELDS>
|
||||||
|
|
||||||
|
<SUBHEAD>Yaw Stabilize Control:</SUBHEAD>
|
||||||
|
<DESC>
|
||||||
|
How fast the copter reacts to user or autopilot input.
|
||||||
|
Higher = more aggressive control.
|
||||||
|
Too high = slow wobbles
|
||||||
|
</DESC>
|
||||||
|
<FIELDS>
|
||||||
|
<FIELD>
|
||||||
|
<NAME>P</NAME>
|
||||||
|
<PARAMNAME>STB_YAW_P</PARAMNAME>
|
||||||
|
<RANGEMIN>0.001</RANGEMIN>
|
||||||
|
<RANGEMAX>10</RANGEMAX>
|
||||||
|
<STEP>0.001</STEP>
|
||||||
|
</FIELD>
|
||||||
|
<FIELD>
|
||||||
|
<NAME>I</NAME>
|
||||||
|
<PARAMNAME>STB_YAW_I</PARAMNAME>
|
||||||
|
<RANGEMIN>0</RANGEMIN>
|
||||||
|
<RANGEMAX>5</RANGEMAX>
|
||||||
|
<STEP>0.001</STEP>
|
||||||
|
</FIELD>
|
||||||
|
<FIELD>
|
||||||
|
<NAME>IMAX</NAME>
|
||||||
|
<PARAMNAME>STB_YAW_IMAX</PARAMNAME>
|
||||||
|
<RANGEMIN>0</RANGEMIN>
|
||||||
|
<RANGEMAX>50</RANGEMAX>
|
||||||
|
<STEP>1</STEP>
|
||||||
|
</FIELD>
|
||||||
|
</FIELDS>
|
||||||
</Item>
|
</Item>
|
||||||
<!-- Loiter -->
|
<!-- Loiter -->
|
||||||
<Item>
|
<Item>
|
||||||
|
@ -140,7 +204,7 @@ How much angle is applied to make the copter accelerate to the desired speed.
|
||||||
<PARAMNAME>LOITER_LON_IMAX</PARAMNAME>
|
<PARAMNAME>LOITER_LON_IMAX</PARAMNAME>
|
||||||
<RANGEMIN>0</RANGEMIN>
|
<RANGEMIN>0</RANGEMIN>
|
||||||
<RANGEMAX>50</RANGEMAX>
|
<RANGEMAX>50</RANGEMAX>
|
||||||
<STEP>0.1</STEP>
|
<STEP>1</STEP>
|
||||||
</FIELD>
|
</FIELD>
|
||||||
</FIELDS>
|
</FIELDS>
|
||||||
<SUBHEAD>Loiter Speed:</SUBHEAD>
|
<SUBHEAD>Loiter Speed:</SUBHEAD>
|
||||||
|
|
|
@ -226,6 +226,7 @@
|
||||||
<Compile Include="Attributes\DisplayTextAttribute.cs" />
|
<Compile Include="Attributes\DisplayTextAttribute.cs" />
|
||||||
<Compile Include="Attributes\PrivateAttribute.cs" />
|
<Compile Include="Attributes\PrivateAttribute.cs" />
|
||||||
<Compile Include="CodeGen.cs" />
|
<Compile Include="CodeGen.cs" />
|
||||||
|
<Compile Include="Utilities\CollectionExtensions.cs" />
|
||||||
<Compile Include="Utilities\ParameterMetaDataConstants.cs" />
|
<Compile Include="Utilities\ParameterMetaDataConstants.cs" />
|
||||||
<Compile Include="Controls\BackstageView\BackstageView.cs">
|
<Compile Include="Controls\BackstageView\BackstageView.cs">
|
||||||
<SubType>UserControl</SubType>
|
<SubType>UserControl</SubType>
|
||||||
|
|
|
@ -1733,8 +1733,18 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
static void DoUpdateWorker_DoWork(object sender, Controls.ProgressWorkerEventArgs e)
|
static void DoUpdateWorker_DoWork(object sender, Controls.ProgressWorkerEventArgs e)
|
||||||
{
|
{
|
||||||
((ProgressReporterDialogue)sender).UpdateProgressAndStatus(-1, "Getting Base URL");
|
// TODO: Is this the right place?
|
||||||
MainV2.updateCheckMain((ProgressReporterDialogue)sender);
|
#region Fetch Parameter Meta Data
|
||||||
|
|
||||||
|
var progressReporterDialogue = ((ProgressReporterDialogue) sender);
|
||||||
|
progressReporterDialogue.UpdateProgressAndStatus(-1, "Getting Updated Parameters");
|
||||||
|
|
||||||
|
ParameterMetaDataParser.GetParameterInformation();
|
||||||
|
|
||||||
|
#endregion Fetch Parameter Meta Data
|
||||||
|
|
||||||
|
progressReporterDialogue.UpdateProgressAndStatus(-1, "Getting Base URL");
|
||||||
|
MainV2.updateCheckMain(progressReporterDialogue);
|
||||||
}
|
}
|
||||||
|
|
||||||
private static bool updateCheck(ProgressReporterDialogue frmProgressReporter, string baseurl, string subdir)
|
private static bool updateCheck(ProgressReporterDialogue frmProgressReporter, string baseurl, string subdir)
|
||||||
|
|
Binary file not shown.
|
@ -0,0 +1,47 @@
|
||||||
|
using System;
|
||||||
|
using System.Collections;
|
||||||
|
using System.Collections.Generic;
|
||||||
|
using System.Linq;
|
||||||
|
using System.Text;
|
||||||
|
|
||||||
|
namespace ArdupilotMega.Utilities
|
||||||
|
{
|
||||||
|
public static class CollectionExtensions
|
||||||
|
{
|
||||||
|
/// <summary>
|
||||||
|
/// Performs the specified <paramref name="action"/> on each element of the <paramref name="enumerable"/>.
|
||||||
|
///
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="enumerable">An enumerable instance.
|
||||||
|
/// </param><param name="action"/>
|
||||||
|
public static void ForEach(this IEnumerable enumerable, Action<object> action)
|
||||||
|
{
|
||||||
|
foreach (object obj in enumerable)
|
||||||
|
action(obj);
|
||||||
|
}
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Performs the specified <paramref name="action"/> on each element of the <paramref name="enumerable"/>.
|
||||||
|
///
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="enumerable">An enumerable instance.
|
||||||
|
/// </param><param name="action"/>
|
||||||
|
public static void ForEach<T>(this IEnumerable enumerable, Action<T> action)
|
||||||
|
{
|
||||||
|
foreach (T obj in enumerable)
|
||||||
|
action(obj);
|
||||||
|
}
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Performs the specified <paramref name="action"/> on each element of the <paramref name="enumerable"/>.
|
||||||
|
///
|
||||||
|
/// </summary>
|
||||||
|
/// <typeparam name="T">The type contained in the <paramref name="enumerable"/>.
|
||||||
|
/// </typeparam><param name="enumerable"/><param name="action"/>
|
||||||
|
public static void ForEach<T>(this IEnumerable<T> enumerable, Action<T> action)
|
||||||
|
{
|
||||||
|
foreach (T obj in enumerable)
|
||||||
|
action(obj);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
|
@ -2,11 +2,23 @@
|
||||||
{
|
{
|
||||||
public sealed class ParameterMetaDataConstants
|
public sealed class ParameterMetaDataConstants
|
||||||
{
|
{
|
||||||
public const string Delimeter = "@";
|
#region Markers
|
||||||
|
|
||||||
|
public const string ParamDelimeter = "@";
|
||||||
|
public const string PathDelimeter = ",";
|
||||||
public const string Param = "Param";
|
public const string Param = "Param";
|
||||||
|
public const string Group = "Group";
|
||||||
|
public const string Path = "Path";
|
||||||
|
|
||||||
|
#endregion
|
||||||
|
|
||||||
|
#region Meta Keys
|
||||||
|
|
||||||
public const string DisplayName = "DisplayName";
|
public const string DisplayName = "DisplayName";
|
||||||
public const string Description = "Description";
|
public const string Description = "Description";
|
||||||
public const string Units = "Units";
|
public const string Units = "Units";
|
||||||
public const string Range = "Range";
|
public const string Range = "Range";
|
||||||
|
|
||||||
|
#endregion
|
||||||
}
|
}
|
||||||
}
|
}
|
|
@ -7,13 +7,15 @@ using System.Net;
|
||||||
using System.Text.RegularExpressions;
|
using System.Text.RegularExpressions;
|
||||||
using System.Windows.Forms;
|
using System.Windows.Forms;
|
||||||
using System.Xml;
|
using System.Xml;
|
||||||
|
using ArdupilotMega.Utilities;
|
||||||
using log4net;
|
using log4net;
|
||||||
|
|
||||||
namespace ArdupilotMega.Utilities
|
namespace ArdupilotMega.Utilities
|
||||||
{
|
{
|
||||||
public static class ParameterMetaDataParser
|
public static class ParameterMetaDataParser
|
||||||
{
|
{
|
||||||
private static readonly Regex _paramMetaRegex = new Regex(String.Format("{0}(?<MetaKey>[^:]+):(?<MetaValue>.+)", ParameterMetaDataConstants.Delimeter));
|
private static readonly Regex _paramMetaRegex = new Regex(String.Format("{0}(?<MetaKey>[^:]+):(?<MetaValue>.+)", ParameterMetaDataConstants.ParamDelimeter));
|
||||||
|
private static readonly Regex _parentDirectoryRegex = new Regex("(?<ParentDirectory>[../]*)(?<Path>.+)");
|
||||||
private static readonly ILog log =
|
private static readonly ILog log =
|
||||||
LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);
|
LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);
|
||||||
|
|
||||||
|
@ -33,53 +35,18 @@ namespace ArdupilotMega.Utilities
|
||||||
objXmlTextWriter.WriteStartDocument();
|
objXmlTextWriter.WriteStartDocument();
|
||||||
|
|
||||||
foreach (string parameterLocation in parameterLocations)
|
foreach (string parameterLocation in parameterLocations)
|
||||||
{
|
|
||||||
log.Info(parameterLocation);
|
|
||||||
|
|
||||||
var request = WebRequest.Create(parameterLocation);
|
|
||||||
|
|
||||||
// Plenty of timeout
|
|
||||||
request.Timeout = 10000;
|
|
||||||
|
|
||||||
// Set the Method property of the request to GET.
|
|
||||||
request.Method = "GET";
|
|
||||||
|
|
||||||
// Get the response.
|
|
||||||
using (var response = request.GetResponse())
|
|
||||||
{
|
|
||||||
// Display the status.
|
|
||||||
log.Info(((HttpWebResponse)response).StatusDescription);
|
|
||||||
|
|
||||||
// Get the stream containing content returned by the server.
|
|
||||||
using (var dataStream = response.GetResponseStream())
|
|
||||||
{
|
|
||||||
if (dataStream != null)
|
|
||||||
{
|
|
||||||
// Open the stream using a StreamReader for easy access.
|
|
||||||
using (var reader = new StreamReader(dataStream))
|
|
||||||
{
|
{
|
||||||
// Write the start element for this parameter location
|
// Write the start element for this parameter location
|
||||||
objXmlTextWriter.WriteStartElement(parameterLocation);
|
objXmlTextWriter.WriteStartElement(parameterLocation.ToLower().Contains("arducopter") ? MainV2.Firmwares.ArduCopter2.ToString() : MainV2.Firmwares.ArduPlane.ToString());
|
||||||
|
|
||||||
// Read and parse the content.
|
// Read and parse the content.
|
||||||
ParseParameterInformation(reader.ReadToEnd(), objXmlTextWriter);
|
string dataFromAddress = ReadDataFromAddress(parameterLocation);
|
||||||
|
ParseGroupInformation(dataFromAddress, objXmlTextWriter, parameterLocation);
|
||||||
|
ParseParameterInformation(dataFromAddress, objXmlTextWriter);
|
||||||
|
|
||||||
// Write the end element for this parameter location
|
// Write the end element for this parameter location
|
||||||
objXmlTextWriter.WriteEndElement();
|
objXmlTextWriter.WriteEndElement();
|
||||||
|
|
||||||
// Close the reader
|
|
||||||
reader.Close();
|
|
||||||
}
|
|
||||||
|
|
||||||
// Close the datastream
|
|
||||||
dataStream.Close();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Close the response
|
|
||||||
response.Close();
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Clear the stream
|
// Clear the stream
|
||||||
|
@ -90,6 +57,67 @@ namespace ArdupilotMega.Utilities
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Parses the group parameter information.
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="fileContents">The file contents.</param>
|
||||||
|
/// <param name="objXmlTextWriter">The obj XML text writer.</param>
|
||||||
|
/// <param name="parameterLocation">The parameter location.</param>
|
||||||
|
private static void ParseGroupInformation(string fileContents, XmlTextWriter objXmlTextWriter, string parameterLocation)
|
||||||
|
{
|
||||||
|
var parsedInformation = ParseKeyValuePairs(fileContents, ParameterMetaDataConstants.Group);
|
||||||
|
if (parsedInformation != null && parsedInformation.Count > 0)
|
||||||
|
{
|
||||||
|
// node is the prefix of the parameter group here
|
||||||
|
parsedInformation.ForEach(node =>
|
||||||
|
{
|
||||||
|
// node.Value is a nested dictionary containing the additional meta data
|
||||||
|
// In this case we are looking for the @Path key
|
||||||
|
if (node.Value != null && node.Value.Count > 0)
|
||||||
|
{
|
||||||
|
// Find the @Path key
|
||||||
|
node.Value
|
||||||
|
.Where(meta => meta.Key == ParameterMetaDataConstants.Path)
|
||||||
|
// We might have multiple paths to inspect, so break them out by the delimeter
|
||||||
|
.ForEach(path => path.Value.Split(new []{ ParameterMetaDataConstants.PathDelimeter }, StringSplitOptions.None)
|
||||||
|
.ForEach(separatedPath =>
|
||||||
|
{
|
||||||
|
// Match based on the regex defined at the top of this class
|
||||||
|
Match pathMatch = _parentDirectoryRegex.Match(separatedPath);
|
||||||
|
if (pathMatch.Success && pathMatch.Groups["Path"] != null && !String.IsNullOrEmpty(pathMatch.Groups["Path"].Value))
|
||||||
|
{
|
||||||
|
if (pathMatch.Groups["ParentDirectory"] != null && !String.IsNullOrEmpty(pathMatch.Groups["ParentDirectory"].Value))
|
||||||
|
{
|
||||||
|
// How many directories from the original path do we have to move
|
||||||
|
int numberOfParentDirectoryMoves = pathMatch.Groups["ParentDirectory"].Value.Split(new string[] { "../" }, StringSplitOptions.None).Count();
|
||||||
|
|
||||||
|
// We need to remove the http:// or https:// prefix to build the new URL properly
|
||||||
|
string httpTest = parameterLocation.Substring(0, 7);
|
||||||
|
int trimHttpPrefixIdx = httpTest == "http://" ? 7 : 8;
|
||||||
|
|
||||||
|
// Get the parts of the original URL
|
||||||
|
var parameterLocationParts = parameterLocation.Substring(trimHttpPrefixIdx, parameterLocation.Length - trimHttpPrefixIdx).Split(new char[] { '/' });
|
||||||
|
|
||||||
|
// Rebuild the new url taking into account the numberOfParentDirectoryMoves
|
||||||
|
string urlAfterParentDirectory = string.Empty;
|
||||||
|
for (int i = 0; i < parameterLocationParts.Length && i < parameterLocationParts.Length - numberOfParentDirectoryMoves; i++)
|
||||||
|
{
|
||||||
|
urlAfterParentDirectory += parameterLocationParts[i] + "/";
|
||||||
|
}
|
||||||
|
|
||||||
|
// This is the URL of the file we need to parse for comments
|
||||||
|
string newPath = String.Format("{0}{1}{2}", parameterLocation.Substring(0, trimHttpPrefixIdx), urlAfterParentDirectory, pathMatch.Groups["Path"].Value);
|
||||||
|
|
||||||
|
// Parse the param info from the newly constructed URL
|
||||||
|
ParseParameterInformation(ReadDataFromAddress(newPath), objXmlTextWriter, node.Key);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}));
|
||||||
|
}
|
||||||
|
});
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// Parses the parameter information.
|
/// Parses the parameter information.
|
||||||
/// </summary>
|
/// </summary>
|
||||||
|
@ -97,8 +125,50 @@ namespace ArdupilotMega.Utilities
|
||||||
/// <param name="objXmlTextWriter">The obj XML text writer.</param>
|
/// <param name="objXmlTextWriter">The obj XML text writer.</param>
|
||||||
private static void ParseParameterInformation(string fileContents, XmlTextWriter objXmlTextWriter)
|
private static void ParseParameterInformation(string fileContents, XmlTextWriter objXmlTextWriter)
|
||||||
{
|
{
|
||||||
|
ParseParameterInformation(fileContents, objXmlTextWriter, string.Empty);
|
||||||
|
}
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Parses the parameter information.
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="fileContents">The file contents.</param>
|
||||||
|
/// <param name="objXmlTextWriter">The obj XML text writer.</param>
|
||||||
|
/// <param name="parameterPrefix">The parameter prefix.</param>
|
||||||
|
private static void ParseParameterInformation(string fileContents, XmlTextWriter objXmlTextWriter, string parameterPrefix)
|
||||||
|
{
|
||||||
|
var parsedInformation = ParseKeyValuePairs(fileContents, ParameterMetaDataConstants.Param);
|
||||||
|
if(parsedInformation != null && parsedInformation.Count > 0)
|
||||||
|
{
|
||||||
|
parsedInformation.ForEach(node =>
|
||||||
|
{
|
||||||
|
objXmlTextWriter.WriteStartElement(String.Format("{0}{1}", parameterPrefix, node.Key));
|
||||||
|
if (node.Value != null && node.Value.Count > 0)
|
||||||
|
{
|
||||||
|
node.Value.ForEach(meta =>
|
||||||
|
{
|
||||||
|
// Write the key value pair to XML
|
||||||
|
objXmlTextWriter.WriteStartElement(meta.Key);
|
||||||
|
objXmlTextWriter.WriteString(meta.Value);
|
||||||
|
objXmlTextWriter.WriteEndElement();
|
||||||
|
});
|
||||||
|
}
|
||||||
|
objXmlTextWriter.WriteEndElement();
|
||||||
|
});
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Parses the parameter information.
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="fileContents">The file contents.</param>
|
||||||
|
/// <param name="nodeKey">The node key.</param>
|
||||||
|
/// <returns></returns>
|
||||||
|
private static Dictionary<string, Dictionary<string, string>> ParseKeyValuePairs(string fileContents, string nodeKey)
|
||||||
|
{
|
||||||
|
var returnDict = new Dictionary<string, Dictionary<string, string>>();
|
||||||
|
|
||||||
var indicies = new List<int>();
|
var indicies = new List<int>();
|
||||||
GetIndexOfMarkers(ref indicies, fileContents, ParameterMetaDataConstants.Delimeter + ParameterMetaDataConstants.Param, 0);
|
GetIndexOfMarkers(ref indicies, fileContents, ParameterMetaDataConstants.ParamDelimeter + nodeKey, 0);
|
||||||
|
|
||||||
if(indicies.Count > 0)
|
if(indicies.Count > 0)
|
||||||
{
|
{
|
||||||
|
@ -113,7 +183,7 @@ namespace ArdupilotMega.Utilities
|
||||||
if(!String.IsNullOrEmpty(subStringToSearch))
|
if(!String.IsNullOrEmpty(subStringToSearch))
|
||||||
{
|
{
|
||||||
var metaIndicies = new List<int>();
|
var metaIndicies = new List<int>();
|
||||||
GetIndexOfMarkers(ref metaIndicies, subStringToSearch, ParameterMetaDataConstants.Delimeter, 0);
|
GetIndexOfMarkers(ref metaIndicies, subStringToSearch, ParameterMetaDataConstants.ParamDelimeter, 0);
|
||||||
|
|
||||||
if(metaIndicies.Count > 0)
|
if(metaIndicies.Count > 0)
|
||||||
{
|
{
|
||||||
|
@ -123,10 +193,12 @@ namespace ArdupilotMega.Utilities
|
||||||
// Match based on the regex defined at the top of this class
|
// Match based on the regex defined at the top of this class
|
||||||
Match paramNameKeyMatch = _paramMetaRegex.Match(paramNameKey);
|
Match paramNameKeyMatch = _paramMetaRegex.Match(paramNameKey);
|
||||||
|
|
||||||
if (paramNameKeyMatch.Success && paramNameKeyMatch.Groups["MetaKey"].Value == ParameterMetaDataConstants.Param)
|
if (paramNameKeyMatch.Success && paramNameKeyMatch.Groups["MetaKey"].Value == nodeKey)
|
||||||
|
{
|
||||||
|
string key = paramNameKeyMatch.Groups["MetaValue"].Value.Trim(new char[] {' '});
|
||||||
|
var metaDict = new Dictionary<string, string>();
|
||||||
|
if(!returnDict.ContainsKey(key))
|
||||||
{
|
{
|
||||||
objXmlTextWriter.WriteStartElement(paramNameKeyMatch.Groups["MetaValue"].Value.Trim(new char[] { ' ' }));
|
|
||||||
|
|
||||||
// Loop through the indicies of the meta data found
|
// Loop through the indicies of the meta data found
|
||||||
for (int x = 1; x < metaIndicies.Count; x++)
|
for (int x = 1; x < metaIndicies.Count; x++)
|
||||||
{
|
{
|
||||||
|
@ -143,20 +215,21 @@ namespace ArdupilotMega.Utilities
|
||||||
// Test for success
|
// Test for success
|
||||||
if (metaMatch.Success)
|
if (metaMatch.Success)
|
||||||
{
|
{
|
||||||
// Write the key value pair to XML
|
string metaKey = metaMatch.Groups["MetaKey"].Value.Trim(new char[] {' '});
|
||||||
objXmlTextWriter.WriteStartElement(metaMatch.Groups["MetaKey"].Value.Trim(new char[] { ' ' }));
|
if(!metaDict.ContainsKey(metaKey))
|
||||||
objXmlTextWriter.WriteString(metaMatch.Groups["MetaValue"].Value.Trim(new char[] { ' ' }));
|
{
|
||||||
objXmlTextWriter.WriteEndElement();
|
metaDict.Add(metaKey, metaMatch.Groups["MetaValue"].Value.Trim(new char[] { ' ' }));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
// End this parameter node
|
}
|
||||||
objXmlTextWriter.WriteEndElement();
|
returnDict.Add(key, metaDict);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
return returnDict;
|
||||||
}
|
}
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
|
@ -188,5 +261,67 @@ namespace ArdupilotMega.Utilities
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Reads the data from address.
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="address">The address.</param>
|
||||||
|
/// <returns></returns>
|
||||||
|
private static string ReadDataFromAddress(string address)
|
||||||
|
{
|
||||||
|
string data = string.Empty;
|
||||||
|
|
||||||
|
log.Info(address);
|
||||||
|
|
||||||
|
// Make sure we don't blow up if the user is not connected or the endpoint is not available
|
||||||
|
try
|
||||||
|
{
|
||||||
|
var request = WebRequest.Create(address);
|
||||||
|
|
||||||
|
// Plenty of timeout
|
||||||
|
request.Timeout = 10000;
|
||||||
|
|
||||||
|
// Set the Method property of the request to GET.
|
||||||
|
request.Method = "GET";
|
||||||
|
|
||||||
|
// Get the response.
|
||||||
|
using (var response = request.GetResponse())
|
||||||
|
{
|
||||||
|
// Display the status.
|
||||||
|
log.Info(((HttpWebResponse)response).StatusDescription);
|
||||||
|
|
||||||
|
// Get the stream containing content returned by the server.
|
||||||
|
using (var dataStream = response.GetResponseStream())
|
||||||
|
{
|
||||||
|
if (dataStream != null)
|
||||||
|
{
|
||||||
|
// Open the stream using a StreamReader for easy access.
|
||||||
|
using (var reader = new StreamReader(dataStream))
|
||||||
|
{
|
||||||
|
// Store the data to return
|
||||||
|
data = reader.ReadToEnd();
|
||||||
|
|
||||||
|
// Close the reader
|
||||||
|
reader.Close();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Close the datastream
|
||||||
|
dataStream.Close();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Close the response
|
||||||
|
response.Close();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Return the data
|
||||||
|
return data;
|
||||||
|
}
|
||||||
|
catch (WebException ex)
|
||||||
|
{
|
||||||
|
log.Error(String.Format("The request to {0} failed.", address), ex);
|
||||||
|
}
|
||||||
|
return string.Empty;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -3,6 +3,7 @@ using System.Configuration;
|
||||||
using System.IO;
|
using System.IO;
|
||||||
using System.Windows.Forms;
|
using System.Windows.Forms;
|
||||||
using System.Xml.Linq;
|
using System.Xml.Linq;
|
||||||
|
using System.Linq;
|
||||||
|
|
||||||
namespace ArdupilotMega.Utilities
|
namespace ArdupilotMega.Utilities
|
||||||
{
|
{
|
||||||
|
@ -32,7 +33,19 @@ namespace ArdupilotMega.Utilities
|
||||||
{
|
{
|
||||||
// Use this to find the endpoint node we are looking for
|
// Use this to find the endpoint node we are looking for
|
||||||
// Either it will be pulled from a file in the ArduPlane hierarchy or the ArduCopter hierarchy
|
// Either it will be pulled from a file in the ArduPlane hierarchy or the ArduCopter hierarchy
|
||||||
string endpointSearchString = (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) ? "arduplane" : "arducopter";
|
var element = _parameterMetaDataXML.Element(MainV2.cs.firmware.ToString());
|
||||||
|
if(element != null && element.HasElements)
|
||||||
|
{
|
||||||
|
var node = element.Element(nodeKey);
|
||||||
|
if(node != null && node.HasElements)
|
||||||
|
{
|
||||||
|
var metaValue = node.Element(metaKey);
|
||||||
|
if(metaValue != null)
|
||||||
|
{
|
||||||
|
return metaValue.Value;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
return string.Empty;
|
return string.Empty;
|
||||||
}
|
}
|
||||||
|
|
|
@ -8,6 +8,10 @@
|
||||||
<appSettings>
|
<appSettings>
|
||||||
<add key="UpdateLocation"
|
<add key="UpdateLocation"
|
||||||
value="http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/bin/Release/"/>
|
value="http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/bin/Release/"/>
|
||||||
|
<add key="ParameterLocations"
|
||||||
|
value="http://ardupilot-mega.googlecode.com/git/ArduCopter/Parameters.pde"/>
|
||||||
|
<add key="ParameterMetaDataXMLFileName"
|
||||||
|
value="ParameterMetaData.xml"/>
|
||||||
</appSettings>
|
</appSettings>
|
||||||
<log4net>
|
<log4net>
|
||||||
<appender name="Console" type="log4net.Appender.ConsoleAppender">
|
<appender name="Console" type="log4net.Appender.ConsoleAppender">
|
||||||
|
|
|
@ -101,6 +101,70 @@ Too high = slow wobbles
|
||||||
<STEP>0.001</STEP>
|
<STEP>0.001</STEP>
|
||||||
</FIELD>
|
</FIELD>
|
||||||
</FIELDS>
|
</FIELDS>
|
||||||
|
|
||||||
|
<SUBHEAD>Yaw Angular Rate Control:</SUBHEAD>
|
||||||
|
<DESC>How much throttle is applied to rotate the copter at the desired speed.
|
||||||
|
</DESC>
|
||||||
|
<FIELDS>
|
||||||
|
<FIELD>
|
||||||
|
<NAME>P</NAME>
|
||||||
|
<PARAMNAME>RATE_YAW_P</PARAMNAME>
|
||||||
|
<RANGEMIN>0.001</RANGEMIN>
|
||||||
|
<RANGEMAX>5</RANGEMAX>
|
||||||
|
<STEP>0.001</STEP>
|
||||||
|
</FIELD>
|
||||||
|
<FIELD>
|
||||||
|
<NAME>I</NAME>
|
||||||
|
<PARAMNAME>RATE_YAW_I</PARAMNAME>
|
||||||
|
<RANGEMIN>0</RANGEMIN>
|
||||||
|
<RANGEMAX>5</RANGEMAX>
|
||||||
|
<STEP>0.001</STEP>
|
||||||
|
</FIELD>
|
||||||
|
<FIELD>
|
||||||
|
<NAME>D</NAME>
|
||||||
|
<PARAMNAME>RATE_YAW_D</PARAMNAME>
|
||||||
|
<RANGEMIN>0</RANGEMIN>
|
||||||
|
<RANGEMAX>5</RANGEMAX>
|
||||||
|
<STEP>0.001</STEP>
|
||||||
|
</FIELD>
|
||||||
|
<FIELD>
|
||||||
|
<NAME>IMAX</NAME>
|
||||||
|
<PARAMNAME>RATE_YAW_IMAX</PARAMNAME>
|
||||||
|
<RANGEMIN>0</RANGEMIN>
|
||||||
|
<RANGEMAX>50</RANGEMAX>
|
||||||
|
<STEP>1</STEP>
|
||||||
|
</FIELD>
|
||||||
|
</FIELDS>
|
||||||
|
|
||||||
|
<SUBHEAD>Yaw Stabilize Control:</SUBHEAD>
|
||||||
|
<DESC>
|
||||||
|
How fast the copter reacts to user or autopilot input.
|
||||||
|
Higher = more aggressive control.
|
||||||
|
Too high = slow wobbles
|
||||||
|
</DESC>
|
||||||
|
<FIELDS>
|
||||||
|
<FIELD>
|
||||||
|
<NAME>P</NAME>
|
||||||
|
<PARAMNAME>STB_YAW_P</PARAMNAME>
|
||||||
|
<RANGEMIN>0.001</RANGEMIN>
|
||||||
|
<RANGEMAX>10</RANGEMAX>
|
||||||
|
<STEP>0.001</STEP>
|
||||||
|
</FIELD>
|
||||||
|
<FIELD>
|
||||||
|
<NAME>I</NAME>
|
||||||
|
<PARAMNAME>STB_YAW_I</PARAMNAME>
|
||||||
|
<RANGEMIN>0</RANGEMIN>
|
||||||
|
<RANGEMAX>5</RANGEMAX>
|
||||||
|
<STEP>0.001</STEP>
|
||||||
|
</FIELD>
|
||||||
|
<FIELD>
|
||||||
|
<NAME>IMAX</NAME>
|
||||||
|
<PARAMNAME>STB_YAW_IMAX</PARAMNAME>
|
||||||
|
<RANGEMIN>0</RANGEMIN>
|
||||||
|
<RANGEMAX>50</RANGEMAX>
|
||||||
|
<STEP>1</STEP>
|
||||||
|
</FIELD>
|
||||||
|
</FIELDS>
|
||||||
</Item>
|
</Item>
|
||||||
<!-- Loiter -->
|
<!-- Loiter -->
|
||||||
<Item>
|
<Item>
|
||||||
|
@ -140,7 +204,7 @@ How much angle is applied to make the copter accelerate to the desired speed.
|
||||||
<PARAMNAME>LOITER_LON_IMAX</PARAMNAME>
|
<PARAMNAME>LOITER_LON_IMAX</PARAMNAME>
|
||||||
<RANGEMIN>0</RANGEMIN>
|
<RANGEMIN>0</RANGEMIN>
|
||||||
<RANGEMAX>50</RANGEMAX>
|
<RANGEMAX>50</RANGEMAX>
|
||||||
<STEP>0.1</STEP>
|
<STEP>1</STEP>
|
||||||
</FIELD>
|
</FIELD>
|
||||||
</FIELDS>
|
</FIELDS>
|
||||||
<SUBHEAD>Loiter Speed:</SUBHEAD>
|
<SUBHEAD>Loiter Speed:</SUBHEAD>
|
||||||
|
|
|
@ -1 +1 @@
|
||||||
1.1.4498.32482
|
1.1.4499.14296
|
Loading…
Reference in New Issue