private void updatedefaultlist(object crap) { try { if (paramfiles == null) { paramfiles = GitHubContent.GetDirContent("diydrones", "ardupilot", "/Tools/Frame_params/", ".param"); } BeginInvoke((Action) delegate { CMB_paramfiles.DataSource = paramfiles.ToArray(); CMB_paramfiles.DisplayMember = "name"; CMB_paramfiles.Enabled = true; BUT_paramfileload.Enabled = true; }); } catch (Exception ex) { log.Error(ex); } }
private void BUT_paramfileload_Click(object sender, EventArgs e) { string filepath = Application.StartupPath + Path.DirectorySeparatorChar + CMB_paramfiles.Text; if (CMB_paramfiles.SelectedValue == null) { CustomMessageBox.Show("Please select an option first"); return; } try { byte[] data = GitHubContent.GetFileContent("diydrones", "ardupilot", ((GitHubContent.FileInfo)CMB_paramfiles.SelectedValue).path); File.WriteAllBytes(filepath, data); Hashtable param2 = Utilities.ParamFile.loadParamFile(filepath); Form paramCompareForm = new ParamCompare(null, MainV2.comPort.MAV.param, param2); ThemeManager.ApplyThemeTo(paramCompareForm); if (paramCompareForm.ShowDialog() == DialogResult.OK) { CustomMessageBox.Show("Loaded parameters!", "Loaded"); } if (OnChange != null) { OnChange(null, null); return; } this.Activate(); } catch (Exception ex) { CustomMessageBox.Show("Failed to load file.\n" + ex); } }