planner quick hil fix

gains 4500 4500 4500 500 and reverse rudder
This commit is contained in:
Michael Oborne 2011-10-09 21:30:28 +08:00
parent e232a0936f
commit 6797510236
3 changed files with 34 additions and 7 deletions

11
.gitignore vendored
View File

@ -7,4 +7,13 @@ CMakeFiles
CMakeCache.txt
cmake_install.cmake
build
/Tools/ArdupilotMegaPlanner/bin/Release/gmapcache
/Tools/ArdupilotMegaPlanner/bin/Release/gmapcache
/Tools/ArdupilotMegaPlanner/APMPlannerXplanes/APMPlannerXplanes/Debug
/Tools/ArdupilotMegaPlanner/CustomImages
/Tools/ArdupilotMegaPlanner/Updater/obj
/Tools/ArdupilotMegaPlanner/Updater/bin
/Tools/ArdupilotMegaPlanner/bin/Debug
/Tools/ArdupilotMegaPlanner/bin/APM Planner.app
/Tools/ArdupilotMegaPlanner/obj
/Tools/ArdupilotMegaPlanner/resedit/bin
/Tools/ArdupilotMegaPlanner/resedit/obj

View File

@ -26,6 +26,7 @@ namespace ArdupilotMega.GCSViews
EndPoint Remote = (EndPoint)(new IPEndPoint(IPAddress.Any, 0));
byte[] udpdata = new byte[113 * 9 + 5]; // 113 types - 9 items per type (index+8) + 5 byte header
float[][] DATA = new float[113][];
TDataFromAeroSimRC aeroin = new TDataFromAeroSimRC();
DateTime now = DateTime.Now;
DateTime lastgpsupdate = DateTime.Now;
List<string> position = new List<string>();
@ -836,7 +837,7 @@ namespace ArdupilotMega.GCSViews
}
else if (receviedbytes == 582)
{
TDataFromAeroSimRC aeroin = new TDataFromAeroSimRC();
aeroin = new TDataFromAeroSimRC();
object temp = aeroin;
@ -1154,7 +1155,7 @@ namespace ArdupilotMega.GCSViews
throttle_out = 1;
rudder_out = (float)MainV2.cs.hilch4 / -ruddergain;
collective_out = (float)(MainV2.cs.hilch3 - 1000) / throttlegain;
collective_out = (float)(MainV2.cs.hilch3 - 1500) / throttlegain;
}
else
{
@ -1164,7 +1165,7 @@ namespace ArdupilotMega.GCSViews
throttle_out = ((float)MainV2.cs.hilch3 + 5000) / throttlegain;
rudder_out = (float)MainV2.cs.hilch4 / ruddergain;
}
/*
if ((roll_out == -1 || roll_out == 1) && (pitch_out == -1 || pitch_out == 1))
{
this.Invoke((MethodInvoker)delegate
@ -1176,7 +1177,7 @@ namespace ArdupilotMega.GCSViews
catch { }
});
}
*/
// Limit min and max
roll_out = Constrain(roll_out, -1, 1);
pitch_out = Constrain(pitch_out, -1, 1);
@ -1207,7 +1208,14 @@ namespace ArdupilotMega.GCSViews
else { list3.Clear(); }
if (CHKgraphthrottle.Checked)
{
list4.Add(time, throttle_out);
if (heli)
{
list4.Add(time, collective_out);
}
else
{
list4.Add(time, throttle_out);
}
}
else { list4.Clear(); }
}
@ -1223,6 +1231,11 @@ namespace ArdupilotMega.GCSViews
{
updateScreenDisplay(lastfdmdata.latitude, lastfdmdata.longitude, lastfdmdata.altitude * .3048, lastfdmdata.phi, lastfdmdata.theta, lastfdmdata.psi, lastfdmdata.psi, roll_out, pitch_out, rudder_out, throttle_out);
}
if (RAD_aerosimrc.Checked)
{
updateScreenDisplay(aeroin.Model_fLatitude * deg2rad, aeroin.Model_fLongitude * deg2rad, aeroin.Model_fPosZ, aeroin.Model_fRoll, aeroin.Model_fPitch, aeroin.Model_fHeading, aeroin.Model_fHeading, roll_out, pitch_out, rudder_out, throttle_out);
}
}
}
catch (Exception e) { Console.WriteLine("Error updateing screen stuff " + e.ToString()); }
@ -1240,6 +1253,11 @@ namespace ArdupilotMega.GCSViews
Array.Copy(BitConverter.GetBytes((double)(rudder_out * REV_rudder)), 0, AeroSimRC, 16, 8);
Array.Copy(BitConverter.GetBytes((double)(throttle_out)), 0, AeroSimRC, 24, 8);
if (heli)
{
Array.Copy(BitConverter.GetBytes((double)(collective_out)), 0, AeroSimRC, 24, 8);
}
try
{
SimulatorRECV.SendTo(AeroSimRC, Remote);

View File

@ -11,7 +11,7 @@
<dsig:Transform Algorithm="urn:schemas-microsoft-com:HashTransforms.Identity" />
</dsig:Transforms>
<dsig:DigestMethod Algorithm="http://www.w3.org/2000/09/xmldsig#sha1" />
<dsig:DigestValue>KL2GgPg3v0nfw+58LySJfeIHyEM=</dsig:DigestValue>
<dsig:DigestValue>JxmjTgyhsfYjYCKuWvibXDaws3I=</dsig:DigestValue>
</hash>
</dependentAssembly>
</dependency>