2012-04-05 21:50:04 -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;
|
2012-04-06 05:27:26 -03:00
|
|
|
|
using ArdupilotMega.Controls.BackstageView;
|
2012-04-24 10:49:27 -03:00
|
|
|
|
using ArdupilotMega.Controls;
|
2012-04-05 21:50:04 -03:00
|
|
|
|
|
|
|
|
|
namespace ArdupilotMega.GCSViews.ConfigurationView
|
|
|
|
|
{
|
2012-07-22 04:51:05 -03:00
|
|
|
|
public partial class ConfigHardwareOptions : UserControl, IActivate
|
2012-04-05 21:50:04 -03:00
|
|
|
|
{
|
2012-04-06 05:27:26 -03:00
|
|
|
|
bool startup = false;
|
|
|
|
|
|
|
|
|
|
const float rad2deg = (float)(180 / Math.PI);
|
|
|
|
|
const float deg2rad = (float)(1.0 / rad2deg);
|
|
|
|
|
|
2012-04-05 21:50:04 -03:00
|
|
|
|
public ConfigHardwareOptions()
|
|
|
|
|
{
|
|
|
|
|
InitializeComponent();
|
|
|
|
|
}
|
|
|
|
|
|
2012-04-06 05:27:26 -03:00
|
|
|
|
private void BUT_MagCalibration_Click(object sender, EventArgs e)
|
2012-04-05 21:50:04 -03:00
|
|
|
|
{
|
2012-04-25 07:10:11 -03:00
|
|
|
|
// list of x,y,z 's
|
2012-04-14 05:03:38 -03:00
|
|
|
|
List<Tuple<float, float, float>> data = new List<Tuple<float, float, float>>();
|
2012-04-06 05:27:26 -03:00
|
|
|
|
|
2012-04-25 07:10:11 -03:00
|
|
|
|
// backup current rate and set to 10 hz
|
2012-04-14 05:03:38 -03:00
|
|
|
|
byte backupratesens = MainV2.cs.ratesensors;
|
|
|
|
|
MainV2.cs.ratesensors = 10;
|
|
|
|
|
MainV2.comPort.requestDatastream((byte)MAVLink.MAV_DATA_STREAM.RAW_SENSORS, MainV2.cs.ratesensors); // mag captures at 10 hz
|
2012-04-06 05:27:26 -03:00
|
|
|
|
|
2012-04-14 05:03:38 -03:00
|
|
|
|
CustomMessageBox.Show("Data will be collected for 30 seconds, Please click ok and move the apm around all axises");
|
2012-04-06 05:27:26 -03:00
|
|
|
|
|
2012-04-14 05:03:38 -03:00
|
|
|
|
DateTime deadline = DateTime.Now.AddSeconds(30);
|
2012-04-06 05:27:26 -03:00
|
|
|
|
|
2012-04-14 05:03:38 -03:00
|
|
|
|
float oldmx = 0;
|
|
|
|
|
float oldmy = 0;
|
|
|
|
|
float oldmz = 0;
|
2012-04-05 21:50:04 -03:00
|
|
|
|
|
2012-04-14 05:03:38 -03:00
|
|
|
|
while (deadline > DateTime.Now)
|
|
|
|
|
{
|
2012-04-25 07:10:11 -03:00
|
|
|
|
// dont let the gui hang
|
2012-04-14 05:03:38 -03:00
|
|
|
|
Application.DoEvents();
|
2012-04-06 05:27:26 -03:00
|
|
|
|
|
2012-04-14 05:03:38 -03:00
|
|
|
|
if (oldmx != MainV2.cs.mx &&
|
|
|
|
|
oldmy != MainV2.cs.my &&
|
|
|
|
|
oldmz != MainV2.cs.mz)
|
2012-04-06 05:27:26 -03:00
|
|
|
|
{
|
2012-04-14 05:03:38 -03:00
|
|
|
|
data.Add(new Tuple<float, float, float>(
|
|
|
|
|
MainV2.cs.mx - (float)MainV2.cs.mag_ofs_x,
|
|
|
|
|
MainV2.cs.my - (float)MainV2.cs.mag_ofs_y,
|
|
|
|
|
MainV2.cs.mz - (float)MainV2.cs.mag_ofs_z));
|
|
|
|
|
|
|
|
|
|
oldmx = MainV2.cs.mx;
|
|
|
|
|
oldmy = MainV2.cs.my;
|
|
|
|
|
oldmz = MainV2.cs.mz;
|
2012-04-06 05:27:26 -03:00
|
|
|
|
}
|
2012-04-14 05:03:38 -03:00
|
|
|
|
}
|
2012-04-06 05:27:26 -03:00
|
|
|
|
|
2012-04-25 07:10:11 -03:00
|
|
|
|
// restore old sensor rate
|
2012-04-14 05:03:38 -03:00
|
|
|
|
MainV2.cs.ratesensors = backupratesens;
|
2012-04-25 07:10:11 -03:00
|
|
|
|
MainV2.comPort.requestDatastream((byte)MAVLink.MAV_DATA_STREAM.RAW_SENSORS, MainV2.cs.ratesensors);
|
2012-04-06 05:27:26 -03:00
|
|
|
|
|
2012-04-14 05:03:38 -03:00
|
|
|
|
if (data.Count < 10)
|
2012-04-06 05:27:26 -03:00
|
|
|
|
{
|
2012-04-14 05:03:38 -03:00
|
|
|
|
CustomMessageBox.Show("Log does not contain enough data");
|
|
|
|
|
return;
|
|
|
|
|
}
|
2012-04-06 05:27:26 -03:00
|
|
|
|
|
2012-04-14 05:03:38 -03:00
|
|
|
|
double[] ans = MagCalib.LeastSq(data);
|
2012-04-06 05:27:26 -03:00
|
|
|
|
|
2012-04-14 05:03:38 -03:00
|
|
|
|
MagCalib.SaveOffsets(ans);
|
2012-04-05 21:50:04 -03:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
private void linkLabel1_LinkClicked(object sender, LinkLabelLinkClickedEventArgs e)
|
|
|
|
|
{
|
2012-04-06 05:27:26 -03:00
|
|
|
|
try
|
|
|
|
|
{
|
|
|
|
|
//System.Diagnostics.Process.Start("http://www.ngdc.noaa.gov/geomagmodels/Declination.jsp");
|
|
|
|
|
System.Diagnostics.Process.Start("http://www.magnetic-declination.com/");
|
|
|
|
|
}
|
|
|
|
|
catch { CustomMessageBox.Show("Webpage open failed... do you have a virus?\nhttp://www.magnetic-declination.com/"); }
|
|
|
|
|
}
|
2012-04-05 21:50:04 -03:00
|
|
|
|
|
2012-04-06 05:27:26 -03:00
|
|
|
|
private void TXT_declination_Validating(object sender, CancelEventArgs e)
|
|
|
|
|
{
|
|
|
|
|
float ans = 0;
|
|
|
|
|
e.Cancel = !float.TryParse(TXT_declination.Text, out ans);
|
2012-04-05 21:50:04 -03:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
private void TXT_declination_Validated(object sender, EventArgs e)
|
|
|
|
|
{
|
2012-04-06 05:27:26 -03:00
|
|
|
|
if (startup)
|
|
|
|
|
return;
|
|
|
|
|
try
|
|
|
|
|
{
|
|
|
|
|
if (MainV2.comPort.param["COMPASS_DEC"] == null)
|
|
|
|
|
{
|
|
|
|
|
CustomMessageBox.Show("Not Available");
|
|
|
|
|
}
|
|
|
|
|
else
|
|
|
|
|
{
|
|
|
|
|
float dec = 0.0f;
|
|
|
|
|
try
|
|
|
|
|
{
|
|
|
|
|
string declination = TXT_declination.Text;
|
|
|
|
|
float.TryParse(declination, out dec);
|
|
|
|
|
float deg = (float)((int)dec);
|
|
|
|
|
float mins = (dec - deg);
|
|
|
|
|
if (dec > 0)
|
|
|
|
|
{
|
|
|
|
|
dec += ((mins) / 60.0f);
|
|
|
|
|
}
|
|
|
|
|
else
|
|
|
|
|
{
|
|
|
|
|
dec -= ((mins) / 60.0f);
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
catch { CustomMessageBox.Show("Invalid input!"); return; }
|
|
|
|
|
|
|
|
|
|
TXT_declination.Text = dec.ToString();
|
2012-04-05 21:50:04 -03:00
|
|
|
|
|
2012-04-06 05:27:26 -03:00
|
|
|
|
MainV2.comPort.setParam("COMPASS_DEC", dec * deg2rad);
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
catch { CustomMessageBox.Show("Set COMPASS_DEC Failed"); }
|
2012-04-05 21:50:04 -03:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
2012-04-06 05:27:26 -03:00
|
|
|
|
private void CHK_enablecompass_CheckedChanged(object sender, EventArgs e)
|
|
|
|
|
{
|
2012-04-19 08:22:02 -03:00
|
|
|
|
if (((CheckBox)sender).Checked == true)
|
|
|
|
|
{
|
|
|
|
|
CHK_autodec.Enabled = true;
|
|
|
|
|
TXT_declination.Enabled = true;
|
|
|
|
|
}
|
|
|
|
|
else
|
|
|
|
|
{
|
|
|
|
|
CHK_autodec.Enabled = false;
|
|
|
|
|
TXT_declination.Enabled = false;
|
|
|
|
|
}
|
|
|
|
|
|
2012-04-06 05:27:26 -03:00
|
|
|
|
if (startup)
|
|
|
|
|
return;
|
|
|
|
|
try
|
|
|
|
|
{
|
|
|
|
|
if (MainV2.comPort.param["MAG_ENABLE"] == null)
|
|
|
|
|
{
|
|
|
|
|
CustomMessageBox.Show("Not Available");
|
|
|
|
|
}
|
|
|
|
|
else
|
|
|
|
|
{
|
|
|
|
|
MainV2.comPort.setParam("MAG_ENABLE", ((CheckBox)sender).Checked == true ? 1 : 0);
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
catch { CustomMessageBox.Show("Set MAG_ENABLE Failed"); }
|
2012-04-05 21:50:04 -03:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
private void CHK_enablesonar_CheckedChanged(object sender, EventArgs e)
|
|
|
|
|
{
|
2012-04-06 05:27:26 -03:00
|
|
|
|
if (startup)
|
|
|
|
|
return;
|
|
|
|
|
try
|
|
|
|
|
{
|
|
|
|
|
if (MainV2.comPort.param["SONAR_ENABLE"] == null)
|
|
|
|
|
{
|
|
|
|
|
CustomMessageBox.Show("Not Available");
|
|
|
|
|
}
|
|
|
|
|
else
|
|
|
|
|
{
|
|
|
|
|
MainV2.comPort.setParam("SONAR_ENABLE", ((CheckBox)sender).Checked == true ? 1 : 0);
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
catch { CustomMessageBox.Show("Set SONAR_ENABLE Failed"); }
|
|
|
|
|
}
|
2012-04-05 21:50:04 -03:00
|
|
|
|
|
2012-04-06 05:27:26 -03:00
|
|
|
|
private void CHK_enableairspeed_CheckedChanged(object sender, EventArgs e)
|
|
|
|
|
{
|
|
|
|
|
if (startup)
|
|
|
|
|
return;
|
|
|
|
|
try
|
|
|
|
|
{
|
|
|
|
|
if (MainV2.comPort.param["ARSPD_ENABLE"] == null)
|
|
|
|
|
{
|
|
|
|
|
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
|
|
|
|
}
|
|
|
|
|
else
|
|
|
|
|
{
|
|
|
|
|
MainV2.comPort.setParam("ARSPD_ENABLE", ((CheckBox)sender).Checked == true ? 1 : 0);
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
catch { CustomMessageBox.Show("Set ARSPD_ENABLE Failed"); }
|
2012-04-05 21:50:04 -03:00
|
|
|
|
}
|
|
|
|
|
|
2012-04-06 05:27:26 -03:00
|
|
|
|
private void CHK_enableoptflow_CheckedChanged(object sender, EventArgs e)
|
|
|
|
|
{
|
|
|
|
|
|
|
|
|
|
if (startup)
|
|
|
|
|
return;
|
|
|
|
|
try
|
|
|
|
|
{
|
|
|
|
|
if (MainV2.comPort.param["FLOW_ENABLE"] == null)
|
|
|
|
|
{
|
|
|
|
|
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
|
|
|
|
}
|
|
|
|
|
else
|
|
|
|
|
{
|
|
|
|
|
MainV2.comPort.setParam("FLOW_ENABLE", ((CheckBox)sender).Checked == true ? 1 : 0);
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
catch { CustomMessageBox.Show("Set FLOW_ENABLE Failed"); }
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
private void CMB_sonartype_SelectedIndexChanged(object sender, EventArgs e)
|
2012-04-05 21:50:04 -03:00
|
|
|
|
{
|
2012-04-06 05:27:26 -03:00
|
|
|
|
if (startup)
|
|
|
|
|
return;
|
|
|
|
|
try
|
|
|
|
|
{
|
|
|
|
|
if (MainV2.comPort.param["SONAR_TYPE"] == null)
|
|
|
|
|
{
|
|
|
|
|
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
|
|
|
|
}
|
|
|
|
|
else
|
|
|
|
|
{
|
|
|
|
|
MainV2.comPort.setParam("SONAR_TYPE", ((ComboBox)sender).SelectedIndex);
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
catch { CustomMessageBox.Show("Set SONAR_TYPE Failed"); }
|
|
|
|
|
}
|
|
|
|
|
|
2012-07-22 04:51:05 -03:00
|
|
|
|
public void Activate()
|
2012-04-06 05:27:26 -03:00
|
|
|
|
{
|
|
|
|
|
if (!MainV2.comPort.BaseStream.IsOpen)
|
|
|
|
|
{
|
|
|
|
|
this.Enabled = false;
|
|
|
|
|
return;
|
|
|
|
|
}
|
|
|
|
|
else
|
|
|
|
|
{
|
|
|
|
|
this.Enabled = true;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
startup = true;
|
|
|
|
|
|
|
|
|
|
if (MainV2.comPort.param["ARSPD_ENABLE"] != null)
|
2012-05-16 09:21:27 -03:00
|
|
|
|
{
|
2012-04-06 05:27:26 -03:00
|
|
|
|
CHK_enableairspeed.Checked = MainV2.comPort.param["ARSPD_ENABLE"].ToString() == "1" ? true : false;
|
2012-05-16 09:21:27 -03:00
|
|
|
|
CHK_enableairspeed.Enabled = true;
|
|
|
|
|
}
|
2012-04-06 05:27:26 -03:00
|
|
|
|
if (MainV2.comPort.param["SONAR_ENABLE"] != null)
|
2012-05-16 09:21:27 -03:00
|
|
|
|
{
|
2012-04-06 05:27:26 -03:00
|
|
|
|
CHK_enablesonar.Checked = MainV2.comPort.param["SONAR_ENABLE"].ToString() == "1" ? true : false;
|
2012-05-16 09:21:27 -03:00
|
|
|
|
CHK_enablesonar.Enabled = true;
|
|
|
|
|
}
|
2012-04-06 05:27:26 -03:00
|
|
|
|
if (MainV2.comPort.param["MAG_ENABLE"] != null)
|
2012-05-16 09:21:27 -03:00
|
|
|
|
{
|
2012-04-06 05:27:26 -03:00
|
|
|
|
CHK_enablecompass.Checked = MainV2.comPort.param["MAG_ENABLE"].ToString() == "1" ? true : false;
|
2012-05-16 09:21:27 -03:00
|
|
|
|
CHK_enablecompass.Enabled = true;
|
|
|
|
|
}
|
2012-04-06 05:27:26 -03:00
|
|
|
|
if (MainV2.comPort.param["COMPASS_DEC"] != null)
|
2012-05-16 09:21:27 -03:00
|
|
|
|
{
|
2012-04-06 05:27:26 -03:00
|
|
|
|
TXT_declination.Text = (float.Parse(MainV2.comPort.param["COMPASS_DEC"].ToString()) * rad2deg).ToString();
|
2012-05-16 09:21:27 -03:00
|
|
|
|
}
|
2012-04-06 05:27:26 -03:00
|
|
|
|
if (MainV2.comPort.param["SONAR_TYPE"] != null)
|
2012-05-16 09:21:27 -03:00
|
|
|
|
{
|
2012-04-06 05:27:26 -03:00
|
|
|
|
CMB_sonartype.SelectedIndex = int.Parse(MainV2.comPort.param["SONAR_TYPE"].ToString());
|
2012-05-16 09:21:27 -03:00
|
|
|
|
}
|
2012-04-06 05:27:26 -03:00
|
|
|
|
if (MainV2.comPort.param["FLOW_ENABLE"] != null)
|
2012-05-16 09:21:27 -03:00
|
|
|
|
{
|
2012-04-06 05:27:26 -03:00
|
|
|
|
CHK_enableoptflow.Checked = MainV2.comPort.param["FLOW_ENABLE"].ToString() == "1" ? true : false;
|
2012-05-16 09:21:27 -03:00
|
|
|
|
CHK_enableoptflow.Enabled = true;
|
|
|
|
|
}
|
2012-04-19 08:22:02 -03:00
|
|
|
|
if (MainV2.comPort.param["COMPASS_AUTODEC"] != null)
|
2012-05-16 09:21:27 -03:00
|
|
|
|
{
|
2012-04-19 08:22:02 -03:00
|
|
|
|
CHK_autodec.Checked = MainV2.comPort.param["COMPASS_AUTODEC"].ToString() == "1" ? true : false;
|
2012-05-16 09:21:27 -03:00
|
|
|
|
}
|
2012-04-05 21:50:04 -03:00
|
|
|
|
|
2012-04-06 05:27:26 -03:00
|
|
|
|
startup = false;
|
2012-04-05 21:50:04 -03:00
|
|
|
|
}
|
2012-04-14 05:03:38 -03:00
|
|
|
|
|
|
|
|
|
private void BUT_MagCalibrationLog_Click(object sender, EventArgs e)
|
|
|
|
|
{
|
|
|
|
|
string minthro = "30";
|
|
|
|
|
Common.InputBox("Min Throttle", "Use only data above this throttle percent.", ref minthro);
|
|
|
|
|
|
|
|
|
|
int ans = 0;
|
|
|
|
|
int.TryParse(minthro, out ans);
|
|
|
|
|
|
|
|
|
|
MagCalib.ProcessLog(ans);
|
|
|
|
|
}
|
2012-04-19 08:22:02 -03:00
|
|
|
|
|
|
|
|
|
private void CHK_autodec_CheckedChanged(object sender, EventArgs e)
|
|
|
|
|
{
|
|
|
|
|
if (((CheckBox)sender).Checked == true)
|
|
|
|
|
{
|
|
|
|
|
TXT_declination.Enabled = false;
|
|
|
|
|
}
|
|
|
|
|
else
|
|
|
|
|
{
|
|
|
|
|
TXT_declination.Enabled = true;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
if (startup)
|
|
|
|
|
return;
|
|
|
|
|
try
|
|
|
|
|
{
|
|
|
|
|
if (MainV2.comPort.param["COMPASS_AUTODEC"] == null)
|
|
|
|
|
{
|
|
|
|
|
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
|
|
|
|
}
|
|
|
|
|
else
|
|
|
|
|
{
|
|
|
|
|
MainV2.comPort.setParam("COMPASS_AUTODEC", ((CheckBox)sender).Checked == true ? 1 : 0);
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
catch { CustomMessageBox.Show("Set COMPASS_AUTODEC Failed"); }
|
|
|
|
|
}
|
2012-04-05 21:50:04 -03:00
|
|
|
|
}
|
2012-04-14 05:03:38 -03:00
|
|
|
|
}
|