mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Configurator.Net: Kill old VmBase class, update sensor and Tx views
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1664 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
72d9f52d3b
commit
3299aa272d
@ -11,7 +11,7 @@ namespace ArducopterConfigurator.PresentationModels
|
||||
/// There is a unit test to cover it but it will need fixing.
|
||||
/// TODO: test this
|
||||
/// </remarks>
|
||||
public class AltitudeHoldConfigVm : CrudVm, IPresentationModel, ISupportsPropertyPopulation
|
||||
public class AltitudeHoldConfigVm : CrudVm
|
||||
{
|
||||
public AltitudeHoldConfigVm()
|
||||
{
|
||||
|
@ -4,11 +4,9 @@ using System.Diagnostics;
|
||||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public class CalibrationOffsetsDataVm : VmBase, IPresentationModel
|
||||
public class CalibrationOffsetsDataVm : NotifyProperyChangedBase, IPresentationModel
|
||||
{
|
||||
public CalibrationOffsetsDataVm()
|
||||
{
|
||||
PropsInUpdateOrder = new[]
|
||||
private readonly string[] PropsInUpdateOrder = new[]
|
||||
{
|
||||
"GyroRollOffset",
|
||||
"GyroPitchOffset",
|
||||
@ -18,6 +16,10 @@ namespace ArducopterConfigurator.PresentationModels
|
||||
"AccelZOffset"
|
||||
};
|
||||
|
||||
public CalibrationOffsetsDataVm()
|
||||
{
|
||||
|
||||
|
||||
RefreshCommand = new DelegateCommand(_ => RefreshValues());
|
||||
UpdateCommand = new DelegateCommand(_ => UpdateValues());
|
||||
}
|
||||
@ -43,7 +45,10 @@ namespace ArducopterConfigurator.PresentationModels
|
||||
public void UpdateValues()
|
||||
{
|
||||
if (sendTextToApm != null)
|
||||
sendTextToApm(this, new sendTextToApmEventArgs(ComposePropsWithCommand("I")));
|
||||
{
|
||||
var apmString = PropertyHelper.ComposePropValuesWithCommand(this, PropsInUpdateOrder, "I");
|
||||
sendTextToApm(this, new sendTextToApmEventArgs(apmString));
|
||||
}
|
||||
}
|
||||
|
||||
public string Name
|
||||
@ -64,7 +69,10 @@ namespace ArducopterConfigurator.PresentationModels
|
||||
|
||||
public void handleLineOfText(string strRx)
|
||||
{
|
||||
PopulatePropsFromUpdate(strRx, true);
|
||||
PropertyHelper.PopulatePropsFromUpdate(this, PropsInUpdateOrder, strRx, true);
|
||||
|
||||
if (updatedByApm != null)
|
||||
updatedByApm(this, EventArgs.Empty);
|
||||
}
|
||||
|
||||
public event EventHandler<sendTextToApmEventArgs> sendTextToApm;
|
||||
|
@ -5,7 +5,7 @@ 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
|
||||
public abstract class CrudVm : NotifyProperyChangedBase, IPresentationModel
|
||||
{
|
||||
protected string updateString;
|
||||
protected string refreshString;
|
||||
@ -33,7 +33,7 @@ namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
if (sendTextToApm != null)
|
||||
{
|
||||
var apmString = PropertyHelper.ComposePropValuesWithCommand(this, updateString);
|
||||
var apmString = PropertyHelper.ComposePropValuesWithCommand(this, PropsInUpdateOrder, updateString);
|
||||
sendTextToApm(this, new sendTextToApmEventArgs(apmString));
|
||||
}
|
||||
}
|
||||
@ -52,7 +52,7 @@ namespace ArducopterConfigurator.PresentationModels
|
||||
|
||||
public void handleLineOfText(string strRx)
|
||||
{
|
||||
PropertyHelper.PopulatePropsFromUpdate(this, strRx, true);
|
||||
PropertyHelper.PopulatePropsFromUpdate(this,PropsInUpdateOrder, strRx, true);
|
||||
|
||||
if (updatedByApm != null)
|
||||
updatedByApm(this, EventArgs.Empty);
|
||||
|
@ -25,25 +25,42 @@ namespace ArducopterConfigurator.PresentationModels
|
||||
///
|
||||
/// When the VM is deactivated, the model tells the APM to cease sending the realtime updates
|
||||
/// </remarks>
|
||||
public class SensorsVm : VmBase, IPresentationModel
|
||||
public class SensorsVm : NotifyProperyChangedBase, IPresentationModel
|
||||
{
|
||||
public string Name
|
||||
{
|
||||
get { return "Sensor Data"; }
|
||||
}
|
||||
|
||||
private readonly string[] _propsInUpdateOrder = new[]
|
||||
{
|
||||
"LoopTime",
|
||||
"GyroRoll",
|
||||
"GyroPitch",
|
||||
"GyroYaw",
|
||||
"Unused", // Throttle
|
||||
"Unused", // control roll
|
||||
"Unused", // control pitch
|
||||
"Unused", // control yaw
|
||||
"MotorFront",
|
||||
"MotorRear",
|
||||
"MotorRight",
|
||||
"MotorLeft",
|
||||
"AccelRoll",
|
||||
"AccelPitch",
|
||||
"AccelZ",
|
||||
};
|
||||
|
||||
public void Activate()
|
||||
{
|
||||
if (sendTextToApm!=null)
|
||||
sendTextToApm(this, new sendTextToApmEventArgs("S"));
|
||||
|
||||
}
|
||||
|
||||
public void DeActivate()
|
||||
{
|
||||
if (sendTextToApm != null)
|
||||
sendTextToApm(this, new sendTextToApmEventArgs("X"));
|
||||
|
||||
}
|
||||
|
||||
public event EventHandler updatedByApm;
|
||||
@ -51,57 +68,12 @@ namespace ArducopterConfigurator.PresentationModels
|
||||
|
||||
public void handleLineOfText(string strRx)
|
||||
{
|
||||
var strs = strRx.Split(',');
|
||||
var ints = new List<int>();
|
||||
foreach (var s in strs)
|
||||
{
|
||||
int val;
|
||||
if (!int.TryParse(s, out val))
|
||||
{
|
||||
Debug.WriteLine("(Flight Data) Could not parse expected integer: " + s);
|
||||
return;
|
||||
}
|
||||
ints.Add(val);
|
||||
}
|
||||
|
||||
if (ints.Count!=15)
|
||||
{
|
||||
Debug.WriteLine("Flight Data seentence expected, but only got one of size: " + ints.Count);
|
||||
return;
|
||||
}
|
||||
|
||||
LoopTime = ints[0];
|
||||
GyroRoll = ints[1];
|
||||
GyroPitch = ints[2];
|
||||
GyroYaw = ints[3];
|
||||
MotorFront = ints[8];
|
||||
MotorRear = ints[9];
|
||||
MotorRight = ints[10];
|
||||
MotorLeft = ints[11];
|
||||
AccelRoll = ints[12];
|
||||
AccelPitch = ints[13];
|
||||
AccelZ = ints[14];
|
||||
PropertyHelper.PopulatePropsFromUpdate(this, _propsInUpdateOrder, strRx, false);
|
||||
}
|
||||
|
||||
|
||||
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
|
||||
{
|
||||
@ -233,5 +205,7 @@ namespace ArducopterConfigurator.PresentationModels
|
||||
FirePropertyChanged("AccelZ");
|
||||
}
|
||||
}
|
||||
|
||||
public int Unused { get; set; }
|
||||
}
|
||||
}
|
@ -4,11 +4,9 @@ using System.Diagnostics;
|
||||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public class TransmitterChannelsVm : VmBase, IPresentationModel
|
||||
public class TransmitterChannelsVm : NotifyProperyChangedBase, IPresentationModel
|
||||
{
|
||||
public TransmitterChannelsVm()
|
||||
{
|
||||
PropsInUpdateOrder = new[]
|
||||
private readonly string[] _propsInUpdateOrder = new[]
|
||||
{
|
||||
"Roll", // Aileron
|
||||
"Pitch", // Elevator
|
||||
@ -21,6 +19,9 @@ namespace ArducopterConfigurator.PresentationModels
|
||||
"YawMidValue",
|
||||
};
|
||||
|
||||
|
||||
public TransmitterChannelsVm()
|
||||
{
|
||||
ResetCommand = new DelegateCommand(_ => ResetWatermarks());
|
||||
}
|
||||
|
||||
@ -34,7 +35,6 @@ namespace ArducopterConfigurator.PresentationModels
|
||||
ModeMax = ModeMin = Mode;
|
||||
}
|
||||
|
||||
|
||||
public ICommand ResetCommand { get; private set; }
|
||||
|
||||
public int RollMidValue { get; set; }
|
||||
@ -204,9 +204,6 @@ namespace ArducopterConfigurator.PresentationModels
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
private int _mode;
|
||||
public int Mode
|
||||
{
|
||||
@ -310,7 +307,8 @@ namespace ArducopterConfigurator.PresentationModels
|
||||
|
||||
public void handleLineOfText(string strRx)
|
||||
{
|
||||
PopulatePropsFromUpdate(strRx, false);
|
||||
PropertyHelper.PopulatePropsFromUpdate(this, _propsInUpdateOrder, strRx, false);
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
@ -1,4 +1,5 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
|
||||
namespace ArducopterConfigurator
|
||||
{
|
||||
@ -9,11 +10,6 @@ namespace ArducopterConfigurator
|
||||
}
|
||||
|
||||
|
||||
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>
|
||||
@ -31,18 +27,17 @@ namespace ArducopterConfigurator
|
||||
// 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)
|
||||
public static string ComposePropValuesWithCommand(object obj, IList<string> propertiesToUpdate, string commandChar)
|
||||
{
|
||||
var strings = new string[obj.PropsInUpdateOrder.Length];
|
||||
for (int i = 0; i < obj.PropsInUpdateOrder.Length; i++)
|
||||
var strings = new string[propertiesToUpdate.Count];
|
||||
for (int i = 0; i < propertiesToUpdate.Count; i++)
|
||||
{
|
||||
var prop = obj.GetType().GetProperty(obj.PropsInUpdateOrder[i]);
|
||||
var prop = obj.GetType().GetProperty(propertiesToUpdate[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);
|
||||
@ -50,27 +45,27 @@ namespace ArducopterConfigurator
|
||||
|
||||
// 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)
|
||||
public static void PopulatePropsFromUpdate(ISupportsExternalInvokedInpc obj,IList<string> propertiesToUpdate, string strRx, bool fireInpc)
|
||||
{
|
||||
var strs = strRx.Split(',');
|
||||
|
||||
if (obj.PropsInUpdateOrder.Length != strs.Length)
|
||||
if (propertiesToUpdate.Count != strs.Length)
|
||||
{
|
||||
Console.WriteLine("Processing update with " + strs.Length
|
||||
+ " values, but have " + obj.PropsInUpdateOrder.Length
|
||||
+ " values, but have " + propertiesToUpdate.Count
|
||||
+ " properties to populate. Ignoring this update");
|
||||
return;
|
||||
}
|
||||
|
||||
for (int i = 0; i < obj.PropsInUpdateOrder.Length; i++)
|
||||
for (int i = 0; i < propertiesToUpdate.Count; i++)
|
||||
{
|
||||
var prop = obj.GetType().GetProperty(obj.PropsInUpdateOrder[i]);
|
||||
var prop = obj.GetType().GetProperty(propertiesToUpdate[i]);
|
||||
var s = strs[i];
|
||||
object value = null;
|
||||
|
||||
if (prop == null)
|
||||
{
|
||||
Console.WriteLine("Trying to set non existant property: " + obj.PropsInUpdateOrder[i]);
|
||||
Console.WriteLine("Trying to set non existant property: " + propertiesToUpdate[i]);
|
||||
break;
|
||||
}
|
||||
|
||||
@ -79,7 +74,7 @@ namespace ArducopterConfigurator
|
||||
float val;
|
||||
if (!float.TryParse(s, out val))
|
||||
{
|
||||
Console.WriteLine("Error parsing float: {0}, VM: {1}" + s, "TODO");
|
||||
Console.WriteLine("Error parsing float: {0}, VM: {1}" + s, obj);
|
||||
break;
|
||||
}
|
||||
value = val;
|
||||
@ -89,7 +84,7 @@ namespace ArducopterConfigurator
|
||||
float val;
|
||||
if (!float.TryParse(s, out val))
|
||||
{
|
||||
Console.WriteLine("Error parsing float (bool): {0}, VM: {1}" + s, "TODO");
|
||||
Console.WriteLine("Error parsing float (bool): {0}, VM: {1}" + s, obj);
|
||||
break;
|
||||
}
|
||||
value = val != 0.0;
|
||||
@ -100,7 +95,7 @@ namespace ArducopterConfigurator
|
||||
int val;
|
||||
if (!int.TryParse(s, out val))
|
||||
{
|
||||
Console.WriteLine("Error parsing int:{0}, VM: {1}" + s, "TODO");
|
||||
Console.WriteLine("Error parsing int:{0}, VM: {1}" + s, obj);
|
||||
break;
|
||||
}
|
||||
value = val;
|
||||
@ -109,102 +104,7 @@ namespace ArducopterConfigurator
|
||||
prop.SetValue(obj, value, null);
|
||||
|
||||
if (fireInpc)
|
||||
obj.FirePropertyChanged(obj.PropsInUpdateOrder[i]);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
public abstract class VmBase : NotifyProperyChangedBase
|
||||
{
|
||||
protected string[] PropsInUpdateOrder;
|
||||
|
||||
// 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
|
||||
protected string ComposePropsWithCommand(string commandChar)
|
||||
{
|
||||
var strings = new string[PropsInUpdateOrder.Length];
|
||||
for (int i = 0; i < PropsInUpdateOrder.Length; i++)
|
||||
{
|
||||
var prop = this.GetType().GetProperty(PropsInUpdateOrder[i]);
|
||||
|
||||
if (prop.PropertyType == typeof(bool))
|
||||
strings[i] = ((bool)prop.GetValue(this, null)) ? "1" : "0";
|
||||
else
|
||||
strings[i] = prop.GetValue(this, 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
|
||||
protected void PopulatePropsFromUpdate(string strRx, bool fireInpc)
|
||||
{
|
||||
|
||||
var strs = strRx.Split(',');
|
||||
|
||||
if (PropsInUpdateOrder.Length != strs.Length)
|
||||
{
|
||||
Console.WriteLine("Processing update with " + strs.Length
|
||||
+ " values, but have " + PropsInUpdateOrder.Length
|
||||
+ " properties to populate. Ignoring this update");
|
||||
return;
|
||||
}
|
||||
|
||||
for (int i = 0; i < PropsInUpdateOrder.Length; i++)
|
||||
{
|
||||
var prop = this.GetType().GetProperty(PropsInUpdateOrder[i]);
|
||||
var s = strs[i];
|
||||
object value = null;
|
||||
|
||||
if (prop == null)
|
||||
{
|
||||
Console.WriteLine("Trying to set non existant property: " + 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(this, value, null);
|
||||
|
||||
if (fireInpc)
|
||||
FirePropertyChanged(PropsInUpdateOrder[i]);
|
||||
obj.FirePropertyChanged(propertiesToUpdate[i]);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -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);
|
||||
|
@ -110,7 +110,7 @@
|
||||
//
|
||||
// FlightDataVmBindingSource
|
||||
//
|
||||
this.FlightDataVmBindingSource.DataSource = typeof(ArducopterConfigurator.PresentationModels.FlightDataVm);
|
||||
this.FlightDataVmBindingSource.DataSource = typeof(ArducopterConfigurator.PresentationModels.SensorsVm);
|
||||
//
|
||||
// label5
|
||||
//
|
||||
|
@ -17,7 +17,7 @@ namespace ArducopterConfigurator.views
|
||||
InitializeComponent();
|
||||
}
|
||||
|
||||
public override void SetDataContext(FlightDataVm vm)
|
||||
public override void SetDataContext(SensorsVm vm)
|
||||
{
|
||||
FlightDataVmBindingSource.DataSource = vm;
|
||||
|
||||
@ -26,5 +26,5 @@ namespace ArducopterConfigurator.views
|
||||
}
|
||||
}
|
||||
// Required for VS2008 designer. No functional value
|
||||
public class FlightDataViewDesignable : ViewCommon<FlightDataVm> { }
|
||||
public class FlightDataViewDesignable : ViewCommon<SensorsVm> { }
|
||||
}
|
||||
|
@ -22,7 +22,7 @@ namespace ArducopterConfigurator
|
||||
// IPresentationModel to IView map
|
||||
private readonly Dictionary<Type, Type> _viewMap = new Dictionary<Type, Type>
|
||||
{
|
||||
{typeof (FlightDataVm), typeof (FlightDataView)},
|
||||
{typeof (SensorsVm), typeof (FlightDataView)},
|
||||
{typeof (TransmitterChannelsVm), typeof (TransmitterChannelsView)},
|
||||
{typeof (CalibrationOffsetsDataVm), typeof (CalibrationView)},
|
||||
{typeof (MotorCommandsVm), typeof (MotorCommandsView)},
|
||||
|
Loading…
Reference in New Issue
Block a user