2012-07-16 10:43:49 -03:00
|
|
|
|
using System;
|
|
|
|
|
using System.Collections.Generic;
|
|
|
|
|
using System.ComponentModel;
|
|
|
|
|
using System.Drawing;
|
|
|
|
|
using System.Data;
|
|
|
|
|
using System.Linq;
|
|
|
|
|
using System.Text;
|
|
|
|
|
using System.Windows.Forms;
|
|
|
|
|
using ArdupilotMega.Controls.BackstageView;
|
|
|
|
|
using System.Collections;
|
|
|
|
|
using ArdupilotMega.Controls;
|
|
|
|
|
using System.Diagnostics;
|
|
|
|
|
|
|
|
|
|
namespace ArdupilotMega.GCSViews.ConfigurationView
|
|
|
|
|
{
|
2012-07-22 04:51:05 -03:00
|
|
|
|
public partial class ConfigAP_Limits : UserControl, IActivate
|
2012-07-16 10:43:49 -03:00
|
|
|
|
{
|
|
|
|
|
public ConfigAP_Limits()
|
|
|
|
|
{
|
|
|
|
|
InitializeComponent();
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
private void LNK_wiki_LinkClicked(object sender, LinkLabelLinkClickedEventArgs e)
|
|
|
|
|
{
|
|
|
|
|
Process.Start(new ProcessStartInfo("https://code.google.com/p/ardupilot-mega/wiki/APLimitsLibrary"));
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
private void ProcessChange(object sender, EventArgs e)
|
|
|
|
|
{
|
|
|
|
|
if (sender.GetType() == typeof(CheckBox))
|
|
|
|
|
{
|
|
|
|
|
CheckBox chk = ((CheckBox)sender);
|
|
|
|
|
MainV2.comPort.setParam(chk.Name, chk.Checked ? 1 : 0);
|
|
|
|
|
}
|
|
|
|
|
else if (sender.GetType() == typeof(NumericUpDown))
|
|
|
|
|
{
|
|
|
|
|
NumericUpDown nud = ((NumericUpDown)sender);
|
|
|
|
|
MainV2.comPort.setParam(nud.Name, (float)nud.Value);
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
private void LIM_ENABLED_CheckedChanged(object sender, EventArgs e)
|
|
|
|
|
{
|
|
|
|
|
if (!MainV2.comPort.param.ContainsKey("LIM_ENABLED"))
|
|
|
|
|
{
|
|
|
|
|
CustomMessageBox.Show("This feature is not enabled in your firmware.");
|
|
|
|
|
return;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
if (LIM_ENABLED.Checked)
|
|
|
|
|
{
|
|
|
|
|
groupBox1.Enabled = true;
|
|
|
|
|
}
|
|
|
|
|
else
|
|
|
|
|
{
|
|
|
|
|
groupBox1.Enabled = false;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
ProcessChange(sender, e);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
private void LIM_REQUIRED_CheckedChanged(object sender, EventArgs e)
|
|
|
|
|
{
|
|
|
|
|
if (LIM_REQUIRED.Checked)
|
|
|
|
|
{
|
|
|
|
|
groupBox5.Enabled = true;
|
|
|
|
|
}
|
|
|
|
|
else
|
|
|
|
|
{
|
|
|
|
|
groupBox5.Enabled = false;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
ProcessChange(sender, e);
|
|
|
|
|
}
|
|
|
|
|
|
2012-07-22 04:51:05 -03:00
|
|
|
|
public void Activate()
|
2012-07-16 10:43:49 -03:00
|
|
|
|
{
|
|
|
|
|
PopulateData();
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
void PopulateData()
|
|
|
|
|
{
|
|
|
|
|
Hashtable copy = new Hashtable(MainV2.comPort.param);
|
|
|
|
|
|
|
|
|
|
foreach (string key in copy.Keys)
|
|
|
|
|
{
|
|
|
|
|
Control[] ctls = this.Controls.Find(key, true);
|
|
|
|
|
if (ctls.Length > 0)
|
|
|
|
|
{
|
|
|
|
|
if (ctls[0].GetType() == typeof(CheckBox))
|
|
|
|
|
{
|
|
|
|
|
CheckBox chk = ((CheckBox)ctls[0]);
|
|
|
|
|
Console.WriteLine(chk.Name + " "+ copy[key]);
|
|
|
|
|
|
|
|
|
|
chk.Checked = (float)copy[key] == 1 ? true: false;
|
2012-08-02 07:04:54 -03:00
|
|
|
|
chk.Enabled = true;
|
2012-07-16 10:43:49 -03:00
|
|
|
|
}
|
|
|
|
|
else if (ctls[0].GetType() == typeof(NumericUpDown))
|
|
|
|
|
{
|
|
|
|
|
NumericUpDown nud = ((NumericUpDown)ctls[0]);
|
|
|
|
|
nud.Value = (decimal)(float)copy[key];
|
2012-08-02 07:04:54 -03:00
|
|
|
|
nud.Enabled = true;
|
2012-07-16 10:43:49 -03:00
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
}
|