2011-11-21 20:32:11 -04:00
|
|
|
|
using System;
|
|
|
|
|
using System.Collections.Generic;
|
|
|
|
|
using System.Linq;
|
|
|
|
|
using System.Text;
|
2011-11-29 09:49:11 -04:00
|
|
|
|
using IronPython.Hosting;
|
2011-11-21 20:32:11 -04:00
|
|
|
|
|
|
|
|
|
namespace ArdupilotMega
|
|
|
|
|
{
|
|
|
|
|
public class Script
|
|
|
|
|
{
|
|
|
|
|
DateTime timeout = DateTime.Now;
|
2011-11-24 20:07:14 -04:00
|
|
|
|
List<string> items = new List<string>();
|
2012-01-29 03:45:20 -04:00
|
|
|
|
static Microsoft.Scripting.Hosting.ScriptEngine engine;
|
|
|
|
|
static Microsoft.Scripting.Hosting.ScriptScope scope;
|
2011-11-24 20:07:14 -04:00
|
|
|
|
|
|
|
|
|
// keeps history
|
2012-04-05 21:50:04 -03:00
|
|
|
|
MAVLink.mavlink_rc_channels_override_t rc = new MAVLink.mavlink_rc_channels_override_t();
|
2011-11-24 20:07:14 -04:00
|
|
|
|
|
|
|
|
|
public Script()
|
|
|
|
|
{
|
2011-12-17 05:22:40 -04:00
|
|
|
|
Dictionary<string, object> options = new Dictionary<string, object>();
|
|
|
|
|
options["Debug"] = true;
|
|
|
|
|
|
|
|
|
|
if (engine != null)
|
|
|
|
|
engine.Runtime.Shutdown();
|
|
|
|
|
|
2012-03-03 03:42:41 -04:00
|
|
|
|
engine = Python.CreateEngine(options);
|
2011-11-29 09:49:11 -04:00
|
|
|
|
scope = engine.CreateScope();
|
|
|
|
|
|
2012-12-07 05:19:46 -04:00
|
|
|
|
scope.SetVariable("cs", MainV2.comPort.MAV.cs);
|
2011-11-29 09:49:11 -04:00
|
|
|
|
scope.SetVariable("Script", this);
|
2012-03-03 03:42:41 -04:00
|
|
|
|
scope.SetVariable("mavutil", this);
|
2011-11-29 09:49:11 -04:00
|
|
|
|
|
|
|
|
|
engine.CreateScriptSourceFromString("print 'hello world from python'").Execute(scope);
|
|
|
|
|
engine.CreateScriptSourceFromString("print cs.roll").Execute(scope);
|
|
|
|
|
|
|
|
|
|
|
2012-12-07 05:19:46 -04:00
|
|
|
|
object thisBoxed = MainV2.comPort.MAV.cs;
|
2011-11-24 20:07:14 -04:00
|
|
|
|
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);
|
|
|
|
|
}
|
2011-11-29 09:49:11 -04:00
|
|
|
|
}
|
|
|
|
|
|
2012-03-03 03:42:41 -04:00
|
|
|
|
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)
|
|
|
|
|
{
|
2011-11-29 09:49:11 -04:00
|
|
|
|
|
2012-03-03 03:42:41 -04:00
|
|
|
|
return null;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
public void Sleep(int ms)
|
|
|
|
|
{
|
2011-11-29 09:49:11 -04:00
|
|
|
|
System.Threading.Thread.Sleep(ms);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
public void runScript(string script)
|
|
|
|
|
{
|
|
|
|
|
try
|
|
|
|
|
{
|
|
|
|
|
engine.CreateScriptSourceFromString(script).Execute(scope);
|
|
|
|
|
}
|
|
|
|
|
catch (Exception e)
|
|
|
|
|
{
|
2012-03-09 11:18:12 -04:00
|
|
|
|
System.Windows.Forms.CustomMessageBox.Show("Error running script " + e.Message);
|
2011-11-29 09:49:11 -04:00
|
|
|
|
}
|
|
|
|
|
}
|
2011-11-21 20:32:11 -04:00
|
|
|
|
|
|
|
|
|
public enum Conditional
|
|
|
|
|
{
|
2011-11-24 20:07:14 -04:00
|
|
|
|
NONE = 0,
|
|
|
|
|
LT,
|
2011-11-21 20:32:11 -04:00
|
|
|
|
LTEQ,
|
|
|
|
|
EQ,
|
|
|
|
|
GT,
|
2011-11-24 20:07:14 -04:00
|
|
|
|
GTEQ,
|
|
|
|
|
NEQ
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
public bool ChangeParam(string param, float value)
|
|
|
|
|
{
|
|
|
|
|
return MainV2.comPort.setParam(param, value);
|
|
|
|
|
}
|
|
|
|
|
|
2011-11-29 09:49:11 -04:00
|
|
|
|
public float GetParam(string param)
|
|
|
|
|
{
|
2012-12-07 05:19:46 -04:00
|
|
|
|
if (MainV2.comPort.MAV.param[param] != null)
|
|
|
|
|
return (float)MainV2.comPort.MAV.param[param];
|
2011-11-29 09:49:11 -04:00
|
|
|
|
|
|
|
|
|
return 0.0f;
|
|
|
|
|
}
|
|
|
|
|
|
2011-11-24 20:07:14 -04:00
|
|
|
|
public bool ChangeMode(string mode)
|
|
|
|
|
{
|
|
|
|
|
MainV2.comPort.setMode(mode);
|
|
|
|
|
return true;
|
|
|
|
|
}
|
|
|
|
|
|
2011-11-29 09:49:11 -04:00
|
|
|
|
public bool WaitFor(string message, int timeout)
|
2011-11-24 20:07:14 -04:00
|
|
|
|
{
|
2011-11-29 09:49:11 -04:00
|
|
|
|
int timein = 0;
|
2012-12-07 05:19:46 -04:00
|
|
|
|
while (!MainV2.comPort.MAV.cs.message.Contains(message))
|
2012-03-03 03:42:41 -04:00
|
|
|
|
{
|
2011-11-24 20:07:14 -04:00
|
|
|
|
System.Threading.Thread.Sleep(5);
|
2011-11-29 09:49:11 -04:00
|
|
|
|
timein += 5;
|
|
|
|
|
if (timein > timeout)
|
|
|
|
|
return false;
|
2011-11-24 20:07:14 -04:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
return true;
|
2011-11-21 20:32:11 -04:00
|
|
|
|
}
|
2012-03-03 03:42:41 -04:00
|
|
|
|
|
|
|
|
|
public bool SendRC(int channel, ushort pwm, bool sendnow)
|
2011-11-24 20:07:14 -04:00
|
|
|
|
{
|
|
|
|
|
switch (channel)
|
|
|
|
|
{
|
|
|
|
|
case 1:
|
2012-12-07 05:19:46 -04:00
|
|
|
|
MainV2.comPort.MAV.cs.rcoverridech1 = pwm;
|
2011-11-24 20:07:14 -04:00
|
|
|
|
rc.chan1_raw = pwm;
|
|
|
|
|
break;
|
|
|
|
|
case 2:
|
2012-12-07 05:19:46 -04:00
|
|
|
|
MainV2.comPort.MAV.cs.rcoverridech2 = pwm;
|
2011-11-24 20:07:14 -04:00
|
|
|
|
rc.chan2_raw = pwm;
|
|
|
|
|
break;
|
|
|
|
|
case 3:
|
2012-12-07 05:19:46 -04:00
|
|
|
|
MainV2.comPort.MAV.cs.rcoverridech3 = pwm;
|
2011-11-24 20:07:14 -04:00
|
|
|
|
rc.chan3_raw = pwm;
|
|
|
|
|
break;
|
|
|
|
|
case 4:
|
2012-12-07 05:19:46 -04:00
|
|
|
|
MainV2.comPort.MAV.cs.rcoverridech4 = pwm;
|
2011-11-24 20:07:14 -04:00
|
|
|
|
rc.chan4_raw = pwm;
|
|
|
|
|
break;
|
|
|
|
|
case 5:
|
2012-12-07 05:19:46 -04:00
|
|
|
|
MainV2.comPort.MAV.cs.rcoverridech5 = pwm;
|
2011-11-24 20:07:14 -04:00
|
|
|
|
rc.chan5_raw = pwm;
|
|
|
|
|
break;
|
|
|
|
|
case 6:
|
2012-12-07 05:19:46 -04:00
|
|
|
|
MainV2.comPort.MAV.cs.rcoverridech6 = pwm;
|
2011-11-24 20:07:14 -04:00
|
|
|
|
rc.chan6_raw = pwm;
|
|
|
|
|
break;
|
|
|
|
|
case 7:
|
2012-12-07 05:19:46 -04:00
|
|
|
|
MainV2.comPort.MAV.cs.rcoverridech7 = pwm;
|
2011-11-24 20:07:14 -04:00
|
|
|
|
rc.chan7_raw = pwm;
|
|
|
|
|
break;
|
|
|
|
|
case 8:
|
2012-12-07 05:19:46 -04:00
|
|
|
|
MainV2.comPort.MAV.cs.rcoverridech8 = pwm;
|
2011-11-24 20:07:14 -04:00
|
|
|
|
rc.chan8_raw = pwm;
|
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
|
2012-12-07 05:19:46 -04:00
|
|
|
|
rc.target_component = MainV2.comPort.MAV.compid;
|
|
|
|
|
rc.target_system = MainV2.comPort.MAV.sysid;
|
2011-11-24 20:07:14 -04:00
|
|
|
|
|
2011-11-29 09:49:11 -04:00
|
|
|
|
if (sendnow)
|
|
|
|
|
{
|
|
|
|
|
MainV2.comPort.sendPacket(rc);
|
|
|
|
|
System.Threading.Thread.Sleep(20);
|
|
|
|
|
MainV2.comPort.sendPacket(rc);
|
|
|
|
|
MainV2.comPort.sendPacket(rc);
|
|
|
|
|
}
|
2011-11-24 20:07:14 -04:00
|
|
|
|
|
2011-11-29 09:49:11 -04:00
|
|
|
|
return true;
|
2011-11-24 20:07:14 -04:00
|
|
|
|
}
|
2011-11-21 20:32:11 -04:00
|
|
|
|
}
|
2012-03-03 03:42:41 -04:00
|
|
|
|
}
|