public virtual short getRawValueForChannel(int channel) { if (!IsJoystickValid()) { return(0); } state = GetCurrentState(); short ans = pickchannel(channel, JoyChannels[channel].axis, false, 0); log.DebugFormat("{0} = {1} = {2}", channel, ans, state.X); return(ans); }
/// <summary> /// Updates the rcoverride values and controls the mode changes /// </summary> protected virtual void mainloop() { while (enabled && IsJoystickValid()) { try { System.Threading.Thread.Sleep(50); //joystick stuff state = GetCurrentState(); //Console.WriteLine(state); if (getNumberPOV() > 0) { int pov = getHatSwitchDirection(); if (pov != -1) { int angle = pov / 100; //0 = down = 18000 //0 = up = 0 // 0 if (angle > 270 || angle < 90) { hat1 += 500; } // 180 if (angle > 90 && angle < 270) { hat1 -= 500; } // 90 if (angle > 0 && angle < 180) { hat2 += 500; } // 270 if (angle > 180 && angle < 360) { hat2 -= 500; } } } if (elevons) { //g.channel_roll.set_pwm(BOOL_TO_SIGN(g.reverse_elevons) * (BOOL_TO_SIGN(g.reverse_ch2_elevon) * int(ch2_temp - elevon2_trim) - BOOL_TO_SIGN(g.reverse_ch1_elevon) * int(ch1_temp - elevon1_trim)) / 2 + 1500); //g.channel_pitch.set_pwm( (BOOL_TO_SIGN(g.reverse_ch2_elevon) * int(ch2_temp - elevon2_trim) + BOOL_TO_SIGN(g.reverse_ch1_elevon) * int(ch1_temp - elevon1_trim)) / 2 + 1500); short roll = pickchannel(1, JoyChannels[1].axis, false, JoyChannels[1].expo); short pitch = pickchannel(2, JoyChannels[2].axis, false, JoyChannels[2].expo); if (getJoystickAxis(1) != joystickaxis.None) { Interface.MAV.cs.rcoverridech1 = (short) (BOOL_TO_SIGN(JoyChannels[1].reverse) * ((int)(pitch - 1500) - (int)(roll - 1500)) / 2 + 1500); } if (getJoystickAxis(2) != joystickaxis.None) { Interface.MAV.cs.rcoverridech2 = (short) (BOOL_TO_SIGN(JoyChannels[2].reverse) * ((int)(pitch - 1500) + (int)(roll - 1500)) / 2 + 1500); } } else { if (getJoystickAxis(1) != joystickaxis.None) { Interface.MAV.cs.rcoverridech1 = pickchannel(1, JoyChannels[1].axis, JoyChannels[1].reverse, JoyChannels[1].expo); } //(ushort)(((int)state.Rz / 65.535) + 1000); if (getJoystickAxis(2) != joystickaxis.None) { Interface.MAV.cs.rcoverridech2 = pickchannel(2, JoyChannels[2].axis, JoyChannels[2].reverse, JoyChannels[2].expo); } //(ushort)(((int)state.Y / 65.535) + 1000); } if (getJoystickAxis(3) != joystickaxis.None) { Interface.MAV.cs.rcoverridech3 = pickchannel(3, JoyChannels[3].axis, JoyChannels[3].reverse, JoyChannels[3].expo); //(ushort)(1000 - ((int)slider[0] / 65.535) + 1000); } if (getJoystickAxis(4) != joystickaxis.None) { Interface.MAV.cs.rcoverridech4 = pickchannel(4, JoyChannels[4].axis, JoyChannels[4].reverse, JoyChannels[4].expo); //(ushort)(((int)state.X / 65.535) + 1000); } if (getJoystickAxis(5) != joystickaxis.None) { Interface.MAV.cs.rcoverridech5 = pickchannel(5, JoyChannels[5].axis, JoyChannels[5].reverse, JoyChannels[5].expo); } if (getJoystickAxis(6) != joystickaxis.None) { Interface.MAV.cs.rcoverridech6 = pickchannel(6, JoyChannels[6].axis, JoyChannels[6].reverse, JoyChannels[6].expo); } if (getJoystickAxis(7) != joystickaxis.None) { Interface.MAV.cs.rcoverridech7 = pickchannel(7, JoyChannels[7].axis, JoyChannels[7].reverse, JoyChannels[7].expo); } if (getJoystickAxis(8) != joystickaxis.None) { Interface.MAV.cs.rcoverridech8 = pickchannel(8, JoyChannels[8].axis, JoyChannels[8].reverse, JoyChannels[8].expo); } if (getJoystickAxis(9) != joystickaxis.None) { Interface.MAV.cs.rcoverridech9 = pickchannel(9, JoyChannels[9].axis, JoyChannels[9].reverse, JoyChannels[9].expo); } if (getJoystickAxis(10) != joystickaxis.None) { Interface.MAV.cs.rcoverridech10 = pickchannel(10, JoyChannels[10].axis, JoyChannels[10].reverse, JoyChannels[10].expo); } if (getJoystickAxis(11) != joystickaxis.None) { Interface.MAV.cs.rcoverridech11 = pickchannel(11, JoyChannels[11].axis, JoyChannels[11].reverse, JoyChannels[11].expo); } if (getJoystickAxis(12) != joystickaxis.None) { Interface.MAV.cs.rcoverridech12 = pickchannel(12, JoyChannels[12].axis, JoyChannels[12].reverse, JoyChannels[12].expo); } if (getJoystickAxis(13) != joystickaxis.None) { Interface.MAV.cs.rcoverridech13 = pickchannel(13, JoyChannels[13].axis, JoyChannels[13].reverse, JoyChannels[13].expo); } if (getJoystickAxis(14) != joystickaxis.None) { Interface.MAV.cs.rcoverridech14 = pickchannel(14, JoyChannels[14].axis, JoyChannels[14].reverse, JoyChannels[14].expo); } if (getJoystickAxis(15) != joystickaxis.None) { Interface.MAV.cs.rcoverridech15 = pickchannel(15, JoyChannels[15].axis, JoyChannels[15].reverse, JoyChannels[15].expo); } if (getJoystickAxis(16) != joystickaxis.None) { Interface.MAV.cs.rcoverridech16 = pickchannel(16, JoyChannels[16].axis, JoyChannels[16].reverse, JoyChannels[16].expo); } if (getJoystickAxis(17) != joystickaxis.None) { Interface.MAV.cs.rcoverridech17 = pickchannel(17, JoyChannels[17].axis, JoyChannels[17].reverse, JoyChannels[17].expo); } if (getJoystickAxis(18) != joystickaxis.None) { Interface.MAV.cs.rcoverridech18 = pickchannel(18, JoyChannels[18].axis, JoyChannels[18].reverse, JoyChannels[18].expo); } // disable button actions when not connected. if (Interface.BaseStream.IsOpen) { DoJoystickButtonFunction(); } //Console.WriteLine("{0} {1} {2} {3}", Interface.MAV.cs.rcoverridech1, Interface.MAV.cs.rcoverridech2, Interface.MAV.cs.rcoverridech3, Interface.MAV.cs.rcoverridech4); } catch (SharpDX.SharpDXException ex) { log.Error(ex); clearRCOverride(); _context.Send( delegate { CustomMessageBox.Show("Lost Joystick", "Lost Joystick"); }, null); return; } catch (Exception ex) { log.Info("Joystick thread error " + ex.ToString()); } // so we cant fall out } }