public Joystick() { self = this; for (int a = 0; a < JoyButtons.Length; a++) JoyButtons[a].buttonno = -1; loadconfig(); }
public Joystick() { self = this; for (int a = 0; a < JoyButtons.Length; a++) JoyButtons[a].buttonno = -1; if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduPlane) { loadconfig("joystickbuttons" + MainV2.comPort.MAV.cs.firmware + ".xml", "joystickaxis" + MainV2.comPort.MAV.cs.firmware + ".xml"); } else if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduCopter2) { loadconfig("joystickbuttons" + MainV2.comPort.MAV.cs.firmware + ".xml", "joystickaxis" + MainV2.comPort.MAV.cs.firmware + ".xml"); } else if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduRover) { loadconfig("joystickbuttons" + MainV2.comPort.MAV.cs.firmware + ".xml", "joystickaxis" + MainV2.comPort.MAV.cs.firmware + ".xml"); } else { loadconfig(); } }
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 { } // all config is loaded from the xmls Joystick joy = new Joystick(); joy.elevons = CHK_elevons.Checked; 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(); noButtons = Math.Min(15, noButtons); for (int f = 0; f < noButtons; f++) { string name = (f).ToString(); doButtontoUI(name, 10, CMB_CH8.Bottom + 20 + f * 25); var config = joy.getButton(f); joy.setButton(f, config); } 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 (InputLostException ex) { if (MainV2.joystick != null && MainV2.joystick.enabled == true) { BUT_enable_Click(null, null); } } catch { } progressBarRoll.Value = MainV2.comPort.MAV.cs.rcoverridech1; progressBarPith.Value = MainV2.comPort.MAV.cs.rcoverridech2; progressBarThrottle.Value = MainV2.comPort.MAV.cs.rcoverridech3; progressBarRudder.Value = MainV2.comPort.MAV.cs.rcoverridech4; ProgressBarCH5.Value = MainV2.comPort.MAV.cs.rcoverridech5; ProgressBarCH6.Value = MainV2.comPort.MAV.cs.rcoverridech6; ProgressBarCH7.Value = MainV2.comPort.MAV.cs.rcoverridech7; ProgressBarCH8.Value = MainV2.comPort.MAV.cs.rcoverridech8; try { for (int f = 0; f < noButtons; f++) { string name = (f).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 Joystick_Load(object sender, EventArgs e) { try { DeviceList joysticklist = Joystick.getDevices(); foreach (DeviceInstance device in joysticklist) { CMB_joysticks.Items.Add(device.ProductName); } } catch { CustomMessageBox.Show("Error geting joystick list: do you have the directx redist installed?"); this.Close(); return; } if (CMB_joysticks.Items.Count > 0) CMB_joysticks.SelectedIndex = 0; CMB_CH1.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis))); CMB_CH2.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis))); CMB_CH3.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis))); CMB_CH4.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis))); CMB_CH5.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis))); CMB_CH6.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis))); CMB_CH7.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis))); CMB_CH8.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis))); try { /* //CMB_CH1 CMB_CH1.Text = MainV2.config["CMB_CH1"].ToString(); CMB_CH2.Text = MainV2.config["CMB_CH2"].ToString(); CMB_CH3.Text = MainV2.config["CMB_CH3"].ToString(); CMB_CH4.Text = MainV2.config["CMB_CH4"].ToString(); CMB_CH5.Text = MainV2.config["CMB_CH5"].ToString(); CMB_CH6.Text = MainV2.config["CMB_CH6"].ToString(); CMB_CH7.Text = MainV2.config["CMB_CH7"].ToString(); CMB_CH8.Text = MainV2.config["CMB_CH8"].ToString(); //revCH1 revCH1.Checked = bool.Parse(MainV2.config["revCH1"].ToString()); revCH2.Checked = bool.Parse(MainV2.config["revCH2"].ToString()); revCH3.Checked = bool.Parse(MainV2.config["revCH3"].ToString()); revCH4.Checked = bool.Parse(MainV2.config["revCH4"].ToString()); revCH5.Checked = bool.Parse(MainV2.config["revCH5"].ToString()); revCH6.Checked = bool.Parse(MainV2.config["revCH6"].ToString()); revCH7.Checked = bool.Parse(MainV2.config["revCH7"].ToString()); revCH8.Checked = bool.Parse(MainV2.config["revCH8"].ToString()); //expo_ch1 expo_ch1.Text = MainV2.config["expo_ch1"].ToString(); expo_ch2.Text = MainV2.config["expo_ch2"].ToString(); expo_ch3.Text = MainV2.config["expo_ch3"].ToString(); expo_ch4.Text = MainV2.config["expo_ch4"].ToString(); expo_ch5.Text = MainV2.config["expo_ch5"].ToString(); expo_ch6.Text = MainV2.config["expo_ch6"].ToString(); expo_ch7.Text = MainV2.config["expo_ch7"].ToString(); expo_ch8.Text = MainV2.config["expo_ch8"].ToString(); */ CHK_elevons.Checked = bool.Parse(MainV2.config["joy_elevons"].ToString()); } catch { } // IF 1 DOESNT EXIST NONE WILL var tempjoystick = new Joystick(); label14.Text += " "+MainV2.comPort.MAV.cs.firmware.ToString(); for (int a = 1; a <= 8; a++) { var config = tempjoystick.getChannel(a); findandsetcontrol("CMB_CH" + a, config.axis.ToString()); findandsetcontrol("revCH" + a, config.reverse.ToString()); findandsetcontrol("expo_ch" + a, config.expo.ToString()); } if (MainV2.joystick != null && MainV2.joystick.enabled) { timer1.Start(); BUT_enable.Text = "Disable"; } startup = false; }
public static joystickaxis getMovingAxis(string name, int threshold) { self.name = name; var joystick = new Joystick().AcquireJoystick(name); if (joystick == null) return joystickaxis.ARx; System.Threading.Thread.Sleep(50); var obj = joystick.CurrentJoystickState(); Hashtable values = new Hashtable(); // get the state of the joystick before. Type type = obj.GetType(); PropertyInfo[] properties = type.GetProperties(); foreach (PropertyInfo property in properties) { values[property.Name] = int.Parse(property.GetValue(obj, null).ToString()); } values["Slider1"] = obj.GetSlider()[0]; values["Slider2"] = obj.GetSlider()[1]; values["Hatud1"] = obj.GetPointOfView()[0]; values["Hatlr2"] = obj.GetPointOfView()[0]; values["Custom1"] = 0; values["Custom2"] = 0; CustomMessageBox.Show("Please move the joystick axis you want assigned to this function after clicking ok"); DateTime start = DateTime.Now; while (start.AddSeconds(10) > DateTime.Now) { joystick.Poll(); System.Threading.Thread.Sleep(50); var nextstate = joystick.CurrentJoystickState(); int[] slider = nextstate.GetSlider(); int[] hat1 = nextstate.GetPointOfView(); type = nextstate.GetType(); properties = type.GetProperties(); foreach (PropertyInfo property in properties) { //Console.WriteLine("Name: " + property.Name + ", Value: " + property.GetValue(obj, null)); log.InfoFormat("test name {0} old {1} new {2} ", property.Name, values[property.Name], int.Parse(property.GetValue(nextstate, null).ToString())); log.InfoFormat("{0} {1} {2}", property.Name, (int) values[property.Name], (int.Parse(property.GetValue(nextstate, null).ToString()) + threshold)); if ((int) values[property.Name] > (int.Parse(property.GetValue(nextstate, null).ToString()) + threshold) || (int) values[property.Name] < (int.Parse(property.GetValue(nextstate, null).ToString()) - threshold)) { log.Info(property.Name); joystick.Unacquire(); return (joystickaxis) Enum.Parse(typeof (joystickaxis), property.Name); } } // slider1 if ((int) values["Slider1"] > (slider[0] + threshold) || (int) values["Slider1"] < (slider[0] - threshold)) { joystick.Unacquire(); return joystickaxis.Slider1; } // slider2 if ((int) values["Slider2"] > (slider[1] + threshold) || (int) values["Slider2"] < (slider[1] - threshold)) { joystick.Unacquire(); return joystickaxis.Slider2; } // Hatud1 if ((int) values["Hatud1"] != (hat1[0])) { joystick.Unacquire(); return joystickaxis.Hatud1; } // Hatlr2 if ((int) values["Hatlr2"] != (hat1[0])) { joystick.Unacquire(); return joystickaxis.Hatlr2; } } CustomMessageBox.Show("No valid option was detected"); return joystickaxis.None; }
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),Joystick.buttonfunction.ChangeMode, 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 BUT_enable_Click(object sender, EventArgs e) { if (MainV2.joystick == null || MainV2.joystick.enabled == false) { try { if (MainV2.joystick != null) MainV2.joystick.UnAcquireJoyStick(); } catch { } // all config is loaded from the xmls Joystick joy = new Joystick(); joy.elevons = CHK_elevons.Checked; //show error message if a joystick is not connected when Enable is clicked if (!joy.start(CMB_joysticks.Text)) { CustomMessageBox.Show("Please Connect a Joystick", "No Joystick"); joy.Dispose(); return; } Settings.Instance["joystick_name"] = CMB_joysticks.Text; MainV2.joystick = joy; MainV2.joystick.enabled = true; BUT_enable.Text = "Disable"; //timer1.Start(); } else { MainV2.joystick.enabled = false; MainV2.joystick.clearRCOverride(); MainV2.joystick = null; //timer1.Stop(); BUT_enable.Text = "Enable"; } }
public Joystick() { self = this; }
private void Joystick_Load(object sender, EventArgs e) { try { var joysticklist = Joystick.getDevices(); foreach (DeviceInstance device in joysticklist) { CMB_joysticks.Items.Add(device.ProductName.TrimUnPrintable()); } } catch { CustomMessageBox.Show("Error geting joystick list: do you have the directx redist installed?"); this.Close(); return; } if (CMB_joysticks.Items.Count > 0 && CMB_joysticks.SelectedIndex == -1) { CMB_joysticks.SelectedIndex = 0; } try { if (Settings.Instance.ContainsKey("joystick_name") && Settings.Instance["joystick_name"].ToString() != "") { CMB_joysticks.Text = Settings.Instance["joystick_name"].ToString(); } } catch { } try { if (Settings.Instance.ContainsKey("joy_elevons")) { CHK_elevons.Checked = bool.Parse(Settings.Instance["joy_elevons"].ToString()); } } catch { } // IF 1 DOESNT EXIST NONE WILL var tempjoystick = new Joystick(() => MainV2.comPort); label14.Text += " " + MainV2.comPort.MAV.cs.firmware.ToString(); var y = label8.Bottom; this.SuspendLayout(); for (int a = 1; a <= maxaxis; a++) { var config = tempjoystick.getChannel(a); var ax = new JoystickAxis() { ChannelNo = a, Label = "Ch " + a, AxisArray = (Enum.GetValues(typeof(Joystick.joystickaxis))), ChannelValue = config.axis.ToString(), ExpoValue = config.expo.ToString(), ReverseValue = config.reverse, Location = new Point(0, y), Name = "axis" + a }; ax.Detect = () => Joystick.getMovingAxis(CMB_joysticks.Text, 16000).ToString(); ax.Reverse = () => MainV2.joystick?.setReverse(ax.ChannelNo, ax.ReverseValue); ax.SetAxis = () => MainV2.joystick?.setAxis(ax.ChannelNo, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), ax.ChannelValue)); ax.GetValue = () => { return((short)MainV2.comPort.MAV.cs.GetType().GetField("rcoverridech" + ax.ChannelNo) .GetValue(MainV2.comPort.MAV.cs)); }; Controls.Add(ax); y += ax.Height; if ((ax.Bottom + 30) > this.Height) { this.Height = ax.Bottom; } if ((ax.Right) > this.Width) { this.Width = ax.Right; } } this.ResumeLayout(); if (MainV2.joystick != null && MainV2.joystick.enabled) { timer1.Start(); BUT_enable.Text = "Disable"; } startup = false; }
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(() => MainV2.comPort); for (int a = 1; a <= maxaxis; a++) { var config = joy.getChannel(a); joy.setChannel(a, config.axis, config.reverse, config.expo); } joy.elevons = CHK_elevons.Checked; joy.AcquireJoystick(CMB_joysticks.Text); joy.name = CMB_joysticks.Text; noButtons = joy.getNumButtons(); noButtons = Math.Min(16, noButtons); SuspendLayout(); MainV2.joystick = joy; var maxctl = Controls.Find("axis" + 1, false).FirstOrDefault(); for (int f = 0; f < noButtons; f++) { string name = (f).ToString(); doButtontoUI(name, maxctl.Right + 100, maxctl.Top + f * maxctl.Height); var config = joy.getButton(f); joy.setButton(f, config); } ResumeLayout(); 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); MainV2.comPort.MAV.cs.rcoverridech9 = joy.getValueForChannel(9, CMB_joysticks.Text); MainV2.comPort.MAV.cs.rcoverridech10 = joy.getValueForChannel(10, CMB_joysticks.Text); MainV2.comPort.MAV.cs.rcoverridech11 = joy.getValueForChannel(11, CMB_joysticks.Text); MainV2.comPort.MAV.cs.rcoverridech12 = joy.getValueForChannel(12, CMB_joysticks.Text); MainV2.comPort.MAV.cs.rcoverridech13 = joy.getValueForChannel(13, CMB_joysticks.Text); MainV2.comPort.MAV.cs.rcoverridech14 = joy.getValueForChannel(14, CMB_joysticks.Text); MainV2.comPort.MAV.cs.rcoverridech15 = joy.getValueForChannel(15, CMB_joysticks.Text); MainV2.comPort.MAV.cs.rcoverridech16 = joy.getValueForChannel(16, CMB_joysticks.Text); MainV2.comPort.MAV.cs.rcoverridech17 = joy.getValueForChannel(17, CMB_joysticks.Text); MainV2.comPort.MAV.cs.rcoverridech18 = joy.getValueForChannel(18, CMB_joysticks.Text); //Console.WriteLine(DateTime.Now.Millisecond + " end "); } } catch (SharpDX.SharpDXException ex) { ex.ToString(); if (MainV2.joystick != null && MainV2.joystick.enabled == true) { BUT_enable_Click(null, null); } if (ex.Message.Contains("DIERR_NOTACQUIRED")) { MainV2.joystick = null; } } catch { } try { for (int f = 0; f < noButtons; f++) { string name = (f).ToString(); var items = this.Controls.Find("hbar" + name, false); if (items.Length > 0) { ((HorizontalProgressBar)items[0]).Value = MainV2.joystick.isButtonPressed(f) ? 100 : 0; } } } catch { } // this is for buttons - silent fail }