forked from ArduPilot/MissionPlanner
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Script.cs
216 lines (186 loc) · 7.24 KB
/
Script.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
211
212
213
214
215
216
using IronPython.Hosting;
using Microsoft.Scripting.Hosting;
using MissionPlanner.Utilities;
using System;
using System.Collections.Generic;
using System.IO;
using System.Linq;
namespace MissionPlanner
{
public class Script
{
Microsoft.Scripting.Hosting.ScriptEngine engine;
Microsoft.Scripting.Hosting.ScriptScope scope;
// keeps history
MAVLink.mavlink_rc_channels_override_t rc = new MAVLink.mavlink_rc_channels_override_t();
public StringRedirectWriter OutputWriter { get; private set; }
public Script(bool redirectOutput = false)
{
Dictionary<string, object> options = new Dictionary<string, object>();
options["Debug"] = true;
if (engine != null)
engine.Runtime.Shutdown();
engine = Python.CreateEngine(options);
var paths = engine.GetSearchPaths();
paths.Add(Settings.GetRunningDirectory() + "Lib.zip");
paths.Add(Settings.GetRunningDirectory() + "lib");
paths.Add(Settings.GetRunningDirectory());
engine.SetSearchPaths(paths);
scope = engine.CreateScope();
var all = System.Reflection.Assembly.GetExecutingAssembly();
var asss = AppDomain.CurrentDomain.GetAssemblies();
foreach (var ass in asss)
{
engine.Runtime.LoadAssembly(ass);
}
scope.SetVariable("Ports", MainV2.Comports);
scope.SetVariable("MAV", MainV2.comPort);
scope.SetVariable("cs", MainV2.comPort.MAV.cs);
scope.SetVariable("Script", this);
scope.SetVariable("mavutil", this);
scope.SetVariable("Joystick", MainV2.joystick);
engine.CreateScriptSourceFromString("print 'hello world from python'").Execute(scope);
engine.CreateScriptSourceFromString("print cs.roll").Execute(scope);
if (redirectOutput)
{
//Redirect output through this writer
//this writer will not actually write to the memorystreams
OutputWriter = new Utilities.StringRedirectWriter();
engine.Runtime.IO.SetErrorOutput(new MemoryStream(), OutputWriter);
engine.Runtime.IO.SetOutput(new MemoryStream(), OutputWriter);
}
else
OutputWriter = null;
/*
object thisBoxed = MainV2.comPort.MAV.cs;
Type test = thisBoxed.GetType();
foreach (var field in test.GetProperties())
{
// field.Name has the field's name.
object fieldValue;
try
{
fieldValue = field.GetValue(thisBoxed, null); // Get value
}
catch { continue; }
// Get the TypeCode enumeration. Multiple types get mapped to a common typecode.
TypeCode typeCode = Type.GetTypeCode(fieldValue.GetType());
items.Add(field.Name);
}
*/
}
public object mavlink_connection(string device, int baud = 115200, int source_system = 255,
bool write = false, bool append = false,
bool robust_parsing = true, bool notimestamps = false, bool input = true)
{
return null;
}
public object recv_match(string condition = null, string type = null, bool blocking = false)
{
return null;
}
public void Sleep(int ms)
{
System.Threading.Thread.Sleep(ms);
}
public void runScript(string filename)
{
try
{
Console.WriteLine("Run Script " + scope);
engine.CreateScriptSourceFromFile(filename).Execute(scope);
Console.WriteLine("Run Script Done");
}
catch (Exception e)
{
if (OutputWriter != null)
OutputWriter.Write(engine.GetService<ExceptionOperations>().FormatException(e));
CustomMessageBox.Show("Error running script " + engine.GetService<ExceptionOperations>().FormatException(e));
}
}
public enum Conditional
{
NONE = 0,
LT,
LTEQ,
EQ,
GT,
GTEQ,
NEQ
}
public bool ChangeParam(string param, float value)
{
return MainV2.comPort.setParam(param, value);
}
public float GetParam(string param)
{
if (MainV2.comPort.MAV.param[param] != null)
return (float)MainV2.comPort.MAV.param[param];
return 0.0f;
}
public bool ChangeMode(string mode)
{
MainV2.comPort.setMode(mode);
return true;
}
public bool WaitFor(string message, int timeout)
{
int timein = 0;
while (!MainV2.comPort.MAV.cs.messages.Any(a => a.message.Contains(message)))
{
System.Threading.Thread.Sleep(5);
timein += 5;
if (timein > timeout)
return false;
}
return true;
}
public bool SendRC(int channel, short pwm, bool sendnow)
{
switch (channel)
{
case 1:
MainV2.comPort.MAV.cs.rcoverridech1 = pwm;
rc.chan1_raw = (ushort)pwm;
break;
case 2:
MainV2.comPort.MAV.cs.rcoverridech2 = pwm;
rc.chan2_raw = (ushort)pwm;
break;
case 3:
MainV2.comPort.MAV.cs.rcoverridech3 = pwm;
rc.chan3_raw = (ushort)pwm;
break;
case 4:
MainV2.comPort.MAV.cs.rcoverridech4 = pwm;
rc.chan4_raw = (ushort)pwm;
break;
case 5:
MainV2.comPort.MAV.cs.rcoverridech5 = pwm;
rc.chan5_raw = (ushort)pwm;
break;
case 6:
MainV2.comPort.MAV.cs.rcoverridech6 = pwm;
rc.chan6_raw = (ushort)pwm;
break;
case 7:
MainV2.comPort.MAV.cs.rcoverridech7 = pwm;
rc.chan7_raw = (ushort)pwm;
break;
case 8:
MainV2.comPort.MAV.cs.rcoverridech8 = pwm;
rc.chan8_raw = (ushort)pwm;
break;
}
rc.target_component = MainV2.comPort.MAV.compid;
rc.target_system = MainV2.comPort.MAV.sysid;
if (sendnow)
{
MainV2.comPort.sendPacket(rc, rc.target_system, rc.target_component);
System.Threading.Thread.Sleep(20);
MainV2.comPort.sendPacket(rc, rc.target_system, rc.target_component);
}
return true;
}
}
}