Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

RTS enable is now settable with a checkbox under the COM port selector #3260

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 11 additions & 0 deletions Controls/ConnectionControl.Designer.cs

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

4 changes: 4 additions & 0 deletions Controls/ConnectionControl.cs
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,10 @@ public ComboBox CMB_serialport
get { return this.cmb_Connection; }
}

public CheckBox chk_RTSEnable
{
get { return this.chk_RTS; }
}

/// <summary>
/// Called from the main form - set whether we are connected or not currently.
Expand Down
33 changes: 30 additions & 3 deletions Controls/ConnectionControl.resx
Original file line number Diff line number Diff line change
Expand Up @@ -192,7 +192,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;cmb_Baud.ZOrder" xml:space="preserve">
<value>3</value>
<value>4</value>
</data>
<data name="cmb_Connection.Location" type="System.Drawing.Point, System.Drawing">
<value>0, 0</value>
Expand All @@ -216,7 +216,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;cmb_Connection.ZOrder" xml:space="preserve">
<value>2</value>
<value>3</value>
</data>
<data name="linkLabel1.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
Expand Down Expand Up @@ -246,7 +246,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;linkLabel1.ZOrder" xml:space="preserve">
<value>1</value>
<value>2</value>
</data>
<data name="cmb_sysid.Location" type="System.Drawing.Point, System.Drawing">
<value>102, 27</value>
Expand All @@ -267,6 +267,33 @@
<value>$this</value>
</data>
<data name="&gt;&gt;cmb_sysid.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="chk_RTS.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="chk_RTS.Location" type="System.Drawing.Point, System.Drawing">
<value>49, 30</value>
</data>
<data name="chk_RTS.Size" type="System.Drawing.Size, System.Drawing">
<value>48, 17</value>
</data>
<data name="chk_RTS.TabIndex" type="System.Int32, mscorlib">
<value>5</value>
</data>
<data name="chk_RTS.Text" xml:space="preserve">
<value>RTS</value>
</data>
<data name="&gt;&gt;chk_RTS.Name" xml:space="preserve">
<value>chk_RTS</value>
</data>
<data name="&gt;&gt;chk_RTS.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;chk_RTS.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;chk_RTS.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
Expand Down
13 changes: 0 additions & 13 deletions ExtLibs/ArduPilot/Mavlink/MAVLinkInterface.cs
Original file line number Diff line number Diff line change
Expand Up @@ -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))
{
Expand Down
29 changes: 29 additions & 0 deletions ExtLibs/Utilities/Settings.cs
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand Down
2 changes: 1 addition & 1 deletion GCSViews/ConfigurationView/ConfigFirmwareManifest.cs
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
Expand Down
20 changes: 17 additions & 3 deletions MainV2.cs
Original file line number Diff line number Diff line change
Expand Up @@ -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}");
Expand Down Expand Up @@ -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)
{
Expand Down Expand Up @@ -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();
Expand Down Expand Up @@ -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
{
Expand All @@ -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
{
Expand Down Expand Up @@ -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();
Expand Down
Loading