2012-09-19 20:37:36 -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 ArdupilotMega.Controls;
|
2012-09-30 20:53:54 -03:00
|
|
|
|
using System.Diagnostics;
|
2012-09-19 20:37:36 -03:00
|
|
|
|
|
|
|
|
|
namespace ArdupilotMega.GCSViews.ConfigurationView
|
|
|
|
|
{
|
|
|
|
|
public partial class ConfigFailSafe : UserControl, IActivate, IDeactivate
|
|
|
|
|
{
|
|
|
|
|
Timer timer = new Timer();
|
2012-09-30 20:53:54 -03:00
|
|
|
|
//
|
2012-09-19 20:37:36 -03:00
|
|
|
|
|
|
|
|
|
public ConfigFailSafe()
|
|
|
|
|
{
|
|
|
|
|
InitializeComponent();
|
|
|
|
|
|
|
|
|
|
// setup rc update
|
|
|
|
|
timer.Tick += new EventHandler(timer_Tick);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
public void Deactivate()
|
|
|
|
|
{
|
|
|
|
|
timer.Stop();
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
void timer_Tick(object sender, EventArgs e)
|
|
|
|
|
{
|
|
|
|
|
// update all linked controls - 10hz
|
|
|
|
|
try
|
|
|
|
|
{
|
|
|
|
|
MainV2.cs.UpdateCurrentSettings(currentStateBindingSource);
|
|
|
|
|
}
|
|
|
|
|
catch { }
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
public void Activate()
|
|
|
|
|
{
|
2012-09-30 20:53:54 -03:00
|
|
|
|
mavlinkCheckBoxthr_fs.setup(1, 0, "THR_FAILSAFE", MainV2.comPort.param, mavlinkNumericUpDownthr_fs_value);
|
|
|
|
|
mavlinkNumericUpDownthr_fs_value.setup(800, 1200, 1, 1, "THR_FS_VALUE", MainV2.comPort.param);
|
|
|
|
|
mavlinkCheckBoxthr_fs_action.setup(1, 0, "THR_FS_ACTION",MainV2.comPort.param);
|
|
|
|
|
mavlinkCheckBoxgcs_fs.setup(1, 0, "FS_GCS_ENABL", MainV2.comPort.param);
|
|
|
|
|
mavlinkCheckBoxshort_fs.setup(1, 0, "FS_SHORT_ACTN", MainV2.comPort.param);
|
|
|
|
|
mavlinkCheckBoxlong_fs.setup(1, 0, "FS_LONG_ACTN", MainV2.comPort.param);
|
|
|
|
|
|
2012-09-19 20:37:36 -03:00
|
|
|
|
timer.Enabled = true;
|
|
|
|
|
timer.Interval = 100;
|
|
|
|
|
timer.Start();
|
|
|
|
|
|
|
|
|
|
CustomMessageBox.Show("Ensure your props are not on the Plane/Quad","FailSafe",MessageBoxButtons.OK,MessageBoxIcon.Exclamation);
|
|
|
|
|
}
|
2012-09-30 20:53:54 -03:00
|
|
|
|
|
|
|
|
|
private void LNK_wiki_LinkClicked(object sender, LinkLabelLinkClickedEventArgs e)
|
|
|
|
|
{
|
|
|
|
|
Process.Start(new ProcessStartInfo("http://code.google.com/p/ardupilot-mega/wiki/APM2xFailsafe"));
|
|
|
|
|
}
|
2012-11-09 23:16:51 -04:00
|
|
|
|
|
|
|
|
|
private void lbl_armed_Paint(object sender, PaintEventArgs e)
|
|
|
|
|
{
|
|
|
|
|
if (lbl_armed.Text == "True")
|
|
|
|
|
{
|
|
|
|
|
lbl_armed.Text = "Armed";
|
|
|
|
|
}
|
|
|
|
|
else if (lbl_armed.Text == "False")
|
|
|
|
|
{
|
|
|
|
|
lbl_armed.Text = "Disarmed";
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
private void lbl_gpslock_Paint(object sender, PaintEventArgs e)
|
|
|
|
|
{
|
|
|
|
|
int _gpsfix = 0;
|
|
|
|
|
try
|
|
|
|
|
{
|
|
|
|
|
_gpsfix = int.Parse(lbl_gpslock.Text);
|
|
|
|
|
}
|
|
|
|
|
catch { return; }
|
|
|
|
|
string gps = "";
|
|
|
|
|
|
|
|
|
|
if (_gpsfix == 0)
|
|
|
|
|
{
|
|
|
|
|
gps = ("GPS: No GPS");
|
|
|
|
|
}
|
|
|
|
|
else if (_gpsfix == 1)
|
|
|
|
|
{
|
|
|
|
|
gps = ("GPS: No Fix");
|
|
|
|
|
}
|
|
|
|
|
else if (_gpsfix == 2)
|
|
|
|
|
{
|
|
|
|
|
gps = ("GPS: 3D Fix");
|
|
|
|
|
}
|
|
|
|
|
else if (_gpsfix == 3)
|
|
|
|
|
{
|
|
|
|
|
gps = ("GPS: 3D Fix");
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
lbl_gpslock.Text = gps;
|
|
|
|
|
}
|
2012-09-19 20:37:36 -03:00
|
|
|
|
}
|
|
|
|
|
}
|