diff --git a/Controls/ConnectionControl.Designer.cs b/Controls/ConnectionControl.Designer.cs index 05282d3dfd..6e25d40558 100644 --- a/Controls/ConnectionControl.Designer.cs +++ b/Controls/ConnectionControl.Designer.cs @@ -33,6 +33,7 @@ private void InitializeComponent() this.cmb_Connection = new System.Windows.Forms.ComboBox(); this.linkLabel1 = new System.Windows.Forms.LinkLabel(); this.cmb_sysid = new System.Windows.Forms.ComboBox(); + this.chk_RTS = new System.Windows.Forms.CheckBox(); this.SuspendLayout(); // // cmb_Baud @@ -90,9 +91,18 @@ private void InitializeComponent() this.cmb_sysid.SelectedIndexChanged += new System.EventHandler(this.CMB_sysid_SelectedIndexChanged); this.cmb_sysid.Format += new System.Windows.Forms.ListControlConvertEventHandler(this.cmb_sysid_Format); // + // chk_RTS + // + resources.ApplyResources(this.chk_RTS, "chk_RTS"); + this.chk_RTS.BackColor = System.Drawing.Color.Black; + this.chk_RTS.ForeColor = System.Drawing.Color.White; + this.chk_RTS.Name = "chk_RTS"; + this.chk_RTS.UseVisualStyleBackColor = false; + // // ConnectionControl // this.BackgroundImage = global::MissionPlanner.Properties.Resources.bgdark; + this.Controls.Add(this.chk_RTS); this.Controls.Add(this.cmb_sysid); this.Controls.Add(this.linkLabel1); this.Controls.Add(this.cmb_Connection); @@ -112,5 +122,6 @@ private void InitializeComponent() private System.Windows.Forms.ComboBox cmb_Connection; private System.Windows.Forms.LinkLabel linkLabel1; public System.Windows.Forms.ComboBox cmb_sysid; + private System.Windows.Forms.CheckBox chk_RTS; } } diff --git a/Controls/ConnectionControl.cs b/Controls/ConnectionControl.cs index cb64de7ac5..6eb987c404 100644 --- a/Controls/ConnectionControl.cs +++ b/Controls/ConnectionControl.cs @@ -28,6 +28,10 @@ public ComboBox CMB_serialport get { return this.cmb_Connection; } } + public CheckBox chk_RTSEnable + { + get { return this.chk_RTS; } + } /// /// Called from the main form - set whether we are connected or not currently. diff --git a/Controls/ConnectionControl.resx b/Controls/ConnectionControl.resx index 1f9b9ac45a..579081518b 100644 --- a/Controls/ConnectionControl.resx +++ b/Controls/ConnectionControl.resx @@ -192,7 +192,7 @@ $this - 3 + 4 0, 0 @@ -216,7 +216,7 @@ $this - 2 + 3 True @@ -246,7 +246,7 @@ $this - 1 + 2 102, 27 @@ -267,6 +267,33 @@ $this + 1 + + + True + + + 49, 30 + + + 48, 17 + + + 5 + + + RTS + + + chk_RTS + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + 0 diff --git a/ExtLibs/ArduPilot/Mavlink/MAVLinkInterface.cs b/ExtLibs/ArduPilot/Mavlink/MAVLinkInterface.cs index 62f814622a..7648d1f1a9 100644 --- a/ExtLibs/ArduPilot/Mavlink/MAVLinkInterface.cs +++ b/ExtLibs/ArduPilot/Mavlink/MAVLinkInterface.cs @@ -750,19 +750,6 @@ No Mavlink Heartbeat Packets where read from this port - Verify Baud Rate and se count++; - // if we get no data, try enableing rts/cts - if (buffer.Length == 0 && BaseStream is SerialPort && start.AddSeconds(20) < DateTime.Now) - { - try - { - log.Debug("about to set RTS to " + !BaseStream.RtsEnable); - BaseStream.RtsEnable = !BaseStream.RtsEnable; - } - catch - { - } - } - // SLCAN check if (Regex.IsMatch(plaintxtline, @"\rT[0-9A-Z]{9,32}$", RegexOptions.Multiline)) { diff --git a/ExtLibs/Utilities/Settings.cs b/ExtLibs/Utilities/Settings.cs index d4f6abaa24..e258e066ac 100644 --- a/ExtLibs/Utilities/Settings.cs +++ b/ExtLibs/Utilities/Settings.cs @@ -108,6 +108,23 @@ public string GetString(string key, string @default = "") return result; } + public bool GetRTSEnable(string COMPort) + { + try + { + return bool.Parse(this[COMPort + "_RTSENABLE"]); + } + catch + { + return false; + } + } + + public void SetRTSEnable(string COMPort, bool Enabled) + { + this[COMPort + "_RTSENABLE"] = Enabled.ToString(); + } + public string BaudRate { get @@ -124,6 +141,18 @@ public string BaudRate set { this[ComPort + "_BAUD"] = value; } } + public bool RtsEnable + { + get + { + return GetRTSEnable(ComPort); + } + set + { + SetRTSEnable(ComPort, value); + } + } + public string LogDir { get diff --git a/GCSViews/ConfigurationView/ConfigFirmwareManifest.cs b/GCSViews/ConfigurationView/ConfigFirmwareManifest.cs index 002d43ff8b..0dee91227f 100644 --- a/GCSViews/ConfigurationView/ConfigFirmwareManifest.cs +++ b/GCSViews/ConfigurationView/ConfigFirmwareManifest.cs @@ -537,7 +537,7 @@ private void Lbl_bootloaderupdate_Click(object sender, EventArgs e) // connect to mavlink var mav = new MAVLinkInterface(); MainV2.instance.doConnect(mav, MainV2._connectionControl.CMB_serialport.Text, - MainV2._connectionControl.CMB_baudrate.Text, false); + MainV2._connectionControl.CMB_baudrate.Text, false, RTSEnable: MainV2._connectionControl.chk_RTSEnable.Checked); if (mav.BaseStream == null || !mav.BaseStream.IsOpen) { diff --git a/MainV2.cs b/MainV2.cs index 107958546a..df6986b07a 100644 --- a/MainV2.cs +++ b/MainV2.cs @@ -1506,7 +1506,8 @@ public void doDisconnect(MAVLinkInterface comPort) this.MenuConnect.Image = global::MissionPlanner.Properties.Resources.light_connect_icon; } - public void doConnect(MAVLinkInterface comPort, string portname, string baud, bool getparams = true, bool showui = true) + public void doConnect(MAVLinkInterface comPort, string portname, string baud, bool getparams = true, bool showui = true, + bool RTSEnable = false) { bool skipconnectcheck = false; log.Info($"We are connecting to {portname} {baud}"); @@ -1607,6 +1608,7 @@ public void doConnect(MAVLinkInterface comPort, string portname, string baud, bo { if (baud != "" && baud != "0" && baud.IsNumber()) comPort.BaseStream.BaudRate = int.Parse(baud); + comPort.BaseStream.RtsEnable = RTSEnable; } catch (Exception exp) { @@ -1924,7 +1926,7 @@ private void Connect() } else { - doConnect(comPort, _connectionControl.CMB_serialport.Text, _connectionControl.CMB_baudrate.Text); + doConnect(comPort, _connectionControl.CMB_serialport.Text, _connectionControl.CMB_baudrate.Text, RTSEnable: _connectionControl.chk_RTSEnable.Checked); } _connectionControl.UpdateSysIDS(); @@ -2010,6 +2012,8 @@ private void CMB_serialport_SelectedIndexChanged(object sender, EventArgs e) { _connectionControl.CMB_baudrate.Enabled = true; } + _connectionControl.chk_RTSEnable.Enabled = _connectionControl.CMB_baudrate.Enabled; + _connectionControl.chk_RTSEnable.Visible = _connectionControl.chk_RTSEnable.Enabled; try { @@ -2018,7 +2022,15 @@ private void CMB_serialport_SelectedIndexChanged(object sender, EventArgs e) { _connectionControl.CMB_baudrate.Text = Settings.Instance[_connectionControl.CMB_serialport.Text.Replace(" ", "_") + "_BAUD"]; - } + } + } + catch + { + } + + try + { + _connectionControl.chk_RTSEnable.Checked = Settings.Instance.GetRTSEnable(_connectionControl.CMB_serialport.Text); } catch { @@ -2259,6 +2271,8 @@ private void SaveConfig() if (_connectionControl != null) Settings.Instance.BaudRate = _connectionControl.CMB_baudrate.Text; + Settings.Instance.RtsEnable = _connectionControl.chk_RTSEnable.Checked; + Settings.Instance.APMFirmware = MainV2.comPort.MAV.cs.firmware.ToString(); Settings.Instance.Save();