-
Notifications
You must be signed in to change notification settings - Fork 2.4k
/
Copy pathMAVLinkParam.cs
210 lines (187 loc) · 6.13 KB
/
MAVLinkParam.cs
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
using System;
using System.Runtime.Serialization;
public partial class MAVLink
{
public class MAVLinkParam
{
/// <summary>
/// Paramater name
/// </summary>
public string Name { get; set; }
/// <summary>
/// Over the wire storage format
/// </summary>
public MAV_PARAM_TYPE Type { get; set; }
/// <summary>
/// Value of paramter as a double
/// </summary>
public double Value
{
get
{
return GetValue();
}
set
{
SetValue(value);
}
}
private MAV_PARAM_TYPE _typeap = 0;
public MAV_PARAM_TYPE TypeAP {
get
{
if (_typeap != 0)
return _typeap;
return Type;
}
set
{
_typeap = value;
}
}
byte uint8_value { get { return data[0]; } }
sbyte int8_value { get { return (sbyte)data[0]; } }
ushort uint16_value { get { return BitConverter.ToUInt16(data, 0); } }
short int16_value { get { return BitConverter.ToInt16(data, 0); } }
UInt32 uint32_value { get { return BitConverter.ToUInt32(data, 0); } }
Int32 int32_value { get { return BitConverter.ToInt32(data, 0); } }
[IgnoreDataMember]
public float float_value { get { return BitConverter.ToSingle(data, 0); } }
byte[] _data = new byte[4];
[IgnoreDataMember]
public byte[] data
{
get { return _data; }
set
{
_data = value;
Array.Resize(ref _data, 4);
}
}
private MAVLinkParam()
{
}
/// <summary>
/// used as a generic input to type the input data
/// </summary>
/// <param name="name"></param>
/// <param name="value"></param>
/// <param name="wiretype"></param>
public MAVLinkParam(string name, double value, MAV_PARAM_TYPE wiretype)
{
Name = name;
Type = wiretype;
Value = value;
}
/// <summary>
/// Used to set Ardupilot Params
/// </summary>
/// <param name="name"></param>
/// <param name="inputwire"></param>
/// <param name="wiretype"></param>
/// <param name="typeap"></param>
public MAVLinkParam(string name, byte[] inputwire, MAV_PARAM_TYPE wiretype, MAV_PARAM_TYPE typeap)
{
Name = name;
Type = wiretype;
TypeAP = typeap;
Array.Copy(inputwire, _data, 4);
}
public double GetValue()
{
switch (Type)
{
case MAV_PARAM_TYPE.UINT8:
return (double)uint8_value;
case MAV_PARAM_TYPE.INT8:
return (double)int8_value;
case MAV_PARAM_TYPE.UINT16:
return (double)uint16_value;
case MAV_PARAM_TYPE.INT16:
return (double)int16_value;
case MAV_PARAM_TYPE.UINT32:
return (double)uint32_value;
case MAV_PARAM_TYPE.INT32:
return (double)int32_value;
case MAV_PARAM_TYPE.REAL32:
/*
item.float_value
0.8
(double)item.float_value
0.800000011920929
*/
return (double)(decimal)float_value;
}
throw new FormatException("invalid type");
}
public void SetValue(double input)
{
switch (Type)
{
case MAV_PARAM_TYPE.UINT8:
data = BitConverter.GetBytes((byte)input);
Array.Resize(ref _data, 4);
break;
case MAV_PARAM_TYPE.INT8:
data = BitConverter.GetBytes((sbyte)input);
Array.Resize(ref _data, 4);
break;
case MAV_PARAM_TYPE.UINT16:
data = BitConverter.GetBytes((ushort)input);
Array.Resize(ref _data, 4);
break;
case MAV_PARAM_TYPE.INT16:
data = BitConverter.GetBytes((short)input);
Array.Resize(ref _data, 4);
break;
case MAV_PARAM_TYPE.UINT32:
data = BitConverter.GetBytes((UInt32)input);
break;
case MAV_PARAM_TYPE.INT32:
data = BitConverter.GetBytes((Int32)input);
break;
case MAV_PARAM_TYPE.REAL32:
data = BitConverter.GetBytes((float)input);
break;
}
}
public static explicit operator byte(MAVLinkParam v)
{
return (byte)v.Value;
}
public static explicit operator sbyte(MAVLinkParam v)
{
return (sbyte)v.Value;
}
public static explicit operator short(MAVLinkParam v)
{
return (short)v.Value;
}
public static explicit operator ushort(MAVLinkParam v)
{
return (ushort)v.Value;
}
public static explicit operator int(MAVLinkParam v)
{
return (int)v.Value;
}
public static explicit operator uint(MAVLinkParam v)
{
return (uint)v.Value;
}
public static explicit operator float (MAVLinkParam v)
{
return (float)v.Value;
}
public static explicit operator double(MAVLinkParam v)
{
return (double)v.Value;
}
public override string ToString()
{
if (Type == MAV_PARAM_TYPE.REAL32)
return ((float)this).ToString();
return Value.ToString();
}
}
}