Beispiel #1
1
        /// <summary>
        /// upload to Parrot boards
        /// </summary>
        /// <param name="filename"></param>
        public bool UploadParrot(string filename, BoardDetect.boards board)
        {
            string vehicleName = board.ToString().Substring(0, 1).ToUpper() + board.ToString().Substring(1).ToLower();
            Ping ping = new Ping();
            PingReply pingReply = pingParrotVehicle(ping);

            updateProgress(0, "Trying to connect to " + vehicleName);

            if (pingReply == null || pingReply.Status != IPStatus.Success)
            {
                bool ssidFound = isParrotWifiConnected(vehicleName);

                if (!ssidFound)
                {
                    CustomMessageBox.Show("Please connect to " + vehicleName + " Wifi now and after that press OK", vehicleName, MessageBoxButtons.OK);
                    ssidFound = isParrotWifiConnected(vehicleName);
                    pingReply = pingParrotVehicle(ping);
                }

                while (pingReply == null || pingReply.Status != IPStatus.Success)
                {
                    if (!ssidFound)
                    {
                        if (CustomMessageBox.Show("You don't seem connected to " + vehicleName + " Wifi. Please connect to it and press OK to try again", vehicleName, MessageBoxButtons.OKCancel) == DialogResult.Cancel)
                        {
                            return false;
                        }
                    }
                    else if (CustomMessageBox.Show("You seem connected to " + vehicleName + " Wifi but it didn't answer our request. Do you want to try again?", vehicleName, MessageBoxButtons.OKCancel) == DialogResult.Cancel)
                    {
                        return false;
                    }

                    ssidFound = isParrotWifiConnected(vehicleName);
                    pingReply = pingParrotVehicle(ping);
                }
            }

            try
            {
                AdbServer.Instance.StartServer("adb.exe", true);
                IAdbClient adbClient = AdbClient.Instance;

                string response = adbClient.Connect(new DnsEndPoint("192.168.42.1", 9050));

                if (!response.Contains("connected to 192.168.42.1:9050"))
                {
                    string ntimes = "four";

                    if (board == BoardDetect.boards.disco)
                    {
                        ntimes = "two";
                    }

                    CustomMessageBox.Show("Please press " + vehicleName + " Power button " + ntimes + " times", vehicleName, MessageBoxButtons.OK);
                    response = adbClient.Connect(new DnsEndPoint("192.168.42.1", 9050));

                    while (!response.Contains("connected to 192.168.42.1:9050"))
                    {
                        if (CustomMessageBox.Show("Couldn't contact " + vehicleName + ". Press the Power button " + ntimes + " times. Do you want to try to connect again?", vehicleName, MessageBoxButtons.OKCancel) == DialogResult.Cancel)
                        {
                            return false;
                        }

                        response = adbClient.Connect(new DnsEndPoint("192.168.42.1", 9050));
                    }
                }

                DeviceData device = adbClient.GetDevices().First();
                ConsoleOutputReceiver consoleOut = new ConsoleOutputReceiver();

                try
                {
                    using (SyncService service = new SyncService(device))
                    {
                        using (FileStream stream = File.OpenRead(filename))
                        {
                            updateProgress(10, "Uploading software...");
                            service.Push(stream, "/data/ftp/internal_000/APM/" + (board == BoardDetect.boards.disco ? "apm-plane-disco" : "arducopter"), 777, DateTime.Now, CancellationToken.None);
                            updateProgress(50, "Software uploaded");
                        }

                        if (board != BoardDetect.boards.disco)
                        {
                            using (MemoryStream stream = new MemoryStream())
                            using (StreamReader sr = new StreamReader(stream))
                            {
                                updateProgress(60, "Looking for need to update init scripts...");
                                service.Pull("/etc/init.d/rcS_mode_default", stream, CancellationToken.None);

                                bool initChanged = false;
                                List<string> initLines = new List<string>();
                                string[] initAPLines = { "if test -x /data/ftp/internal_000/APM/start_ardupilot.sh && test -x /data/ftp/internal_000/APM/arducopter; then",
                                                         "  /data/ftp/internal_000/APM/start_ardupilot.sh &",
                                                         "else" };
                                int[] initAPLinesIndex = Enumerable.Repeat(-1, initAPLines.Length).ToArray();
                                int dragonLineIndex = -1;

                                stream.Seek(0, SeekOrigin.Begin);

                                while (!sr.EndOfStream)
                                {
                                    string line = sr.ReadLine();

                                    int dragonIndex = line.IndexOf("DragonStarter.sh");
                                    bool acLine = line.ToLower().Trim().StartsWith("arducopter");

                                    if (dragonIndex != -1)
                                    {
                                        int dragonCommentIndex = line.IndexOf('#');

                                        if (dragonCommentIndex != -1 && dragonCommentIndex < dragonIndex)
                                        {
                                            line = line.Remove(dragonCommentIndex, 1);
                                            initChanged = true;
                                        }

                                        if (line.Substring(0, 2) != "  ")
                                        {
                                            line = line.Insert(0, "  ");
                                            initChanged = true;
                                        }

                                        dragonLineIndex = initLines.Count;
                                    }
                                    else if (acLine)
                                    {
                                        initChanged = true;
                                        continue;
                                    }
                                    else
                                    {
                                        foreach (int i in Enumerable.Range(0, initAPLines.Length))
                                        {
                                            if (line == initAPLines[i])
                                            {
                                                initAPLinesIndex[i] = initLines.Count;
                                                break;
                                            }
                                        }
                                    }

                                    initLines.Add(line);
                                }

                                if (initAPLinesIndex[0] == -1 ||
                                    initAPLinesIndex[1] != (initAPLinesIndex[0] + 1) ||
                                    initAPLinesIndex[2] != (initAPLinesIndex[1] + 1) ||
                                    dragonLineIndex != (initAPLinesIndex[2] + 1))
                                {
                                    foreach(int i in initAPLinesIndex)
                                    {
                                        if(i != -1)
                                        {
                                            if (i < dragonLineIndex)
                                                dragonLineIndex--;

                                            initLines.RemoveAt(i);
                                        }
                                    }

                                    initLines.InsertRange(dragonLineIndex, initAPLines);

                                    if (initLines[dragonLineIndex + initAPLines.Length + 1] != "fi")
                                    {
                                        initLines.Insert(dragonLineIndex + initAPLines.Length + 1, "fi");
                                    }

                                    initChanged = true;
                                }

                                string startAPText = "#!/bin/sh\n\n" +
                                                     "# startup fan\n" +
                                                     "echo 1 > /sys/devices/platform/user_gpio/FAN/value\n\n" +
                                                     "while :; do\n" +
                                                     "  ulogger -t \"rcS_mode_default\" -p I \"Launching ArduPilot\"\n" +
                                                     "  /data/ftp/internal_000/APM/arducopter -A udp:192.168.42.255:14550:bcast -B /dev/ttyPA1 -C udp:192.168.42.255:14551:bcast -l /data/ftp/internal_000/APM/logs -t /data/ftp/internal_000/APM/terrain\n" +
                                                     "done\n";

                                // if the above script is changed, change this date to a future date
                                DateTime startAPDate = new DateTime(2016, 10, 21, 05, 10, 19);
                                FileStatistics startAPStat = service.Stat("/data/ftp/internal_000/APM/start_ardupilot.sh");

                                if (startAPStat.FileMode == 0 || startAPStat.Time.CompareTo(startAPDate) < 0)
                                {
                                    updateProgress(70, "Uploading ArduPilot startup script...");
                                    using (MemoryStream startScriptStream = new MemoryStream(sr.CurrentEncoding.GetBytes(startAPText)))
                                    {
                                        service.Push(startScriptStream, "/data/ftp/internal_000/APM/start_ardupilot.sh", 777, startAPDate, CancellationToken.None);
                                    }
                                }

                                FileStatistics binaryStat = service.Stat("/usr/bin/arducopter");

                                if (initChanged || (binaryStat.FileMode.HasFlag(UnixFileMode.Regular)))
                                {
                                    adbClient.ExecuteRemoteCommand("mount -o remount,rw /", device, consoleOut);

                                    if (binaryStat.FileMode.HasFlag(UnixFileMode.Regular))
                                    {
                                        // remove old binary location
                                        adbClient.ExecuteRemoteCommand("rm -f /usr/bin/arducopter", device, consoleOut);
                                    }

                                    if (initChanged)
                                    {
                                        // only backup init file if a backup doesn't exist
                                        adbClient.ExecuteRemoteCommand("mv -n /etc/init.d/rcS_mode_default /etc/init.d/rcS_mode_default.backup", device, consoleOut);

                                        updateProgress(80, "Writing modified init script");
                                        stream.SetLength(0);

                                        using (StreamWriter sw = new StreamWriter(stream, sr.CurrentEncoding))
                                        {
                                            sw.NewLine = "\n";
                                            initLines.ForEach(line => sw.WriteLine(line));
                                            sw.Flush();
                                            stream.Seek(0, SeekOrigin.Begin);
                                            service.Push(stream, "/etc/init.d/rcS_mode_default", 755, DateTime.Now, CancellationToken.None);

                                            // a bug in 'adb push' sets 'group' and 'other' permissions equal to 'owner' so we run chmod to have the correct original permissions
                                            adbClient.ExecuteRemoteCommand("chmod 755 /etc/init.d/rcS_mode_default", device, consoleOut);
                                        }
                                    }
                                }
                                updateProgress(90, "Scripts updated");
                            }
                        }
                    }
                }
                finally
                {
                    updateProgress(100, "Rebooting...");
                    adbClient.ExecuteRemoteCommand("reboot.sh", device, consoleOut);
                }

                CustomMessageBox.Show("Firmware installed!");
                updateProgress(-1, "Firmware installed");
            }
            catch (Exception e)
            {
                log.Error(e);
                Console.WriteLine("An error occurred: " + e.ToString());
                updateProgress(-1, "ERROR: " + e.Message);
                return false;
            }
            finally
            {
                AdbClient.Instance.KillAdb();
            }

            return true;
        }
Beispiel #2
0
        /// <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;
        }
Beispiel #3
0
        /// <summary>
        /// upload to arduino standalone
        /// </summary>
        /// <param name="filename"></param>
        /// <param name="board"></param>
        public bool UploadFlash(string comport, string filename, BoardDetect.boards board)
        {
            if (board == BoardDetect.boards.px4 || board == BoardDetect.boards.px4v2 || board == BoardDetect.boards.px4v4)
            {
                try
                {
                    return UploadPX4(filename, board);
                }
                catch (MissingFieldException)
                {
                    CustomMessageBox.Show("Please update, your install is currupt", Strings.ERROR);
                    return false;
                }
            }

            if (board == BoardDetect.boards.vrbrainv40 || board == BoardDetect.boards.vrbrainv45 ||
                board == BoardDetect.boards.vrbrainv50 || board == BoardDetect.boards.vrbrainv51 ||
                board == BoardDetect.boards.vrbrainv52 || board == BoardDetect.boards.vrcorev10 ||
                board == BoardDetect.boards.vrubrainv51 || board == BoardDetect.boards.vrubrainv52)
            {
                return UploadVRBRAIN(filename, board);
            }

            byte[] FLASH = new byte[1];
            try
            {
                updateProgress(0, Strings.ReadingHexFile);
                using (StreamReader sr = new StreamReader(filename))
                {
                    FLASH = readIntelHEXv2(sr);
                }
                log.InfoFormat("\n\nSize: {0}\n\n", FLASH.Length);
            }
            catch (Exception ex)
            {
                updateProgress(0, Strings.FailedReadHEX);
                CustomMessageBox.Show(Strings.FailedToReadHex + ex.Message);
                return false;
            }
            IArduinoComms port = new ArduinoSTK();

            if (board == BoardDetect.boards.b1280)
            {
                if (FLASH.Length > 126976)
                {
                    CustomMessageBox.Show("Firmware is to big for a 1280, Please upgrade your hardware!!");
                    return false;
                }
                //port = new ArduinoSTK();
                port.BaudRate = 57600;
            }
            else if (board == BoardDetect.boards.b2560 || board == BoardDetect.boards.b2560v2)
            {
                port = new ArduinoSTKv2
                {
                    BaudRate = 115200
                };
            }
            port.DataBits = 8;
            port.StopBits = System.IO.Ports.StopBits.One;
            port.Parity = System.IO.Ports.Parity.None;
            port.DtrEnable = true;

            try
            {
                port.PortName = comport;

                port.Open();

                if (port.connectAP())
                {
                    log.Info("starting");
                    updateProgress(0, String.Format(Strings.UploadingBytesToBoard, FLASH.Length) + board);

                    // this is enough to make ap_var reset
                    //port.upload(new byte[256], 0, 2, 0);

                    port.Progress += updateProgress;

                    if (!port.uploadflash(FLASH, 0, FLASH.Length, 0))
                    {
                        if (port.IsOpen)
                            port.Close();
                        throw new Exception("Upload failed. Lost sync. Try Arduino!!");
                    }

                    port.Progress -= updateProgress;

                    updateProgress(100, Strings.UploadComplete);

                    log.Info("Uploaded");

                    int start = 0;
                    short length = 0x100;

                    byte[] flashverify = new byte[FLASH.Length + 256];

                    updateProgress(0, Strings.VerifyFirmware);

                    while (start < FLASH.Length)
                    {
                        updateProgress((int) ((start/(float) FLASH.Length)*100), Strings.VerifyFirmware);
                        port.setaddress(start);
                        //log.Info("Downloading " + length + " at " + start);
                        port.downloadflash(length).CopyTo(flashverify, start);
                        start += length;
                    }

                    for (int s = 0; s < FLASH.Length; s++)
                    {
                        if (FLASH[s] != flashverify[s])
                        {
                            CustomMessageBox.Show(
                                String.Format(Strings.UploadSucceededButVerifyFailed, FLASH[s].ToString("X"),
                                    flashverify[s].ToString("X")) + s);
                            port.Close();
                            return false;
                        }
                    }

                    updateProgress(100, Strings.VerifyComplete);
                }
                else
                {
                    updateProgress(0, Strings.FailedUpload);
                    CustomMessageBox.Show(Strings.CommunicationErrorNoConnection);
                }
                port.Close();

                try
                {
                    ((SerialPort) port).Open();
                }
                catch
                {
                }

                //CustomMessageBox.Show("1. If you are updating your firmware from a previous version, please verify your parameters are appropriate for the new version.\n2. Please ensure your accelerometer is calibrated after installing or re-calibrated after updating the firmware.");

                try
                {
                    ((SerialPort) port).Close();
                }
                catch
                {
                }

                updateProgress(100, Strings.Done);
            }
            catch (Exception ex)
            {
                updateProgress(0, Strings.FailedUpload);
                CustomMessageBox.Show(Strings.CheckPortSettingsOr + ex);
                try
                {
                    port.Close();
                }
                catch
                {
                }
                return false;
            }
            MainV2.comPort.giveComport = false;
            return true;
        }
Beispiel #4
0
        /// <summary>
        /// return the software id from eeprom
        /// </summary>
        /// <param name="comport">Port</param>
        /// <param name="version">Board type</param>
        /// <returns></returns>
        public static int decodeApVar(string comport, BoardDetect.boards version)
        {
            IArduinoComms port = new ArduinoSTK();
            if (version == boards.b1280)
            {
                port = new ArduinoSTK();
                port.BaudRate = 57600;
            }
            else if (version == boards.b2560 || version == boards.b2560v2)
            {
                port = new ArduinoSTKv2();
                port.BaudRate = 115200;
            }
            else { return -1; }
            port.PortName = comport;
            port.DtrEnable = true;
            port.Open();
            port.connectAP();
            byte[] buffer = port.download(1024 * 4);
            port.Close();

            if (buffer[0] != 'A' && buffer[0] != 'P' || buffer[1] != 'P' && buffer[1] != 'A') // this is the apvar header
            {
                return -1;
            }
            else
            {
                if (buffer[0] == 'A' && buffer[1] == 'P' && buffer[2] == 2)
                { // apvar header and version
                    int pos = 4;
                    byte key = 0;
                    while (pos < (1024 * 4))
                    {
                        int size = buffer[pos] & 63;
                        pos++;
                        key = buffer[pos];
                        pos++;

                        log.InfoFormat("{0:X4}: key {1} size {2}\n ", pos - 2, key, size + 1);

                        if (key == 0xff)
                        {
                            log.InfoFormat("end sentinal at {0}", pos - 2);
                            break;
                        }

                        if (key == 0)
                        {
                            //Array.Reverse(buffer, pos, 2);
                            return BitConverter.ToUInt16(buffer, pos);
                        }

                        for (int i = 0; i <= size; i++)
                        {
                            Console.Write(" {0:X2}", buffer[pos]);
                            pos++;
                        }
                    }
                }

                if (buffer[0] == 'P' && buffer[1] == 'A' && buffer[2] == 5) // ap param
                {
                    int pos = 4;
                    byte key = 0;
                    while (pos < (1024 * 4))
                    {
                        key = buffer[pos];
                        pos++;
                        int group = buffer[pos];
                        pos++;
                        int type = buffer[pos];
                        pos++;

                        int size = type_size((ap_var_type)Enum.Parse(typeof(ap_var_type), type.ToString()));

                        Console.Write("{0:X4}: type {1} ({2}) key {3} group {4} size {5}\n ", pos - 2, type, type_names[type], key, group, size);

                        if (key == 0xff)
                        {
                            log.InfoFormat("end sentinal at {0}", pos - 2);
                            break;
                        }

                        if (key == 0)
                        {
                            //Array.Reverse(buffer, pos, 2);
                            return BitConverter.ToUInt16(buffer, pos);
                        }

                        for (int i = 0; i < size; i++)
                        {
                            Console.Write(" {0:X2}", buffer[pos]);
                            pos++;
                        }
                    }
                }

                if (buffer[0] == 'P' && buffer[1] == 'A' && buffer[2] == 6) // ap param
                {
                    int pos = 4;
                    byte key = 0;
                    while (pos < (1024 * 4))
                    {
                        key = buffer[pos];
                        pos++;

                        if (key == 0xff)
                        {
                            log.InfoFormat("end sentinal at {0}", pos - 1);
                            break;
                        }

                        int type = buffer[pos] & 0x3f; // 6 bits

                        uint group = BitConverter.ToUInt32(buffer, pos);//((byte)(buffer[pos]) >> 6) | ((byte)(buffer[pos + 1]) << 8) | ((byte)(buffer[pos + 2]) << 16); // 18 bits

                        group = (group >> 6) & 0x3ffff;
                        pos++;
                        pos++;
                        pos++;

                        int size = BoardDetect.type_size((BoardDetect.ap_var_type)Enum.Parse(typeof(BoardDetect.ap_var_type), type.ToString()));

                            Console.Write("{0:X4}: type {1} ({2}) key {3} group_element {4} size {5} value ", pos - 4, type, BoardDetect.type_names[type], key, group, size);

                        if (key == 0)
                        {
                            //Array.Reverse(buffer, pos, 2);
                             return BitConverter.ToUInt16(buffer, pos);
                        }

                        for (int i = 0; i < size; i++)
                        {
                            Console.Write(" {0:X2}", buffer[pos]);
                            pos++;
                        }
                        Console.WriteLine();
                    }
                }
            }
            return -1;
        }
Beispiel #5
0
        /// <summary>
        /// Upload firmware
        /// </summary>
        /// <param name="comport"></param>
        /// <param name="filename"></param>
        /// <param name="board"></param>
        /// <returns>pass/fail</returns>
        public bool UploadFlash(string comport, string filename, BoardDetect.boards board)
        {
            if (board == BoardDetect.boards.px4 || board == BoardDetect.boards.px4v2 || board == BoardDetect.boards.px4v4)
            {
                try
                {
                    return UploadPX4(filename, board);
                }
                catch (MissingFieldException)
                {
                    CustomMessageBox.Show("Please update, your install is currupt", Strings.ERROR);
                    return false;
                }
            }

            if (board == BoardDetect.boards.vrbrainv40 || board == BoardDetect.boards.vrbrainv45 ||
                board == BoardDetect.boards.vrbrainv50 || board == BoardDetect.boards.vrbrainv51 ||
                board == BoardDetect.boards.vrbrainv52 || board == BoardDetect.boards.vrcorev10 ||
                board == BoardDetect.boards.vrubrainv51 || board == BoardDetect.boards.vrubrainv52)
            {
                return UploadVRBRAIN(filename, board);
            }

            if (board == BoardDetect.boards.bebop2)
            {
                return UploadParrot(filename, board);
            }

            return UploadArduino(comport, filename, board);
        }
        //Load custom firmware (old CTRL+C shortcut)
        private void Custom_firmware_label_Click(object sender, EventArgs e)
        {
            using (var fd = new OpenFileDialog {
                Filter = "Firmware (*.hex;*.px4;*.vrx;*.apj)|*.hex;*.px4;*.vrx;*.apj|All files (*.*)|*.*"
            })
            {
                if (Directory.Exists(custom_fw_dir))
                {
                    fd.InitialDirectory = custom_fw_dir;
                }
                fd.ShowDialog();
                if (File.Exists(fd.FileName))
                {
                    custom_fw_dir = Path.GetDirectoryName(fd.FileName);
                    Settings.Instance["FirmwareFileDirectory"] = custom_fw_dir;

                    fw.Progress -= fw_ProgressPDR;
                    fw.Progress += fw_Progress1;

                    var boardtype = BoardDetect.boards.none;
                    try
                    {
                        if (fd.FileName.ToLower().EndsWith(".px4") || fd.FileName.ToLower().EndsWith(".apj"))
                        {
                            if (solo.Solo.is_solo_alive &&
                                CustomMessageBox.Show("Solo", "Is this a Solo?", CustomMessageBox.MessageBoxButtons.YesNo) == CustomMessageBox.DialogResult.Yes)
                            {
                                boardtype = BoardDetect.boards.solo;
                            }
                            else
                            {
                                boardtype = BoardDetect.boards.px4v2;
                            }
                        }
                        else
                        {
                            var ports = Win32DeviceMgmt.GetAllCOMPorts();

                            if (ExtraDeviceInfo != null)
                            {
                                try
                                {
                                    ports.AddRange(ExtraDeviceInfo.Invoke());
                                }
                                catch
                                {
                                }
                            }

                            boardtype = BoardDetect.DetectBoard(MainV2.comPortName, ports);
                        }

                        if (boardtype == BoardDetect.boards.none)
                        {
                            CustomMessageBox.Show(Strings.CantDetectBoardVersion);
                            return;
                        }
                    }
                    catch
                    {
                        CustomMessageBox.Show(Strings.CanNotConnectToComPortAnd, Strings.ERROR);
                        return;
                    }

                    fw.UploadFlash(MainV2.comPortName, fd.FileName, boardtype);
                }
            }
        }
Beispiel #7
0
        /// <summary>
        /// upload to arduino standalone
        /// </summary>
        /// <param name="filename"></param>
        /// <param name="board"></param>
        public bool UploadFlash(string comport, string filename, BoardDetect.boards board)
        {
            if (board == BoardDetect.boards.px4|| board == BoardDetect.boards.px4v2)
            {
                return UploadPX4(filename);
            }

            byte[] FLASH = new byte[1];
            StreamReader sr = null;
            try
            {
                updateProgress(0, "Reading Hex File");
                sr = new StreamReader(filename);
                FLASH = readIntelHEXv2(sr);
                sr.Close();
                log.InfoFormat("\n\nSize: {0}\n\n", FLASH.Length);
            }
            catch (Exception ex)
            {
                if (sr != null)
                {
                    sr.Dispose();
                }
                updateProgress(0, "Failed read HEX");
                CustomMessageBox.Show("Failed to read firmware.hex : " + ex.Message);
                return false;
            }
            IArduinoComms port = new ArduinoSTK();

            if (board == BoardDetect.boards.b1280)
            {
                if (FLASH.Length > 126976)
                {
                    CustomMessageBox.Show("Firmware is to big for a 1280, Please upgrade your hardware!!");
                    return false;
                }
                //port = new ArduinoSTK();
                port.BaudRate = 57600;
            }
            else if (board == BoardDetect.boards.b2560 || board == BoardDetect.boards.b2560v2)
            {
                port = new ArduinoSTKv2
                {
                    BaudRate = 115200
                };
            }
            port.DataBits = 8;
            port.StopBits = System.IO.Ports.StopBits.One;
            port.Parity = System.IO.Ports.Parity.None;
            port.DtrEnable = true;

            try
            {
                port.PortName = comport;

                port.Open();

                if (port.connectAP())
                {
                    log.Info("starting");
                    updateProgress(0, "Uploading " + FLASH.Length + " bytes to Board: " + board);

                    // this is enough to make ap_var reset
                    //port.upload(new byte[256], 0, 2, 0);

                    port.Progress += updateProgress;

                    if (!port.uploadflash(FLASH, 0, FLASH.Length, 0))
                    {
                        if (port.IsOpen)
                            port.Close();
                        throw new Exception("Upload failed. Lost sync. Try Arduino!!");
                    }

                    port.Progress -= updateProgress;

                    updateProgress(100, "Upload Complete");

                    log.Info("Uploaded");

                    int start = 0;
                    short length = 0x100;

                    byte[] flashverify = new byte[FLASH.Length + 256];

                    updateProgress(0, "Verify Firmware");

                    while (start < FLASH.Length)
                    {
                        updateProgress((int)((start / (float)FLASH.Length) * 100), "Verify Firmware");
                        port.setaddress(start);
                        log.Info("Downloading " + length + " at " + start);
                        port.downloadflash(length).CopyTo(flashverify, start);
                        start += length;
                    }

                    for (int s = 0; s < FLASH.Length; s++)
                    {
                        if (FLASH[s] != flashverify[s])
                        {
                            CustomMessageBox.Show("Upload succeeded, but verify failed: exp " + FLASH[s].ToString("X") + " got " + flashverify[s].ToString("X") + " at " + s);
                            port.Close();
                            return false;
                        }
                    }

                    updateProgress(100, "Verify Complete");
                }
                else
                {
                    updateProgress(0,"Failed upload");
                    CustomMessageBox.Show("Communication Error - no connection");
                }
                port.Close();

                try
                {
                    ((SerialPort)port).Open();
                }
                catch { }

                //CustomMessageBox.Show("1. If you are updating your firmware from a previous version, please verify your parameters are appropriate for the new version.\n2. Please ensure your accelerometer is calibrated after installing or re-calibrated after updating the firmware.");

                try
                {
                    ((SerialPort)port).Close();
                }
                catch { }

                updateProgress(100, "Done");
            }
            catch (Exception ex)
            {
                updateProgress(0,"Failed upload");
                CustomMessageBox.Show("Check port settings or Port in use? " + ex);
                try
                {
                    port.Close();
                }
                catch { }
                return false;
            }
            MainV2.comPort.giveComport = false;
            return true;
        }