2012-07-25 10:44:24 -03:00
|
|
|
|
using System;
|
|
|
|
|
using System.ComponentModel;
|
|
|
|
|
using System.Diagnostics;
|
|
|
|
|
using System.Drawing;
|
|
|
|
|
using System.Linq;
|
|
|
|
|
using System.Windows.Forms;
|
|
|
|
|
using ArdupilotMega.Controls.BackstageView;
|
|
|
|
|
using ArdupilotMega.Presenter;
|
|
|
|
|
using Transitions;
|
2012-09-03 19:46:56 -03:00
|
|
|
|
using System.Collections;
|
2012-07-25 10:44:24 -03:00
|
|
|
|
|
|
|
|
|
namespace ArdupilotMega.GCSViews.ConfigurationView
|
|
|
|
|
{
|
|
|
|
|
public partial class ConfigMount : UserControl, IActivate
|
|
|
|
|
{
|
|
|
|
|
private Transition[] _ErrorTransition;
|
|
|
|
|
private Transition _NoErrorTransition;
|
2012-09-03 19:46:56 -03:00
|
|
|
|
bool startup = true;
|
2012-07-25 10:44:24 -03:00
|
|
|
|
|
|
|
|
|
public ConfigMount()
|
|
|
|
|
{
|
|
|
|
|
InitializeComponent();
|
|
|
|
|
PBOX_WarningIcon.Opacity = 0.0F;
|
|
|
|
|
LBL_Error.Opacity = 0.0F;
|
|
|
|
|
|
|
|
|
|
var delay = new Transition(new TransitionType_Linear(2000));
|
|
|
|
|
var fadeIn = new Transition(new TransitionType_Linear(800));
|
|
|
|
|
fadeIn.add(PBOX_WarningIcon, "Opacity", 1.0F);
|
|
|
|
|
fadeIn.add(LBL_Error, "Opacity", 1.0F);
|
|
|
|
|
|
|
|
|
|
_ErrorTransition = new[] { delay, fadeIn };
|
|
|
|
|
|
|
|
|
|
_NoErrorTransition = new Transition(new TransitionType_Linear(10));
|
|
|
|
|
_NoErrorTransition.add(PBOX_WarningIcon, "Opacity", 0.0F);
|
|
|
|
|
_NoErrorTransition.add(LBL_Error, "Opacity", 0.0F);
|
|
|
|
|
|
|
|
|
|
//setup button actions
|
|
|
|
|
foreach (var btn in Controls.Cast<Control>().OfType<Button>())
|
|
|
|
|
btn.Click += HandleButtonClick;
|
|
|
|
|
|
|
|
|
|
LNK_wiki.MouseEnter += (s, e) => FadeLinkTo((LinkLabel)s, Color.CornflowerBlue);
|
|
|
|
|
LNK_wiki.MouseLeave += (s, e) => FadeLinkTo((LinkLabel)s, Color.WhiteSmoke);
|
|
|
|
|
|
|
|
|
|
SetErrorMessageOpacity();
|
2012-07-29 20:23:42 -03:00
|
|
|
|
|
|
|
|
|
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
|
|
|
|
|
{
|
|
|
|
|
mavlinkComboBoxTilt.Items.AddRange(Enum.GetNames(typeof(Channelap)));
|
|
|
|
|
mavlinkComboBoxRoll.Items.AddRange(Enum.GetNames(typeof(Channelap)));
|
|
|
|
|
mavlinkComboBoxPan.Items.AddRange(Enum.GetNames(typeof(Channelap)));
|
|
|
|
|
}
|
|
|
|
|
else
|
|
|
|
|
{
|
|
|
|
|
mavlinkComboBoxTilt.Items.AddRange(Enum.GetNames(typeof(Channelac)));
|
|
|
|
|
mavlinkComboBoxRoll.Items.AddRange(Enum.GetNames(typeof(Channelac)));
|
|
|
|
|
mavlinkComboBoxPan.Items.AddRange(Enum.GetNames(typeof(Channelac)));
|
|
|
|
|
}
|
2012-07-25 10:44:24 -03:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
// 0 = disabled 1 = enabled
|
|
|
|
|
enum Channelap
|
|
|
|
|
{
|
|
|
|
|
Disable = 0,
|
2012-07-29 20:23:42 -03:00
|
|
|
|
RC5 = 1,
|
|
|
|
|
RC6 = 1,
|
|
|
|
|
RC7 = 1,
|
2012-09-03 19:46:56 -03:00
|
|
|
|
RC8 = 1,
|
|
|
|
|
RC9 = 1,
|
|
|
|
|
RC10 = 1,
|
|
|
|
|
RC11 = 1
|
2012-07-25 10:44:24 -03:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
// 0 = disabled 1 = enabled
|
|
|
|
|
enum Channelac
|
|
|
|
|
{
|
|
|
|
|
Disable = 0,
|
2012-09-03 19:46:56 -03:00
|
|
|
|
RC5 = 1,
|
|
|
|
|
RC6 = 1,
|
|
|
|
|
RC7 = 1,
|
|
|
|
|
RC8 = 1,
|
|
|
|
|
RC10 = 1,
|
|
|
|
|
RC11 = 1
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
enum Channelinput
|
|
|
|
|
{
|
|
|
|
|
Disable = 0,
|
2012-09-19 20:37:36 -03:00
|
|
|
|
RC5 = 5,
|
2012-09-03 19:46:56 -03:00
|
|
|
|
RC6 = 6,
|
2012-09-19 20:37:36 -03:00
|
|
|
|
RC7 = 7,
|
|
|
|
|
RC8 = 8
|
2012-07-25 10:44:24 -03:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
public void Activate()
|
|
|
|
|
{
|
2012-09-03 19:46:56 -03:00
|
|
|
|
Hashtable copy = new Hashtable(MainV2.comPort.param);
|
|
|
|
|
|
|
|
|
|
foreach (string item in copy.Keys)
|
2012-07-25 10:44:24 -03:00
|
|
|
|
{
|
2012-07-29 20:23:42 -03:00
|
|
|
|
if (item.EndsWith("_FUNCTION"))
|
|
|
|
|
{
|
|
|
|
|
switch (MainV2.comPort.param[item].ToString())
|
|
|
|
|
{
|
|
|
|
|
case "6":
|
|
|
|
|
mavlinkComboBoxPan.Text = item.Replace("_FUNCTION", "");
|
|
|
|
|
break;
|
|
|
|
|
case "7":
|
|
|
|
|
mavlinkComboBoxTilt.Text = item.Replace("_FUNCTION", "");
|
|
|
|
|
break;
|
|
|
|
|
case "8":
|
|
|
|
|
mavlinkComboBoxRoll.Text = item.Replace("_FUNCTION", "");
|
|
|
|
|
break;
|
|
|
|
|
default:
|
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
}
|
2012-07-25 10:44:24 -03:00
|
|
|
|
}
|
|
|
|
|
|
2012-09-03 19:46:56 -03:00
|
|
|
|
startup = false;
|
|
|
|
|
|
2012-08-06 11:22:57 -03:00
|
|
|
|
try
|
|
|
|
|
{
|
|
|
|
|
updatePitch();
|
|
|
|
|
updateRoll();
|
|
|
|
|
updateYaw();
|
|
|
|
|
}
|
|
|
|
|
catch (Exception ex) { CustomMessageBox.Show("Failed to set Param\n" + ex.ToString()); this.Enabled = false; return; }
|
2012-07-25 10:44:24 -03:00
|
|
|
|
}
|
|
|
|
|
|
2012-09-03 19:46:56 -03:00
|
|
|
|
void ensureDisabled(ComboBox cmb, int number, string exclude = "")
|
2012-08-02 07:04:54 -03:00
|
|
|
|
{
|
|
|
|
|
foreach (string item in cmb.Items)
|
|
|
|
|
{
|
|
|
|
|
if (MainV2.comPort.param.ContainsKey(item+"_FUNCTION")) {
|
|
|
|
|
float ans = (float)MainV2.comPort.param[item+"_FUNCTION"];
|
|
|
|
|
|
2012-09-03 19:46:56 -03:00
|
|
|
|
if (item == exclude)
|
|
|
|
|
continue;
|
|
|
|
|
|
2012-08-02 07:04:54 -03:00
|
|
|
|
if (ans == number)
|
|
|
|
|
{
|
|
|
|
|
MainV2.comPort.setParam(item + "_FUNCTION",0);
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
2012-07-25 10:44:24 -03:00
|
|
|
|
void updatePitch()
|
|
|
|
|
{
|
|
|
|
|
// pitch
|
2012-08-26 01:59:21 -03:00
|
|
|
|
if (mavlinkComboBoxTilt.Text == "")
|
|
|
|
|
return;
|
|
|
|
|
|
2012-07-29 20:23:42 -03:00
|
|
|
|
if (mavlinkComboBoxTilt.Text != "Disable")
|
|
|
|
|
{
|
2012-08-02 07:04:54 -03:00
|
|
|
|
MainV2.comPort.setParam(mavlinkComboBoxTilt.Text + "_FUNCTION", 7);
|
2012-08-26 01:59:21 -03:00
|
|
|
|
MainV2.comPort.setParam("MNT_STAB_TILT", 1);
|
2012-08-02 07:04:54 -03:00
|
|
|
|
}
|
|
|
|
|
else
|
|
|
|
|
{
|
2012-08-26 01:59:21 -03:00
|
|
|
|
MainV2.comPort.setParam("MNT_STAB_TILT", 0);
|
2012-09-03 19:46:56 -03:00
|
|
|
|
ensureDisabled(mavlinkComboBoxTilt, 7);
|
2012-07-29 20:23:42 -03:00
|
|
|
|
}
|
2012-09-03 19:46:56 -03:00
|
|
|
|
|
2012-07-29 20:23:42 -03:00
|
|
|
|
|
|
|
|
|
mavlinkNumericUpDownTSM.setup(800, 2200, 1, 1, mavlinkComboBoxTilt.Text +"_MIN", MainV2.comPort.param);
|
|
|
|
|
mavlinkNumericUpDownTSMX.setup(800, 2200, 1, 1, mavlinkComboBoxTilt.Text + "_MAX", MainV2.comPort.param);
|
2012-08-26 01:59:21 -03:00
|
|
|
|
mavlinkNumericUpDownTAM.setup(-90, 0, 100, 1, "MNT_ANGMIN_TIL", MainV2.comPort.param);
|
|
|
|
|
mavlinkNumericUpDownTAMX.setup(0, 90, 100, 1, "MNT_ANGMAX_TIL", MainV2.comPort.param);
|
2012-07-29 20:23:42 -03:00
|
|
|
|
mavlinkCheckBoxTR.setup(-1, 1, mavlinkComboBoxTilt.Text + "_REV", MainV2.comPort.param);
|
2012-09-03 19:46:56 -03:00
|
|
|
|
CMB_inputch_tilt.setup(typeof(Channelinput), "MNT_RC_IN_TILT", MainV2.comPort.param);
|
2012-07-25 10:44:24 -03:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
void updateRoll()
|
|
|
|
|
{
|
|
|
|
|
// roll
|
2012-08-26 01:59:21 -03:00
|
|
|
|
if (mavlinkComboBoxRoll.Text == "")
|
|
|
|
|
return;
|
|
|
|
|
|
2012-07-29 20:23:42 -03:00
|
|
|
|
if (mavlinkComboBoxRoll.Text != "Disable")
|
|
|
|
|
{
|
|
|
|
|
MainV2.comPort.setParam(mavlinkComboBoxRoll.Text + "_FUNCTION", 8);
|
|
|
|
|
MainV2.comPort.setParam("MNT_STAB_ROLL", 1);
|
|
|
|
|
}
|
2012-08-02 07:04:54 -03:00
|
|
|
|
else
|
|
|
|
|
{
|
2012-08-06 11:22:57 -03:00
|
|
|
|
MainV2.comPort.setParam("MNT_STAB_ROLL", 0);
|
2012-08-02 07:04:54 -03:00
|
|
|
|
ensureDisabled(mavlinkComboBoxRoll,8);
|
|
|
|
|
}
|
2012-07-29 20:23:42 -03:00
|
|
|
|
|
|
|
|
|
mavlinkNumericUpDownRSM.setup(800, 2200, 1, 1, mavlinkComboBoxRoll.Text +"_MIN", MainV2.comPort.param);
|
|
|
|
|
mavlinkNumericUpDownRSMX.setup(800, 2200, 1, 1, mavlinkComboBoxRoll.Text + "_MAX", MainV2.comPort.param);
|
2012-08-26 01:59:21 -03:00
|
|
|
|
mavlinkNumericUpDownRAM.setup(-90, 0, 100, 1, "MNT_ANGMIN_ROL", MainV2.comPort.param);
|
|
|
|
|
mavlinkNumericUpDownRAMX.setup(0, 90, 100, 1, "MNT_ANGMAX_ROL", MainV2.comPort.param);
|
2012-07-29 20:23:42 -03:00
|
|
|
|
mavlinkCheckBoxRR.setup(-1, 1, mavlinkComboBoxRoll.Text + "_REV", MainV2.comPort.param);
|
2012-09-03 19:46:56 -03:00
|
|
|
|
CMB_inputch_roll.setup(typeof(Channelinput), "MNT_RC_IN_ROLL", MainV2.comPort.param);
|
2012-07-25 10:44:24 -03:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
void updateYaw()
|
|
|
|
|
{
|
|
|
|
|
// yaw
|
2012-08-26 01:59:21 -03:00
|
|
|
|
if (mavlinkComboBoxPan.Text == "")
|
|
|
|
|
return;
|
|
|
|
|
|
2012-07-29 20:23:42 -03:00
|
|
|
|
if (mavlinkComboBoxPan.Text != "Disable")
|
|
|
|
|
{
|
|
|
|
|
MainV2.comPort.setParam(mavlinkComboBoxPan.Text + "_FUNCTION", 6);
|
2012-08-26 01:59:21 -03:00
|
|
|
|
MainV2.comPort.setParam("MNT_STAB_PAN", 1);
|
2012-07-29 20:23:42 -03:00
|
|
|
|
}
|
2012-08-02 07:04:54 -03:00
|
|
|
|
else
|
|
|
|
|
{
|
2012-08-26 01:59:21 -03:00
|
|
|
|
MainV2.comPort.setParam("MNT_STAB_PAN", 0);
|
2012-08-02 07:04:54 -03:00
|
|
|
|
ensureDisabled(mavlinkComboBoxPan,6);
|
|
|
|
|
}
|
2012-07-29 20:23:42 -03:00
|
|
|
|
|
|
|
|
|
mavlinkNumericUpDownPSM.setup(800, 2200, 1, 1, mavlinkComboBoxPan.Text + "_MIN", MainV2.comPort.param);
|
|
|
|
|
mavlinkNumericUpDownPSMX.setup(800, 2200, 1, 1, mavlinkComboBoxPan.Text + "_MAX", MainV2.comPort.param);
|
2012-08-26 01:59:21 -03:00
|
|
|
|
mavlinkNumericUpDownPAM.setup(-90, 0, 100, 1, "MNT_ANGMIN_PAN", MainV2.comPort.param);
|
|
|
|
|
mavlinkNumericUpDownPAMX.setup(0, 90, 100, 1, "MNT_ANGMAX_PAN", MainV2.comPort.param);
|
2012-07-29 20:23:42 -03:00
|
|
|
|
mavlinkCheckBoxPR.setup(-1, 1, mavlinkComboBoxPan.Text + "_REV", MainV2.comPort.param);
|
2012-09-03 19:46:56 -03:00
|
|
|
|
CMB_inputch_pan.setup(typeof(Channelinput), "MNT_RC_IN_PAN", MainV2.comPort.param);
|
2012-07-25 10:44:24 -03:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
private void SetErrorMessageOpacity()
|
|
|
|
|
{
|
|
|
|
|
/* if (_presenter.HasError)
|
|
|
|
|
{
|
|
|
|
|
// Todo - is this the prob? maybe single log trasition
|
|
|
|
|
var t = new Transition(new TransitionType_Acceleration(1000));
|
|
|
|
|
t.add(PBOX_WarningIcon, "Opacity", 1.0F);
|
|
|
|
|
t.add(LBL_Error, "Opacity", 1.0F);
|
|
|
|
|
t.run();
|
|
|
|
|
|
|
|
|
|
//Transition.runChain(_ErrorTransition);
|
|
|
|
|
}
|
|
|
|
|
else*/
|
|
|
|
|
{
|
|
|
|
|
_NoErrorTransition.run();
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
private static void FadeLinkTo(LinkLabel l, Color c)
|
|
|
|
|
{
|
|
|
|
|
var changeColorTransition = new Transition(new TransitionType_Linear(300));
|
|
|
|
|
changeColorTransition.add(l, "LinkColor", c);
|
|
|
|
|
changeColorTransition.run();
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
// Common handler for all buttons
|
|
|
|
|
// Will execute an ICommand if one is found on the button Tag
|
|
|
|
|
private static void HandleButtonClick(object sender, EventArgs e)
|
|
|
|
|
{
|
|
|
|
|
if (sender is Button)
|
|
|
|
|
{
|
|
|
|
|
var cmd = (sender as Button).Tag as ICommand;
|
|
|
|
|
|
|
|
|
|
if (cmd != null)
|
|
|
|
|
if (cmd.CanExecute(null))
|
|
|
|
|
cmd.Execute(null);
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
// Something has changed on the presenter - This may be an Icommand
|
|
|
|
|
// enabled state, so update the buttons as appropriate
|
|
|
|
|
void CheckCommandStates(object sender, PropertyChangedEventArgs propertyChangedEventArgs)
|
|
|
|
|
{
|
|
|
|
|
foreach (var btn in Controls.Cast<Control>().OfType<Button>())
|
|
|
|
|
{
|
|
|
|
|
var cmd = btn.Tag as ICommand;
|
|
|
|
|
if (cmd != null)
|
|
|
|
|
btn.Enabled = cmd.CanExecute(null);
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
private void LNK_Wiki_Clicked(object sender, LinkLabelLinkClickedEventArgs e)
|
|
|
|
|
{
|
|
|
|
|
Process.Start(new ProcessStartInfo("http://code.google.com/p/arducopter/wiki/AC2_Camera"));
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
private void mavlinkComboBox_SelectedIndexChanged(object sender, EventArgs e)
|
|
|
|
|
{
|
2012-09-03 19:46:56 -03:00
|
|
|
|
if (startup == true)
|
|
|
|
|
return;
|
|
|
|
|
|
|
|
|
|
ComboBox cmb = sender as ComboBox;
|
2012-07-25 10:44:24 -03:00
|
|
|
|
|
2012-08-06 11:22:57 -03:00
|
|
|
|
try
|
|
|
|
|
{
|
2012-09-03 19:46:56 -03:00
|
|
|
|
|
|
|
|
|
// cleanup all others - disableing any previous selection
|
|
|
|
|
ensureDisabled(cmb, 6, mavlinkComboBoxPan.Text);
|
|
|
|
|
ensureDisabled(cmb, 7, mavlinkComboBoxTilt.Text);
|
|
|
|
|
ensureDisabled(cmb, 8, mavlinkComboBoxRoll.Text);
|
|
|
|
|
|
|
|
|
|
// enable 3 axis stabilize
|
|
|
|
|
if (MainV2.comPort.param.ContainsKey("MNT_MODE"))
|
|
|
|
|
MainV2.comPort.setParam("MNT_MODE", 3);
|
|
|
|
|
|
2012-08-06 11:22:57 -03:00
|
|
|
|
updatePitch();
|
|
|
|
|
updateRoll();
|
|
|
|
|
updateYaw();
|
|
|
|
|
}
|
2012-09-03 19:46:56 -03:00
|
|
|
|
catch (Exception ex) { CustomMessageBox.Show("Failed to set Param\n" + ex.ToString()); return; }
|
2012-07-25 10:44:24 -03:00
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
}
|