APM Planner 1.1.19

fix log download
misc
This commit is contained in:
Michael Oborne 2012-01-10 08:16:10 +08:00
parent 861222f81d
commit eb236b313b
19 changed files with 235 additions and 127 deletions

View File

@ -680,9 +680,6 @@
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
</None>
<None Include="app.config" />
<None Include="arducopter-fgmodel.zip">
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
</None>
<None Include="arducopter-xplane.zip">
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
</None>

View File

@ -32,6 +32,8 @@ namespace ArdupilotMega
public Camera()
{
InitializeComponent();
doCalc();
}
void doCalc()

View File

@ -48,7 +48,9 @@ namespace ArdupilotMega
/// </summary>
public class GMapMarkerRect : GMapMarker
{
public Pen Pen;
public Pen Pen = new Pen(Brushes.White, 2);
public Color Color { get { return Pen.Color; } set { Pen.Color = value; } }
public GMapMarker InnerMarker;
@ -58,8 +60,6 @@ namespace ArdupilotMega
public GMapMarkerRect(PointLatLng p)
: base(p)
{
Pen = new Pen(Brushes.White, 2);
Pen.DashStyle = DashStyle.Dash;
// do not forget set Size of the marker
@ -75,9 +75,9 @@ namespace ArdupilotMega
if (wprad == 0 || MainMap == null)
return;
// undo autochange in mouse over
if (Pen.Color == Color.Blue)
Pen.Color = Color.White;
double width = (MainMap.Manager.GetDistance(MainMap.FromLocalToLatLng(0, 0), MainMap.FromLocalToLatLng(MainMap.Width, 0)) * 1000.0);
double height = (MainMap.Manager.GetDistance(MainMap.FromLocalToLatLng(0, 0), MainMap.FromLocalToLatLng(MainMap.Height, 0)) * 1000.0);
@ -177,6 +177,7 @@ namespace ArdupilotMega
public double Lng = 0;
public double Alt = 0;
public string Tag = "";
public Color color = Color.White;
public PointLatLngAlt(double lat, double lng, double alt, string tag)
{
@ -263,7 +264,43 @@ namespace ArdupilotMega
CIRCLE = 7,
POSITION = 8
}
public static void linearRegression()
{
double[] values = { 4.8, 4.8, 4.5, 3.9, 4.4, 3.6, 3.6, 2.9, 3.5, 3.0, 2.5, 2.2, 2.6, 2.1, 2.2 };
double xAvg = 0;
double yAvg = 0;
for (int x = 0; x < values.Length; x++)
{
xAvg += x;
yAvg += values[x];
}
xAvg = xAvg / values.Length;
yAvg = yAvg / values.Length;
double v1 = 0;
double v2 = 0;
for (int x = 0; x < values.Length; x++)
{
v1 += (x - xAvg) * (values[x] - yAvg);
v2 += Math.Pow(x - xAvg, 2);
}
double a = v1 / v2;
double b = yAvg - a * xAvg;
Console.WriteLine("y = ax + b");
Console.WriteLine("a = {0}, the slope of the trend line.", Math.Round(a, 2));
Console.WriteLine("b = {0}, the intercept of the trend line.", Math.Round(b, 2));
Console.ReadLine();
}
#if MAVLINK10
public static bool translateMode(string modein, ref MAVLink.__mavlink_set_mode_t mode)

View File

@ -432,7 +432,7 @@ namespace ArdupilotMega.GCSViews
{
if (plla == null || plla.Lng == 0 || plla.Lat == 0)
break;
addpolygonmarker(plla.Tag, plla.Lng, plla.Lat, (int)plla.Alt);
addpolygonmarker(plla.Tag, plla.Lng, plla.Lat, (int)plla.Alt,plla.color);
}
RegeneratePolygon();
@ -525,7 +525,7 @@ namespace ArdupilotMega.GCSViews
});
}
private void addpolygonmarker(string tag, double lng, double lat, int alt)
private void addpolygonmarker(string tag, double lng, double lat, int alt, Color? color)
{
try
{
@ -537,13 +537,18 @@ namespace ArdupilotMega.GCSViews
GMapMarkerRect mBorders = new GMapMarkerRect(point);
{
mBorders.InnerMarker = m;
mBorders.MainMap = gMapControl1;
try
{
mBorders.wprad = (int)float.Parse(ArdupilotMega.MainV2.config["TXT_WPRad"].ToString());
}
catch { }
mBorders.InnerMarker = m;
try
{
mBorders.wprad = (int)float.Parse(ArdupilotMega.MainV2.config["TXT_WPRad"].ToString());
}
catch { }
mBorders.MainMap = gMapControl1;
if (color.HasValue)
{
mBorders.Color = color.Value;
}
}
polygons.Markers.Add(m);

View File

@ -884,7 +884,7 @@ namespace ArdupilotMega.GCSViews
/// <param name="lng"></param>
/// <param name="lat"></param>
/// <param name="alt"></param>
private void addpolygonmarker(string tag, double lng, double lat, int alt)
private void addpolygonmarker(string tag, double lng, double lat, int alt, Color? color)
{
try
{
@ -900,6 +900,10 @@ namespace ArdupilotMega.GCSViews
mBorders.InnerMarker = m;
mBorders.wprad = (int)float.Parse(TXT_WPRad.Text);
mBorders.MainMap = MainMap;
if (color.HasValue)
{
mBorders.Color = color.Value;
}
}
objects.Markers.Add(m);
@ -955,7 +959,7 @@ namespace ArdupilotMega.GCSViews
if (objects != null) // during startup
{
pointlist.Add(new PointLatLngAlt(double.Parse(TXT_homelat.Text), double.Parse(TXT_homelng.Text), (int)double.Parse(TXT_homealt.Text), "Home"));
addpolygonmarker("Home", double.Parse(TXT_homelng.Text), double.Parse(TXT_homelat.Text), 0);
addpolygonmarker("Home", double.Parse(TXT_homelng.Text), double.Parse(TXT_homelat.Text), 0, null);
}
}
else
@ -1029,8 +1033,14 @@ namespace ArdupilotMega.GCSViews
if (cell4 == "?" || cell3 == "?")
continue;
pointlist.Add(new PointLatLngAlt(double.Parse(cell3), double.Parse(cell4), (int)double.Parse(cell2) + homealt, (a + 1).ToString()));
addpolygonmarker((a + 1).ToString(), double.Parse(cell4), double.Parse(cell3), (int)double.Parse(cell2));
if (command == (byte)MAVLink.MAV_CMD.LOITER_TIME || command == (byte)MAVLink.MAV_CMD.LOITER_TURNS || command == (byte)MAVLink.MAV_CMD.LOITER_UNLIM) {
pointlist.Add(new PointLatLngAlt(double.Parse(cell3), double.Parse(cell4), (int)double.Parse(cell2) + homealt, (a + 1).ToString()){ color = Color.LightBlue });
addpolygonmarker((a + 1).ToString(), double.Parse(cell4), double.Parse(cell3), (int)double.Parse(cell2) , Color.LightBlue);
} else {
pointlist.Add(new PointLatLngAlt(double.Parse(cell3), double.Parse(cell4), (int)double.Parse(cell2) + homealt, (a + 1).ToString()));
addpolygonmarker((a + 1).ToString(), double.Parse(cell4), double.Parse(cell3), (int)double.Parse(cell2) ,null);
}
avglong += double.Parse(Commands.Rows[a].Cells[Lon.Index].Value.ToString());
avglat += double.Parse(Commands.Rows[a].Cells[Lat.Index].Value.ToString());

View File

@ -257,14 +257,18 @@ namespace ArdupilotMega.GCSViews
{
System.Diagnostics.ProcessStartInfo _procstartinfo = new System.Diagnostics.ProcessStartInfo();
_procstartinfo.WorkingDirectory = Path.GetDirectoryName(Application.ExecutablePath);
_procstartinfo.Arguments = "--realtime --suspend --nice --simulation-rate=50 --logdirectivefile=jsbsim/fgout.xml --script=jsbsim/rascal_test.xml";
_procstartinfo.Arguments = "--realtime --suspend --nice --simulation-rate=1000 --logdirectivefile=jsbsim/fgout.xml --script=jsbsim/rascal_test.xml";
_procstartinfo.FileName = "JSBSim.exe";
// Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar +
_procstartinfo.UseShellExecute = true;
//_procstartinfo.RedirectStandardOutput = true;
System.Diagnostics.Process.Start(_procstartinfo);
System.Threading.Thread.Sleep(2000);
SITLSEND = new UdpClient(simIP, 5501);
}
@ -543,11 +547,15 @@ namespace ArdupilotMega.GCSViews
udpdata = new byte[udpdata.Length];
try
{
int recv = SimulatorRECV.ReceiveFrom(udpdata, ref Remote);
while (SimulatorRECV.Available > 0)
{
int recv = SimulatorRECV.ReceiveFrom(udpdata, ref Remote);
RECVprocess(udpdata, recv, comPort);
RECVprocess(udpdata, recv, comPort);
}
}
catch (Exception ex) { //OutputLog.AppendText("Xplanes Data Problem - You need DATA IN/OUT 3, 4, 17, 18, 19, 20\n" + ex.Message + "\n");
}
catch (Exception ex) { OutputLog.AppendText("Xplanes Data Problem - You need DATA IN/OUT 3, 4, 17, 18, 19, 20\n" + ex.Message + "\n"); }
}
if (MavLink != null && MavLink.Client != null && MavLink.Client.Connected && MavLink.Available > 0)
{
@ -583,7 +591,7 @@ namespace ArdupilotMega.GCSViews
if (hzcounttime.Second != DateTime.Now.Second)
{
//Console.WriteLine("SIM hz {0}", hzcount);
Console.WriteLine("SIM hz {0}", hzcount);
hzcount = 0;
hzcounttime = DateTime.Now;
}
@ -619,18 +627,23 @@ namespace ArdupilotMega.GCSViews
{
JSBSimSEND = new TcpClient();
JSBSimSEND.Client.NoDelay = true;
JSBSimSEND.Connect(simIP, simPort);
JSBSimSEND.Connect("127.0.0.1", simPort);
OutputLog.AppendText("Sending to port TCP " + simPort + " (planner->sim)\n");
System.Threading.Thread.Sleep(2000);
//JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("set position/h-agl-ft 0\r\n"));
JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("info\n"));
JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("set position/lat-gc-deg " + MainV2.HomeLocation.Lat + "\r\n"));
JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("set position/long-gc-deg " + MainV2.HomeLocation.Lng + "\r\n"));
JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("set attitude/phi-rad 0\n"));
JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("set attitude/theta-rad 0\n"));
JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("resume\n"));
JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("set attitude/phi-rad 0\r\n"));
JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("set attitude/theta-rad 0\r\n"));
JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("set attitude/psi-rad 0\r\n"));
JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("info\r\n"));
JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("resume\r\n"));
}
catch { }
catch { Console.WriteLine("JSB console fail"); }
}
private void SetupUDPXplanes()
@ -1125,30 +1138,37 @@ namespace ArdupilotMega.GCSViews
if (RAD_JSBSim.Checked && chkSensor.Checked)
{
byte[] buffer = new byte[1500];
while (JSBSimSEND.Client.Available > 5)
{
int read = JSBSimSEND.Client.Receive(buffer);
}
byte[] sitlout = new byte[16 * 8 + 1 * 4]; // 16 * double + 1 * int
int a = 0;
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.latitude), a, sitlout, a, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.longitude), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.latitude * rad2deg), a, sitlout, a, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.longitude * rad2deg), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.altitude), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.psi), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.v_north), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.v_east), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.A_X_pilot), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.A_Y_pilot), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.psi * rad2deg), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.v_north * ft2m), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.v_east * ft2m), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.A_X_pilot * ft2m), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.A_Y_pilot * ft2m), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.A_Z_pilot), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.phidot), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.thetadot), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.psidot), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.phi), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.theta), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.psi), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.vcas), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.A_Z_pilot * ft2m), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.phidot * rad2deg), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.thetadot * rad2deg), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.psidot * rad2deg), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.phi * rad2deg), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.theta * rad2deg), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.psi * rad2deg), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.vcas * ft2m), 0, sitlout, a += 8, 8);
// Console.WriteLine(lastfdmdata.theta);
Array.Copy(BitConverter.GetBytes((int)0x4c56414e), 0, sitlout, a += 8, 4);
SITLSEND.Send(sitlout, sitlout.Length);
return;

View File

@ -277,8 +277,8 @@ namespace hud
if (DateTime.Now.Second != countdate.Second)
{
countdate = DateTime.Now;
//Console.WriteLine("HUD " + count + " hz drawtime " + (huddrawtime / count) + " gl " + opengl);
if ((huddrawtime / count) > 500)
Console.WriteLine("HUD " + count + " hz drawtime " + (huddrawtime / count) + " gl " + opengl);
if ((huddrawtime / count) > 1000)
opengl = false;
count = 0;

View File

@ -121,10 +121,11 @@ namespace ArdupilotMega
{
MethodInvoker m = delegate()
{
CHK_logs.Items.Clear();
for (int a = 1; a <= logcount; a++)
//CHK_logs.Items.Clear();
//for (int a = 1; a <= logcount; a++)
if (!CHK_logs.Items.Contains(logcount))
{
CHK_logs.Items.Add(a);
CHK_logs.Items.Add(logcount);
}
};
try
@ -189,23 +190,8 @@ namespace ArdupilotMega
if (line.Contains("reset to FLY") || line.Contains("interactive setup") || line.Contains("CLI:") || line.Contains("Ardu"))
{
comPort.Write("logs\r");
}
if (line.Contains("logs"))
{
Regex regex2 = new Regex(@"^([0-9]+)", RegexOptions.IgnoreCase);
if (regex2.IsMatch(line))
{
MatchCollection matchs = regex2.Matches(line);
logcount = int.Parse(matchs[0].Groups[0].Value);
genchkcombo(logcount);
status = serialstatus.Done;
}
}
if (line.Contains("No logs"))
{
status = serialstatus.Done;
}
break;
case serialstatus.Closefile:
sw.Close();
@ -252,6 +238,21 @@ namespace ArdupilotMega
break;
case serialstatus.Done:
//
if (line.Contains("start") && line.Contains("end"))
{
Regex regex2 = new Regex(@"^Log ([0-9]+),", RegexOptions.IgnoreCase);
if (regex2.IsMatch(line))
{
MatchCollection matchs = regex2.Matches(line);
logcount = int.Parse(matchs[0].Groups[1].Value);
genchkcombo(logcount);
//status = serialstatus.Done;
}
}
if (line.Contains("No logs"))
{
status = serialstatus.Done;
}
break;
case serialstatus.Reading:
if (line.Contains("packets read") || line.Contains("Done") || line.Contains("logs enabled"))
@ -774,6 +775,7 @@ namespace ArdupilotMega
System.Threading.Thread.Sleep(100);
TXT_seriallog.AppendText("!!Allow 30 seconds for erase\n");
status = serialstatus.Done;
CHK_logs.Items.Clear();
}
private void BUT_redokml_Click(object sender, EventArgs e)

View File

@ -1599,7 +1599,7 @@ namespace ArdupilotMega
}
}
if (loadinglabel != null)
loadinglabel.Text = "Starting Updater";
updatelabel(loadinglabel,"Starting Updater");
Console.WriteLine("Start " + P.StartInfo.FileName + " with " + P.StartInfo.Arguments);
P.Start();
try
@ -1746,6 +1746,9 @@ namespace ArdupilotMega
if (loadinglabel != null)
updatelabel(loadinglabel, "Getting " + file);
// from head
long bytes = response.ContentLength;
// Create a request using a URL that can receive a post.
request = WebRequest.Create(baseurl + file);
// Set the Method property of the request to POST.
@ -1756,8 +1759,7 @@ namespace ArdupilotMega
Console.WriteLine(((HttpWebResponse)response).StatusDescription);
// Get the stream containing content returned by the server.
dataStream = response.GetResponseStream();
long bytes = response.ContentLength;
long contlen = bytes;
byte[] buf1 = new byte[1024];
@ -1776,7 +1778,7 @@ namespace ArdupilotMega
if (dt.Second != DateTime.Now.Second)
{
if (loadinglabel != null)
updatelabel(loadinglabel, "Getting " + file + ": " + Math.Abs(bytes) + " bytes");//(((double)(contlen - bytes) / (double)contlen) * 100).ToString("0.0") + "%";
updatelabel(loadinglabel, "Getting " + file + ": " + (((double)(contlen - bytes) / (double)contlen) * 100).ToString("0.0") + "%"); //+ Math.Abs(bytes) + " bytes");
dt = DateTime.Now;
}
}

View File

@ -26,6 +26,8 @@ namespace ArdupilotMega
//MessageBox.Show("NOTE: This version may break advanced mission scripting");
//Common.linearRegression();
Application.EnableVisualStyles();
Application.SetCompatibleTextRenderingDefault(false);
try

View File

@ -34,5 +34,5 @@ using System.Resources;
// by using the '*' as shown below:
// [assembly: AssemblyVersion("1.0.*")]
[assembly: AssemblyVersion("1.0.0.0")]
[assembly: AssemblyFileVersion("1.1.18")]
[assembly: AssemblyFileVersion("1.1.19")]
[assembly: NeutralResourcesLanguageAttribute("")]

View File

@ -55,14 +55,14 @@
<contact type="BOGEY" name="LEFT_MLG">
<location unit="IN">
<x> 33.1 </x>
<y> -9.9 </y>
<y> -12.9 </y>
<z> -13.1 </z>
</location>
<static_friction> 1.0 </static_friction>
<dynamic_friction> 0.8 </dynamic_friction>
<rolling_friction> 0.02 </rolling_friction>
<spring_coeff unit="LBS/FT"> 12 </spring_coeff>
<damping_coeff unit="LBS/FT/SEC"> 1 </damping_coeff>
<static_friction> 0.8 </static_friction>
<dynamic_friction> 0.5 </dynamic_friction>
<rolling_friction> 0.1 </rolling_friction>
<spring_coeff unit="LBS/FT"> 480 </spring_coeff>
<damping_coeff unit="LBS/FT/SEC"> 100 </damping_coeff>
<max_steer unit="DEG"> 0.0 </max_steer>
<brake_group> NONE </brake_group>
<retractable>0</retractable>
@ -70,14 +70,14 @@
<contact type="BOGEY" name="RIGHT_MLG">
<location unit="IN">
<x> 33.1 </x>
<y> 9.9 </y>
<y> 12.9 </y>
<z> -13.1 </z>
</location>
<static_friction> 1.0 </static_friction>
<dynamic_friction> 0.8 </dynamic_friction>
<rolling_friction> 0.02 </rolling_friction>
<spring_coeff unit="LBS/FT"> 12 </spring_coeff>
<damping_coeff unit="LBS/FT/SEC"> 1 </damping_coeff>
<static_friction> 0.8 </static_friction>
<dynamic_friction> 0.5 </dynamic_friction>
<rolling_friction> 0.1 </rolling_friction>
<spring_coeff unit="LBS/FT"> 480 </spring_coeff>
<damping_coeff unit="LBS/FT/SEC"> 100 </damping_coeff>
<max_steer unit="DEG"> 0.0 </max_steer>
<brake_group> NONE </brake_group>
<retractable>0</retractable>
@ -86,18 +86,13 @@
<location unit="IN">
<x> 68.9 </x>
<y> 0 </y>
<!-- this sets the position of the tail wheel much
lower than it should be, so that we start with
zero pitch, which makes for a better simulation
of ground start on the accelerometers/gyros in
ArduPlane -->
<z> -7.8 </z>
<z> -3 </z>
</location>
<static_friction> 1.0 </static_friction>
<dynamic_friction> 0.8 </dynamic_friction>
<rolling_friction> 0.02 </rolling_friction>
<spring_coeff unit="LBS/FT"> 12 </spring_coeff>
<damping_coeff unit="LBS/FT/SEC"> 1 </damping_coeff>
<static_friction> 8.0 </static_friction>
<dynamic_friction> 5.0 </dynamic_friction>
<rolling_friction> 0.1 </rolling_friction>
<spring_coeff unit="LBS/FT"> 480 </spring_coeff>
<damping_coeff unit="LBS/FT/SEC"> 100 </damping_coeff>
<max_steer unit="DEG"> 360.0 </max_steer>
<brake_group> NONE </brake_group>
<retractable>0</retractable>

View File

@ -123,16 +123,18 @@ dynamics model, and external 3D model.
<script>
setlistener("/sim/signals/fdm-initialized", func {
var left = screen.display.new(20, 10);
left.add("/surface-positions/right-aileron-pos-norm");
left.add("/surface-positions/elevator-pos-norm");
left.add("/surface-positions/rudder-pos-norm");
left.add("/engines/engine/rpm");
left.add("/apm/aileron");
left.add("/apm/elevator");
left.add("/apm/rudder");
left.add("/apm/throttle");
var right = screen.display.new(-250, 20);
right.add("/orientation/pitch-deg");
right.add("/orientation/roll-deg");
right.add("/position/altitude-agl-ft");
right.add("/velocities/airspeed-kt");
right.add("/apm/pitch");
right.add("/apm/roll");
right.add("/apm/altitude");
right.add("/apm/heading");
right.add("/apm/airspeed");
right.add("/apm/groundspeed");
});
</script>
</rascal>

View File

@ -86,7 +86,7 @@
<location unit="IN">
<x> 68.9 </x>
<y> 0 </y>
<z> -6.6 </z>
<z> -3 </z>
</location>
<static_friction> 0.8 </static_friction>
<dynamic_friction> 0.5 </dynamic_friction>

View File

@ -38,3 +38,35 @@ var update_airdata = func( dt ) {
setprop("/accelerations/airspeed-ktps", accel_filt);
}
round10 = func(v) {
if (v == nil) return 0;
return 0.1*int(v*10);
}
round100 = func(v) {
if (v == nil) return 0;
return 0.01*int(v*100);
}
var update_vars = func( dt ) {
asl_ft = getprop("/position/altitude-ft");
ground = getprop("/position/ground-elev-ft");
agl_m = (asl_ft - ground) * 0.3048;
setprop("/apm/altitude", round10(agl_m));
setprop("/apm/pitch", round10(getprop("/orientation/pitch-deg")));
setprop("/apm/roll", round10(getprop("/orientation/roll-deg")));
setprop("/apm/heading", round10(getprop("/orientation/heading-deg")));
setprop("/apm/aileron", round100(getprop("/surface-positions/right-aileron-pos-norm")));
setprop("/apm/elevator", round100(getprop("/surface-positions/elevator-pos-norm")));
setprop("/apm/rudder", round100(getprop("/surface-positions/rudder-pos-norm")));
setprop("/apm/throttle", round10(getprop("/engines/engine/rpm")));
setprop("/apm/groundspeed", round10(0.514444444*getprop("/instrumentation/gps/indicated-ground-speed-kt")));
# airspeed-kt is actually in feet per second (FDM NET bug)
setprop("/apm/airspeed", round10(0.3048*getprop("/velocities/airspeed-kt")));
}

View File

@ -10,6 +10,7 @@ var main_loop = func {
last_time = time;
update_airdata( dt );
update_vars( dt );
update_ugear( dt );
settimer(main_loop, 0);

View File

@ -71,20 +71,21 @@ Arducotper UAV Model
</payload>
<nasal>
<arducopter>
<file>Aircraft/arducopter/quad.nas</file>
<script>
setlistener("/sim/signals/fdm-initialized", func {
var left = screen.display.new(20, 10);
left.add("/engines/engine[0]/rpm");
left.add("/engines/engine[1]/rpm");
left.add("/engines/engine[2]/rpm");
left.add("/engines/engine[3]/rpm");
left.add("/apm/motor_right");
left.add("/apm/motor_left");
left.add("/apm/motor_front");
left.add("/apm/motor_back");
var right = screen.display.new(-250, 20);
right.add("/position/altitude-agl-ft");
right.add("/orientation/roll-deg");
right.add("/orientation/pitch-deg");
right.add("/orientation/heading-deg");
right.add("/instrumentation/gps/indicated-ground-speed-kt");
right.add("/apm/altitude");
right.add("/apm/roll");
right.add("/apm/pitch");
right.add("/apm/heading");
right.add("/apm/airspeed");
});
</script>
</arducopter>

View File

@ -193,9 +193,9 @@
</DO_SET_SERVO>
<DO_REPEAT_SERVO>
<P1>Ser No</P1>
<P2>Repeat#</P2>
<P3>Delay (s)</P3>
<P4>PWM</P4>
<P2>PWM</P2>
<P3>Repeat#</P3>
<P4>Delay (s)</P4>
<X></X>
<Y></Y>
<Z></Z>
@ -431,9 +431,9 @@
</DO_SET_SERVO>
<DO_REPEAT_SERVO>
<P1>Ser No</P1>
<P2>Repeat#</P2>
<P3>Delay (s)</P3>
<P4>PWM</P4>
<P2>PWM</P2>
<P3>Repeat#</P3>
<P4>Delay (s)</P4>
<X></X>
<Y></Y>
<Z></Z>

View File

@ -193,9 +193,9 @@
</DO_SET_SERVO>
<DO_REPEAT_SERVO>
<P1>Ser No</P1>
<P2>Repeat#</P2>
<P3>Delay (s)</P3>
<P4>PWM</P4>
<P2>PWM</P2>
<P3>Repeat#</P3>
<P4>Delay (s)</P4>
<X></X>
<Y></Y>
<Z></Z>
@ -431,9 +431,9 @@
</DO_SET_SERVO>
<DO_REPEAT_SERVO>
<P1>Ser No</P1>
<P2>Repeat#</P2>
<P3>Delay (s)</P3>
<P4>PWM</P4>
<P2>PWM</P2>
<P3>Repeat#</P3>
<P4>Delay (s)</P4>
<X></X>
<Y></Y>
<Z></Z>