mirror of https://github.com/ArduPilot/ardupilot
Configurator.Net: More tweaks for Mono
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1562 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
4cc0992e65
commit
e545eb1758
|
@ -76,8 +76,20 @@ namespace ArducopterConfigurator
|
|||
void bgWorker_ProgressChanged(object sender, ProgressChangedEventArgs e)
|
||||
{
|
||||
// Thanks to BG worker, this should be raised on the UI thread
|
||||
|
||||
var lineReceived = e.UserState as string;
|
||||
if (LineOfDataReceived != null)
|
||||
|
||||
|
||||
// for (int i = 0; i < lineReceived.Length; i++)
|
||||
// {
|
||||
// var c = lineReceived[i];
|
||||
// Console.WriteLine("{0}] U+{1:x4} {2}", i, (int)c, (int)c);
|
||||
// }
|
||||
//
|
||||
//
|
||||
//
|
||||
|
||||
if (LineOfDataReceived != null)
|
||||
LineOfDataReceived(lineReceived);
|
||||
}
|
||||
|
||||
|
|
|
@ -1,3 +1,4 @@
|
|||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Diagnostics;
|
||||
|
||||
|
@ -25,6 +26,7 @@ namespace ArducopterConfigurator.PresentationModels
|
|||
|
||||
protected override void OnStringReceived(string strRx)
|
||||
{
|
||||
Console.WriteLine("Badoosh strnig rxd");
|
||||
PopulatePropsFromUpdate(strRx,true);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -1,3 +1,4 @@
|
|||
using System;
|
||||
using System.Diagnostics;
|
||||
using System.Text;
|
||||
|
||||
|
@ -86,11 +87,15 @@ namespace ArducopterConfigurator
|
|||
// property update order, and reflection to get the property type
|
||||
protected void PopulatePropsFromUpdate(string strRx, bool fireInpc)
|
||||
{
|
||||
|
||||
|
||||
var strs = strRx.Split(',');
|
||||
|
||||
|
||||
|
||||
if (PropsInUpdateOrder.Length!=strs.Length)
|
||||
{
|
||||
Debug.WriteLine("Processing update with only " + strs.Length
|
||||
Console.WriteLine("Processing update with only " + strs.Length
|
||||
+ " values, but have " + PropsInUpdateOrder.Length
|
||||
+ " properties to populate. Ignoring this update");
|
||||
return;
|
||||
|
@ -107,7 +112,7 @@ namespace ArducopterConfigurator
|
|||
float val;
|
||||
if (!float.TryParse(s, out val))
|
||||
{
|
||||
Debug.WriteLine("Error parsing float: " + s);
|
||||
Console.WriteLine("Error parsing float: " + s);
|
||||
break;
|
||||
}
|
||||
value = val;
|
||||
|
@ -117,7 +122,7 @@ namespace ArducopterConfigurator
|
|||
float val;
|
||||
if (!float.TryParse(s, out val))
|
||||
{
|
||||
Debug.WriteLine("Error parsing float (bool): " + s);
|
||||
Console.WriteLine("Error parsing float (bool): " + s);
|
||||
break;
|
||||
}
|
||||
value = val != 0.0;
|
||||
|
@ -128,7 +133,7 @@ namespace ArducopterConfigurator
|
|||
int val;
|
||||
if (!int.TryParse(s, out val))
|
||||
{
|
||||
Debug.WriteLine("Error parsing int: " + s);
|
||||
Console.WriteLine("Error parsing int: " + s);
|
||||
break;
|
||||
}
|
||||
value = val;
|
||||
|
@ -136,6 +141,9 @@ namespace ArducopterConfigurator
|
|||
|
||||
prop.SetValue(this, value, null);
|
||||
|
||||
Console.WriteLine("Badoosh firing inpc");
|
||||
|
||||
|
||||
if (fireInpc)
|
||||
FirePropertyChanged(PropsInUpdateOrder[i]);
|
||||
}
|
||||
|
|
|
@ -30,7 +30,12 @@ namespace ArducopterConfigurator.PresentationModels
|
|||
|
||||
public float KPrate { get; set; }
|
||||
|
||||
public bool MagnetometerEnable { get; set; }
|
||||
private bool magnetometerEnable;
|
||||
public bool MagnetometerEnable
|
||||
{
|
||||
get { return magnetometerEnable; }
|
||||
set { magnetometerEnable = value; }
|
||||
}
|
||||
|
||||
private void RefreshValues()
|
||||
{
|
||||
|
|
|
@ -71,10 +71,6 @@ namespace ArducopterConfigurator.PresentationModels
|
|||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
private int _mode;
|
||||
public int Mode
|
||||
{
|
||||
|
@ -154,42 +150,6 @@ namespace ArducopterConfigurator.PresentationModels
|
|||
PopulatePropsFromUpdate(strReceived,false);
|
||||
}
|
||||
|
||||
|
||||
private void manualPropset(string strReceived)
|
||||
{
|
||||
// PopulatePropsFromUpdate(strReceived,false);
|
||||
var strs = strReceived.Split(',');
|
||||
var ints = new List<int>();
|
||||
foreach (var s in strs)
|
||||
{
|
||||
int val;
|
||||
if (!int.TryParse(s, out val))
|
||||
{
|
||||
Debug.WriteLine("Could not parse expected integer: " + s);
|
||||
return;
|
||||
}
|
||||
ints.Add(val);
|
||||
}
|
||||
|
||||
if (ints.Count != 9)
|
||||
{
|
||||
Debug.WriteLine("Tx Data sentence expected, but only got one of size: " + ints.Count);
|
||||
return;
|
||||
}
|
||||
|
||||
Roll = ints[0];
|
||||
// Pitch = ints[1];
|
||||
// Yaw = ints[2];
|
||||
Throttle = ints[3];
|
||||
// Mode = ints[4];
|
||||
// Aux = ints[5];
|
||||
// RollMidValue = ints[6];
|
||||
// PitchMidValue = ints[7];
|
||||
// YawMidValue = ints[8];
|
||||
|
||||
|
||||
}
|
||||
|
||||
public override string Name
|
||||
{
|
||||
get { return "Transmitter Channels"; }
|
||||
|
|
|
@ -24,9 +24,13 @@ namespace ArducopterConfigurator
|
|||
var session = new CommsSession();
|
||||
//var session = new FakeCommsSession();
|
||||
|
||||
|
||||
var mainVm = new MainVm(session);
|
||||
|
||||
|
||||
Application.Run(new mainForm(mainVm));
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
}
|
||||
|
|
|
@ -20,6 +20,9 @@ namespace ArducopterConfigurator.Views
|
|||
public override void SetDataContext(AcroModeConfigVm model)
|
||||
{
|
||||
AcroModeConfigVmBindingSource.DataSource = model;
|
||||
|
||||
if (Program.IsMonoRuntime)
|
||||
model.PropertyChanged += ((sender, e) => AcroModeConfigVmBindingSource.ResetBindings(false));
|
||||
}
|
||||
|
||||
}
|
||||
|
|
|
@ -20,6 +20,9 @@ namespace ArducopterConfigurator.Views
|
|||
public override void SetDataContext(AltitudeHoldConfigVm model)
|
||||
{
|
||||
AltitudeHoldConfigBindingSource.DataSource = model;
|
||||
|
||||
if (Program.IsMonoRuntime)
|
||||
model.PropertyChanged += ((sender, e) => AltitudeHoldConfigBindingSource.ResetBindings(false));
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -20,6 +20,10 @@ namespace ArducopterConfigurator.Views
|
|||
public override void SetDataContext(CalibrationOffsetsDataVm model)
|
||||
{
|
||||
calibrationOffsetsDataVmBindingSource.DataSource = model;
|
||||
|
||||
|
||||
if (Program.IsMonoRuntime)
|
||||
model.PropertyChanged += ((sender, e) => calibrationOffsetsDataVmBindingSource.ResetBindings(false));
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -18,7 +18,9 @@ namespace ArducopterConfigurator.Views
|
|||
public override void SetDataContext(PositionHoldConfigVm model)
|
||||
{
|
||||
PositionHoldConfigBindingSource.DataSource = model;
|
||||
_vm = model;
|
||||
|
||||
if (Program.IsMonoRuntime)
|
||||
model.PropertyChanged += ((sender, e) => PositionHoldConfigBindingSource.ResetBindings(false));
|
||||
}
|
||||
}
|
||||
// Required for VS2008 designer. No functional value
|
||||
|
|
|
@ -20,6 +20,13 @@ namespace ArducopterConfigurator.Views
|
|||
public override void SetDataContext(StableModeConfigVm model)
|
||||
{
|
||||
StableModeConfigVmBindingSource.DataSource = model;
|
||||
|
||||
if (Program.IsMonoRuntime)
|
||||
model.PropertyChanged += (delegate
|
||||
{
|
||||
Console.WriteLine("Badoosh1");
|
||||
StableModeConfigVmBindingSource.ResetBindings(false);
|
||||
});
|
||||
}
|
||||
|
||||
}
|
||||
|
|
|
@ -19,6 +19,9 @@ namespace ArducopterConfigurator.Views
|
|||
public override void SetDataContext(TransmitterChannelsVm model)
|
||||
{
|
||||
TransmitterChannelsBindingSource.DataSource = model;
|
||||
|
||||
if (Program.IsMonoRuntime)
|
||||
model.PropertyChanged += ((sender, e) => TransmitterChannelsBindingSource.ResetBindings(false));
|
||||
}
|
||||
|
||||
}
|
||||
|
|
|
@ -7,8 +7,6 @@ namespace ArducopterConfigurator.Views
|
|||
// cannot be abstract due to vs2008 designer
|
||||
public class ViewCommon<T> : UserControl, IView<T> where T : IPresentationModel
|
||||
{
|
||||
protected T _vm;
|
||||
|
||||
public virtual void SetDataContext(T model)
|
||||
{
|
||||
}
|
||||
|
|
|
@ -1,6 +1,7 @@
|
|||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Diagnostics;
|
||||
using System.Drawing;
|
||||
using System.Data;
|
||||
using System.Drawing.Drawing2D;
|
||||
|
@ -330,7 +331,15 @@ namespace ArducopterConfigurator.Views.controls
|
|||
public int Value
|
||||
{
|
||||
get { return _val; }
|
||||
set { _val = value; Refresh(); }
|
||||
set
|
||||
{
|
||||
if (_val != value)
|
||||
{
|
||||
_val = value;
|
||||
Refresh();
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
[System.ComponentModel.Description("Gets or sets whether the indicator is vertical")]
|
||||
|
|
|
@ -128,7 +128,6 @@ namespace ArducopterConfigurator
|
|||
|
||||
private void tabCtrlConfigs_Selected(object sender, TabControlEventArgs e)
|
||||
{
|
||||
Console.WriteLine("Tab click");
|
||||
var control = e.TabPage.Controls[0];
|
||||
control.Size = e.TabPage.ClientRectangle.Size;
|
||||
var tabVm = e.TabPage.Tag as MonitorVm;
|
||||
|
|
Loading…
Reference in New Issue