mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
APM Planner 1.1.28
fix updatechecker fix battery config screen
This commit is contained in:
parent
ce11d51f7a
commit
a9b2f39a66
@ -52,7 +52,7 @@
|
||||
resources.ApplyResources(this.BUT_updatecheck, "BUT_updatecheck");
|
||||
this.BUT_updatecheck.Name = "BUT_updatecheck";
|
||||
this.BUT_updatecheck.UseVisualStyleBackColor = true;
|
||||
this.BUT_updatecheck.Click += new System.EventHandler(Help.BUT_updatecheck_Click);
|
||||
this.BUT_updatecheck.Click += new System.EventHandler(this.BUT_updatecheck_Click);
|
||||
//
|
||||
// Help
|
||||
//
|
||||
|
@ -22,29 +22,9 @@ namespace ArdupilotMega.GCSViews
|
||||
catch { }
|
||||
}
|
||||
|
||||
public static void BUT_updatecheck_Click(object sender, EventArgs e)
|
||||
public void BUT_updatecheck_Click(object sender, EventArgs e)
|
||||
{
|
||||
Form loading = new Form();
|
||||
loading.Width = 400;
|
||||
loading.Height = 150;
|
||||
loading.StartPosition = FormStartPosition.CenterScreen;
|
||||
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(MainV2));
|
||||
loading.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon")));
|
||||
|
||||
Label loadinglabel = new Label();
|
||||
loadinglabel.Location = new System.Drawing.Point(50, 40);
|
||||
loadinglabel.Name = "load";
|
||||
loadinglabel.AutoSize = true;
|
||||
loadinglabel.Text = "Checking...";
|
||||
loadinglabel.Size = new System.Drawing.Size(100, 20);
|
||||
|
||||
loading.Controls.Add(loadinglabel);
|
||||
loading.Show();
|
||||
|
||||
System.Threading.Thread t12 = new System.Threading.Thread(delegate() { try { MainV2.updatecheck(loadinglabel); } catch (Exception ex) { Console.WriteLine(ex.ToString()); } }); // wait for tcp connections
|
||||
t12.Name = "Update check thread";
|
||||
t12.Start();
|
||||
MainV2.threads.Add(t12);
|
||||
MainV2.doupdate();
|
||||
}
|
||||
|
||||
private void CHK_showconsole_CheckedChanged(object sender, EventArgs e)
|
||||
@ -54,7 +34,7 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
private void Help_Load(object sender, EventArgs e)
|
||||
{
|
||||
richTextBox1.Rtf = new ComponentResourceManager(this.GetType()).GetString("Help_text");
|
||||
richTextBox1.Rtf = new ComponentResourceManager(this.GetType()).GetString("help_text");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -196,7 +196,7 @@
|
||||
<value>BUT_updatecheck</value>
|
||||
</data>
|
||||
<data name=">>BUT_updatecheck.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.4199.27022, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||
</data>
|
||||
<data name=">>BUT_updatecheck.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
@ -220,9 +220,9 @@
|
||||
<value>Help</value>
|
||||
</data>
|
||||
<data name=">>$this.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
<value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||
</data>
|
||||
<data name="Help_text" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<data name="help_text" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\Welcome_to_Michael_Oborne.rtf;System.String, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;Windows-1252</value>
|
||||
</data>
|
||||
</root>
|
@ -13,6 +13,8 @@ using ZedGraph; // Graphs
|
||||
using ArdupilotMega;
|
||||
using System.Reflection;
|
||||
|
||||
using System.Drawing.Drawing2D;
|
||||
|
||||
// Written by Michael Oborne
|
||||
namespace ArdupilotMega.GCSViews
|
||||
{
|
||||
@ -903,46 +905,17 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
|
||||
|
||||
var answer = HIL.Utils.EarthRatesToBodyRatesRyan(att.roll * -rad2deg, att.pitch * rad2deg, att.yaw * rad2deg, aeroin.Model_fAngVelX * rad2deg, aeroin.Model_fAngVelY * rad2deg, aeroin.Model_fAngVelZ * rad2deg);
|
||||
var answer = HIL.Utils.EarthRatesToBodyRatesMine(att.roll * rad2deg, att.pitch * rad2deg, att.yaw * rad2deg, aeroin.Model_fAngVelX * rad2deg, aeroin.Model_fAngVelY * rad2deg, aeroin.Model_fAngVelZ * rad2deg);
|
||||
Console.WriteLine("\n{0:0.000} {1:0.000} {2:0.000} ", answer.Item1 * deg2rad, answer.Item2 * deg2rad, answer.Item3 * deg2rad);
|
||||
|
||||
//answer = HIL.Utils.OGLtoBCBF(aeroin.Model_fAngVelX * rad2deg, aeroin.Model_fAngVelY * rad2deg, aeroin.Model_fAngVelZ * rad2deg, att.pitch * rad2deg, att.roll * rad2deg, att.yaw * rad2deg);
|
||||
//Console.WriteLine("{0:0.000} {1:0.000} {2:0.000} ", answer.Item1 * deg2rad, answer.Item2 * deg2rad, answer.Item3 * deg2rad);
|
||||
|
||||
// answer = HIL.Utils.EarthRatesToBodyRatesRyan(att.roll * rad2deg, att.pitch * rad2deg, att.yaw * rad2deg, aeroin.Model_fAngVelY * rad2deg, aeroin.Model_fAngVelX * rad2deg, aeroin.Model_fAngVelZ * rad2deg);
|
||||
//Console.WriteLine("{0:0.000} {1:0.000} {2:0.000} ", answer.Item1 * deg2rad, answer.Item2 * deg2rad, answer.Item3 * deg2rad);
|
||||
|
||||
// answer = HIL.Utils.EarthRatesToBodyRatesRyan(att.roll * rad2deg, att.pitch * rad2deg, att.yaw * rad2deg, aeroin.Model_fAngVelX * rad2deg, aeroin.Model_fAngVelZ * rad2deg, aeroin.Model_fAngVelY * rad2deg);
|
||||
//Console.WriteLine("{0:0.000} {1:0.000} {2:0.000} ", answer.Item1 * deg2rad, answer.Item2 * deg2rad, answer.Item3 * deg2rad);
|
||||
|
||||
// answer = HIL.Utils.EarthRatesToBodyRatesRyan(att.roll * rad2deg, att.pitch * rad2deg, att.yaw * rad2deg, aeroin.Model_fAngVelZ * rad2deg, aeroin.Model_fAngVelY * rad2deg, aeroin.Model_fAngVelX * rad2deg);
|
||||
//Console.WriteLine("{0:0.000} {1:0.000} {2:0.000} ", answer.Item1 * deg2rad, answer.Item2 * deg2rad, answer.Item3 * deg2rad);
|
||||
|
||||
// answer = HIL.Utils.EarthRatesToBodyRatesRyan(att.roll * rad2deg, att.pitch * rad2deg, att.yaw * rad2deg, aeroin.Model_fAngVelY * rad2deg, aeroin.Model_fAngVelZ * rad2deg, aeroin.Model_fAngVelX * rad2deg);
|
||||
//Console.WriteLine("{0:0.000} {1:0.000} {2:0.000} ", answer.Item1 * deg2rad, answer.Item2 * deg2rad, answer.Item3 * deg2rad);
|
||||
|
||||
//answer = HIL.Utils.EarthRatesToBodyRatesRyan(att.roll * rad2deg, att.pitch * rad2deg, att.yaw * rad2deg, aeroin.Model_fAngVelZ * rad2deg, aeroin.Model_fAngVelX * rad2deg, aeroin.Model_fAngVelY * rad2deg);
|
||||
//Console.WriteLine("{0:0.000} {1:0.000} {2:0.000} ", answer.Item1 * deg2rad, answer.Item2 * deg2rad, answer.Item3 * deg2rad);
|
||||
|
||||
|
||||
//att.pitchspeed = (float)answer.Item1 * deg2rad;
|
||||
//att.rollspeed = (float)answer.Item2 * deg2rad;
|
||||
//att.yawspeed = (float)answer.Item3 * deg2rad;
|
||||
// att.pitchspeed = (float)answer.Item1 * -deg2rad;
|
||||
// att.rollspeed = (float)answer.Item2 * -deg2rad;
|
||||
// att.yawspeed = (float)answer.Item3 * -deg2rad;
|
||||
|
||||
//att.pitchspeed = (float)(Math.Cos(att.yaw) * aeroin.Model_fAngVelX - Math.Sin(att.yaw) * aeroin.Model_fAngVelY);
|
||||
//att.rollspeed = (float)(Math.Sin(att.yaw) * aeroin.Model_fAngVelX + Math.Cos(att.yaw) * aeroin.Model_fAngVelY);
|
||||
// att.yawspeed = (float)-aeroin.Model_fAngVelZ * deg2rad;
|
||||
|
||||
// if (aeroin.Model_fAngVelX > 2 || aeroin.Model_fAngVelZ < -2 || aeroin.Model_fAngVelY > 2 || aeroin.Model_fAngVelY < -2)
|
||||
// Console.Write("head {0:0.000}\troll {1:0.000}\tx {2:0.000} \ty {3:0.000} x2 {4:0.000} y2 {5:0.000} \n", aeroin.Model_fHeading * rad2deg, att.roll * rad2deg, aeroin.Model_fAngVelX, aeroin.Model_fAngVelY, att.pitchspeed, att.rollspeed);
|
||||
|
||||
|
||||
//att.pitchspeed = 0;
|
||||
//att.rollspeed = 0;
|
||||
// att.pitchspeed = (float)answer.Item1 * deg2rad;
|
||||
// att.rollspeed = (float)answer.Item2 * deg2rad;
|
||||
//att.yawspeed = (float)answer.Item3 * -deg2rad;
|
||||
|
||||
|
||||
#if MAVLINK10
|
||||
imu.time_usec = ((ulong)DateTime.Now.ToBinary());
|
||||
|
@ -90,10 +90,6 @@ namespace ArdupilotMega.HIL
|
||||
var Ro = radians(yawRate);
|
||||
var Qo = radians(rollRate);
|
||||
|
||||
// CpCy, CpSy, -Sp | local_ax
|
||||
// SrSpCy-CrSy, SrSpSy+CrCy, SrCp | local_ay
|
||||
// CrSpCy+SrSy, CrSpSy-SrCy, CrCp | local_az
|
||||
|
||||
var P = Po * cos(psi) * cos(theta) - Ro * sin(theta) + Qo * cos(theta) * sin(psi);
|
||||
|
||||
var Q = Qo * (cos(phi) * cos(psi) + sin(phi) * sin(psi) * sin(theta)) - Po * (cos(phi) * sin(psi) - cos(psi) * sin(phi) * sin(theta)) + Ro * cos(theta) * sin(phi);
|
||||
@ -103,6 +99,61 @@ namespace ArdupilotMega.HIL
|
||||
return new Tuple<double, double, double>(degrees(P), degrees(Q), degrees(R));
|
||||
}
|
||||
|
||||
public static Tuple<double, double, double> EarthRatesToBodyRatesMine(double roll, double pitch, double yaw,
|
||||
double rollRate, double pitchRate, double yawRate)
|
||||
{
|
||||
// thanks to ryan beall
|
||||
|
||||
var phi = radians(roll);
|
||||
var theta = radians(pitch);
|
||||
var psi = radians(yaw);
|
||||
var Po = radians(pitchRate);
|
||||
var Ro = radians(yawRate);
|
||||
var Qo = radians(rollRate);
|
||||
|
||||
var Q = Po * cos(psi) + Qo * sin(psi);
|
||||
|
||||
var P = Po * sin(psi) + Qo * cos(psi); ;
|
||||
|
||||
var R = Ro;
|
||||
|
||||
return new Tuple<double, double, double>(degrees(P), degrees(Q), degrees(R));
|
||||
|
||||
|
||||
/*
|
||||
double Cr, Cp, Cz;
|
||||
double Sr, Sp, Sz;
|
||||
|
||||
var phi = radians(roll);
|
||||
var theta = radians(pitch);
|
||||
var psi = radians(yaw);
|
||||
var Po = radians(rollRate);
|
||||
var Ro = radians(pitchRate);
|
||||
var Qo = radians(yawRate);
|
||||
|
||||
Cr = Math.Cos((phi));
|
||||
Cp = Math.Cos((theta));
|
||||
Cz = Math.Cos((psi));
|
||||
Sr = Math.Sin((phi));
|
||||
Sp = Math.Sin((theta));
|
||||
Sz = Math.Sin((psi));
|
||||
|
||||
// http://planning.cs.uiuc.edu/node102.html
|
||||
// Z Y X
|
||||
// roll -Sp, CpSr, CpCr
|
||||
// pitch SzCp, SzSpSr+CzCr, SzSpCr-CpCr
|
||||
// yaw CzCp, CzSpSr-SzCr, CzSpCr+SzSr
|
||||
|
||||
var P = -(Qo * Sp) + Po * Cp * Sr + Ro * Cp * Cr;
|
||||
|
||||
var Q = Qo * (Sz * Cp) + Po * (Sz * Sp * Sr + Cz * Cr) + Ro * (Sz * Sp * Cr - Cp * Cr);
|
||||
|
||||
var R = Qo * (Cz * Cp) + Po * (Cz * Sp * Sr - Sz * Cr) + Ro * (Cz * Sp * Cr + Sz * Sr);
|
||||
|
||||
return new Tuple<double, double, double>(degrees(P), degrees(Q), degrees(R));
|
||||
* */
|
||||
}
|
||||
|
||||
public static Tuple<double, double, double> OGLtoBCBF(double phi, double theta, double psi,double x, double y, double z)
|
||||
{
|
||||
double x_NED, y_NED, z_NED;
|
||||
|
@ -240,7 +240,7 @@ namespace hud
|
||||
|
||||
protected override void OnPaint(PaintEventArgs e)
|
||||
{
|
||||
//GL.Enable(EnableCap.AlphaTest);
|
||||
//GL.Enable(EnableCap.AlphaTest)
|
||||
|
||||
if (this.DesignMode)
|
||||
{
|
||||
|
@ -97,6 +97,10 @@ namespace ArdupilotMega
|
||||
|
||||
Application.DoEvents();
|
||||
|
||||
instance = this;
|
||||
|
||||
InitializeComponent();
|
||||
|
||||
srtm.datadirectory = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "srtm";
|
||||
|
||||
var t = Type.GetType("Mono.Runtime");
|
||||
@ -104,15 +108,6 @@ namespace ArdupilotMega
|
||||
|
||||
//talk.SpeakAsync("Welcome to APM Planner");
|
||||
|
||||
try
|
||||
{
|
||||
checkForUpdate();
|
||||
}
|
||||
catch { Console.WriteLine("update check failed"); }
|
||||
|
||||
|
||||
InitializeComponent();
|
||||
|
||||
MyRenderer.currentpressed = MenuFlightData;
|
||||
|
||||
MainMenu.Renderer = new MyRenderer();
|
||||
@ -251,7 +246,7 @@ namespace ArdupilotMega
|
||||
|
||||
Application.DoEvents();
|
||||
|
||||
instance = this;
|
||||
|
||||
splash.Close();
|
||||
}
|
||||
|
||||
@ -1234,7 +1229,6 @@ namespace ArdupilotMega
|
||||
//comPort.requestDatastream((byte)MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_ALL,3);
|
||||
//
|
||||
|
||||
|
||||
MenuFlightData_Click(sender, e);
|
||||
|
||||
try
|
||||
@ -1267,6 +1261,12 @@ namespace ArdupilotMega
|
||||
Name = "Main Serial reader"
|
||||
};
|
||||
t11.Start();
|
||||
|
||||
try
|
||||
{
|
||||
checkForUpdate();
|
||||
}
|
||||
catch { Console.WriteLine("update check failed"); }
|
||||
}
|
||||
|
||||
public static String ComputeWebSocketHandshakeSecurityHash09(String secWebSocketKey)
|
||||
@ -1689,7 +1689,7 @@ namespace ArdupilotMega
|
||||
DialogResult dr = MessageBox.Show("Update Found\n\nDo you wish to update now?", "Update Now", MessageBoxButtons.YesNo);
|
||||
if (dr == DialogResult.Yes)
|
||||
{
|
||||
GCSViews.Help.BUT_updatecheck_Click(null, null);
|
||||
doupdate();
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -1698,6 +1698,38 @@ namespace ArdupilotMega
|
||||
}
|
||||
}
|
||||
|
||||
public static void doupdate()
|
||||
{
|
||||
//System.Threading.Thread t12 = new System.Threading.Thread(delegate()
|
||||
{
|
||||
|
||||
Form loading = new Form();
|
||||
loading.Width = 400;
|
||||
loading.Height = 150;
|
||||
loading.StartPosition = FormStartPosition.CenterScreen;
|
||||
loading.TopMost = true;
|
||||
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(MainV2));
|
||||
loading.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon")));
|
||||
|
||||
Label loadinglabel = new Label();
|
||||
loadinglabel.Location = new System.Drawing.Point(50, 40);
|
||||
loadinglabel.Name = "load";
|
||||
loadinglabel.AutoSize = true;
|
||||
loadinglabel.Text = "Checking...";
|
||||
loadinglabel.Size = new System.Drawing.Size(100, 20);
|
||||
|
||||
loading.Controls.Add(loadinglabel);
|
||||
loading.Show();
|
||||
|
||||
try { MainV2.updatecheck(loadinglabel); } catch (Exception ex) { Console.WriteLine(ex.ToString()); }
|
||||
|
||||
}
|
||||
//);
|
||||
//t12.Name = "Update check thread";
|
||||
//t12.Start();
|
||||
//MainV2.threads.Add(t12);
|
||||
}
|
||||
|
||||
private static bool updatecheck(Label loadinglabel, string baseurl, string subdir)
|
||||
{
|
||||
bool update = false;
|
||||
|
@ -29,16 +29,19 @@ namespace ArdupilotMega
|
||||
|
||||
//Common.linearRegression();
|
||||
|
||||
var answer = HIL.Utils.EarthRatesToBodyRatesRyan(0, 0, 0, 0, 5, 0);
|
||||
var answer = HIL.Utils.EarthRatesToBodyRatesMine(0, 0, 0, 0, 5, 0);
|
||||
Console.WriteLine("roll {0:0.000} {1:0.000} {2:0.000} ", answer.Item1 , answer.Item2 , answer.Item3);
|
||||
|
||||
answer = HIL.Utils.EarthRatesToBodyRatesRyan(0, 0, 45, 2.5, 2.5, 0);
|
||||
answer = HIL.Utils.EarthRatesToBodyRatesMine(0, 0, 45, 0, 5, 0);
|
||||
Console.WriteLine("roll {0:0.000} {1:0.000} {2:0.000} ", answer.Item1, answer.Item2, answer.Item3);
|
||||
|
||||
answer = HIL.Utils.EarthRatesToBodyRatesRyan(0, 0, 90, 5, 0, 0);
|
||||
answer = HIL.Utils.EarthRatesToBodyRatesMine(0, 0, 90, 0, 5, 0);
|
||||
Console.WriteLine("roll {0:0.000} {1:0.000} {2:0.000} ", answer.Item1, answer.Item2, answer.Item3);
|
||||
|
||||
// Console.ReadLine();
|
||||
answer = HIL.Utils.EarthRatesToBodyRatesMine(0, 0, 135, 0, 5, 0);
|
||||
Console.WriteLine("roll {0:0.000} {1:0.000} {2:0.000} ", answer.Item1, answer.Item2, answer.Item3);
|
||||
|
||||
//Console.ReadLine();
|
||||
|
||||
//return;
|
||||
|
||||
|
@ -34,5 +34,5 @@ using System.Resources;
|
||||
// by using the '*' as shown below:
|
||||
// [assembly: AssemblyVersion("1.0.*")]
|
||||
[assembly: AssemblyVersion("1.0.0.0")]
|
||||
[assembly: AssemblyFileVersion("1.1.27")]
|
||||
[assembly: AssemblyFileVersion("1.1.28")]
|
||||
[assembly: NeutralResourcesLanguageAttribute("")]
|
||||
|
@ -146,8 +146,14 @@ namespace ArdupilotMega.Setup
|
||||
MainV2.cs.rateposition = 0;
|
||||
MainV2.cs.ratestatus = 0;
|
||||
|
||||
try
|
||||
{
|
||||
|
||||
MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RC_CHANNELS, 10);
|
||||
|
||||
}
|
||||
catch { }
|
||||
|
||||
BUT_Calibrateradio.Text = "Click when Done";
|
||||
|
||||
run = true;
|
||||
@ -253,8 +259,14 @@ namespace ArdupilotMega.Setup
|
||||
MainV2.cs.rateposition = oldpos;
|
||||
MainV2.cs.ratestatus = oldstatus;
|
||||
|
||||
try
|
||||
{
|
||||
|
||||
MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RC_CHANNELS, oldrc);
|
||||
|
||||
}
|
||||
catch { }
|
||||
|
||||
if (Configuration != null)
|
||||
{
|
||||
Configuration.startup = true;
|
||||
@ -408,14 +420,29 @@ namespace ArdupilotMega.Setup
|
||||
bool not_supported = false;
|
||||
if (MainV2.comPort.param["BATT_MONITOR"] != null)
|
||||
{
|
||||
if (MainV2.comPort.param["BATT_MONITOR"].ToString() != "0")
|
||||
if (MainV2.comPort.param["BATT_MONITOR"].ToString() != "0.0")
|
||||
{
|
||||
CMB_batmontype.SelectedIndex = getIndex(CMB_batmontype,(int)float.Parse(MainV2.comPort.param["BATT_MONITOR"].ToString()));
|
||||
}
|
||||
|
||||
if (TXT_ampspervolt.Text == "13.6612")
|
||||
{
|
||||
CMB_batmonsensortype.SelectedIndex = 1;
|
||||
}
|
||||
else if (TXT_ampspervolt.Text == "27.3224")
|
||||
{
|
||||
CMB_batmonsensortype.SelectedIndex = 2;
|
||||
}
|
||||
else if (TXT_ampspervolt.Text == "54.64481")
|
||||
{
|
||||
CMB_batmonsensortype.SelectedIndex = 3;
|
||||
}
|
||||
else
|
||||
{
|
||||
CMB_batmonsensortype.SelectedIndex = 0;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
if (MainV2.comPort.param["BATT_CAPACITY"] != null)
|
||||
TXT_battcapacity.Text = MainV2.comPort.param["BATT_CAPACITY"].ToString();
|
||||
@ -729,6 +756,9 @@ namespace ArdupilotMega.Setup
|
||||
groupBox4.Enabled = true;
|
||||
CMB_batmonsensortype.Enabled = false;
|
||||
TXT_ampspervolt.Enabled = false;
|
||||
TXT_inputvoltage.Enabled = true;
|
||||
TXT_measuredvoltage.Enabled = true;
|
||||
TXT_divider.Enabled = true;
|
||||
}
|
||||
|
||||
MainV2.comPort.setParam("BATT_MONITOR", selection);
|
||||
|
File diff suppressed because it is too large
Load Diff
Loading…
Reference in New Issue
Block a user