private void timerWrite_Tick(object sender, EventArgs e) { CDroneManager.WriteParameter(ParameterName, Value); CDroneManager.ReadParameter(ParameterName); timerWrite.Stop(); }
static void CDroneManager_OnPacket(object packet, int sysId, int compId) { if (packet.GetType() == typeof(MAVLink.mavlink_statustext_t)) { MAVLink.mavlink_statustext_t status = (MAVLink.mavlink_statustext_t)packet; string messageString = ASCIIEncoding.ASCII.GetString(status.text); UpdateStatus(messageString.Substring(0, Math.Max(0, messageString.IndexOf('\0')))); } if (packet.GetType() == typeof(MAVLink.mavlink_heartbeat_t)) { // // Return a heartbeat to the drone, this ensures the drones knows the GCS is on // // and won't panic when on Guided mode // CHeartbeatThread.Initialize(); // if ((lastPacket != null) && (lastPacket.GetType() == typeof(MAVLink.mavlink_heartbeat_t))) { // This means we got 2 heartbeats in a row. This shouldn't happen - More messages need to be received CDroneManager.SetConstantUpdates(); } OnRefreshDroneInfo?.Invoke(); } lastPacket = packet; }
void CManager_OnRefreshDroneInfo() { this.SafeInvoke((Action) delegate { if (this.IsDisposed) { return; } CDroneManager.UpdateLastFlightMode(CDroneManager.Mode); labelMode.Text = APMModes.ModeToString(CDroneManager.Mode); labelAlt.Text = CDroneManager.DronePosition.altFromGround.ToString("0.0m"); labelHDOP.Text = String.Format("{0:0.0m} ({1})", CDroneManager.GPSHdop, CDroneManager.GPSSatelliteCount); labelHeading.Text = CDroneManager.DronePosition.heading.ToString("0.0°"); CultureInfo cultureInfo = CultureInfo.GetCultureInfoByIetfLanguageTag("en-US"); TextInfo textInfo = cultureInfo.TextInfo; /*labelDroneState.Text = textInfo.ToTitleCase(CDroneManager.DroneState.ToString().ToLower());*/ labelEKF.Text = CDroneManager.EKFStatus.ToString("0.000") + " (" + CDroneManager.EKFFlags + ")"; }, false); }
private void buttonSetAsCh6_Click(object sender, EventArgs e) { CDroneManager.WriteParameter("TUNE", double.Parse(ch6ParameterValue)); CDroneManager.ReadParameter("TUNE", false); CDroneManager.WriteParameter("TUNE_LOW", Ch6MinValue); CDroneManager.WriteParameter("TUNE_HIGH", Ch6MaxValue); CDroneManager.ReadParameter("TUNE_LOW", true); CDroneManager.ReadParameter("TUNE_HIGH", true); }
private void Connect() { comm = new CSerialComm(); comm.Comport = Properties.Settings.Default.Comport; comm.Baudrate = Properties.Settings.Default.Baud; if (comm.Connect()) { CDroneManager.Initialize(comm); buttonConnect.Text = "Disconnect"; RefreshAll(); } }
private void RefreshAll() { CDroneManager.ReadParameter("TUNE", false); CDroneManager.ReadParameter("TUNE_LOW", false); CDroneManager.ReadParameter("TUNE_HIGh", false); touchSpinPitchP.RefreshParameter(); touchSpinPitchI.RefreshParameter(); touchSpinPitchD.RefreshParameter(); touchSpinPitchImax.RefreshParameter(); touchSpinRollP.RefreshParameter(); touchSpinRollI.RefreshParameter(); touchSpinRollD.RefreshParameter(); touchSpinRollImax.RefreshParameter(); touchSpinYawP.RefreshParameter(); touchSpinYawI.RefreshParameter(); touchSpinYawD.RefreshParameter(); touchSpinYawImax.RefreshParameter(); touchSpinAltP.RefreshParameter(); touchSpinAltI.RefreshParameter(); touchSpinAltD.RefreshParameter(); }
public void RefreshParameter() { CDroneManager.ReadParameter(ParameterName, false); }
private void buttonClearCh6_Click(object sender, EventArgs e) { CDroneManager.WriteParameter("TUNE", 0); }