/// <summary> /// STK v2 generate packet /// </summary> /// <param name="serialPort"></param> /// <param name="message"></param> /// <returns></returns> static byte[] genstkv2packet(SerialPort serialPort, byte[] message) { byte[] data = new byte[300]; byte ck = 0; data[0] = 0x1b; ck ^= data[0]; data[1] = 0x1; ck ^= data[1]; data[2] = (byte)((message.Length >> 8) & 0xff); ck ^= data[2]; data[3] = (byte)(message.Length & 0xff); ck ^= data[3]; data[4] = 0xe; ck ^= data[4]; int a = 5; foreach (byte let in message) { data[a] = let; ck ^= let; a++; } data[a] = ck; a++; serialPort.Write(data, 0, a); //Console.WriteLine("about to read packet"); byte[] ret = BoardDetect.readpacket(serialPort); //if (ret[1] == 0x0) { //Console.WriteLine("received OK"); } return ret; }
/// <summary> /// Detects APM board version /// </summary> /// <param name="port"></param> /// <returns> (1280/2560/2560-2/px4/px4v2)</returns> public static boards DetectBoard(string port) { SerialPort serialPort = new SerialPort(); serialPort.PortName = port; if (!MainV2.MONO) { ObjectQuery query = new ObjectQuery("SELECT * FROM Win32_SerialPort"); // Win32_USBControllerDevice ManagementObjectSearcher searcher = new ManagementObjectSearcher(query); foreach (ManagementObject obj2 in searcher.Get()) { Console.WriteLine("PNPID: " + obj2.Properties["PNPDeviceID"].Value.ToString()); // check vid and pid if (obj2.Properties["PNPDeviceID"].Value.ToString().Contains(@"USB\VID_2341&PID_0010")) { // check port name as well if (obj2.Properties["Name"].Value.ToString().ToUpper().Contains(serialPort.PortName.ToUpper())) { log.Info("is a 2560-2"); return boards.b2560v2; } } if (obj2.Properties["PNPDeviceID"].Value.ToString().Contains(@"USB\VID_26AC&PID_0010")) { // check port name as well //if (obj2.Properties["Name"].Value.ToString().ToUpper().Contains(serialPort.PortName.ToUpper())) { log.Info("is a px4"); return boards.px4; } } if (obj2.Properties["PNPDeviceID"].Value.ToString().Contains(@"USB\VID_26AC&PID_0011")) { log.Info("is a px4v2"); return boards.px4v2; } if (obj2.Properties["PNPDeviceID"].Value.ToString().Contains(@"USB\VID_26AC&PID_0001")) { log.Info("is a px4v2 bootloader"); return boards.px4v2; } if (obj2.Properties["PNPDeviceID"].Value.ToString().Contains(@"USB\VID_26AC&PID_0016")) { log.Info("is a px4v2 bootloader"); CustomMessageBox.Show("You appear to have a bootloader with a bad PID value, please update your bootloader."); return boards.px4v2; } //|| obj2.Properties["PNPDeviceID"].Value.ToString().Contains(@"USB\VID_26AC&PID_0012") || obj2.Properties["PNPDeviceID"].Value.ToString().Contains(@"USB\VID_26AC&PID_0013") || obj2.Properties["PNPDeviceID"].Value.ToString().Contains(@"USB\VID_26AC&PID_0014") || obj2.Properties["PNPDeviceID"].Value.ToString().Contains(@"USB\VID_26AC&PID_0015") || obj2.Properties["PNPDeviceID"].Value.ToString().Contains(@"USB\VID_26AC&PID_0016") } } else { // if its mono if (DialogResult.Yes == CustomMessageBox.Show("Is this a APM 2+?", "APM 2+", MessageBoxButtons.YesNo)) { return boards.b2560v2; } else { if (DialogResult.Yes == CustomMessageBox.Show("Is this a PX4/PIXHAWK?", "PX4/PIXHAWK", MessageBoxButtons.YesNo)) { if (DialogResult.Yes == CustomMessageBox.Show("Is this a PIXHAWK?", "PIXHAWK", MessageBoxButtons.YesNo)) { return boards.px4v2; } return boards.px4; } else { return boards.b2560; } } } if (serialPort.IsOpen) serialPort.Close(); serialPort.DtrEnable = true; serialPort.BaudRate = 57600; serialPort.Open(); Thread.Sleep(100); int a = 0; while (a < 20) // 20 * 50 = 1 sec { //Console.WriteLine("write " + DateTime.Now.Millisecond); serialPort.DiscardInBuffer(); serialPort.Write(new byte[] { (byte)'0', (byte)' ' }, 0, 2); a++; Thread.Sleep(50); //Console.WriteLine("btr {0}", serialPort.BytesToRead); if (serialPort.BytesToRead >= 2) { byte b1 = (byte)serialPort.ReadByte(); byte b2 = (byte)serialPort.ReadByte(); if (b1 == 0x14 && b2 == 0x10) { serialPort.Close(); log.Info("is a 1280"); return boards.b1280; } } } serialPort.Close(); log.Warn("Not a 1280"); Thread.Sleep(500); serialPort.DtrEnable = true; serialPort.BaudRate = 115200; serialPort.Open(); Thread.Sleep(100); a = 0; while (a < 4) { byte[] temp = new byte[] { 0x6, 0, 0, 0, 0 }; temp = BoardDetect.genstkv2packet(serialPort, temp); a++; Thread.Sleep(50); try { if (temp[0] == 6 && temp[1] == 0 && temp.Length == 2) { serialPort.Close(); //HKEY_LOCAL_MACHINE\SYSTEM\CurrentControlSet\Enum\USB\VID_2341&PID_0010\640333439373519060F0\Device Parameters if (!MainV2.MONO && !Thread.CurrentThread.CurrentCulture.IsChildOf(CultureInfoEx.GetCultureInfo("zh-Hans"))) { ObjectQuery query = new ObjectQuery("SELECT * FROM Win32_SerialPort"); // Win32_USBControllerDevice ManagementObjectSearcher searcher = new ManagementObjectSearcher(query); foreach (ManagementObject obj2 in searcher.Get()) { //Console.WriteLine("Dependant : " + obj2["Dependent"]); // all apm 1-1.4 use a ftdi on the imu board. /* obj2.Properties.ForEach(x => { try { log.Info(((PropertyData)x).Name.ToString() + " = " + ((PropertyData)x).Value.ToString()); } catch { } }); */ // check vid and pid if (obj2.Properties["PNPDeviceID"].Value.ToString().Contains(@"USB\VID_2341&PID_0010")) { // check port name as well if (obj2.Properties["Name"].Value.ToString().ToUpper().Contains(serialPort.PortName.ToUpper())) { log.Info("is a 2560-2"); return boards.b2560v2; } } } log.Info("is a 2560"); return boards.b2560; } } } catch { } } serialPort.Close(); log.Warn("Not a 2560"); if (DialogResult.Yes == CustomMessageBox.Show("Is this a APM 2+?", "APM 2+", MessageBoxButtons.YesNo)) { return boards.b2560v2; } else { if (DialogResult.Yes == CustomMessageBox.Show("Is this a PX4/PIXHAWK?", "PX4/PIXHAWK", MessageBoxButtons.YesNo)) { if (DialogResult.Yes == CustomMessageBox.Show("Is this a PIXHAWK?", "PIXHAWK", MessageBoxButtons.YesNo)) { return boards.px4v2; } return boards.px4; } else { return boards.b2560; } } }
private void UploadFW(bool custom = false) { ICommsSerial comPort = new SerialPort(); var uploader = new Uploader(); if (MainV2.comPort.BaseStream.IsOpen) { try { getTelemPortWithRadio(ref comPort); uploader.PROG_MULTI_MAX = 64; } catch (Exception ex) { CustomMessageBox.Show("Error " + ex); } } try { comPort.PortName = MainV2.comPort.BaseStream.PortName; comPort.BaudRate = 115200; comPort.Open(); } catch { CustomMessageBox.Show("Invalid ComPort or in use"); return; } // prep what we are going to upload var iHex = new IHex(); iHex.LogEvent += iHex_LogEvent; iHex.ProgressEvent += iHex_ProgressEvent; var bootloadermode = false; // attempt bootloader mode try { if (upload_xmodem(comPort)) { comPort.Close(); return; } comPort.BaudRate = 115200; uploader_ProgressEvent(0); uploader_LogEvent("Trying Bootloader Mode"); uploader.port = comPort; uploader.connect_and_sync(); uploader.ProgressEvent += uploader_ProgressEvent; uploader.LogEvent += uploader_LogEvent; uploader_LogEvent("In Bootloader Mode"); bootloadermode = true; } catch (Exception ex1) { log.Error(ex1); // cleanup bootloader mode fail, and try firmware mode comPort.Close(); if (MainV2.comPort.BaseStream.IsOpen) { // default baud... guess comPort.BaudRate = 57600; } else { comPort.BaudRate = MainV2.comPort.BaseStream.BaudRate; } try { comPort.Open(); } catch { CustomMessageBox.Show("Error opening port", "Error"); return; } uploader.ProgressEvent += uploader_ProgressEvent; uploader.LogEvent += uploader_LogEvent; uploader_LogEvent("Trying Firmware Mode"); bootloadermode = false; } // check for either already bootloadermode, or if we can do a ATI to ID the firmware if (bootloadermode || doConnect(comPort)) { // put into bootloader mode/update mode if (!bootloadermode) { try { comPort.Write("AT&UPDATE\r\n"); var left = comPort.ReadExisting(); log.Info(left); Sleep(700); comPort.BaudRate = 115200; } catch { } if (upload_xmodem(comPort)) { comPort.Close(); return; } comPort.BaudRate = 115200; } try { // force sync after changing baudrate uploader.connect_and_sync(); } catch { CustomMessageBox.Show("Failed to sync with Radio"); goto exit; } var device = Uploader.Board.FAILED; var freq = Uploader.Frequency.FAILED; // get the device type and frequency in the bootloader uploader.getDevice(ref device, ref freq); // get firmware for this device if (getFirmware(device, custom)) { // load the hex try { iHex.load(firmwarefile); } catch { CustomMessageBox.Show("Bad Firmware File"); goto exit; } // upload the hex and verify try { uploader.upload(comPort, iHex); } catch (Exception ex) { CustomMessageBox.Show("Upload Failed " + ex.Message); } } else { CustomMessageBox.Show("Failed to download new firmware"); } } else { CustomMessageBox.Show("Failed to identify Radio"); } exit: if (comPort.IsOpen) comPort.Close(); }
private static void Main(string[] args) { ExtractPacketAddresses("ublox 6mdata.raw", "Addrneo6m.txt", 0x1420, 0x26ddf4); ExtractPacketAddresses("6mdata.raw", "Addrneo6m-2.txt", 0x1420, 0x26ddf4); ExtractPacketAddresses("datalea6h.raw", "Addrlea6h.txt", 0x3e4c, 0x8546dc); ExtractPacketAddresses("datalea6h-nu602.raw", "Addrlea6hnu602.txt", 0x3e4c, 0x8546dc); ExtractPacketAddresses("dataneo7n.raw", "Addrneo7n.txt", 0x20001188, 0x862f0c); ExtractPacketAddresses("UBX_M8_301_HPG_111_REFERENCE_NEOM8P2.b45d5e63c7aa261bd58dfbcbc22bad68.bin", "Addrm8p.txt", 0, 0x6df34, true); ExtractPacketAddresses("UBX_M8_301_HPG_111_REFERENCE_NEOM8P2.b45d5e63c7aa261bd58dfbcbc22bad68.bin", "Addrm8p22.txt", 0, 0x6e308, true); ExtractPacketAddresses("EXT_G60_LEA-6H.fd1146bafac24b1347701312d42bb698.bin", "Addrlea6h-2.txt", 0, 0x546dc); ExtractPacketAddresses("FW101_EXT_TITLIS.42ec35ce38d201fd723f2c8b49b6a537.bin", "Addr7.txt", 0, 0x62f0c); ExtractPacketAddresses("UBLOX_M8_201.89cc4f1cd4312a0ac1b56c790f7c1622.bin", "Addr8_201.txt", 0, 0x739e8); ExtractPacketAddresses("UBX_M8_301_SPG.911f2b77b649eb90f4be14ce56717b49.bin", "Addr8_301.txt", 0, 0x7904c, true); ExtractPacketAddresses("UBX_M8_301_HPG_100_REFERENCE.dd38fd00c1d64d05d5b458d8a8fa4b41.bin", "Addrm8p_301_100.txt", 0, 0x6805c, true); ExtractPacketAddresses("UBX_M8_301_HPG_100_REFERENCE.dd38fd00c1d64d05d5b458d8a8fa4b41.bin", "Addrm8p_301_100-2.txt", 0, 0x68394, true); ExtractPacketAddresses("UBX_M8_301_HPG_130_REFERENCE_NEOM8P2.59a07babb501ba6a89ff87cac2f2765f.bin", "Addrm8p_301_130-2.txt", 0, 0x718a8, true); ExtractPacketAddresses("UBX_M8_301_HPG_130_REFERENCE_NEOM8P2.59a07babb501ba6a89ff87cac2f2765f.bin", "Addrm8p_301_130-2a.txt", 0, 0x71ca0, true); ExtractPacketAddresses("DO_EXT_301_HPG_140_REFERENCE.ab799cc302b64f28ba73b55dfa945a04.bin", "Addrm8p_301_140.txt", 0x73980, 0x73980, true); //0005bd16 // 5bd1a from 20 B1 == 00 bf var fileBytes = File.ReadAllBytes("DO_EXT_301_HPG_140_REFERENCE.ab799cc302b64f28ba73b55dfa945a04.bin"); var binreader = new BinaryReader(new MemoryStream(fileBytes)); string[] desc = { "UBX8", "?", "-1", "fwbase ","fwstart", "fwend", "-1", "-1", "0", "-1", "?", "?" }; for (int a = 0; a < 12; a++) { var item = binreader.ReadInt32(); Console.WriteLine("{1}\t0x{0:X} = {0}", item, desc[a]); } /* * 0.0 - Verifying image * * 0.0 Image (file size 502984) for u-blox8 accepted * * 0.0 Image Ver '3.01 (db0c89)' * 0.0 - CRC= 0x90A97896 0xEE9EBE1E * 0.0 - Trying to open port STDIO * * undefined4 __fastcall dochecksum(int *param_1,uint param_2) * * { * int *piVar1; * int iVar2; * int iVar3; * uint uVar4; * * uVar4 = param_2 >> 2; * iVar2 = 0; * iVar3 = 0; * piVar1 = param_1; * while (uVar4 != 0) { * iVar2 = iVar2 + *piVar1; * piVar1 = piVar1 + 1; * iVar3 = iVar3 + iVar2; * uVar4 = uVar4 - 1; * } * if ((iVar2 == *(int *)((int)param_1 + (param_2 & 0xfffffffc))) && * (iVar3 == *(int *)((int)param_1 + (param_2 & 0xfffffffc) + 4))) { * return 1; * } * return 0; * } * */ // should == 502972 or 502976 000000000007ACBC 000000000001EB2F binreader.BaseStream.Seek(4, SeekOrigin.Begin); var ivar2 = 0; var ivar3 = 0; while (binreader.BaseStream.Position < binreader.BaseStream.Length - 8) { var b = binreader.ReadInt32(); ivar2 = ivar2 + b; ivar3 = ivar3 + ivar2; } var crc1 = binreader.ReadInt32(); var crc2 = binreader.ReadInt32(); if (ivar2 == crc1 && ivar3 == crc2) { Console.WriteLine("CRC passes"); } else { Console.WriteLine("CRC fails should be 0x{0:X8} 0x{1:X8} currently {2:X8} {3:X8}", ivar2, ivar3, crc1, crc2); } Console.ReadLine(); return; ICommsSerial port;// = /*new TcpSerial();*/ //new SerialPort("com35" ,115200); port = new MissionPlanner.Comms.SerialPort(); port.PortName = "com5"; port.BaudRate = 115200; // mp internal pass //port.PortName = "127.0.0.1"; //port.BaudRate = 500; port.ReadBufferSize = 1024 * 1024; port.Open(); /* * * ????? * 0x00800000 0x80000 flash * 0x20000000 0x20000 ram * 0x20080000 0x20000 ram * 0x00200000 0x8000 rom * * For ublox6 ROM7.03 use: * * to enable RXM-RAW - addr 000016c8 * b5 62 09 01 10 00 c8 16 00 00 00 00 00 00 97 69 21 00 00 00 02 10 2b 22 * * * to enable RXM-SFRB - addr 0000190c * b5 62 09 01 10 00 0c 19 00 00 00 00 00 00 83 69 21 00 00 00 02 11 5f f0 * */ var rxmraw6m = new downloadreq(); rxmraw6m.clas = 0x9; rxmraw6m.subclass = 0x1; rxmraw6m.length = 0x10; rxmraw6m.flags = 0; rxmraw6m.startaddr = 0x16c8; rxmraw6m.data = new byte[] { 0x97, 0x69, 0x21, 0x00, 0x00, 0x00, 0x02, 0x10 }; var rxmsfrb6m = new downloadreq(); rxmsfrb6m.clas = 0x9; rxmsfrb6m.subclass = 0x1; rxmsfrb6m.length = 0x10; rxmsfrb6m.flags = 0; rxmsfrb6m.startaddr = 0x190c; rxmsfrb6m.data = new byte[] { 0x83, 0x69, 0x21, 0x00, 0x00, 0x00, 0x02, 0x11 }; var rxmraw6h = new downloadreq(); rxmraw6h.clas = 0x9; rxmraw6h.subclass = 0x1; rxmraw6h.length = 0x10; rxmraw6h.flags = 0; rxmraw6h.startaddr = 0x40F4; rxmraw6h.data = new byte[] { 0xe7, 0xb9, 0x81, 0x00, 0x00, 0x00, 0x02, 0x10 }; var rxmsfrb6h = new downloadreq(); rxmsfrb6h.clas = 0x9; rxmsfrb6h.subclass = 0x1; rxmsfrb6h.length = 0x10; rxmsfrb6h.flags = 0; rxmsfrb6h.startaddr = 0x4360; rxmsfrb6h.data = new byte[] { 0xd3, 0xb9, 0x81, 0x00, 0x00, 0x00, 0x02, 0x11 }; byte[] turnonbytes = { 0, 1, 0, 0, 0, 0, 0, 0 }; byte[] header = { 0xb5, 0x62 }; /* * Load FW binary 'C:\Users\hog\Downloads\NL602-patched-fw (1).bin' * Binary check success, G60 image valid. * Version: 7.03 (45970) Mar 17 2011 16:26:24 * FLASH Base: 0x800000 * FW Base: 0x800000 * FW Start: 0x800048 * FW End: 0x860AD4 * FW Size: 0x60ADC * * Identifying Flash * Flash: ManID=0x90, DevID=0x90 * * firmware: 0x200000 */ //turnon(port, header, 2, 0x20); //turnon(port, header, 2, 0x12); //turnon(port, header, 2, 0x23); //turnon(port, header, 2, 0x24); //turnon(port, header, 2, 0x51); //turnon(port, header, 2, 0x52); // turnon(port.BaseStream, header, 3, 0xA); // turnon(port.BaseStream, header, 3, 0xF); //writepacket(port.BaseStream, header, rxmraw); //writepacket(port.BaseStream, header, rxmsfrb); //writepacket(port.BaseStream, header, rxmraw6h); //writepacket(port.BaseStream, header, rxmsfrb6h); //writepacket(port.BaseStream, header, rxmraw6m); //writepacket(port.BaseStream, header, rxmsfrb6m); //return; //turnon(port.BaseStream, header, 2, 0x10); //turnon(port.BaseStream, header, 2, 0x11); //testmsg.startaddr += 8; //testmsg.data = turnonbytes; //writepacket(port.BaseStream, header, testmsg); /* * System.Threading.Thread.Sleep(200); * * while (port.IsOpen) * { * * while (port.BytesToRead > 0) * { * byte data = (byte)port.ReadByte(); * * // Console.Write("{0,2:x}",data); * * processbyte(data); * } * * } * * port.Close(); * * // Console.ReadLine(); * * return; */ // safeboot var buf = new byte[] { 0xB5, 0x62, 0x09, 0x07, 0x00, 0x00, 0x10, 0x39 }; buf = new byte[] { 0xB5, 0x62, 0x09, 0x07, 0x01, 0x00, 0x01, 0x12, 0x4D }; //port.Write(buf, 0, buf.Length); //port.Close(); //Thread.Sleep(1000); //port.Open(); // dump rom/memory req = new uploadreq(); req.clas = 0x9; req.subclass = 0x2; req.length = 12; req.startaddr = 0x800001; req.datasize = 128; req.flags = 0; var deadline = DateTime.MinValue; uint lastaddr = 0; while (port.IsOpen) { // determine when to send a new/next request if (deadline < DateTime.Now || lastaddr != req.startaddr) { var datastruct = StaticUtils.StructureToByteArray(req); var checksum = ubx_checksum(datastruct, datastruct.Length); port.Write(header, 0, header.Length); port.Write(datastruct, 0, datastruct.Length); port.Write(checksum, 0, checksum.Length); deadline = DateTime.Now.AddMilliseconds(200); lastaddr = req.startaddr; } Thread.Sleep(0); while (port.BytesToRead > 0) { var data = (byte)port.ReadByte(); // Console.Write("{0,2:x}",data); processbyte(data); } } }
/// <summary> /// detects STK version 1 or 2 /// </summary> /// <param name="port">comportname</param> /// <returns>string either (1280/2560) or "" for none</returns> public static string DetectVersion(string port) { SerialPort serialPort = new SerialPort(); serialPort.PortName = port; if (serialPort.IsOpen) serialPort.Close(); serialPort.DtrEnable = true; serialPort.BaudRate = 57600; serialPort.Open(); serialPort.toggleDTR(); Thread.Sleep(100); int a = 0; while (a < 20) // 20 * 50 = 1 sec { //Console.WriteLine("write " + DateTime.Now.Millisecond); serialPort.DiscardInBuffer(); serialPort.Write(new byte[] { (byte)'0', (byte)' ' }, 0, 2); a++; Thread.Sleep(50); //Console.WriteLine("btr {0}", serialPort.BytesToRead); if (serialPort.BytesToRead >= 2) { byte b1 = (byte)serialPort.ReadByte(); byte b2 = (byte)serialPort.ReadByte(); if (b1 == 0x14 && b2 == 0x10) { serialPort.Close(); log.Info("is a 1280"); return "1280"; } } } serialPort.Close(); log.Warn("Not a 1280"); Thread.Sleep(500); serialPort.DtrEnable = true; serialPort.BaudRate = 115200; serialPort.Open(); serialPort.toggleDTR(); Thread.Sleep(100); a = 0; while (a < 4) { byte[] temp = new byte[] { 0x6, 0, 0, 0, 0 }; temp = ArduinoDetect.genstkv2packet(serialPort, temp); a++; Thread.Sleep(50); try { if (temp[0] == 6 && temp[1] == 0 && temp.Length == 2) { serialPort.Close(); log.Info("is a 2560"); return "2560"; } } catch { } } serialPort.Close(); log.Warn("Not a 2560"); return ""; }
private static void Main(string[] args) { ExtractPacketAddresses("ublox 6mdata.raw", "Addrneo6m.txt", 0x1420, 0x26ddf4); ExtractPacketAddresses("6mdata.raw", "Addrneo6m-2.txt", 0x1420, 0x26ddf4); ExtractPacketAddresses("datalea6h.raw", "Addrlea6h.txt", 0x3e4c, 0x8546dc); ExtractPacketAddresses("datalea6h-nu602.raw", "Addrlea6hnu602.txt", 0x3e4c, 0x8546dc); ExtractPacketAddresses("dataneo7n.raw", "Addrneo7n.txt", 0x20001188, 0x862f0c); ExtractPacketAddresses("UBX_M8_301_HPG_111_REFERENCE_NEOM8P2.b45d5e63c7aa261bd58dfbcbc22bad68.bin", "Addrm8p.txt", 0, 0x6df34, true); ExtractPacketAddresses("UBX_M8_301_HPG_111_REFERENCE_NEOM8P2.b45d5e63c7aa261bd58dfbcbc22bad68.bin", "Addrm8p22.txt", 0, 0x6e308, true); ExtractPacketAddresses("EXT_G60_LEA-6H.fd1146bafac24b1347701312d42bb698.bin", "Addrlea6h-2.txt", 0, 0x546dc); ExtractPacketAddresses("FW101_EXT_TITLIS.42ec35ce38d201fd723f2c8b49b6a537.bin", "Addr7.txt", 0, 0x62f0c); ExtractPacketAddresses("UBLOX_M8_201.89cc4f1cd4312a0ac1b56c790f7c1622.bin", "Addr8_201.txt", 0, 0x739e8); ExtractPacketAddresses("UBX_M8_301_SPG.911f2b77b649eb90f4be14ce56717b49.bin", "Addr8_301.txt", 0, 0x7904c, true); ExtractPacketAddresses("UBX_M8_301_HPG_100_REFERENCE.dd38fd00c1d64d05d5b458d8a8fa4b41.bin", "Addrm8p_301_100.txt", 0, 0x6805c, true); ExtractPacketAddresses("UBX_M8_301_HPG_100_REFERENCE.dd38fd00c1d64d05d5b458d8a8fa4b41.bin", "Addrm8p_301_100-2.txt", 0, 0x68394, true); ExtractPacketAddresses("UBX_M8_301_HPG_130_REFERENCE_NEOM8P2.59a07babb501ba6a89ff87cac2f2765f.bin", "Addrm8p_301_130-2.txt", 0, 0x718a8, true); ExtractPacketAddresses("UBX_M8_301_HPG_130_REFERENCE_NEOM8P2.59a07babb501ba6a89ff87cac2f2765f.bin", "Addrm8p_301_130-2a.txt", 0, 0x71ca0, true); return; ICommsSerial port;// = /*new TcpSerial();*/ //new SerialPort("com35" ,115200); port = new MissionPlanner.Comms.SerialPort(); port.PortName = "com5"; port.BaudRate = 115200; // mp internal pass //port.PortName = "127.0.0.1"; //port.BaudRate = 500; port.ReadBufferSize = 1024 * 1024; port.Open(); /* * * ????? * 0x00800000 0x80000 flash * 0x20000000 0x20000 ram * 0x20080000 0x20000 ram * 0x00200000 0x8000 rom * * For ublox6 ROM7.03 use: * * to enable RXM-RAW - addr 000016c8 * b5 62 09 01 10 00 c8 16 00 00 00 00 00 00 97 69 21 00 00 00 02 10 2b 22 * * * to enable RXM-SFRB - addr 0000190c * b5 62 09 01 10 00 0c 19 00 00 00 00 00 00 83 69 21 00 00 00 02 11 5f f0 * */ var rxmraw6m = new downloadreq(); rxmraw6m.clas = 0x9; rxmraw6m.subclass = 0x1; rxmraw6m.length = 0x10; rxmraw6m.flags = 0; rxmraw6m.startaddr = 0x16c8; rxmraw6m.data = new byte[] { 0x97, 0x69, 0x21, 0x00, 0x00, 0x00, 0x02, 0x10 }; var rxmsfrb6m = new downloadreq(); rxmsfrb6m.clas = 0x9; rxmsfrb6m.subclass = 0x1; rxmsfrb6m.length = 0x10; rxmsfrb6m.flags = 0; rxmsfrb6m.startaddr = 0x190c; rxmsfrb6m.data = new byte[] { 0x83, 0x69, 0x21, 0x00, 0x00, 0x00, 0x02, 0x11 }; var rxmraw6h = new downloadreq(); rxmraw6h.clas = 0x9; rxmraw6h.subclass = 0x1; rxmraw6h.length = 0x10; rxmraw6h.flags = 0; rxmraw6h.startaddr = 0x40F4; rxmraw6h.data = new byte[] { 0xe7, 0xb9, 0x81, 0x00, 0x00, 0x00, 0x02, 0x10 }; var rxmsfrb6h = new downloadreq(); rxmsfrb6h.clas = 0x9; rxmsfrb6h.subclass = 0x1; rxmsfrb6h.length = 0x10; rxmsfrb6h.flags = 0; rxmsfrb6h.startaddr = 0x4360; rxmsfrb6h.data = new byte[] { 0xd3, 0xb9, 0x81, 0x00, 0x00, 0x00, 0x02, 0x11 }; byte[] turnonbytes = { 0, 1, 0, 0, 0, 0, 0, 0 }; byte[] header = { 0xb5, 0x62 }; /* * Load FW binary 'C:\Users\hog\Downloads\NL602-patched-fw (1).bin' * Binary check success, G60 image valid. * Version: 7.03 (45970) Mar 17 2011 16:26:24 * FLASH Base: 0x800000 * FW Base: 0x800000 * FW Start: 0x800048 * FW End: 0x860AD4 * FW Size: 0x60ADC * * Identifying Flash * Flash: ManID=0x90, DevID=0x90 * * firmware: 0x200000 */ //turnon(port, header, 2, 0x20); //turnon(port, header, 2, 0x12); //turnon(port, header, 2, 0x23); //turnon(port, header, 2, 0x24); //turnon(port, header, 2, 0x51); //turnon(port, header, 2, 0x52); // turnon(port.BaseStream, header, 3, 0xA); // turnon(port.BaseStream, header, 3, 0xF); //writepacket(port.BaseStream, header, rxmraw); //writepacket(port.BaseStream, header, rxmsfrb); //writepacket(port.BaseStream, header, rxmraw6h); //writepacket(port.BaseStream, header, rxmsfrb6h); //writepacket(port.BaseStream, header, rxmraw6m); //writepacket(port.BaseStream, header, rxmsfrb6m); //return; //turnon(port.BaseStream, header, 2, 0x10); //turnon(port.BaseStream, header, 2, 0x11); //testmsg.startaddr += 8; //testmsg.data = turnonbytes; //writepacket(port.BaseStream, header, testmsg); /* * System.Threading.Thread.Sleep(200); * * while (port.IsOpen) * { * * while (port.BytesToRead > 0) * { * byte data = (byte)port.ReadByte(); * * // Console.Write("{0,2:x}",data); * * processbyte(data); * } * * } * * port.Close(); * * // Console.ReadLine(); * * return; */ // safeboot var buf = new byte[] { 0xB5, 0x62, 0x09, 0x07, 0x00, 0x00, 0x10, 0x39 }; buf = new byte[] { 0xB5, 0x62, 0x09, 0x07, 0x01, 0x00, 0x01, 0x12, 0x4D }; //port.Write(buf, 0, buf.Length); //port.Close(); //Thread.Sleep(1000); //port.Open(); // dump rom/memory req = new uploadreq(); req.clas = 0x9; req.subclass = 0x2; req.length = 12; req.startaddr = 0x800001; req.datasize = 128; req.flags = 0; var deadline = DateTime.MinValue; uint lastaddr = 0; while (port.IsOpen) { // determine when to send a new/next request if (deadline < DateTime.Now || lastaddr != req.startaddr) { var datastruct = StaticUtils.StructureToByteArray(req); var checksum = ubx_checksum(datastruct, datastruct.Length); port.Write(header, 0, header.Length); port.Write(datastruct, 0, datastruct.Length); port.Write(checksum, 0, checksum.Length); deadline = DateTime.Now.AddMilliseconds(200); lastaddr = req.startaddr; } Thread.Sleep(0); while (port.BytesToRead > 0) { var data = (byte)port.ReadByte(); // Console.Write("{0,2:x}",data); processbyte(data); } } }