mirror of https://github.com/ArduPilot/ardupilot
Configurator.Net: Refactor of simple Update/Refresh Vms
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1654 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
991acad1f0
commit
b37c09d56e
|
@ -46,12 +46,13 @@
|
|||
<Compile Include="PresentationModels\AltitudeHoldConfigVm.cs" />
|
||||
<Compile Include="PresentationModels\ConfigWithPidsBase.cs" />
|
||||
<Compile Include="Core\DelegateCommand.cs" />
|
||||
<Compile Include="PresentationModels\CrudVm.cs" />
|
||||
<Compile Include="PresentationModels\DoubleVm.cs" />
|
||||
<Compile Include="PresentationModels\PositionAltitudePidsVm.cs" />
|
||||
<Compile Include="PresentationModels\FlightControlPidsVm.cs" />
|
||||
<Compile Include="PresentationModels\ItalksToApm.cs" />
|
||||
<Compile Include="PresentationModels\MainVm.cs" />
|
||||
<Compile Include="PresentationModels\FlightDataMonitorVm.cs" />
|
||||
<Compile Include="PresentationModels\SensorsVm.cs" />
|
||||
<Compile Include="PresentationModels\VmBase.cs" />
|
||||
<Compile Include="Views\controls\LinearIndicatorControl.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
|
|
|
@ -2,7 +2,7 @@ using System.ComponentModel;
|
|||
|
||||
namespace ArducopterConfigurator
|
||||
{
|
||||
public abstract class NotifyProperyChangedBase : INotifyPropertyChanged
|
||||
public abstract class NotifyProperyChangedBase : INotifyPropertyChanged, ISupportsExternalInvokedInpc
|
||||
{
|
||||
public event PropertyChangedEventHandler PropertyChanged;
|
||||
|
||||
|
@ -21,7 +21,7 @@ namespace ArducopterConfigurator
|
|||
return false;
|
||||
}
|
||||
|
||||
protected void FirePropertyChanged(string propertyName)
|
||||
public void FirePropertyChanged(string propertyName)
|
||||
{
|
||||
if (PropertyChanged != null)
|
||||
PropertyChanged(this, new PropertyChangedEventArgs(propertyName));
|
||||
|
|
|
@ -2,10 +2,13 @@ using System;
|
|||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public class AcroModeConfigVm : ConfigWithPidsBase, IPresentationModel, ItalksToApm
|
||||
public class AcroModeConfigVm : ConfigWithPidsBase
|
||||
{
|
||||
public AcroModeConfigVm()
|
||||
{
|
||||
updateString = "O";
|
||||
refreshString = "P";
|
||||
|
||||
PropsInUpdateOrder = new[]
|
||||
{
|
||||
"RollP",
|
||||
|
@ -19,55 +22,13 @@ namespace ArducopterConfigurator.PresentationModels
|
|||
"YawD",
|
||||
"TransmitterFactor",
|
||||
};
|
||||
|
||||
RefreshCommand = new DelegateCommand(_ => RefreshValues());
|
||||
UpdateCommand = new DelegateCommand(_ => UpdateValues());
|
||||
}
|
||||
|
||||
public float TransmitterFactor { get; set; }
|
||||
|
||||
public ICommand RefreshCommand { get; private set; }
|
||||
|
||||
public ICommand UpdateCommand { get; private set; }
|
||||
|
||||
|
||||
public void UpdateValues()
|
||||
{
|
||||
if (sendTextToApm != null)
|
||||
sendTextToApm(this, new sendTextToApmEventArgs(ComposePropsWithCommand("O")));
|
||||
}
|
||||
|
||||
public void RefreshValues()
|
||||
{
|
||||
if (sendTextToApm != null)
|
||||
sendTextToApm(this, new sendTextToApmEventArgs("P"));
|
||||
|
||||
}
|
||||
|
||||
public string Name
|
||||
public override string Name
|
||||
{
|
||||
get { return "Acro Mode"; }
|
||||
}
|
||||
|
||||
public void Activate()
|
||||
{
|
||||
RefreshValues();
|
||||
}
|
||||
|
||||
public void DeActivate()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
public event EventHandler updatedByApm;
|
||||
|
||||
public void handleLineOfText(string strRx)
|
||||
{
|
||||
PopulatePropsFromUpdate(strRx,true);
|
||||
if (updatedByApm != null)
|
||||
updatedByApm(this, EventArgs.Empty);
|
||||
}
|
||||
|
||||
public event EventHandler<sendTextToApmEventArgs> sendTextToApm;
|
||||
}
|
||||
}
|
|
@ -9,59 +9,24 @@ namespace ArducopterConfigurator.PresentationModels
|
|||
/// Todo: this one is weird because the APM sends and receives the values
|
||||
/// in a different order
|
||||
/// There is a unit test to cover it but it will need fixing.
|
||||
/// TODO: test this
|
||||
/// </remarks>
|
||||
public class AltitudeHoldConfigVm : VmBase, IPresentationModel, ItalksToApm
|
||||
public class AltitudeHoldConfigVm : CrudVm, IPresentationModel, ISupportsPropertyPopulation
|
||||
{
|
||||
public AltitudeHoldConfigVm()
|
||||
{
|
||||
PropsInUpdateOrder = new[] { "P", "I", "D", };
|
||||
|
||||
RefreshCommand = new DelegateCommand(_ => RefreshValues());
|
||||
UpdateCommand = new DelegateCommand(_ => UpdateValues());
|
||||
updateString = "E";
|
||||
refreshString = "F";
|
||||
PropsInUpdateOrder = new[] {"P", "I", "D",};
|
||||
}
|
||||
|
||||
public ICommand RefreshCommand { get; private set; }
|
||||
public ICommand UpdateCommand { get; private set; }
|
||||
|
||||
public float P { get; set; }
|
||||
public float I { get; set; }
|
||||
public float D { get; set; }
|
||||
|
||||
|
||||
private void RefreshValues()
|
||||
{
|
||||
if (sendTextToApm != null)
|
||||
sendTextToApm(this, new sendTextToApmEventArgs("F"));
|
||||
}
|
||||
|
||||
public void UpdateValues()
|
||||
{
|
||||
if (sendTextToApm != null)
|
||||
sendTextToApm(this, new sendTextToApmEventArgs(ComposePropsWithCommand("E")));
|
||||
}
|
||||
|
||||
public string Name
|
||||
public override string Name
|
||||
{
|
||||
get { return "Altitude Hold"; }
|
||||
}
|
||||
|
||||
public void Activate()
|
||||
{
|
||||
RefreshValues();
|
||||
}
|
||||
|
||||
public void DeActivate()
|
||||
{
|
||||
}
|
||||
|
||||
public event EventHandler updatedByApm;
|
||||
|
||||
public void handleLineOfText(string strRx)
|
||||
{
|
||||
PopulatePropsFromUpdate(strRx, true);
|
||||
|
||||
}
|
||||
|
||||
public event EventHandler<sendTextToApmEventArgs> sendTextToApm;
|
||||
}
|
||||
}
|
|
@ -4,7 +4,7 @@ using System.Diagnostics;
|
|||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public class CalibrationOffsetsDataVm : VmBase, IPresentationModel, ItalksToApm
|
||||
public class CalibrationOffsetsDataVm : VmBase, IPresentationModel
|
||||
{
|
||||
public CalibrationOffsetsDataVm()
|
||||
{
|
||||
|
|
|
@ -1,10 +1,9 @@
|
|||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Diagnostics;
|
||||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public abstract class ConfigWithPidsBase : VmBase
|
||||
public abstract class ConfigWithPidsBase : CrudVm
|
||||
{
|
||||
|
||||
public float RollP { get; set; }
|
||||
|
@ -18,5 +17,7 @@ namespace ArducopterConfigurator.PresentationModels
|
|||
public float YawP { get; set; }
|
||||
public float YawI { get; set; }
|
||||
public float YawD { get; set; }
|
||||
|
||||
|
||||
}
|
||||
}
|
|
@ -0,0 +1,65 @@
|
|||
using System;
|
||||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
/// <summary>
|
||||
/// Common base for the simple VMs that deal with an update from APM and Get and Update them
|
||||
/// </summary>
|
||||
public abstract class CrudVm : NotifyProperyChangedBase, ISupportsPropertyPopulation, ItalksToApm, IPresentationModel
|
||||
{
|
||||
protected string updateString;
|
||||
protected string refreshString;
|
||||
|
||||
protected CrudVm()
|
||||
{
|
||||
RefreshCommand = new DelegateCommand(_ => RefreshValues());
|
||||
UpdateCommand = new DelegateCommand(_ => UpdateValues());
|
||||
}
|
||||
|
||||
public string[] PropsInUpdateOrder { get; protected set; }
|
||||
|
||||
public ICommand RefreshCommand { get; private set; }
|
||||
|
||||
public ICommand UpdateCommand { get; private set; }
|
||||
|
||||
protected void RefreshValues()
|
||||
{
|
||||
if (sendTextToApm != null)
|
||||
sendTextToApm(this, new sendTextToApmEventArgs(refreshString));
|
||||
|
||||
}
|
||||
|
||||
protected void UpdateValues()
|
||||
{
|
||||
if (sendTextToApm != null)
|
||||
{
|
||||
var apmString = PropertyHelper.ComposePropValuesWithCommand(this, updateString);
|
||||
sendTextToApm(this, new sendTextToApmEventArgs(apmString));
|
||||
}
|
||||
}
|
||||
|
||||
public abstract string Name { get; }
|
||||
|
||||
public void Activate()
|
||||
{
|
||||
RefreshValues();
|
||||
}
|
||||
|
||||
public void DeActivate()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
public void handleLineOfText(string strRx)
|
||||
{
|
||||
PropertyHelper.PopulatePropsFromUpdate(this, strRx, true);
|
||||
|
||||
if (updatedByApm != null)
|
||||
updatedByApm(this, EventArgs.Empty);
|
||||
}
|
||||
|
||||
public event EventHandler<sendTextToApmEventArgs> sendTextToApm;
|
||||
|
||||
public event EventHandler updatedByApm;
|
||||
}
|
||||
}
|
|
@ -23,7 +23,7 @@ namespace ArducopterConfigurator.PresentationModels
|
|||
|
||||
MonitorVms = new BindingList<IPresentationModel>
|
||||
{
|
||||
new FlightDataVm(),
|
||||
new SensorsVm(),
|
||||
new TransmitterChannelsVm(),
|
||||
new FlightControlPidsVm(),
|
||||
new PositionAltitudePidsVm(),
|
||||
|
|
|
@ -2,10 +2,13 @@ using System;
|
|||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public class PositionHoldConfigVm : ConfigWithPidsBase, IPresentationModel, ItalksToApm
|
||||
public class PositionHoldConfigVm : ConfigWithPidsBase
|
||||
{
|
||||
public PositionHoldConfigVm()
|
||||
{
|
||||
updateString = "C";
|
||||
refreshString = "D";
|
||||
|
||||
PropsInUpdateOrder = new[]
|
||||
{
|
||||
"RollP",
|
||||
|
@ -17,58 +20,15 @@ namespace ArducopterConfigurator.PresentationModels
|
|||
"MaximumAngle",
|
||||
"GeoCorrectionFactor",
|
||||
};
|
||||
|
||||
RefreshCommand = new DelegateCommand(_ => RefreshValues());
|
||||
UpdateCommand = new DelegateCommand(_ => UpdateValues());
|
||||
}
|
||||
|
||||
public float MaximumAngle { get; set; }
|
||||
|
||||
public float GeoCorrectionFactor { get; set; }
|
||||
|
||||
public ICommand RefreshCommand { get; private set; }
|
||||
|
||||
public ICommand UpdateCommand { get; private set; }
|
||||
|
||||
//Send an 'C' followed by numeric values to transmit user defined roll and pitch PID values for gyro stabilized flight control. Each value is separated by a semi-colon in the form:
|
||||
//C[P GPS ROLL];[I GPS ROLL];[D GPS ROLL];[P GPS PITCH];[I GPS PITCH];[D GPS PITCH];[GPS MAX ANGLE];[GEOG Correction factor]
|
||||
public void UpdateValues()
|
||||
{
|
||||
if (sendTextToApm != null)
|
||||
sendTextToApm(this,new sendTextToApmEventArgs(ComposePropsWithCommand("C")));
|
||||
}
|
||||
|
||||
public void RefreshValues()
|
||||
{
|
||||
if (sendTextToApm != null)
|
||||
sendTextToApm(this,new sendTextToApmEventArgs("D"));
|
||||
}
|
||||
|
||||
public string Name
|
||||
public override string Name
|
||||
{
|
||||
get { return "Position Hold"; }
|
||||
}
|
||||
|
||||
public void Activate()
|
||||
{
|
||||
RefreshValues();
|
||||
}
|
||||
|
||||
public void DeActivate()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
public void handleLineOfText(string strRx)
|
||||
{
|
||||
PopulatePropsFromUpdate(strRx,true);
|
||||
if (updatedByApm != null)
|
||||
updatedByApm(this,EventArgs.Empty);
|
||||
|
||||
}
|
||||
|
||||
public event EventHandler<sendTextToApmEventArgs> sendTextToApm;
|
||||
|
||||
public event EventHandler updatedByApm;
|
||||
}
|
||||
}
|
|
@ -5,11 +5,31 @@ using System.IO.Ports;
|
|||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public class FlightDataVm : VmBase, IPresentationModel, ItalksToApm
|
||||
/// <summary>
|
||||
/// View Model for the sensors monitor and calibration
|
||||
/// </summary>
|
||||
/// <remarks>
|
||||
/// This tab is for the monitoring and calibration of the Gyro/Accel sensors
|
||||
///
|
||||
/// When it is activated, it retrieves the current sensor calibration values
|
||||
/// Then, it requests the constant stream of sensor readings in order to provide
|
||||
/// a live view.
|
||||
///
|
||||
/// The user can change the calibration offsets, and upload the new values.
|
||||
/// When this happens, the model tells the APM to cease sending the realtime updates,
|
||||
/// then sends the new offset values, then resumes the updates
|
||||
///
|
||||
/// There is a command to automatically fill the sensor offset values, from the
|
||||
/// current values of the sensors. The user would do this when the copter is
|
||||
/// sitting still and level
|
||||
///
|
||||
/// When the VM is deactivated, the model tells the APM to cease sending the realtime updates
|
||||
/// </remarks>
|
||||
public class SensorsVm : VmBase, IPresentationModel
|
||||
{
|
||||
public string Name
|
||||
{
|
||||
get { return "Flight Data"; }
|
||||
get { return "Sensor Data"; }
|
||||
}
|
||||
|
||||
public void Activate()
|
||||
|
@ -31,29 +51,7 @@ namespace ArducopterConfigurator.PresentationModels
|
|||
|
||||
public void handleLineOfText(string strRx)
|
||||
{
|
||||
OnStringReceived(strRx);
|
||||
}
|
||||
|
||||
public event EventHandler<sendTextToApmEventArgs> sendTextToApm;
|
||||
|
||||
|
||||
// 2,-10,3,-2,1011,1012,1002,1000,1001,1003,1002,1004
|
||||
// Loop Time = 2
|
||||
// Roll Gyro Rate = -10
|
||||
// Pitch Gyro Rate = 3
|
||||
// Yaw Gyro Rate = -2
|
||||
// Throttle Output = 1011
|
||||
// Roll PID Output = 1012
|
||||
// Pitch PID Output = 1002
|
||||
// Yaw PID Output 1000
|
||||
// Front Motor Command = 1001 PWM output sent to right motor (ranges from 1000-2000)
|
||||
// Rear Motor Command 1003
|
||||
// Right Motor Command = 1002
|
||||
// Left Motor Command = 1004
|
||||
// then adc 4,3, and 5
|
||||
private void OnStringReceived(string data)
|
||||
{
|
||||
var strs = data.Split(',');
|
||||
var strs = strRx.Split(',');
|
||||
var ints = new List<int>();
|
||||
foreach (var s in strs)
|
||||
{
|
||||
|
@ -85,6 +83,24 @@ namespace ArducopterConfigurator.PresentationModels
|
|||
AccelZ = ints[14];
|
||||
}
|
||||
|
||||
public event EventHandler<sendTextToApmEventArgs> sendTextToApm;
|
||||
|
||||
|
||||
// 2,-10,3,-2,1011,1012,1002,1000,1001,1003,1002,1004
|
||||
// Loop Time = 2
|
||||
// Roll Gyro Rate = -10
|
||||
// Pitch Gyro Rate = 3
|
||||
// Yaw Gyro Rate = -2
|
||||
// Throttle Output = 1011
|
||||
// Roll PID Output = 1012
|
||||
// Pitch PID Output = 1002
|
||||
// Yaw PID Output 1000
|
||||
// Front Motor Command = 1001 PWM output sent to right motor (ranges from 1000-2000)
|
||||
// Rear Motor Command 1003
|
||||
// Right Motor Command = 1002
|
||||
// Left Motor Command = 1004
|
||||
// then adc 4,3, and 5
|
||||
|
||||
|
||||
private int _loopTime;
|
||||
public int LoopTime
|
|
@ -2,10 +2,13 @@ using System;
|
|||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public class StableModeConfigVm : ConfigWithPidsBase, IPresentationModel, ItalksToApm
|
||||
public class StableModeConfigVm : ConfigWithPidsBase
|
||||
{
|
||||
public StableModeConfigVm()
|
||||
{
|
||||
updateString = "A";
|
||||
refreshString = "B";
|
||||
|
||||
PropsInUpdateOrder = new[]
|
||||
{
|
||||
"RollP",
|
||||
|
@ -20,59 +23,15 @@ namespace ArducopterConfigurator.PresentationModels
|
|||
"KPrate",
|
||||
"MagnetometerEnable",
|
||||
};
|
||||
|
||||
RefreshCommand = new DelegateCommand(_ => RefreshValues());
|
||||
UpdateCommand = new DelegateCommand(_ => UpdateValues());
|
||||
}
|
||||
|
||||
public ICommand RefreshCommand { get; private set; }
|
||||
|
||||
public ICommand UpdateCommand { get; private set; }
|
||||
|
||||
public float KPrate { get; set; }
|
||||
|
||||
private bool magnetometerEnable;
|
||||
public bool MagnetometerEnable
|
||||
{
|
||||
get { return magnetometerEnable; }
|
||||
set { magnetometerEnable = value; }
|
||||
}
|
||||
public bool MagnetometerEnable { get; set; }
|
||||
|
||||
private void RefreshValues()
|
||||
{
|
||||
if (sendTextToApm != null)
|
||||
sendTextToApm(this, new sendTextToApmEventArgs("B"));
|
||||
|
||||
}
|
||||
|
||||
public void UpdateValues()
|
||||
{
|
||||
if (sendTextToApm != null)
|
||||
sendTextToApm(this,new sendTextToApmEventArgs(ComposePropsWithCommand("A")));
|
||||
}
|
||||
|
||||
public string Name
|
||||
public override string Name
|
||||
{
|
||||
get { return "Stable Mode"; }
|
||||
}
|
||||
|
||||
public void Activate()
|
||||
{
|
||||
RefreshValues();
|
||||
}
|
||||
|
||||
public void DeActivate()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
public event EventHandler updatedByApm;
|
||||
|
||||
public void handleLineOfText(string strRx)
|
||||
{
|
||||
PopulatePropsFromUpdate(strRx,true);
|
||||
}
|
||||
|
||||
public event EventHandler<sendTextToApmEventArgs> sendTextToApm;
|
||||
}
|
||||
}
|
|
@ -4,7 +4,7 @@ using System.Diagnostics;
|
|||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public class TransmitterChannelsVm : VmBase, ItalksToApm, IPresentationModel
|
||||
public class TransmitterChannelsVm : VmBase, IPresentationModel
|
||||
{
|
||||
public TransmitterChannelsVm()
|
||||
{
|
||||
|
|
|
@ -2,6 +2,122 @@ using System;
|
|||
|
||||
namespace ArducopterConfigurator
|
||||
{
|
||||
|
||||
public interface ISupportsExternalInvokedInpc
|
||||
{
|
||||
void FirePropertyChanged(string propName);
|
||||
}
|
||||
|
||||
|
||||
public interface ISupportsPropertyPopulation : ISupportsExternalInvokedInpc
|
||||
{
|
||||
string [] PropsInUpdateOrder { get;}
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Helper class that takes an update from the APM and writes to properties of an object using reflection
|
||||
/// </summary>
|
||||
/// <remarks>
|
||||
/// The APM gives us a stream of values .eg 4.0,5.2,3.4 etc
|
||||
/// They are in a certain known order, e.g pitch P, pitch I, pitch D... etc
|
||||
///
|
||||
/// instead of having specific value assignment logic in every class to pick
|
||||
/// apart the update and populate properties, this guy will Set the properties
|
||||
/// in the correct order. All the interested class needs to provide is the
|
||||
/// list of property names in the same order as the update from the APM
|
||||
/// </remarks>
|
||||
public static class PropertyHelper
|
||||
{
|
||||
// Common method for creating the update data
|
||||
// sentence sent to APM is the commandChar followed by the property
|
||||
// vals in the correct order, seperated by semicolons
|
||||
public static string ComposePropValuesWithCommand(ISupportsPropertyPopulation obj, string commandChar)
|
||||
{
|
||||
var strings = new string[obj.PropsInUpdateOrder.Length];
|
||||
for (int i = 0; i < obj.PropsInUpdateOrder.Length; i++)
|
||||
{
|
||||
var prop = obj.GetType().GetProperty(obj.PropsInUpdateOrder[i]);
|
||||
|
||||
if (prop.PropertyType == typeof(bool))
|
||||
strings[i] = ((bool)prop.GetValue(obj, null)) ? "1" : "0";
|
||||
else
|
||||
strings[i] = prop.GetValue(obj, null).ToString();
|
||||
|
||||
}
|
||||
|
||||
return commandChar + string.Join(";", strings);
|
||||
}
|
||||
|
||||
// Common method for populating properties, using a hardcoded
|
||||
// property update order, and reflection to get the property type
|
||||
public static void PopulatePropsFromUpdate(ISupportsPropertyPopulation obj,string strRx, bool fireInpc)
|
||||
{
|
||||
var strs = strRx.Split(',');
|
||||
|
||||
if (obj.PropsInUpdateOrder.Length != strs.Length)
|
||||
{
|
||||
Console.WriteLine("Processing update with " + strs.Length
|
||||
+ " values, but have " + obj.PropsInUpdateOrder.Length
|
||||
+ " properties to populate. Ignoring this update");
|
||||
return;
|
||||
}
|
||||
|
||||
for (int i = 0; i < obj.PropsInUpdateOrder.Length; i++)
|
||||
{
|
||||
var prop = obj.GetType().GetProperty(obj.PropsInUpdateOrder[i]);
|
||||
var s = strs[i];
|
||||
object value = null;
|
||||
|
||||
if (prop == null)
|
||||
{
|
||||
Console.WriteLine("Trying to set non existant property: " + obj.PropsInUpdateOrder[i]);
|
||||
break;
|
||||
}
|
||||
|
||||
if (prop.PropertyType == typeof(float))
|
||||
{
|
||||
float val;
|
||||
if (!float.TryParse(s, out val))
|
||||
{
|
||||
Console.WriteLine("Error parsing float: {0}, VM: {1}" + s, "TODO");
|
||||
break;
|
||||
}
|
||||
value = val;
|
||||
}
|
||||
if (prop.PropertyType == typeof(bool))
|
||||
{
|
||||
float val;
|
||||
if (!float.TryParse(s, out val))
|
||||
{
|
||||
Console.WriteLine("Error parsing float (bool): {0}, VM: {1}" + s, "TODO");
|
||||
break;
|
||||
}
|
||||
value = val != 0.0;
|
||||
}
|
||||
|
||||
if (prop.PropertyType == typeof(int))
|
||||
{
|
||||
int val;
|
||||
if (!int.TryParse(s, out val))
|
||||
{
|
||||
Console.WriteLine("Error parsing int:{0}, VM: {1}" + s, "TODO");
|
||||
break;
|
||||
}
|
||||
value = val;
|
||||
}
|
||||
|
||||
prop.SetValue(obj, value, null);
|
||||
|
||||
if (fireInpc)
|
||||
obj.FirePropertyChanged(obj.PropsInUpdateOrder[i]);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
public abstract class VmBase : NotifyProperyChangedBase
|
||||
{
|
||||
protected string[] PropsInUpdateOrder;
|
||||
|
|
|
@ -21,8 +21,8 @@ namespace ArducopterConfigurator
|
|||
var t = Type.GetType("Mono.Runtime");
|
||||
IsMonoRuntime = (t != null);
|
||||
|
||||
var session = new CommsSession();
|
||||
//var session = new FakeCommsSession();
|
||||
//var session = new CommsSession();
|
||||
var session = new FakeCommsSession();
|
||||
|
||||
|
||||
var mainVm = new MainVm(session);
|
||||
|
|
Loading…
Reference in New Issue