private void OpenBg(object PRsender, bool getparams, ProgressWorkerEventArgs progressWorkerEventArgs)
{
frmProgressReporter.UpdateProgressAndStatus(-1, Strings.MavlinkConnecting);
giveComport = true;
if (BaseStream is SerialPort)
{
// allow settings to settle - previous dtr
System.Threading.Thread.Sleep(1000);
}
Terrain = new TerrainFollow(this);
bool hbseen = false;
try
{
BaseStream.ReadBufferSize = 16*1024;
lock (objlock) // so we dont have random traffic
{
log.Info("Open port with " + BaseStream.PortName + " " + BaseStream.BaudRate);
BaseStream.Open();
BaseStream.DiscardInBuffer();
// other boards seem to have issues if there is no delay? posible bootloader timeout issue
Thread.Sleep(1000);
}
MAVLinkMessage buffer = MAVLinkMessage.Invalid;
MAVLinkMessage buffer1 = MAVLinkMessage.Invalid;
DateTime start = DateTime.Now;
DateTime deadline = start.AddSeconds(CONNECT_TIMEOUT_SECONDS);
var countDown = new System.Timers.Timer {Interval = 1000, AutoReset = false};
countDown.Elapsed += (sender, e) =>
{
int secondsRemaining = (deadline - e.SignalTime).Seconds;
frmProgressReporter.UpdateProgressAndStatus(-1, string.Format(Strings.Trying, secondsRemaining));
if (secondsRemaining > 0) countDown.Start();
};
countDown.Start();
// px4 native
BaseStream.WriteLine("sh /etc/init.d/rc.usb");
int count = 0;
while (true)
{
if (progressWorkerEventArgs.CancelRequested)
{
progressWorkerEventArgs.CancelAcknowledged = true;
countDown.Stop();
if (BaseStream.IsOpen)
BaseStream.Close();
giveComport = false;
return;
}
log.Info(DateTime.Now.Millisecond + " Start connect loop ");
if (DateTime.Now > deadline)
{
//if (Progress != null)
// Progress(-1, "No Heartbeat Packets");
countDown.Stop();
this.Close();
if (hbseen)
{
progressWorkerEventArgs.ErrorMessage = Strings.Only1Hb;
throw new Exception(Strings.Only1HbD);
}
else
{
progressWorkerEventArgs.ErrorMessage = "No Heartbeat Packets Received";
throw new Exception(@"Can not establish a connection\n
Please check the following
1. You have firmware loaded
2. You have the correct serial port selected
3. PX4 - You have the microsd card installed
4. Try a diffrent usb port\n\n" +
"No Mavlink Heartbeat Packets where read from this port - Verify Baud Rate and setup\nMission Planner waits for 2 valid heartbeat packets before connecting");
}
}
System.Threading.Thread.Sleep(1);
// can see 2 heartbeat packets at any time, and will connect - was one after the other
if (buffer.Length == 0)
buffer = getHeartBeat();
System.Threading.Thread.Sleep(1);
if (buffer1.Length == 0)
buffer1 = getHeartBeat();
if (buffer.Length > 0 || buffer1.Length > 0)
hbseen = true;
count++;
// 2 hbs that match
if (buffer.Length > 5 && buffer1.Length > 5 && buffer.sysid == buffer1.sysid && buffer.compid == buffer1.compid)
{
mavlink_heartbeat_t hb = buffer.ToStructure<mavlink_heartbeat_t>();
if (hb.type != (byte) MAVLink.MAV_TYPE.GCS)
{
SetupMavConnect(buffer, hb);
break;
}
}
// 2 hb's that dont match. more than one sysid here
if (buffer.Length > 5 && buffer1.Length > 5 && (buffer.sysid == buffer1.sysid || buffer.compid == buffer1.compid))
{
mavlink_heartbeat_t hb = buffer.ToStructure<mavlink_heartbeat_t>();
if (hb.type != (byte) MAVLink.MAV_TYPE.ANTENNA_TRACKER && hb.type != (byte) MAVLink.MAV_TYPE.GCS)
{
SetupMavConnect(buffer, hb);
break;
}
hb = buffer1.ToStructure<mavlink_heartbeat_t>();
if (hb.type != (byte) MAVLink.MAV_TYPE.ANTENNA_TRACKER && hb.type != (byte) MAVLink.MAV_TYPE.GCS)
{
SetupMavConnect(buffer1, hb);
break;
}
}
}
countDown.Stop();
getVersion();
frmProgressReporter.UpdateProgressAndStatus(0,
"Getting Params.. (sysid " + MAV.sysid + " compid " + MAV.compid + ") ");
byte[] temp = ASCIIEncoding.ASCII.GetBytes("Mission Planner " + Application.ProductVersion + "\0");
Array.Resize(ref temp, 50);
//
generatePacket((byte)MAVLINK_MSG_ID.STATUSTEXT,
new mavlink_statustext_t() { severity = (byte)MAV_SEVERITY.INFO, text = temp });
// mavlink2
generatePacket((byte) MAVLINK_MSG_ID.STATUSTEXT,
new mavlink_statustext_t() {severity = (byte) MAV_SEVERITY.INFO, text = temp}, sysidcurrent,
compidcurrent, true, true);
if (getparams)
{
getParamListBG();
}
if (frmProgressReporter.doWorkArgs.CancelAcknowledged == true)
{
giveComport = false;
if (BaseStream.IsOpen)
BaseStream.Close();
return;
}
}
catch (Exception e)
{
try
{
BaseStream.Close();
}
catch
{
}
giveComport = false;
if (string.IsNullOrEmpty(progressWorkerEventArgs.ErrorMessage))
progressWorkerEventArgs.ErrorMessage = Strings.ConnectFailed;
log.Error(e);
throw;
}
//frmProgressReporter.Close();
giveComport = false;
frmProgressReporter.UpdateProgressAndStatus(100, Strings.Done);
log.Info("Done open " + MAV.sysid + " " + MAV.compid);
MAV.packetslost = 0;
MAV.synclost = 0;
}