Skip to content

Commit

Permalink
Fix ESP32-C3 Dronebridge Reset on First connect
Browse files Browse the repository at this point in the history
  • Loading branch information
EosBandi authored and meee1 committed Jan 9, 2025
1 parent a4eca31 commit c730084
Show file tree
Hide file tree
Showing 5 changed files with 1,910 additions and 1,843 deletions.
16 changes: 15 additions & 1 deletion ExtLibs/Comms/CommsSerialPort.cs
Original file line number Diff line number Diff line change
Expand Up @@ -145,6 +145,10 @@ public void DiscardInBuffer()

public void Open()
{
if (espFix && _baseport is WinSerialPort)
{
((WinSerialPort)_baseport).espFix = true;
}
_baseport.Open();
}

Expand Down Expand Up @@ -194,6 +198,8 @@ public void toggleDTR()
}


public bool espFix = false;

private static readonly object locker = new object();

private static readonly Dictionary<string, string> comportnamecache = new Dictionary<string, string>();
Expand Down Expand Up @@ -407,6 +413,7 @@ public class WinSerialPort : System.IO.Ports.SerialPort, ICommsSerial
{
private static readonly ILog log = LogManager.GetLogger(typeof(WinSerialPort));

public bool espFix = false;
public WinSerialPort()
{
}
Expand Down Expand Up @@ -471,6 +478,7 @@ protected override void Dispose(bool disposing)
// 500ms write timeout - win32 api default
base.WriteTimeout = 500;


if (base.IsOpen)
return;

Expand All @@ -491,7 +499,11 @@ protected override void Dispose(bool disposing)

if (PortName.StartsWith("/"))
if (!File.Exists(PortName))
throw new Exception("No such device");
throw new Exception("No such device");


if (espFix)
base.Handshake = System.IO.Ports.Handshake.RequestToSend;

try
{
Expand All @@ -509,6 +521,8 @@ protected override void Dispose(bool disposing)

throw;
}
if (espFix)
base.Handshake = System.IO.Ports.Handshake.None;
}

public new void Close()
Expand Down
51 changes: 31 additions & 20 deletions GCSViews/ConfigurationView/ConfigPlanner.Designer.cs

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

13 changes: 11 additions & 2 deletions GCSViews/ConfigurationView/ConfigPlanner.cs
Original file line number Diff line number Diff line change
Expand Up @@ -173,6 +173,7 @@ public void Activate()

// setup other config state
SetCheckboxFromConfig("CHK_resetapmonconnect", CHK_resetapmonconnect);
SetCheckboxFromConfig("CHK_rtsresetesp32", CHK_rtsresetesp32);

CMB_rateattitude.Text = MainV2.comPort.MAV.cs.rateattitude.ToString();
CMB_rateposition.Text = MainV2.comPort.MAV.cs.rateposition.ToString();
Expand Down Expand Up @@ -620,7 +621,7 @@ private void CMB_raterc_SelectedIndexChanged(object sender, EventArgs e)
CurrentState.ratercbackup = MainV2.comPort.MAV.cs.raterc;

MainV2.comPort.requestDatastream(MAVLink.MAV_DATA_STREAM.RC_CHANNELS, MainV2.comPort.MAV.cs.raterc);
// request rc info
// request rc info
}

private void CMB_ratesensors_SelectedIndexChanged(object sender, EventArgs e)
Expand Down Expand Up @@ -648,6 +649,14 @@ private void CHK_resetapmonconnect_CheckedChanged(object sender, EventArgs e)
Settings.Instance[((CheckBox)sender).Name] = ((CheckBox)sender).Checked.ToString();
}

private void CHK_rtsresetesp32_CheckedChanged(object sender, EventArgs e)
{
Settings.Instance[((CheckBox)sender).Name] = ((CheckBox)sender).Checked.ToString();
}




private void CHK_speechaltwarning_CheckedChanged(object sender, EventArgs e)
{
if (startup)
Expand Down Expand Up @@ -1121,7 +1130,7 @@ private void chk_displaytooltip_CheckedChanged(object sender, EventArgs e)
{
Settings.Instance["mapicondesc"] = "";
}

}

private void num_linelength_ValueChanged(object sender, EventArgs e)
Expand Down
Loading

0 comments on commit c730084

Please sign in to comment.