fix int/float conversion issue

This commit is contained in:
Michael Oborne 2012-04-30 21:57:06 +08:00
parent 0f6120506b
commit b5908eed7f
1 changed files with 250 additions and 250 deletions

View File

@ -14,234 +14,234 @@ using log4net;
namespace ArdupilotMega.GCSViews.ConfigurationView
{
public partial class ConfigFriendlyParams : BackStageViewContentPanel
{
#region Class Fields
public partial class ConfigFriendlyParams : BackStageViewContentPanel
{
#region Class Fields
private static readonly ILog log =
LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);
private readonly ParameterMetaDataRepository _parameterMetaDataRepository;
private Dictionary<string, string> _params = new Dictionary<string, string>();
private static readonly ILog log =
LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);
private readonly ParameterMetaDataRepository _parameterMetaDataRepository;
private Dictionary<string, string> _params = new Dictionary<string, string>();
#endregion
#endregion
#region Properties
#region Properties
/// <summary>
/// Gets or sets the parameter mode.
/// </summary>
/// <value>
/// The parameter mode.
/// </value>
public string ParameterMode { get; set; }
/// <summary>
/// Gets or sets the parameter mode.
/// </summary>
/// <value>
/// The parameter mode.
/// </value>
public string ParameterMode { get; set; }
#endregion
#endregion
#region Constructor
#region Constructor
public ConfigFriendlyParams()
{
InitializeComponent();
tableLayoutPanel1.Height = this.Height;
_parameterMetaDataRepository = new ParameterMetaDataRepository();
public ConfigFriendlyParams()
{
InitializeComponent();
tableLayoutPanel1.Height = this.Height;
_parameterMetaDataRepository = new ParameterMetaDataRepository();
MainV2.comPort.ParamListChanged += comPort_ParamListChanged;
Resize += this_Resize;
MainV2.comPort.ParamListChanged += comPort_ParamListChanged;
Resize += this_Resize;
BUT_rerequestparams.Click += BUT_rerequestparams_Click;
BUT_writePIDS.Click += BUT_writePIDS_Click;
}
BUT_rerequestparams.Click += BUT_rerequestparams_Click;
BUT_writePIDS.Click += BUT_writePIDS_Click;
}
#endregion
#endregion
#region Events
#region Events
/// <summary>
/// Handles the Click event of the BUT_writePIDS control.
/// </summary>
/// <param name="sender">The source of the event.</param>
/// <param name="e">The <see cref="System.EventArgs"/> instance containing the event data.</param>
protected void BUT_writePIDS_Click(object sender, EventArgs e)
{
bool errorThrown = false;
_params.ForEach(x =>
{
var matchingControls = tableLayoutPanel1.Controls.Find(x.Key, true);
if(matchingControls.Length > 0)
/// <summary>
/// Handles the Click event of the BUT_writePIDS control.
/// </summary>
/// <param name="sender">The source of the event.</param>
/// <param name="e">The <see cref="System.EventArgs"/> instance containing the event data.</param>
protected void BUT_writePIDS_Click(object sender, EventArgs e)
{
bool errorThrown = false;
_params.ForEach(x =>
{
var ctl = (IDynamicParameterControl)matchingControls[0];
try
{
MainV2.comPort.setParam(x.Key, float.Parse(ctl.Value));
}
catch
{
errorThrown = true;
CustomMessageBox.Show("Set " + x.Key + " Failed");
}
}
});
if(!errorThrown)
{
CustomMessageBox.Show("Parameters successfully saved.");
}
}
/// <summary>
/// Handles the Click event of the BUT_rerequestparams control.
/// </summary>
/// <param name="sender">The source of the event.</param>
/// <param name="e">The <see cref="System.EventArgs"/> instance containing the event data.</param>
protected void BUT_rerequestparams_Click(object sender, EventArgs e)
{
if (!MainV2.comPort.BaseStream.IsOpen)
return;
((Control)sender).Enabled = false;
try
{
MainV2.comPort.getParamList();
}
catch (Exception ex)
{
log.Error("Exception getting param list", ex);
CustomMessageBox.Show("Error: getting param list");
}
((Control)sender).Enabled = true;
BindParamList();
}
/// <summary>
/// Handles the Resize event of the this control.
/// </summary>
/// <param name="sender">The source of the event.</param>
/// <param name="e">The <see cref="System.EventArgs"/> instance containing the event data.</param>
protected void this_Resize(object sender, EventArgs e)
{
tableLayoutPanel1.Height = this.Height - 50;
}
/// <summary>
/// Handles the Load event of the ConfigRawParamsV2 control.
/// </summary>
/// <param name="sender">The source of the event.</param>
/// <param name="e">The <see cref="System.EventArgs"/> instance containing the event data.</param>
protected void ConfigRawParamsV2_Load(object sender, EventArgs e)
{
BindParamList();
}
/// <summary>
/// Handles the ParamListChanged event of the comPort control.
/// </summary>
/// <param name="sender">The source of the event.</param>
/// <param name="e">The <see cref="System.EventArgs"/> instance containing the event data.</param>
protected void comPort_ParamListChanged(object sender, EventArgs e)
{
SortParamList();
}
#endregion
#region Methods
/// <summary>
/// Loads the param file.
/// </summary>
/// <param name="Filename">The filename.</param>
/// <returns></returns>
private Hashtable loadParamFile(string Filename)
{
Hashtable param = new Hashtable();
StreamReader sr = new StreamReader(Filename);
while (!sr.EndOfStream)
{
string line = sr.ReadLine();
if (line.Contains("NOTE:"))
CustomMessageBox.Show(line, "Saved Note");
if (line.StartsWith("#"))
continue;
string[] items = line.Split(new char[] { ' ', ',', '\t' }, StringSplitOptions.RemoveEmptyEntries);
if (items.Length != 2)
continue;
string name = items[0];
float value = float.Parse(items[1], new System.Globalization.CultureInfo("en-US"));
MAVLink.modifyParamForDisplay(true, name, ref value);
if (name == "SYSID_SW_MREV")
continue;
if (name == "WP_TOTAL")
continue;
if (name == "CMD_TOTAL")
continue;
if (name == "FENCE_TOTAL")
continue;
if (name == "SYS_NUM_RESETS")
continue;
if (name == "ARSPD_OFFSET")
continue;
if (name == "GND_ABS_PRESS")
continue;
if (name == "GND_TEMP")
continue;
if (name == "CMD_INDEX")
continue;
if (name == "LOG_LASTFILE")
continue;
param[name] = value;
}
sr.Close();
return param;
}
/// <summary>
/// Sorts the param list.
/// </summary>
private void SortParamList()
{
// Clear list
_params.Clear();
// When the parameter list is changed, re sort the list for our View's purposes
MainV2.comPort.param.Keys.ForEach(x =>
{
string displayName = _parameterMetaDataRepository.GetParameterMetaData(x.ToString(), ParameterMetaDataConstants.DisplayName);
string parameterMode = _parameterMetaDataRepository.GetParameterMetaData(x.ToString(), ParameterMetaDataConstants.User);
// If we have a friendly display name AND
if (!String.IsNullOrEmpty(displayName) &&
// The user type is equal to the ParameterMode specified at class instantiation OR
((!String.IsNullOrEmpty(parameterMode) && parameterMode == ParameterMode) ||
// The user type is empty and this is in Advanced mode
String.IsNullOrEmpty(parameterMode) && ParameterMode == ParameterMetaDataConstants.Advanced))
var matchingControls = tableLayoutPanel1.Controls.Find(x.Key, true);
if (matchingControls.Length > 0)
{
var ctl = (IDynamicParameterControl)matchingControls[0];
try
{
MainV2.comPort.setParam(x.Key, float.Parse(ctl.Value));
}
catch
{
errorThrown = true;
CustomMessageBox.Show("Set " + x.Key + " Failed");
}
}
});
if (!errorThrown)
{
_params.Add(x.ToString(), displayName);
CustomMessageBox.Show("Parameters successfully saved.");
}
});
_params = _params.OrderBy(x => x.Value).ToDictionary(x => x.Key, x => x.Value);
}
}
/// <summary>
/// Binds the param list.
/// </summary>
private void BindParamList()
{
tableLayoutPanel1.Controls.Clear();
if (_params == null || _params.Count == 0) SortParamList();
_params.ForEach(x =>
/// <summary>
/// Handles the Click event of the BUT_rerequestparams control.
/// </summary>
/// <param name="sender">The source of the event.</param>
/// <param name="e">The <see cref="System.EventArgs"/> instance containing the event data.</param>
protected void BUT_rerequestparams_Click(object sender, EventArgs e)
{
if (!MainV2.comPort.BaseStream.IsOpen)
return;
((Control)sender).Enabled = false;
try
{
MainV2.comPort.getParamList();
}
catch (Exception ex)
{
log.Error("Exception getting param list", ex);
CustomMessageBox.Show("Error: getting param list");
}
((Control)sender).Enabled = true;
BindParamList();
}
/// <summary>
/// Handles the Resize event of the this control.
/// </summary>
/// <param name="sender">The source of the event.</param>
/// <param name="e">The <see cref="System.EventArgs"/> instance containing the event data.</param>
protected void this_Resize(object sender, EventArgs e)
{
tableLayoutPanel1.Height = this.Height - 50;
}
/// <summary>
/// Handles the Load event of the ConfigRawParamsV2 control.
/// </summary>
/// <param name="sender">The source of the event.</param>
/// <param name="e">The <see cref="System.EventArgs"/> instance containing the event data.</param>
protected void ConfigRawParamsV2_Load(object sender, EventArgs e)
{
BindParamList();
}
/// <summary>
/// Handles the ParamListChanged event of the comPort control.
/// </summary>
/// <param name="sender">The source of the event.</param>
/// <param name="e">The <see cref="System.EventArgs"/> instance containing the event data.</param>
protected void comPort_ParamListChanged(object sender, EventArgs e)
{
SortParamList();
}
#endregion
#region Methods
/// <summary>
/// Loads the param file.
/// </summary>
/// <param name="Filename">The filename.</param>
/// <returns></returns>
private Hashtable loadParamFile(string Filename)
{
Hashtable param = new Hashtable();
StreamReader sr = new StreamReader(Filename);
while (!sr.EndOfStream)
{
string line = sr.ReadLine();
if (line.Contains("NOTE:"))
CustomMessageBox.Show(line, "Saved Note");
if (line.StartsWith("#"))
continue;
string[] items = line.Split(new char[] { ' ', ',', '\t' }, StringSplitOptions.RemoveEmptyEntries);
if (items.Length != 2)
continue;
string name = items[0];
float value = float.Parse(items[1], new System.Globalization.CultureInfo("en-US"));
MAVLink.modifyParamForDisplay(true, name, ref value);
if (name == "SYSID_SW_MREV")
continue;
if (name == "WP_TOTAL")
continue;
if (name == "CMD_TOTAL")
continue;
if (name == "FENCE_TOTAL")
continue;
if (name == "SYS_NUM_RESETS")
continue;
if (name == "ARSPD_OFFSET")
continue;
if (name == "GND_ABS_PRESS")
continue;
if (name == "GND_TEMP")
continue;
if (name == "CMD_INDEX")
continue;
if (name == "LOG_LASTFILE")
continue;
param[name] = value;
}
sr.Close();
return param;
}
/// <summary>
/// Sorts the param list.
/// </summary>
private void SortParamList()
{
// Clear list
_params.Clear();
// When the parameter list is changed, re sort the list for our View's purposes
MainV2.comPort.param.Keys.ForEach(x =>
{
string displayName = _parameterMetaDataRepository.GetParameterMetaData(x.ToString(), ParameterMetaDataConstants.DisplayName);
string parameterMode = _parameterMetaDataRepository.GetParameterMetaData(x.ToString(), ParameterMetaDataConstants.User);
// If we have a friendly display name AND
if (!String.IsNullOrEmpty(displayName) &&
// The user type is equal to the ParameterMode specified at class instantiation OR
((!String.IsNullOrEmpty(parameterMode) && parameterMode == ParameterMode) ||
// The user type is empty and this is in Advanced mode
String.IsNullOrEmpty(parameterMode) && ParameterMode == ParameterMetaDataConstants.Advanced))
{
_params.Add(x.ToString(), displayName);
}
});
_params = _params.OrderBy(x => x.Value).ToDictionary(x => x.Key, x => x.Value);
}
/// <summary>
/// Binds the param list.
/// </summary>
private void BindParamList()
{
tableLayoutPanel1.Controls.Clear();
if (_params == null || _params.Count == 0) SortParamList();
_params.ForEach(x =>
{
if(!String.IsNullOrEmpty(x.Key))
{
@ -269,14 +269,14 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
float upperRange;
float.TryParse(rangeParts[1], out upperRange);
int scaler = Int32.Parse((1/increment).ToString(CultureInfo.InvariantCulture));
int scaler = (int)float.Parse((1 / increment).ToString(CultureInfo.InvariantCulture));
int scaledLowerRange = 0, scaledUpperRange = 0;
int scaledIncrement = (int)increment;
if(scaler > 0)
{
scaledLowerRange = (int)(lowerRange * scaler);
scaledUpperRange = (int)(upperRange * scaler);
scaledIncrement = Int32.Parse((increment * scaler).ToString(CultureInfo.InvariantCulture));
scaledIncrement = (int)float.Parse((increment * scaler).ToString(CultureInfo.InvariantCulture));
intValue *= scaler;
}
@ -336,47 +336,47 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
}
}
});
}
}
/// <summary>
/// Fits the description text.
/// </summary>
/// <param name="description">The description.</param>
/// <returns></returns>
private string FitDescriptionText(string description)
{
return FitDescriptionText(string.Empty, description);
}
/// <summary>
/// Fits the description text.
/// </summary>
/// <param name="description">The description.</param>
/// <returns></returns>
private string FitDescriptionText(string description)
{
return FitDescriptionText(string.Empty, description);
}
/// <summary>
/// Fits the description text.
/// </summary>
/// <param name="units">The units.</param>
/// <param name="description">The description.</param>
/// <returns></returns>
private string FitDescriptionText(string units, string description)
{
var returnDescription = new StringBuilder();
if(!String.IsNullOrEmpty(units))
{
returnDescription.Append(String.Format("Units: {0}{1}", units, Environment.NewLine));
}
/// <summary>
/// Fits the description text.
/// </summary>
/// <param name="units">The units.</param>
/// <param name="description">The description.</param>
/// <returns></returns>
private string FitDescriptionText(string units, string description)
{
var returnDescription = new StringBuilder();
if(!String.IsNullOrEmpty(description))
{
returnDescription.Append("Description: ");
var descriptionParts = description.Split(new char[] {' '});
for(int i = 0; i < descriptionParts.Length; i++)
if (!String.IsNullOrEmpty(units))
{
returnDescription.Append(String.Format("{0} ", descriptionParts[i]));
if (i != 0 && i % 10 == 0) returnDescription.Append(Environment.NewLine);
returnDescription.Append(String.Format("Units: {0}{1}", units, Environment.NewLine));
}
}
return returnDescription.ToString();
}
if (!String.IsNullOrEmpty(description))
{
returnDescription.Append("Description: ");
var descriptionParts = description.Split(new char[] { ' ' });
for (int i = 0; i < descriptionParts.Length; i++)
{
returnDescription.Append(String.Format("{0} ", descriptionParts[i]));
if (i != 0 && i % 10 == 0) returnDescription.Append(Environment.NewLine);
}
}
#endregion
}
return returnDescription.ToString();
}
#endregion
}
}