private void BUT_enable_Click(object sender, EventArgs e) { if (MainV2.joystick == null || MainV2.joystick.enabled == false) { try { if (MainV2.joystick != null) MainV2.joystick.UnAcquireJoyStick(); } catch { } Joystick joy = new Joystick(); try { joy.setChannel(1, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH1.Text), revCH1.Checked, int.Parse(expo_ch1.Text)); joy.setChannel(2, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH2.Text), revCH2.Checked, int.Parse(expo_ch2.Text)); joy.setChannel(3, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH3.Text), revCH3.Checked, int.Parse(expo_ch3.Text)); joy.setChannel(4, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH4.Text), revCH4.Checked, int.Parse(expo_ch4.Text)); joy.setChannel(5, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH5.Text), revCH5.Checked, int.Parse(expo_ch5.Text)); joy.setChannel(6, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH6.Text), revCH6.Checked, int.Parse(expo_ch6.Text)); joy.setChannel(7, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH7.Text), revCH7.Checked, int.Parse(expo_ch7.Text)); joy.setChannel(8, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH8.Text), revCH8.Checked, int.Parse(expo_ch8.Text)); } catch { CustomMessageBox.Show("Bad Channel Setting"); return; } joy.elevons = CHK_elevons.Checked; for (int f = 0; f < noButtons; f++) { string name = (f + 1).ToString(); try { joy.setButton(f, int.Parse(this.Controls.Find("cmbbutton" + name, false)[0].Text), this.Controls.Find("cmbaction" + name, false)[0].Text); } catch { CustomMessageBox.Show("Set Button "+ name + " Failed"); } } joy.start(CMB_joysticks.Text); MainV2.joystick = joy; MainV2.joystick.enabled = true; BUT_enable.Text = "Disable"; //timer1.Start(); } else { MainV2.joystick.enabled = false; MainV2.joystick = null; MAVLink.mavlink_rc_channels_override_t rc = new MAVLink.mavlink_rc_channels_override_t(); rc.target_component = MainV2.comPort.MAV.compid; rc.target_system = MainV2.comPort.MAV.sysid; rc.chan1_raw = 0; rc.chan2_raw = 0; rc.chan3_raw = 0; rc.chan4_raw = 0; rc.chan5_raw = 0; rc.chan6_raw = 0; rc.chan7_raw = 0; rc.chan8_raw = 0; MainV2.comPort.sendPacket(rc); System.Threading.Thread.Sleep(20); MainV2.comPort.sendPacket(rc); System.Threading.Thread.Sleep(20); MainV2.comPort.sendPacket(rc); //timer1.Stop(); BUT_enable.Text = "Enable"; } }
private void timer1_Tick(object sender, EventArgs e) { try { if (MainV2.joystick == null || MainV2.joystick.enabled == false) { //Console.WriteLine(DateTime.Now.Millisecond + " start "); Joystick joy = MainV2.joystick; if (joy == null) { joy = new Joystick(); joy.setChannel(1, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH1.Text), revCH1.Checked, int.Parse(expo_ch1.Text)); joy.setChannel(2, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH2.Text), revCH2.Checked, int.Parse(expo_ch2.Text)); joy.setChannel(3, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH3.Text), revCH3.Checked, int.Parse(expo_ch3.Text)); joy.setChannel(4, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH4.Text), revCH4.Checked, int.Parse(expo_ch4.Text)); joy.setChannel(5, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH5.Text), revCH5.Checked, int.Parse(expo_ch5.Text)); joy.setChannel(6, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH6.Text), revCH6.Checked, int.Parse(expo_ch6.Text)); joy.setChannel(7, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH7.Text), revCH7.Checked, int.Parse(expo_ch7.Text)); joy.setChannel(8, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH8.Text), revCH8.Checked, int.Parse(expo_ch8.Text)); joy.elevons = CHK_elevons.Checked; joy.AcquireJoystick(CMB_joysticks.Text); joy.name = CMB_joysticks.Text; noButtons = joy.getNumButtons(); for (int f = 0; f < noButtons; f++) { string name = (f + 1).ToString(); doButtontoUI(name, 10, CMB_CH8.Bottom + 20 + f * 25); joy.setButton(f, int.Parse(this.Controls.Find("cmbbutton" + name, false)[0].Text), this.Controls.Find("cmbaction" + name, false)[0].Text); } MainV2.joystick = joy; ThemeManager.ApplyThemeTo(this); CMB_joysticks.SelectedIndex = CMB_joysticks.Items.IndexOf(joy.name); } MainV2.joystick.elevons = CHK_elevons.Checked; MainV2.comPort.MAV.cs.rcoverridech1 = joy.getValueForChannel(1, CMB_joysticks.Text); MainV2.comPort.MAV.cs.rcoverridech2 = joy.getValueForChannel(2, CMB_joysticks.Text); MainV2.comPort.MAV.cs.rcoverridech3 = joy.getValueForChannel(3, CMB_joysticks.Text); MainV2.comPort.MAV.cs.rcoverridech4 = joy.getValueForChannel(4, CMB_joysticks.Text); MainV2.comPort.MAV.cs.rcoverridech5 = joy.getValueForChannel(5, CMB_joysticks.Text); MainV2.comPort.MAV.cs.rcoverridech6 = joy.getValueForChannel(6, CMB_joysticks.Text); MainV2.comPort.MAV.cs.rcoverridech7 = joy.getValueForChannel(7, CMB_joysticks.Text); MainV2.comPort.MAV.cs.rcoverridech8 = joy.getValueForChannel(8, CMB_joysticks.Text); //Console.WriteLine(DateTime.Now.Millisecond + " end "); } } catch { } progressBar1.Value = MainV2.comPort.MAV.cs.rcoverridech1; progressBar2.Value = MainV2.comPort.MAV.cs.rcoverridech2; progressBar3.Value = MainV2.comPort.MAV.cs.rcoverridech3; progressBar4.Value = MainV2.comPort.MAV.cs.rcoverridech4; horizontalProgressBar1.Value = MainV2.comPort.MAV.cs.rcoverridech5; horizontalProgressBar2.Value = MainV2.comPort.MAV.cs.rcoverridech6; horizontalProgressBar3.Value = MainV2.comPort.MAV.cs.rcoverridech7; horizontalProgressBar4.Value = MainV2.comPort.MAV.cs.rcoverridech8; try { for (int f = 0; f < noButtons; f++) { string name = (f + 1).ToString(); ((HorizontalProgressBar)this.Controls.Find("hbar" + name, false)[0]).Value = MainV2.joystick.isButtonPressed(f) ? 100 : 0; } } catch { } // this is for buttons - silent fail }
private void BUT_enable_Click(object sender, EventArgs e) { if (MainV2.joystick == null || MainV2.joystick.enabled == false) { try { if (MainV2.joystick != null) { MainV2.joystick.UnAcquireJoyStick(); } } catch { } Joystick joy = new Joystick(); try { joy.setChannel(1, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH1.Text), revCH1.Checked, int.Parse(expo_ch1.Text)); joy.setChannel(2, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH2.Text), revCH2.Checked, int.Parse(expo_ch2.Text)); joy.setChannel(3, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH3.Text), revCH3.Checked, int.Parse(expo_ch3.Text)); joy.setChannel(4, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH4.Text), revCH4.Checked, int.Parse(expo_ch4.Text)); joy.setChannel(5, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH5.Text), revCH5.Checked, int.Parse(expo_ch5.Text)); joy.setChannel(6, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH6.Text), revCH6.Checked, int.Parse(expo_ch6.Text)); joy.setChannel(7, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH7.Text), revCH7.Checked, int.Parse(expo_ch7.Text)); joy.setChannel(8, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH8.Text), revCH8.Checked, int.Parse(expo_ch8.Text)); } catch { CustomMessageBox.Show("Bad Channel Setting"); return; } joy.elevons = CHK_elevons.Checked; for (int f = 0; f < noButtons; f++) { string name = (f + 1).ToString(); try { joy.setButton(f, int.Parse(this.Controls.Find("cmbbutton" + name, false)[0].Text), this.Controls.Find("cmbaction" + name, false)[0].Text); } catch { CustomMessageBox.Show("Set Button " + name + " Failed"); } } joy.start(CMB_joysticks.Text); MainV2.joystick = joy; MainV2.joystick.enabled = true; BUT_enable.Text = "Disable"; //timer1.Start(); } else { MainV2.joystick.enabled = false; MainV2.joystick = null; MAVLink.mavlink_rc_channels_override_t rc = new MAVLink.mavlink_rc_channels_override_t(); rc.target_component = MainV2.comPort.MAV.compid; rc.target_system = MainV2.comPort.MAV.sysid; rc.chan1_raw = 0; rc.chan2_raw = 0; rc.chan3_raw = 0; rc.chan4_raw = 0; rc.chan5_raw = 0; rc.chan6_raw = 0; rc.chan7_raw = 0; rc.chan8_raw = 0; MainV2.comPort.sendPacket(rc); System.Threading.Thread.Sleep(20); MainV2.comPort.sendPacket(rc); System.Threading.Thread.Sleep(20); MainV2.comPort.sendPacket(rc); //timer1.Stop(); BUT_enable.Text = "Enable"; } }