public void DeviceAttached(object USBDevice, object usbdevice) { Task.Run(async() => { Parallel.ForEach(await Test.UsbDevices.GetDeviceInfoList(), async(port) => { var portUsb = await Test.UsbDevices.GetUSB(port).ConfigureAwait(false); if (portUsb == null) { return; } px4uploader.Uploader up; try { portUsb.BaudRate = 115200; up = new px4uploader.Uploader(portUsb); } catch (Exception ex) { Console.WriteLine(ex.Message); return; } try { up.identify(); var msg = String.Format("Found board type {0} boardrev {1} bl rev {2} fwmax {3} on {4}", up.board_type, up.board_rev, up.bl_rev, up.fw_maxsize, port); log.Info(msg); up.close(); //this.InvokeIfRequired(() => lbl_status.Text = msg); detectedport = port; detectedboardid = up.board_type; } catch (Exception) { Console.WriteLine("Not There.."); up.close(); } }); }); }
public Uploader(string port, int baudrate) { self = this; if (port.StartsWith("/")) if (!File.Exists(port)) throw new Exception("No such device"); this.port = new SerialPort(port, baudrate); this.port.ReadTimeout = 50; this.port.WriteTimeout = 50; try { Console.Write("open"); if (port.StartsWith("/")) if (!File.Exists(port)) throw new Exception("No such device"); this.port.Open(); this.port.Write("reboot -b\r"); Console.WriteLine("..done"); } catch (Exception ex) { try { this.port.Close(); } catch { } try { this.Dispose(); GC.Collect(); } catch { } throw ex; } }
/// <summary> /// upload to vrbrain standalone /// </summary> /// <param name="filename"></param> public bool UploadVRBRAIN(string filename) { px4uploader.Uploader up; updateProgress(0, "Reading Hex File"); px4uploader.Firmware fw; try { fw = px4uploader.Firmware.ProcessFirmware(filename); } catch (Exception ex) { CustomMessageBox.Show(Strings.ErrorFirmwareFile + "\n\n" + ex.ToString(), Strings.ERROR); return(false); } try { // check if we are seeing heartbeats MainV2.comPort.BaseStream.Open(); MainV2.comPort.giveComport = true; BoardDetect.boards board = BoardDetect.DetectBoard(MainV2.comPortName); if (MainV2.comPort.getHeartBeat().Length > 0) { MainV2.comPort.doReboot(true); MainV2.comPort.Close(); //specific action for VRBRAIN4 board that needs to be manually disconnected before uploading if (board == BoardDetect.boards.vrbrainv40) { CustomMessageBox.Show("VRBRAIN 4 detected. Please unplug the board, and then press OK and plug back in.\n"); } } else { MainV2.comPort.BaseStream.Close(); CustomMessageBox.Show("Please unplug the board, and then press OK and plug back in.\nMission Planner will look for 30 seconds to find the board"); } } catch (Exception ex) { log.Error(ex); CustomMessageBox.Show("Please unplug the board, and then press OK and plug back in.\nMission Planner will look for 30 seconds to find the board"); } DateTime DEADLINE = DateTime.Now.AddSeconds(30); updateProgress(0, "Scanning comports"); while (DateTime.Now < DEADLINE) { string[] allports = SerialPort.GetPortNames(); foreach (string port in allports) { log.Info(DateTime.Now.Millisecond + " Trying Port " + port); updateProgress(-1, "Connecting"); try { up = new px4uploader.Uploader(port, 115200); } catch (Exception ex) { //System.Threading.Thread.Sleep(50); Console.WriteLine(ex.Message); continue; } try { up.identify(); updateProgress(-1, "Identify"); log.InfoFormat("Found board type {0} boardrev {1} bl rev {2} fwmax {3} on {4}", up.board_type, up.board_rev, up.bl_rev, up.fw_maxsize, port); } catch (Exception) { Console.WriteLine("Not There.."); //Console.WriteLine(ex.Message); up.close(); continue; } up.skipotp = true; try { up.currentChecksum(fw); } catch { up.__reboot(); up.close(); CustomMessageBox.Show("No need to upload. already on the board"); return(true); } try { up.ProgressEvent += new px4uploader.Uploader.ProgressEventHandler(up_ProgressEvent); up.LogEvent += new px4uploader.Uploader.LogEventHandler(up_LogEvent); updateProgress(0, "Upload"); up.upload(fw); updateProgress(100, "Upload Done"); } catch (Exception ex) { updateProgress(0, "ERROR: " + ex.Message); log.Info(ex); Console.WriteLine(ex.ToString()); return(false); } finally { up.close(); } if (up.board_type == 1140 || up.board_type == 1145 || up.board_type == 1150 || up.board_type == 1151 || up.board_type == 1152 || up.board_type == 1210 || up.board_type == 1351 || up.board_type == 1352 || up.board_type == 1411 || up.board_type == 1520) {//VR boards have no tone alarm if (up.board_type == 1140) { CustomMessageBox.Show("Upload complete! Please unplug and reconnect board."); } else { CustomMessageBox.Show("Upload complete!"); } } else { // wait for IO firmware upgrade and boot to a mavlink state CustomMessageBox.Show("Please wait for the musical tones to finish before clicking OK"); } return(true); } } updateProgress(0, "ERROR: No Response from board"); return(false); }
/// <summary> /// upload to vrbrain standalone /// </summary> /// <param name="filename"></param> public bool UploadVRBRAIN(string filename, BoardDetect.boards board) { px4uploader.Uploader up; updateProgress(0, "Reading Hex File"); px4uploader.Firmware fw; try { fw = px4uploader.Firmware.ProcessFirmware(filename); } catch (Exception ex) { CustomMessageBox.Show(Strings.ErrorFirmwareFile + "\n\n" + ex.ToString(), Strings.ERROR); return false; } try { // check if we are seeing heartbeats MainV2.comPort.BaseStream.Open(); MainV2.comPort.giveComport = true; if (MainV2.comPort.getHeartBeat().Length > 0) { MainV2.comPort.doReboot(true); MainV2.comPort.Close(); //specific action for VRBRAIN4 board that needs to be manually disconnected before uploading if (board == BoardDetect.boards.vrbrainv40) { CustomMessageBox.Show( "VRBRAIN 4 detected. Please unplug the board, and then press OK and plug back in.\n"); } } else { MainV2.comPort.BaseStream.Close(); CustomMessageBox.Show(Strings.PleaseUnplugTheBoardAnd); } } catch (Exception ex) { log.Error(ex); CustomMessageBox.Show(Strings.PleaseUnplugTheBoardAnd); } DateTime DEADLINE = DateTime.Now.AddSeconds(30); updateProgress(0, "Scanning comports"); while (DateTime.Now < DEADLINE) { string[] allports = SerialPort.GetPortNames(); foreach (string port in allports) { log.Info(DateTime.Now.Millisecond + " Trying Port " + port); updateProgress(-1, "Connecting"); try { up = new px4uploader.Uploader(port, 115200); } catch (Exception ex) { //System.Threading.Thread.Sleep(50); Console.WriteLine(ex.Message); continue; } try { up.identify(); updateProgress(-1, "Identify"); log.InfoFormat("Found board type {0} boardrev {1} bl rev {2} fwmax {3} on {4}", up.board_type, up.board_rev, up.bl_rev, up.fw_maxsize, port); } catch (Exception) { Console.WriteLine("Not There.."); //Console.WriteLine(ex.Message); up.close(); continue; } up.skipotp = true; try { up.currentChecksum(fw); } catch { up.__reboot(); up.close(); CustomMessageBox.Show(Strings.NoNeedToUpload); return true; } try { up.ProgressEvent += new px4uploader.Uploader.ProgressEventHandler(up_ProgressEvent); up.LogEvent += new px4uploader.Uploader.LogEventHandler(up_LogEvent); updateProgress(0, "Upload"); up.upload(fw); updateProgress(100, "Upload Done"); } catch (Exception ex) { updateProgress(0, "ERROR: " + ex.Message); log.Info(ex); Console.WriteLine(ex.ToString()); return false; } finally { up.close(); } if (up.board_type == 1140 || up.board_type == 1145 || up.board_type == 1150 || up.board_type == 1151 || up.board_type == 1152 || up.board_type == 1210 || up.board_type == 1351 || up.board_type == 1352 || up.board_type == 1411 || up.board_type == 1520) { //VR boards have no tone alarm if (up.board_type == 1140) CustomMessageBox.Show("Upload complete! Please unplug and reconnect board."); else CustomMessageBox.Show("Upload complete!"); } else { // wait for IO firmware upgrade and boot to a mavlink state CustomMessageBox.Show(Strings.PleaseWaitForTheMusicalTones); } return true; } } updateProgress(0, "ERROR: No Response from board"); return false; }
public void UploadPX4(string filename) { DateTime DEADLINE = DateTime.Now.AddSeconds(30); Uploader up; px4uploader.Firmware fw = px4uploader.Firmware.ProcessFirmware(filename); CustomMessageBox.Show("Press reset the board, and then press OK within 5 seconds.\nMission Planner will look for 30 seconds to find the board"); while (DateTime.Now < DEADLINE) { string port = MainV2.comPortName; Console.WriteLine(DateTime.Now.Millisecond + " Trying Port " + port); lbl_status.Text = "Connecting"; Application.DoEvents(); try { up = new Uploader(port, 115200); } catch (Exception ex) { //System.Threading.Thread.Sleep(50); Console.WriteLine(ex.Message); continue; } try { up.identify(); lbl_status.Text = "Identify"; Application.DoEvents(); Console.WriteLine("Found board type {0} boardrev {1} bl rev {2} fwmax {3} on {4}", up.board_type, up.board_rev, up.bl_rev, up.fw_maxsize, port); up.currentChecksum(fw); } catch (Exception) { Console.WriteLine("Not There.."); //Console.WriteLine(ex.Message); up.close(); continue; } try { up.ProgressEvent += new Uploader.ProgressEventHandler(up_ProgressEvent); up.LogEvent += new Uploader.LogEventHandler(up_LogEvent); progress.Value = 0; Application.DoEvents(); up.upload(fw); lbl_status.Text = "Done"; Application.DoEvents(); } catch (Exception ex) { lbl_status.Text = "ERROR: " + ex.Message; Application.DoEvents(); Console.WriteLine(ex.ToString()); } up.close(); break; } CustomMessageBox.Show("Please unplug, and plug back in your px4, before you try connecting"); }
/// <summary> /// upload to px4 standalone /// </summary> /// <param name="filename"></param> public bool UploadPX4(string filename) { Uploader up; updateProgress(0, "Reading Hex File"); px4uploader.Firmware fw; try { fw = px4uploader.Firmware.ProcessFirmware(filename); } catch (Exception ex) { CustomMessageBox.Show("Error loading firmware file\n\n" + ex.ToString(), "Error"); return false; } try { // check if we are seeing heartbeats MainV2.comPort.BaseStream.Open(); MainV2.comPort.giveComport = true; if (MainV2.comPort.getHeartBeat().Length > 0) { MainV2.comPort.doReboot(true); MainV2.comPort.Close(); } else { MainV2.comPort.BaseStream.Close(); CustomMessageBox.Show("Please unplug the board, and then press OK and plug back in.\nMission Planner will look for 30 seconds to find the board"); } } catch (Exception ex) { log.Error(ex); CustomMessageBox.Show("Please unplug the board, and then press OK and plug back in.\nMission Planner will look for 30 seconds to find the board"); } DateTime DEADLINE = DateTime.Now.AddSeconds(30); updateProgress(0, "Scanning comports"); while (DateTime.Now < DEADLINE) { string[] allports = SerialPort.GetPortNames(); foreach (string port in allports) { log.Info(DateTime.Now.Millisecond + " Trying Port " + port); updateProgress(-1, "Connecting"); try { up = new Uploader(port, 115200); } catch (Exception ex) { //System.Threading.Thread.Sleep(50); Console.WriteLine(ex.Message); continue; } try { up.identify(); updateProgress(-1, "Identify"); log.InfoFormat("Found board type {0} boardrev {1} bl rev {2} fwmax {3} on {4}", up.board_type, up.board_rev, up.bl_rev, up.fw_maxsize, port); } catch (Exception) { Console.WriteLine("Not There.."); //Console.WriteLine(ex.Message); up.close(); continue; } try { up.currentChecksum(fw); } catch { up.__reboot(); up.close(); CustomMessageBox.Show("No need to upload. already on the board"); return true; } try { up.ProgressEvent += new Uploader.ProgressEventHandler(up_ProgressEvent); up.LogEvent += new Uploader.LogEventHandler(up_LogEvent); updateProgress(0, "Upload"); up.upload(fw); updateProgress(100, "Upload Done"); } catch (Exception ex) { updateProgress(0, "ERROR: " + ex.Message); log.Info(ex); Console.WriteLine(ex.ToString()); return false; } finally { up.close(); } // wait for IO firmware upgrade and boot to a mavlink state CustomMessageBox.Show("Please wait for the musical tones to finish before clicking OK"); return true; } } updateProgress(0, "ERROR: No Responce from board"); return false; }
/// <summary> /// upload to px4 standalone /// </summary> /// <param name="filename"></param> public bool UploadPX4(string filename) { Uploader up; updateProgress(0, "Reading Hex File"); px4uploader.Firmware fw; try { fw = px4uploader.Firmware.ProcessFirmware(filename); } catch (Exception ex) { CustomMessageBox.Show(Strings.ErrorFirmwareFile + "\n\n" + ex.ToString(), Strings.ERROR); return false; } try { // check if we are seeing heartbeats MainV2.comPort.BaseStream.Open(); MainV2.comPort.giveComport = true; BoardDetect.boards board = BoardDetect.DetectBoard(MainV2.comPortName); if (MainV2.comPort.getHeartBeat().Length > 0) { MainV2.comPort.doReboot(true); MainV2.comPort.Close(); //specific action for VRBRAIN4 board that needs to be manually disconnected before uploading if (board == BoardDetect.boards.vrbrainv40) { CustomMessageBox.Show("VRBRAIN 4 detected. Please unplug the board then press OK and plug back in.\n"); } } else { MainV2.comPort.BaseStream.Close(); CustomMessageBox.Show("Please unplug the board, and then press OK and plug back in.\nMission Planner will look for 30 seconds to find the board"); } } catch (Exception ex) { log.Error(ex); CustomMessageBox.Show("Please unplug the board, and then press OK and plug back in.\nMission Planner will look for 30 seconds to find the board"); } DateTime DEADLINE = DateTime.Now.AddSeconds(30); updateProgress(0, "Scanning comports"); while (DateTime.Now < DEADLINE) { string[] allports = SerialPort.GetPortNames(); foreach (string port in allports) { log.Info(DateTime.Now.Millisecond + " Trying Port " + port); updateProgress(-1, "Connecting"); try { up = new Uploader(port, 115200); } catch (Exception ex) { //System.Threading.Thread.Sleep(50); Console.WriteLine(ex.Message); continue; } try { up.identify(); updateProgress(-1, "Identify"); log.InfoFormat("Found board type {0} boardrev {1} bl rev {2} fwmax {3} on {4}", up.board_type, up.board_rev, up.bl_rev, up.fw_maxsize, port); up.ProgressEvent += new Uploader.ProgressEventHandler(up_ProgressEvent); up.LogEvent += new Uploader.LogEventHandler(up_LogEvent); } catch (Exception) { Console.WriteLine("Not There.."); //Console.WriteLine(ex.Message); up.close(); continue; } // test if pausing here stops - System.TimeoutException: The write timed out. System.Threading.Thread.Sleep(500); try { up.verifyotp(); if (up.libre) { MissionPlanner.Utilities.Tracking.AddEvent("FWUpload", "verifyotp", "libre", ""); } else { MissionPlanner.Utilities.Tracking.AddEvent("FWUpload", "verifyotp", "Pass", ""); } } catch (Org.BouncyCastle.Security.InvalidKeyException ex) { MissionPlanner.Utilities.Tracking.AddEvent("FWUpload", "verifyotp","InvalidKeyException",""); log.Error(ex); CustomMessageBox.Show("You are using unsupported hardware.\nThis board does not contain a valid certificate of authenticity.\nPlease contact your hardware vendor about signing your hardware.", "Invalid Cert"); up.skipotp = true; } catch (FormatException ex) { MissionPlanner.Utilities.Tracking.AddEvent("FWUpload", "verifyotp", "FormatException", ""); log.Error(ex); CustomMessageBox.Show("You are using unsupported hardware.\nThis board does not contain a valid certificate of authenticity.\nPlease contact your hardware vendor about signing your hardware.", "Invalid Cert"); up.skipotp = true; } catch (IOException ex) { MissionPlanner.Utilities.Tracking.AddEvent("FWUpload", "verifyotp", "IOException", ""); log.Error(ex); CustomMessageBox.Show("lost communication with the board.", "lost comms"); up.close(); return false; } catch (TimeoutException ex) { MissionPlanner.Utilities.Tracking.AddEvent("FWUpload", "verifyotp", "TimeoutException", ""); log.Error(ex); CustomMessageBox.Show("lost communication with the board.", "lost comms"); up.close(); return false; } catch (Exception ex) { MissionPlanner.Utilities.Tracking.AddEvent("FWUpload", "verifyotp", "Exception", ""); log.Error(ex); CustomMessageBox.Show("lost communication with the board. " + ex.ToString(), "lost comms"); up.close(); return false; } try { up.currentChecksum(fw); } catch (IOException ex) { log.Error(ex); CustomMessageBox.Show("lost communication with the board.", "lost comms"); up.close(); return false; } catch { up.__reboot(); up.close(); CustomMessageBox.Show("No need to upload. already on the board"); return true; } try { updateProgress(0, "Upload"); up.upload(fw); updateProgress(100, "Upload Done"); } catch (Exception ex) { updateProgress(0, "ERROR: " + ex.Message); log.Info(ex); Console.WriteLine(ex.ToString()); return false; } finally { up.close(); } // wait for IO firmware upgrade and boot to a mavlink state CustomMessageBox.Show("Please wait for the musical tones to finish before clicking OK"); return true; } } updateProgress(0, "ERROR: No Response from board"); return false; }
/// <summary> /// upload to px4 standalone /// </summary> /// <param name="filename"></param> public bool UploadPX4(string filename) { DateTime DEADLINE = DateTime.Now.AddSeconds(30); Uploader up; px4uploader.Firmware fw = px4uploader.Firmware.ProcessFirmware(filename); CustomMessageBox.Show("Press reset the board, and then press OK within 5 seconds.\nMission Planner will look for 30 seconds to find the board"); while (DateTime.Now < DEADLINE) { string[] allports = SerialPort.GetPortNames(); foreach (string port in allports) { Console.WriteLine(DateTime.Now.Millisecond + " Trying Port " + port); updateProgress(-1, "Connecting"); try { up = new Uploader(port, 115200); } catch (Exception ex) { //System.Threading.Thread.Sleep(50); Console.WriteLine(ex.Message); continue; } try { up.identify(); updateProgress(-1, "Identify"); Console.WriteLine("Found board type {0} boardrev {1} bl rev {2} fwmax {3} on {4}", up.board_type, up.board_rev, up.bl_rev, up.fw_maxsize, port); up.currentChecksum(fw); } catch (Exception) { Console.WriteLine("Not There.."); //Console.WriteLine(ex.Message); up.close(); continue; } try { up.ProgressEvent += new Uploader.ProgressEventHandler(up_ProgressEvent); up.LogEvent += new Uploader.LogEventHandler(up_LogEvent); updateProgress(0, "Upload"); up.upload(fw); updateProgress(100, "Upload Done"); } catch (Exception ex) { updateProgress(0, "ERROR: " + ex.Message); Console.WriteLine(ex.ToString()); } up.close(); CustomMessageBox.Show("Please unplug, and plug back in your px4, before you try connecting"); return true; } } return false; }
public static bool Uploader(string fn) { Firmware fw; Uploader up; fw = Firmware.ProcessFirmware(fn); Console.WriteLine("Loaded firmware for {0},{1} waiting for the bootloader...", fw.board_id, fw.board_revision); while (true) { string[] ports = GetPortNames(); //ports = new string[] { "COM9"}; foreach (string port in ports) { if (!port.StartsWith("COM") && !port.Contains("APM") && !port.Contains("ACM") && !port.Contains("usb")) { continue; } Console.WriteLine(DateTime.Now.Millisecond + " Trying Port " + port); try { up = new Uploader(port, 115200); } catch (Exception ex) { //System.Threading.Thread.Sleep(50); Console.WriteLine(DateTime.Now.Millisecond + " " + ex.Message); continue; } try { up.identify(); Console.WriteLine("Found board type {0} boardrev {1} bl rev {2} fwmax {3} on {4}", up.board_type, up.board_rev, up.bl_rev, up.fw_maxsize, port); } catch (Exception) { try { //System.Threading.ThreadPool.QueueUserWorkItem(up.__mavlinkreboot); } catch { //up.close(); } Console.WriteLine(DateTime.Now.Millisecond + " " + "Not There.."); //Console.WriteLine(ex.Message); try { up.close(); } catch { } continue; } try { up.currentChecksum(fw); } catch (Exception ex) { Console.WriteLine("No need to upload. already on the board" + ex.ToString()); up.close(); return(true); } try { up.upload(fw); } catch (Exception ex) { Console.WriteLine(ex.ToString()); } up.close(); return(true); } } }
private void FWUpload(object?a) { try { Tuple <int, string> passin = (Tuple <int, string>)a; var index = passin.Item1; var portname = passin.Item2; var tryupload = true; lock (ports) if (ports.Contains(portname)) { tryupload = false; } if (tryupload) { var fw = Firmware.ProcessFirmware(_args[0]); Uploader up = null; try { up = new px4uploader.Uploader(new SerialPort(portname, 115200)); } catch { } if (up != null) { up.ProgressEvent += completed => { /* this.BeginInvoke(new Action(() => * { * textBox1.AppendText(portname + " " + (int)completed + "\r\n"); * }));*/ }; bool flashit = false; bool validcomms = false; try { up.identify(); validcomms = true; up.currentChecksum(fw); flashit = true; } catch (Exception ex) { AppendLine(ex.Message); } if (flashit) { this.BeginInvoke(new Action(() => { textBox1.AppendText(portname + " Flashing fw\r\n"); })); up.upload(fw); } else { this.BeginInvoke(new Action(() => { textBox1.AppendText(portname + " reboot\r\n"); })); up.__reboot(); } lock (ports) ports.Add(portname); up.close(); this.BeginInvoke(new Action(() => { textBox1.AppendText(portname + " Done fw\r\n"); })); if (validcomms) { return; } } } var mav = new MAVLinkInterface(); mav.BaseStream = new SerialPort((string)portname, 115200); var bldone = false; mav.OnPacketReceived += (sender, message) => { if (message.msgid == (ulong)MAVLink.MAVLINK_MSG_ID.STATUSTEXT) { if (ASCIIEncoding.ASCII.GetString(message.ToStructure <MAVLink.mavlink_statustext_t>().text).Trim().Contains("Bootloader up-to-date") || ASCIIEncoding.ASCII.GetString(message.ToStructure <MAVLink.mavlink_statustext_t>().text).Trim().Contains("Flash OK")) { bldone = true; } DisplayText(message); } }; try { mav.BaseStream.Open(); mav.getHeartBeat(); mav.doCommand(MAVLink.MAV_CMD.FLASH_BOOTLOADER, 0, 0, 0, 0, 290876, 0, 0, false); mav.getHeartBeat(); if (!bldone) { mav.getHeartBeat(); } if (!bldone) { mav.getHeartBeat(); } if (!bldone) { mav.getHeartBeat(); } if (!bldone) { mav.getHeartBeat(); } if (!bldone) { mav.getHeartBeat(); } if (!bldone) { mav.getHeartBeat(); } if (!bldone) { mav.getHeartBeat(); } if (!bldone) { mav.getHeartBeat(); } mav.Close(); this.BeginInvoke(new Action(() => { textBox1.AppendText(portname + " Done bl " + (bldone ? "OK" : "FAIL") + "\r\n"); })); } catch (Exception ex) { AppendLine(ex.Message); } } catch (Exception ex) { AppendLine(ex.Message); } }
/// <summary> /// upload to px4 standalone /// </summary> /// <param name="filename"></param> public bool UploadPX4(string filename) { Uploader up; updateProgress(0, "Reading Hex File"); px4uploader.Firmware fw = px4uploader.Firmware.ProcessFirmware(filename); try { // MainV2.comPort.BaseStream.Open(); // if (MainV2.comPort.BaseStream.IsOpen) { // MainV2.comPort.doReboot(true); // MainV2.comPort.Close(); } // else { CustomMessageBox.Show("Please unplug the board, and then press OK and plug back in.\nMission Planner will look for 30 seconds to find the board"); } } catch { // MainV2.comPort.Close(); } DateTime DEADLINE = DateTime.Now.AddSeconds(30); updateProgress(0, "Scanning comports"); while (DateTime.Now < DEADLINE) { string[] allports = SerialPort.GetPortNames(); foreach (string port in allports) { log.Info(DateTime.Now.Millisecond + " Trying Port " + port); updateProgress(-1, "Connecting"); try { up = new Uploader(port, 115200); } catch (Exception ex) { //System.Threading.Thread.Sleep(50); Console.WriteLine(ex.Message); continue; } try { up.identify(); updateProgress(-1, "Identify"); log.InfoFormat("Found board type {0} boardrev {1} bl rev {2} fwmax {3} on {4}", up.board_type, up.board_rev, up.bl_rev, up.fw_maxsize, port); } catch (Exception) { Console.WriteLine("Not There.."); //Console.WriteLine(ex.Message); up.close(); continue; } try { up.currentChecksum(fw); } catch { CustomMessageBox.Show("No need to upload. already on the board"); break; } try { up.ProgressEvent += new Uploader.ProgressEventHandler(up_ProgressEvent); up.LogEvent += new Uploader.LogEventHandler(up_LogEvent); updateProgress(0, "Upload"); up.upload(fw); updateProgress(100, "Upload Done"); } catch (Exception ex) { updateProgress(0, "ERROR: " + ex.Message); log.Info(ex); Console.WriteLine(ex.ToString()); } up.close(); CustomMessageBox.Show("Please unplug, and plug back in your px4, before you try connecting"); return true; } } updateProgress(0, "ERROR: No Responce from board"); return false; }
private void BUT_sn_Click(object sender, EventArgs e) { px4uploader.Uploader up; CustomMessageBox.Show("Please unplug press ok, and plug board in", "px4"); DateTime DEADLINE = DateTime.Now.AddSeconds(30); while (DateTime.Now < DEADLINE) { string[] allports = SerialPort.GetPortNames(); foreach (string port in allports) { Console.WriteLine(DateTime.Now.Millisecond + " Trying Port " + port); try { up = new Uploader(port, 115200); } catch (Exception ex) { //System.Threading.Thread.Sleep(50); Console.WriteLine(ex.Message); continue; } try { up.identify(); Console.WriteLine("Found board type {0} boardrev {1} bl rev {2} fwmax {3} on {4}", up.board_type, up.board_rev, up.bl_rev, up.fw_maxsize, port); byte[] sn = up.__get_sn(); StringBuilder sb = new StringBuilder(); Console.Write("SN: "); for (int s = 0; s < sn.Length; s += 1) { Console.Write(sn[s].ToString("X2")); sb.Append(sn[s].ToString("X2")); } txtboardsn.Text = sb.ToString(); up.close(); CustomMessageBox.Show("Done"); return; } catch (Exception) { Console.WriteLine("Not There.."); //Console.WriteLine(ex.Message); up.close(); continue; } } } }
public static bool Uploader(string fn) { Firmware fw; Uploader up; fw = Firmware.ProcessFirmware(fn); Console.WriteLine("Loaded firmware for {0},{1} waiting for the bootloader...", fw.board_id, fw.board_revision); while (true) { string[] ports = GetPortNames(); //ports = new string[] { "COM9"}; foreach (string port in ports) { if (!port.StartsWith("COM") && !port.Contains("APM") && !port.Contains("ACM") && !port.Contains("usb")) continue; Console.WriteLine(DateTime.Now.Millisecond + " Trying Port "+port); try { up = new Uploader(port, 115200); } catch ( Exception ex) { //System.Threading.Thread.Sleep(50); Console.WriteLine(DateTime.Now.Millisecond + " " +ex.Message); continue; } try { up.identify(); Console.WriteLine("Found board type {0} boardrev {1} bl rev {2} fwmax {3} on {4}", up.board_type, up.board_rev,up.bl_rev,up.fw_maxsize, port); } catch ( Exception) { try { //System.Threading.ThreadPool.QueueUserWorkItem(up.__mavlinkreboot); } catch { //up.close(); } Console.WriteLine(DateTime.Now.Millisecond + " " + "Not There.."); //Console.WriteLine(ex.Message); try { up.close(); } catch { } continue; } try { up.verifyotp(); } catch { up.close(); return false; } try { up.currentChecksum(fw); } catch (Exception ex) { Console.WriteLine("No need to upload. already on the board" + ex.ToString()); up.close(); return true; } try { up.upload(fw); } catch (Exception ex) { Console.WriteLine(ex.ToString()); } up.close(); return true; } } }
private void FWUpload(object a) { Tuple <int, string> passin = (Tuple <int, string>)a; var index = passin.Item1; var portname = passin.Item2; Console.WriteLine("Thread start for " + portname); try { if (!portstatus.ContainsKey(portname)) { portstatus[portname] = ""; } { Uploader up = null; try { up = new px4uploader.Uploader(new SerialPort(portname, 115200)); } catch { } if (up != null) { up.ProgressEvent += completed => { /* this.BeginInvoke(new Action(() => * { * textBox1.AppendText(portname + " " + (int)completed + "\r\n"); * }));*/ }; bool flashit = false; bool validcomms = false; Firmware fw = null; try { up.identify(); validcomms = true; portstatus[portname] += "BL "; UpdateTextBox(); fw = Firmware.ProcessFirmware(_args[0]); up.currentChecksum(fw); fw.board_id = up.board_type; flashit = true; portstatus[portname] += "CS "; UpdateTextBox(); } catch (Exception ex) { if (ex.Message.Contains("Same Firmware")) { portstatus[portname] += "BLUPD OK "; } else { portstatus[portname] += "BLEX "; } UpdateTextBox(); } if (flashit) { DateTime ts = DateTime.Now; up.ProgressEvent += completed => { if (ts.Second != DateTime.Now.Second) { Console.WriteLine("{0}: {1}", portname, completed); ts = DateTime.Now; } }; up.upload(fw); portstatus[portname] += "BLUPD OK "; UpdateTextBox(); } else { up.__reboot(); UpdateTextBox(); } up.close(); if (validcomms) { return; } } } var ports = getPortByVPidInt(txt_vid.Text, txt_pid.Text, txt_int.Text); if (!ports.Contains(portname)) { portstatus[portname] += "NOTML OK "; UpdateTextBox(); return; } var mav = new MAVLinkInterface(); mav.BaseStream = new SerialPort((string)portname, 115200); var bldone = false; mav.OnPacketReceived += (sender, message) => { if (message.msgid == (ulong)MAVLink.MAVLINK_MSG_ID.STATUSTEXT) { if (ASCIIEncoding.ASCII.GetString(message.ToStructure <MAVLink.mavlink_statustext_t>().text).Trim().Contains("Bootloader up-to-date") || ASCIIEncoding.ASCII.GetString(message.ToStructure <MAVLink.mavlink_statustext_t>().text).Trim().Contains("Flash OK")) { bldone = true; portstatus[portname] += ASCIIEncoding.ASCII .GetString(message.ToStructure <MAVLink.mavlink_statustext_t>().text).Trim() .TrimEnd(new char[] { '\0', '\r', '\n' }); UpdateTextBox(); } //DisplayText(message); } }; try { mav.BaseStream.Open(); mav.getHeartBeat(); mav.doCommand(MAVLink.MAV_CMD.FLASH_BOOTLOADER, 0, 0, 0, 0, 290876, 0, 0, false); mav.getHeartBeat(); if (!bldone) { mav.getHeartBeat(); } if (!bldone) { mav.getHeartBeat(); } if (!bldone) { mav.getHeartBeat(); } if (!bldone) { mav.getHeartBeat(); } if (!bldone) { mav.getHeartBeat(); } if (!bldone) { mav.getHeartBeat(); } if (!bldone) { mav.getHeartBeat(); } if (!bldone) { mav.getHeartBeat(); } mav.Close(); if (bldone) { portstatus[portname] += "MLBLUPD OK"; } UpdateTextBox(); } catch (Exception ex) { portstatus[portname] += "MLEX "; UpdateTextBox(); } } catch (Exception ex) { portstatus[portname] += "EX!! "; UpdateTextBox(); } UpdateTextBox(); }
protected override void WndProc(ref Message m) { switch (m.Msg) { case WM_CREATE: try { DEV_BROADCAST_DEVICEINTERFACE devBroadcastDeviceInterface = new DEV_BROADCAST_DEVICEINTERFACE(); IntPtr devBroadcastDeviceInterfaceBuffer; IntPtr deviceNotificationHandle = IntPtr.Zero; Int32 size = 0; // frmMy is the form that will receive device-change messages. size = Marshal.SizeOf(devBroadcastDeviceInterface); devBroadcastDeviceInterface.dbcc_size = size; devBroadcastDeviceInterface.dbcc_devicetype = DBT_DEVTYP_DEVICEINTERFACE; devBroadcastDeviceInterface.dbcc_reserved = 0; devBroadcastDeviceInterface.dbcc_classguid = GUID_DEVINTERFACE_USB_DEVICE.ToByteArray(); devBroadcastDeviceInterfaceBuffer = Marshal.AllocHGlobal(size); Marshal.StructureToPtr(devBroadcastDeviceInterface, devBroadcastDeviceInterfaceBuffer, true); deviceNotificationHandle = NativeMethods.RegisterDeviceNotification(this.Handle, devBroadcastDeviceInterfaceBuffer, DEVICE_NOTIFY_WINDOW_HANDLE); } catch { } break; case WM_DEVICECHANGE: // The WParam value identifies what is occurring. WM_DEVICECHANGE_enum n = (WM_DEVICECHANGE_enum)m.WParam; var l = m.LParam; if (n == WM_DEVICECHANGE_enum.DBT_DEVICEREMOVEPENDING) { Console.WriteLine("DBT_DEVICEREMOVEPENDING"); } if (n == WM_DEVICECHANGE_enum.DBT_DEVNODES_CHANGED) { Console.WriteLine("DBT_DEVNODES_CHANGED"); // DoScan(); } if (n == WM_DEVICECHANGE_enum.DBT_DEVICEARRIVAL) { Console.WriteLine(((WM_DEVICECHANGE_enum)n).ToString()); DEV_BROADCAST_HDR hdr = new DEV_BROADCAST_HDR(); Marshal.PtrToStructure(m.LParam, hdr); try { switch (hdr.dbch_devicetype) { case DBT_DEVTYP_DEVICEINTERFACE: DEV_BROADCAST_DEVICEINTERFACE inter = new DEV_BROADCAST_DEVICEINTERFACE(); Marshal.PtrToStructure(m.LParam, inter); var devname = GetDeviceName(inter); Console.WriteLine("Interface {0} {1}", inter.dbcc_name, devname); break; case DBT_DEVTYP_PORT: DEV_BROADCAST_PORT prt = new DEV_BROADCAST_PORT(); Marshal.PtrToStructure(m.LParam, prt); Console.WriteLine("port {0}", prt.dbcp_name); Uploader up = null; try { up = new px4uploader.Uploader(new SerialPort(prt.dbcp_name, 115200)); up.identify(); up.close(); } catch { } break; } } catch { } //string port = Marshal.PtrToStringAuto((IntPtr)((long)m.LParam + 12)); //Console.WriteLine("Added port {0}",port); } Console.WriteLine("Device Change {0} {1} {2}", m.Msg, (WM_DEVICECHANGE_enum)m.WParam, m.LParam); if (DeviceChanged != null) { try { DeviceChanged((WM_DEVICECHANGE_enum)m.WParam); } catch { } } break; default: //Console.WriteLine(m.ToString()); break; } base.WndProc(ref m); }