Browse Source

Mission planner:

* Added timeout to udp port open
    * Disabled baud selector for udp
    * Fixed problem where selected port might disappear when clicking near
      the port selector
mission-4.1.18
Janne Mantyharju 14 years ago
parent
commit
b115a96daa
  1. 12
      Tools/ArdupilotMegaPlanner/CommsUdpSerial.cs
  2. 7
      Tools/ArdupilotMegaPlanner/MainV2.cs

12
Tools/ArdupilotMegaPlanner/CommsUdpSerial.cs

@ -79,6 +79,18 @@ namespace System.IO.Ports @@ -79,6 +79,18 @@ namespace System.IO.Ports
client = new UdpClient(int.Parse(Port));
int timeout = 5;
while (timeout > 0)
{
if (BytesToRead > 0)
break;
System.Threading.Thread.Sleep(1000);
timeout--;
}
if (BytesToRead == 0)
return;
try
{
client.Receive(ref RemoteIpEndPoint);

7
Tools/ArdupilotMegaPlanner/MainV2.cs

@ -222,9 +222,12 @@ namespace ArdupilotMega @@ -222,9 +222,12 @@ namespace ArdupilotMega
private void CMB_serialport_Click(object sender, EventArgs e)
{
String old_port = CMB_serialport.Text;
CMB_serialport.Items.Clear();
CMB_serialport.Items.AddRange(SerialPort.GetPortNames());
CMB_serialport.Items.Add("UDP");
if (CMB_serialport.Items.Contains(old_port))
CMB_serialport.Text = old_port;
}
public static void fixtheme(Control temp)
@ -672,6 +675,10 @@ namespace ArdupilotMega @@ -672,6 +675,10 @@ namespace ArdupilotMega
private void CMB_serialport_SelectedIndexChanged(object sender, EventArgs e)
{
comportname = CMB_serialport.Text;
if (comportname == "UDP")
CMB_baudrate.Enabled = false;
else
CMB_baudrate.Enabled = true;
try
{
comPort.BaseStream.PortName = CMB_serialport.Text;

Loading…
Cancel
Save