private void BUT_getcurrent_Click(object sender, EventArgs e)
{
ICommsSerial comPort = new SerialPort();
try
{
if (MainV2.comPort.BaseStream.IsOpen)
{
getTelemPortWithRadio(ref comPort);
}
else
{
comPort.PortName = MainV2.comPort.BaseStream.PortName;
comPort.BaudRate = MainV2.comPort.BaseStream.BaudRate;
}
comPort.ReadTimeout = 4000;
comPort.Open();
}
catch
{
CustomMessageBox.Show("Invalid ComPort or in use");
return;
}
lbl_status.Text = "Connecting";
try
{
if (doConnect(comPort))
{
// cleanup
doCommand(comPort, "AT&T");
comPort.DiscardInBuffer();
lbl_status.Text = "Doing Command ATI & RTI";
ATI.Text = doCommand(comPort, "ATI");
var freq =
(Uploader.Frequency)
Enum.Parse(typeof (Uploader.Frequency), doCommand(comPort, "ATI3"));
var board =
(Uploader.Board)
Enum.Parse(typeof (Uploader.Board), doCommand(comPort, "ATI2"));
ATI3.Text = freq.ToString();
ATI2.Text = board.ToString();
// 8 and 9
if (freq == Uploader.Frequency.FREQ_915)
{
MIN_FREQ.DataSource = Range(895000, 1000, 935000);
RMIN_FREQ.DataSource = Range(895000, 1000, 935000);
MAX_FREQ.DataSource = Range(895000, 1000, 935000);
RMAX_FREQ.DataSource = Range(895000, 1000, 935000);
}
else if (freq == Uploader.Frequency.FREQ_433)
{
MIN_FREQ.DataSource = Range(414000, 50, 460000);
RMIN_FREQ.DataSource = Range(414000, 50, 460000);
MAX_FREQ.DataSource = Range(414000, 50, 460000);
RMAX_FREQ.DataSource = Range(414000, 50, 460000);
}
else if (freq == Uploader.Frequency.FREQ_868)
{
MIN_FREQ.DataSource = Range(849000, 1000, 889000);
RMIN_FREQ.DataSource = Range(849000, 1000, 889000);
MAX_FREQ.DataSource = Range(849000, 1000, 889000);
RMAX_FREQ.DataSource = Range(849000, 1000, 889000);
}
if (board == Uploader.Board.DEVICE_ID_RFD900 ||
board == Uploader.Board.DEVICE_ID_RFD900A
|| board == Uploader.Board.DEVICE_ID_RFD900P ||
board == Uploader.Board.DEVICE_ID_RFD900U ||
board == Uploader.Board.DEVICE_ID_RFD900Plus)
{
TXPOWER.DataSource = Range(1, 1, 30);
RTXPOWER.DataSource = Range(1, 1, 30);
}
txt_aeskey.Text = doCommand(comPort, "AT&E?").Trim();
RSSI.Text = doCommand(comPort, "ATI7").Trim();
lbl_status.Text = "Doing Command ATI5";
var answer = doCommand(comPort, "ATI5", true);
var items = answer.Split('\n');
foreach (var item in items)
{
if (item.StartsWith("S"))
{
var values = item.Split(':', '=');
if (values.Length == 3)
{
values[1] = values[1].Replace("/", "_");
var controls = groupBoxLocal.Controls.Find(values[1].Trim(), true);
if (controls.Length > 0)
{
controls[0].Enabled = true;
if (controls[0] is CheckBox)
{
((CheckBox) controls[0]).Checked = values[2].Trim() == "1";
}
else if (controls[0] is TextBox)
{
((TextBox) controls[0]).Text = values[2].Trim();
}
else if (controls[0].Name.Contains("MAVLINK")) //
{
var ans = Enum.Parse(typeof (mavlink_option), values[2].Trim());
((ComboBox) controls[0]).Text = ans.ToString();
}
else if (controls[0] is ComboBox)
{
((ComboBox) controls[0]).Text = values[2].Trim();
}
}
}
}
}
// remote
foreach (Control ctl in groupBoxRemote.Controls)
{
if (ctl.Name != "RSSI")
ctl.ResetText();
}
comPort.DiscardInBuffer();
RTI.Text = doCommand(comPort, "RTI");
try
{
var resp = doCommand(comPort, "RTI2");
if (resp.Trim() != "")
RTI2.Text =
((Uploader.Board)Enum.Parse(typeof(Uploader.Board), resp)).ToString();
}
catch
{
}
txt_Raeskey.Text = doCommand(comPort, "RT&E?").Trim();
lbl_status.Text = "Doing Command RTI5";
answer = doCommand(comPort, "RTI5", true);
items = answer.Split('\n');
foreach (var item in items)
{
if (item.StartsWith("S"))
{
var values = item.Split(':', '=');
if (values.Length == 3)
{
values[1] = values[1].Replace("/", "_");
var controls = groupBoxRemote.Controls.Find("R" + values[1].Trim(), true);
if (controls.Length == 0)
continue;
controls[0].Enabled = true;
if (controls[0] is CheckBox)
{
((CheckBox) controls[0]).Checked = values[2].Trim() == "1";
}
else if (controls[0] is TextBox)
{
((TextBox) controls[0]).Text = values[2].Trim();
}
else if (controls[0].Name.Contains("MAVLINK")) //
{
var ans = Enum.Parse(typeof (mavlink_option), values[2].Trim());
((ComboBox) controls[0]).Text = ans.ToString();
}
else if (controls[0] is ComboBox)
{
((ComboBox) controls[0]).Text = values[2].Trim();
}
}
else
{
/*
if (item.Contains("S15"))
{
answer = doCommand(comPort, "RTS15?");
int rts15 = 0;
if (int.TryParse(answer, out rts15))
{
RS15.Enabled = true;
RS15.Text = rts15.ToString();
}
}
*/
log.Info("Odd config line :" + item);
}
}
}
// off hook
doCommand(comPort, "ATO");
lbl_status.Text = "Done";
}
else
{
// off hook
doCommand(comPort, "ATO");
lbl_status.Text = "Fail";
CustomMessageBox.Show("Failed to enter command mode");
}
comPort.Close();
BUT_Syncoptions.Enabled = true;
BUT_savesettings.Enabled = true;
}
catch (Exception ex)
{
try
{
if (comPort != null)
comPort.Close();
}
catch
{
}
lbl_status.Text = "Error";
CustomMessageBox.Show("Error during read " + ex);
}
}