APM Planner 1.0.77

misc fix's
This commit is contained in:
Michael Oborne 2011-10-04 19:19:25 +08:00
parent 2b1fdb0074
commit 445bd17d8a
19 changed files with 1280 additions and 514 deletions

View File

@ -349,6 +349,15 @@
<DependentUpon>AGauge.cs</DependentUpon>
<SubType>Designer</SubType>
</EmbeddedResource>
<EmbeddedResource Include="GCSViews\Firmware.ru.resx">
<DependentUpon>Firmware.cs</DependentUpon>
</EmbeddedResource>
<EmbeddedResource Include="GCSViews\FlightData.ru.resx">
<DependentUpon>FlightData.cs</DependentUpon>
</EmbeddedResource>
<EmbeddedResource Include="GCSViews\Terminal.ru.resx">
<DependentUpon>Terminal.cs</DependentUpon>
</EmbeddedResource>
<EmbeddedResource Include="Log.zh-Hans.resx">
<DependentUpon>Log.cs</DependentUpon>
</EmbeddedResource>
@ -491,7 +500,9 @@
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
</None>
<None Include="Resources\Welcome_CN.rtf" />
<None Include="Resources\Welcome_to_Michael_Oborne.rtf" />
<None Include="Resources\Welcome_to_Michael_Oborne.rtf">
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
</None>
</ItemGroup>
<ItemGroup>
<Content Include="apm2.ico" />
@ -501,8 +512,12 @@
</Content>
<Content Include="Resources\MAVCmd.zh-Hans.txt" />
<Content Include="Resources\MAVParam.zh-Hans.txt" />
<None Include="Resources\MAVCmd.txt" />
<None Include="Resources\MAVParam.txt" />
<None Include="Resources\MAVCmd.txt">
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
</None>
<None Include="Resources\MAVParam.txt">
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
</None>
<None Include="Resources\new frames-09.png" />
<Content Include="dataflashlog.xml">
<CopyToOutputDirectory>Always</CopyToOutputDirectory>

View File

@ -138,7 +138,7 @@ namespace ArdupilotMega.GCSViews
// setup language selection
CultureInfo ci = null;
foreach (string name in new string[] { "en-US", "zh-Hans" })
foreach (string name in new string[] { "en-US", "zh-Hans", "ru" })
{
ci = MainV2.getcultureinfo(name);
if (ci != null)

View File

@ -695,6 +695,7 @@ namespace ArdupilotMega.GCSViews
int optionoffset = 0;
int total = 0;
bool hitend = false;
while (!sr.EndOfStream)
{
@ -726,11 +727,34 @@ namespace ArdupilotMega.GCSViews
{
optionoffset += (int)Convert.ToUInt16(line.Substring(9, 4), 16) << 4;
}
else if (option == 1)
{
hitend = true;
}
int checksum = Convert.ToInt32(line.Substring(line.Length - 2, 2), 16);
byte checksumact = 0;
for (int z = 0; z < ((line.Length - 1 - 2) / 2) ; z++) // minus 1 for : then mins 2 for checksum itself
{
checksumact += Convert.ToByte(line.Substring(z * 2 + 1, 2), 16);
}
checksumact = (byte)(0x100 - checksumact);
if (checksumact != checksum)
{
MessageBox.Show("The hex file loaded is invalid, please try again.");
throw new Exception("Checksum Failed - Invalid Hex");
}
}
//Regex regex = new Regex(@"^:(..)(....)(..)(.*)(..)$"); // length - address - option - data - checksum
}
if (!hitend)
{
MessageBox.Show("The hex file did no contain an end flag. aborting");
throw new Exception("No end flag in file");
}
Array.Resize<byte>(ref FLASH, total);
return FLASH;

View File

@ -1364,7 +1364,13 @@ namespace ArdupilotMega.GCSViews
}
}
TXT_DefaultAlt.Text = ((float)param["ALT_HOLD_RTL"] * MainV2.cs.multiplierdist).ToString("0");
string hold_alt = ((float)param["ALT_HOLD_RTL"] * MainV2.cs.multiplierdist).ToString("0");
if (hold_alt != "-1")
{
TXT_DefaultAlt.Text = hold_alt;
}
TXT_WPRad.Text = ((float)param["WP_RADIUS"] * MainV2.cs.multiplierdist).ToString("0");
try
{

View File

@ -1555,6 +1555,16 @@ namespace ArdupilotMega.GCSViews
ofd.InitialDirectory = @"C:\Program Files\FlightGear\bin\Win32\";
extra = " --fg-root=\"C:\\Program Files\\FlightGear\\data\"";
}
else if (File.Exists(@"C:\Program Files\FlightGear 2.4.0\bin\Win32\fgfs.exe"))
{
ofd.InitialDirectory = @"C:\Program Files\FlightGear 2.4.0\bin\Win32\";
extra = " --fg-root=\"C:\\Program Files\\FlightGear 2.4.0\\data\"";
}
else if (File.Exists(@"C:\Program Files (x86)\FlightGear 2.4.0\bin\Win32\fgfs.exe"))
{
ofd.InitialDirectory = @"C:\Program Files (x86)\FlightGear 2.4.0\bin\Win32\";
extra = " --fg-root=\"C:\\Program Files (x86)\\FlightGear 2.4.0\\data\"";
}
else if (File.Exists(@"/usr/games/fgfs"))
{
ofd.InitialDirectory = @"/usr/games";

File diff suppressed because it is too large Load Diff

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.0.76")]
[assembly: AssemblyFileVersion("1.0.77")]
[assembly: NeutralResourcesLanguageAttribute("")]

View File

@ -16,15 +16,15 @@ It includes both fixed wing (APM) and rotary wing (!ArduCopter) parameters. Some
||RLL2SRV_P||0||5||0.4||1||1||SERVO_ROLL_P - Attitude control gains - Tuning values for the attitude control PID loops. The P term is the primary tuning value. This determines how the control deflection varies in proportion to the required correction.||
||RLL2SRV_I||0||1||0||1||1||SERVO_ROLL_I - Attitude control gains - Tuning values for the attitude control PID loops. The I term is used to help control surfaces settle. This value should normally be kept low.||
||RLL2SRV_D||0||1||0||1||1||SERVO_ROLL_D - Attitude control gains - Tuning values for the attitude control PID loops. The D term is used to control overshoot. Avoid using or adjusting this term if you are not familiar with tuning PID loops. It should normally be zero for most aircraft.||
||RLL2SRV_IMAX||0||3000||500||100||1||SERVO_ROLL_INT_MAX_CENTIDEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking). Default is 5 degrees.||
||RLL2SRV_IMAX||0||3000||500||100||1||SERVO_ROLL_INT_MAX_DEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking). Default is 5 degrees.||
||PTCH2SRV_P||0||5||0.6||1||1||SERVO_PITCH_P - Attitude control gains - Tuning values for the attitude control PID loops. The P term is the primary tuning value. This determines how the control deflection varies in proportion to the required correction.||
||PTCH2SRV_I||0||1||0||1||1||SERVO_PITCH_I - Attitude control gains - Tuning values for the attitude control PID loops. The I term is used to help control surfaces settle. This value should normally be kept low.||
||PTCH2SRV_D||0||1||0||1||1||SERVO_PITCH_D - Attitude control gains - Tuning values for the attitude control PID loops. The D term is used to control overshoot. Avoid using or adjusting this term if you are not familiar with tuning PID loops. It should normally be zero for most aircraft.||
||PTCH2SRV_IMAX||0||3000||500||100||1||SERVO_PITCH_INT_MAX_CENTIDEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking). Default is 5 degrees.||
||PTCH2SRV_IMAX||0||3000||500||100||1||SERVO_PITCH_INT_MAX_DEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking). Default is 5 degrees.||
||ARSPD2PTCH_P||0||5||0.65||1||1||NAV_PITCH_ASP_P - P. I and D terms for pitch adjustments made to maintain airspeed.||
||ARSPD2PTCH_I||0||1||0||1||1||NAV_PITCH_ASP_I - P. I and D terms for pitch adjustments made to maintain airspeed.||
||ARSPD2PTCH_D||0||1||0||1||1||NAV_PITCH_ASP_D - P. I and D terms for pitch adjustments made to maintain airspeed.||
||ARSPD2PTCH_IMA||0||3000||500||100||1||NAV_PITCH_ASP_INT_MAX_CMSEC - In Degrees - Maximum pitch offset due to the integral. This limits the control output from being overdriven due to a persistent offset (eg. inability to maintain the programmed airspeed).||
||ARSPD2PTCH_IMA||0||3000||500||100||1||NAV_PITCH_ASP_INT_MAX - In Degrees - Maximum pitch offset due to the integral. This limits the control output from being overdriven due to a persistent offset (eg. inability to maintain the programmed airspeed).||
||YW2SRV_P||0||5||0||1||1||SERVO_YAW_P - P. I and D terms for the YAW control. Note units of this control loop are unusual. PID input is in m/s**2||
||YW2SRV_I||0||1||0||1||1||SERVO_YAW_I - P. I and D terms for the YAW control. Note units of this control loop are unusual. PID input is in m/s**2||
||YW2SRV_D||0||1||0||1||1||SERVO_YAW_D - P. I and D terms for the YAW control. Note units of this control loop are unusual. PID input is in m/s**2||
@ -36,7 +36,7 @@ It includes both fixed wing (APM) and rotary wing (!ArduCopter) parameters. Some
||ALT2PTCH_P||0||5||0.65||1||1||NAV_PITCH_ALT_P - P. I and D terms for pitch adjustments made to maintain altitude.||
||ALT2PTCH_I||0||1||0||1||1||NAV_PITCH_ALT_I - P. I and D terms for pitch adjustments made to maintain altitude.||
||ALT2PTCH_D||0||1||0||1||1||NAV_PITCH_ALT_D - P. I and D terms for pitch adjustments made to maintain altitude.||
||ALT2PTCH_IMAX||0||3000||500||100||1||NAV_PITCH_ALT_INT_MAX_CM - In Meters - Maximum pitch offset due to the integral. This limits the control output from being overdriven due to a persistent offset (eg. inability to maintain the programmed altitude).||
||ALT2PTCH_IMAX||0||3000||500||100||1||NAV_PITCH_ALT_INT_MAX - In Meters - Maximum pitch offset due to the integral. This limits the control output from being overdriven due to a persistent offset (eg. inability to maintain the programmed altitude).||
||KFF_PTCHCOMP||-3||3||0.2||0.01||1||PITCH_COMP - In Percent - Adds pitch input to compensate for the loss of lift due to roll control.||
||KFF_RDDRMIX||-3||3||0.5||0.01||1||RUDDER_MIX - Roll to yaw mixing. This allows for co-ordinated turns.||
||KFF_PTCH2THR||-3||3||0||1||1||P_TO_T - Pitch to throttle feed-forward gain.||
@ -107,13 +107,13 @@ It includes both fixed wing (APM) and rotary wing (!ArduCopter) parameters. Some
||AP_OFFSET|| || ||0|| || ||AP_OFFSET||
||TRIM_PITCH_CD|| || ||0|| || ||TRIM_PITCH_CD||
||ALT_HOLD_RTL||0||20000||10000||100||1||ALT_HOLD_HOME_CM - When the user performs a factory reset on the APM. Sets the flag for weather the current altitude or ALT_HOLD_HOME altitude should be used for Return To Launch. Also sets the value of USE_CURRENT_ALT in meters. This is mainly intended to allow users to start using the APM without programming a mission first.||
||XTRK_ANGLE_CD||0||6000||3000||100||1||XTRACK_ENTRY_ANGLE_CENTIDEGREE - Maximum angle used to correct for track following.||
||ROLL_SRV_MAX||0||100||4500||100||0||ROLL_SERVO_MAX_CENTIDEGREE||
||PITCH_SRV_MAX||0||100||4500||100||0||PITCH_SERVO_MAX_CENTIDEGREE||
||RUDER_SRV_MAX||0||100||4500||100||0||RUDDER_SERVO_MAX_CENTIDEGREE||
||LIM_ROLL_CD||0||6000||4500||100||1||HEAD_MAX_CENTIDEGREE - The maximum commanded bank angle in either direction. The default is 45 degrees. Decrease this value if your aircraft is not stable or has difficulty maintaining altitude in a steep bank.||
||LIM_PITCH_MAX||0||6000||1500||100||1||PITCH_MAX_CENTIDEGREE - The maximum commanded pitch up angle. The default is 15 degrees. Care should be taken not to set this value too large, as the aircraft may stall||
||LIM_PITCH_MIN||-6000||0||-2500||100||1||PITCH_MIN_CENTIDEGREE - The maximum commanded pitch down angle. Note that this value must be negative. The default is -25 degrees. Care should be taken not to set this value too large as it may result in overspeeding the aircraft.||
||XTRK_ANGLE_CD||0||6000||3000||100||1||XTRACK_ENTRY_ANGLE_DEGREE - Maximum angle used to correct for track following.||
||ROLL_SRV_MAX||0||100||4500||100||0||ROLL_SERVO_MAX_DEGREE||
||PITCH_SRV_MAX||0||100||4500||100||0||PITCH_SERVO_MAX_DEGREE||
||RUDER_SRV_MAX||0||100||4500||100||0||RUDDER_SERVO_MAX_DEGREE||
||LIM_ROLL_CD||0||6000||4500||100||1||HEAD_MAX_DEGREE - The maximum commanded bank angle in either direction. The default is 45 degrees. Decrease this value if your aircraft is not stable or has difficulty maintaining altitude in a steep bank.||
||LIM_PITCH_MAX||0||6000||1500||100||1||PITCH_MAX_DEGREE - The maximum commanded pitch up angle. The default is 15 degrees. Care should be taken not to set this value too large, as the aircraft may stall||
||LIM_PITCH_MIN||-6000||0||-2500||100||1||PITCH_MIN_DEGREE - The maximum commanded pitch down angle. Note that this value must be negative. The default is -25 degrees. Care should be taken not to set this value too large as it may result in overspeeding the aircraft.||
||GND_ALT_CM||0||500000||0||100||1||GND_ALT_CM||
||GND_ABS_PRESS|| || ||0|| || ||GND_ABS_PRESS||
||COMPASS_DEC||-1.57075||1.57075||0||1|| ||COMPASS_DEC - Compass Declination||

View File

@ -0,0 +1,19 @@
WAYPOINT;WAYPOINT;Delay;Alt;Lat;Long
LOITER_UNLIM;LOITER_UNLIM;N/A;Alt;Lat;Long
LOITER_TURNS;LOITER_TURNS;Turns;Alt;Lat;Long
LOITER_TIME;LOITER_TIME;Time s*10;Alt;Lat;Long
RETURN_TO_LAUNCH;RETURN_TO_LAUNCH;N/A;Alt;Lat;Long
LAND;LAND;N/A;Alt;Lat;Long
TAKEOFF;TAKEOFF;Angle;Alt;N/A;N/A
CONDITION_DELAY;CONDITION_DELAY;N/A;N/A;Time (sec);N/A
CONDITION_CHANGE_ALT;CONDITION_CHANGE_ALT;N/A;Alt;Rate (cm/sec);N/A
CONDITION_DISTANCE;CONDITION_DISTANCE;N/A;N/A;Dist (m);N/A
CONDITION_YAW;CONDITION_YAW;Angle;Speed(deg/sec);Direction (1/-1);Relateiv(1)/Absolute(0)
DO_JUMP;DO_JUMP;WP #;N/A;Repeat Count;N/A
DO_CHANGE_SPEED;DO_CHANGE_SPEED;Type (0=as 1=gs);Speed (m/s);Throttle(%);N/A
DO_SET_HOME;DO_SET_HOME;Current(1)/Spec(0);Alt (m);Lat;Long
DO_SET_PARAMETER;DO_SET_PARAMETER;Param Number;Param Value;N/A;N/A
DO_REPEAT_RELAY;DO_REPEAT_RELAY;N/A;Repeat#;Delay (sec);N/A
DO_SET_RELAY;DO_SET_RELAY;Off(0)/On(1);N/A;N/A;N/A
DO_SET_SERVO;DO_SET_SERVO;Servo No;PWM;N/A;N/A
DO_REPEAT_SERVO;DO_REPEAT_SERVO;Servo No;PWM;Repeat#;Delay (sec)

View File

@ -0,0 +1,221 @@
== MAVLink Parameters == (this is a copy fo the wiki page FYI)
This is a list of all the user-modifiable MAVLink parameters and what they do. You can modify them via the MAVLink parameters window in any compatible GCS, such as the Mission Planner, HK GCS or !QGroundControl.
It includes both fixed wing (APM) and rotary wing (!ArduCopter) parameters. Some may only be relevant for one platform or another.
|| *EEPROM variable name* || *Min* || *Max* || *Default* || *Multiplier* || *Enabled (0 = no, 1 = yes)* || *Comment* ||
||MAH|| || ||1|| || || ||
||CURRENT_ENABLE|| || ||1|| || || ||
||AOA|| || ||1|| || || ||
||MAG_ENABLE|| || ||1|| || || ||
||HDNG2RLL_P||0||5||0.7||1||1||NAV_ROLL_P - Navigation control gains. Tuning values for the navigation control PID loops. The P term is the primary tuning value. This determines how the control deflection varies in proportion to the required correction.||
||HDNG2RLL_I||0||1||0.01||1||1||NAV_ROLL_I - Navigation control gains. Tuning values for the navigation control PID loops. The I term is used to control drift.||
||HDNG2RLL_D||0||1||0.02||1||1||NAV_ROLL_D - Navigation control gains. Tuning values for the navigation control PID loops. The D term is used to control overshoot. Avoid adjusting this term if you are not familiar with tuning PID loops.||
||HDNG2RLL_IMAX||0||3000||500||100||1||NAV_ROLL_INT_MAX_CENTIDEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. native flight AoA). If you find this value is insufficient consider adjusting the AOA parameter.||
||RLL2SRV_P||0||5||0.4||1||1||SERVO_ROLL_P - Attitude control gains - Tuning values for the attitude control PID loops. The P term is the primary tuning value. This determines how the control deflection varies in proportion to the required correction.||
||RLL2SRV_I||0||1||0||1||1||SERVO_ROLL_I - Attitude control gains - Tuning values for the attitude control PID loops. The I term is used to help control surfaces settle. This value should normally be kept low.||
||RLL2SRV_D||0||1||0||1||1||SERVO_ROLL_D - Attitude control gains - Tuning values for the attitude control PID loops. The D term is used to control overshoot. Avoid using or adjusting this term if you are not familiar with tuning PID loops. It should normally be zero for most aircraft.||
||RLL2SRV_IMAX||0||3000||500||100||1||SERVO_ROLL_INT_MAX_DEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking). Default is 5 degrees.||
||PTCH2SRV_P||0||5||0.6||1||1||SERVO_PITCH_P - Attitude control gains - Tuning values for the attitude control PID loops. The P term is the primary tuning value. This determines how the control deflection varies in proportion to the required correction.||
||PTCH2SRV_I||0||1||0||1||1||SERVO_PITCH_I - Attitude control gains - Tuning values for the attitude control PID loops. The I term is used to help control surfaces settle. This value should normally be kept low.||
||PTCH2SRV_D||0||1||0||1||1||SERVO_PITCH_D - Attitude control gains - Tuning values for the attitude control PID loops. The D term is used to control overshoot. Avoid using or adjusting this term if you are not familiar with tuning PID loops. It should normally be zero for most aircraft.||
||PTCH2SRV_IMAX||0||3000||500||100||1||SERVO_PITCH_INT_MAX_DEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking). Default is 5 degrees.||
||ARSPD2PTCH_P||0||5||0.65||1||1||NAV_PITCH_ASP_P - P. I and D terms for pitch adjustments made to maintain airspeed.||
||ARSPD2PTCH_I||0||1||0||1||1||NAV_PITCH_ASP_I - P. I and D terms for pitch adjustments made to maintain airspeed.||
||ARSPD2PTCH_D||0||1||0||1||1||NAV_PITCH_ASP_D - P. I and D terms for pitch adjustments made to maintain airspeed.||
||ARSPD2PTCH_IMA||0||3000||500||100||1||NAV_PITCH_ASP_INT_MAX - In Degrees - Maximum pitch offset due to the integral. This limits the control output from being overdriven due to a persistent offset (eg. inability to maintain the programmed airspeed).||
||YW2SRV_P||0||5||0||1||1||SERVO_YAW_P - P. I and D terms for the YAW control. Note units of this control loop are unusual. PID input is in m/s**2||
||YW2SRV_I||0||1||0||1||1||SERVO_YAW_I - P. I and D terms for the YAW control. Note units of this control loop are unusual. PID input is in m/s**2||
||YW2SRV_D||0||1||0||1||1||SERVO_YAW_D - P. I and D terms for the YAW control. Note units of this control loop are unusual. PID input is in m/s**2||
||YW2SRV_IMAX||0||3000||0||100||1||SERVO_YAW_INT_MAX - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking).||
||ENRGY2THR_P||0||5||0.5||1||1||THROTTLE_TE_P - P. I and D terms for throttle adjustments made to control altitude.||
||ENRGY2THR_I||0||1||0||1||1||THROTTLE_TE_I - P. I and D terms for throttle adjustments made to control altitude.||
||ENRGY2THR_D||0||1||0||1||1||THROTTLE_TE_D - P. I and D terms for throttle adjustments made to control altitude.||
||ENRGY2THR_IMAX||0||100||20||1||1||THROTTLE_TE_INT_MAX - In Percent - Maximum throttle input due to the integral term. This limits the throttle from being overdriven due to a persistent offset (e.g. inability to maintain the programmed altitude).||
||ALT2PTCH_P||0||5||0.65||1||1||NAV_PITCH_ALT_P - P. I and D terms for pitch adjustments made to maintain altitude.||
||ALT2PTCH_I||0||1||0||1||1||NAV_PITCH_ALT_I - P. I and D terms for pitch adjustments made to maintain altitude.||
||ALT2PTCH_D||0||1||0||1||1||NAV_PITCH_ALT_D - P. I and D terms for pitch adjustments made to maintain altitude.||
||ALT2PTCH_IMAX||0||3000||500||100||1||NAV_PITCH_ALT_INT_MAX - In Meters - Maximum pitch offset due to the integral. This limits the control output from being overdriven due to a persistent offset (eg. inability to maintain the programmed altitude).||
||KFF_PTCHCOMP||-3||3||0.2||0.01||1||PITCH_COMP - In Percent - Adds pitch input to compensate for the loss of lift due to roll control.||
||KFF_RDDRMIX||-3||3||0.5||0.01||1||RUDDER_MIX - Roll to yaw mixing. This allows for co-ordinated turns.||
||KFF_PTCH2THR||-3||3||0||1||1||P_TO_T - Pitch to throttle feed-forward gain.||
||KFF_THR2PTCH||-3||3||0||1||1||T_TO_P - Throttle to pitch feed-forward gain.||
||XTRK_GAIN_SC||0||100||100||100||1||XTRACK_GAIN_SCALED - Default value is 1.0 degrees per metre. Values lower than 0.001 will disable crosstrack compensation.||
||ALT_MIX||0||1||1||0.01||1||ALTITUDE_MIX - In Percent - Configures the blend between GPS and pressure altitude. 0 = GPS altitude, 1 = Press alt, 0.5 = half and half, etc.||
||ARSPD_RATIO||0||5||1.9936||1||1||AIRSPEED_RATIO - Adjust AIRSPEED_RATIO in small increments to calibrate the airspeed sensor relative to your GPS. The calculation and default value are optimized for speeds around 12 m/s||
||WP_RADIUS||0||200||30||1||1||WP_RADIUS_DEFAULT - When the user performs a factory reset on the APM, sets the waypoint radius (the radius from a target waypoint within which the APM will consider itself to have arrived at the waypoint) to this value in meters. This is mainly intended to allow users to start using the APM without programming a mission first.||
||WP_LOITER_RAD||0||200||60||1||1||LOITER_RADIUS_DEFAULT - When the user performs a factory reset on the APM, sets the loiter radius (the distance the APM will attempt to maintain from a waypoint while loitering) to this value in meters. This is mainly intended to allow users to start using the APM without programming a mission first.||
||ARSPD_FBW_MIN||5||50||6||1||1||AIRSPEED_FBW_MIN - In m/s - Airspeed corresponding to minimum and maximum throttle in Fly By Wire B mode.||
||ARSPD_FBW_MAX||5||50||22||1||1||AIRSPEED_FBW_MAX - In m/s - Airspeed corresponding to minimum and maximum throttle in Fly By Wire B mode. AIRSPEED_FBW_MAX also sets the maximum airspeed that the cruise airspeed can be ""nudged"" to in AUTO mode when ENABLE_STICK_MIXING is set. In AUTO the cruise airspeed can be increased between AIRSPEED_CRUISE and AIRSPEED_FBW_MAX by positioning the throttle stick in the top 1/2 of its range. Throttle stick in the bottom 1/2 provide regular AUTO control.||
||THR_MIN||0||100||0||1||1||THROTTLE_MIN - The minimum throttle setting to which the autopilot will reduce the throttle while descending. The default is zero, which is suitable for aircraft with a steady power-off glide. Increase this value if your aircraft needs throttle to maintain a stable descent in level flight.||
||THR_MAX||0||100||75||1||1||THROTTLE_MAX - The maximum throttle setting the autopilot will apply. The default is 75%. Reduce this value if your aicraft is overpowered or has complex flight characteristics at high throttle settings.||
||THR_FAILSAFE||0||0||1|| || ||THROTTLE_FAILSAFE - The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel (channel 3). This can be used to achieve a failsafe override on loss of radio control without having to sacrifice one of your FLIGHT_MODE settings as the throttle failsafe overrides the switch-selected mode. Throttle failsafe is enabled by setting THROTTLE_FAILSAFE to 1.||
||THR_FS_ACTION||0||2||1||1|| ||THROTTLE_FAILSAFE_ACTION - The FAILSAFE_ACTION setting determines what APM will do when throttle failsafe mode is entered while flying in AUTO mode. This is important in order to avoid accidental failsafe behaviour when flying waypoints that take the aircraft temporarily out of radio range. If FAILSAFE_ACTION is 1 when failsafe is entered in AUTO or LOITER modes the aircraft will head for home in RTL mode. If the throttle channel moves back up it will return to AUTO or LOITER mode. The default behavior is to ignore throttle failsafe in AUTO and LOITER modes.||
||TRIM_THROTTLE||0||90||45||1||1||THROTTLE_CRUISE - In Percent - The approximate throttle setting to achieve AIRSPEED_CRUISE in level flight. The default is 45% which is reasonable for a modestly powered aircraft.||
||TRIM_AUTO||0||1||1||1||1||AUTO_TRIM - !ArduPilot Mega can update its trim settings by looking at the radio inputs when switching out of MANUAL mode. This allows you to manually trim your aircraft before switching to an assisted mode but it also means that you should avoid switching out of MANUAL while you have any control stick deflection.||
||FLTMODE_CH||5||8||8||1||1||FLIGHT_MODE_CHANNEL - Flight modes assigned to the control channel, and the input channel that is read for the control mode. Use a servo tester or the !ArduPilotMega_demo test program to check your switch settings. ATTENTION: Some !ArduPilot Mega boards have radio channels marked 0-7 and others have them marked the standard 1-8. The FLIGHT_MODE_CHANNEL option uses channel numbers 1-8 (and defaults to 8). If you only have a three-position switch or just want three modes set your switch to produce 1165, 1425, and 1815 microseconds and configure FLIGHT_MODE 1 & 2, 3 & 4 and 5 & 6 to be the same. This is the default. If you have FLIGHT_MODE_CHANNEL set to 8 (the default) and your control channel connected to input channel 8, the hardware failsafe mode will activate for any control input over 1750ms.||
||FLIGHT_MODE_1||0||14||11||1|| ||FLIGHT_MODE_1 - The following standard flight modes are available: MANUAL = Full manual control via the hardware multiplexer. STABILIZE = Tries to maintain level flight but can be overridden with radio control inputs. FLY_BY_WIRE_A = Autopilot style control via user input with manual throttle. FLY_BY_WIRE_B = Autopilot style control via user input, aispeed controlled with throttle. RTL = Returns to the Home location and then LOITERs at a safe altitude. AUTO = Autonomous flight based on programmed waypoints.||
||FLIGHT_MODE_2||0||14||11||1|| ||FLIGHT_MODE_2||
||FLIGHT_MODE_3||0||14||5||1|| ||FLIGHT_MODE_3||
||FLIGHT_MODE_4||0||14||5||1|| ||FLIGHT_MODE_4||
||FLIGHT_MODE_5||0||14||0||1|| ||FLIGHT_MODE_5||
||FLIGHT_MODE_6||0||14||0||1|| ||FLIGHT_MODE_6||
||RC1_MIN||900||2100||1500||1||1||PWM_RC1_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit||
||RC1_MAX||900||2100||1500||1||1||PWM_RC1_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit||
||RC1_TRIM||900||2100||1200||1||1||PWM_RC1_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit||
||RC2_MIN||900||2100||1500||1||1||PWM_RC2_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit||
||RC2_MAX||900||2100||1500||1||1||PWM_RC2_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit||
||RC2_TRIM||900||2100||1200||1||1||PWM_RC2_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit||
||RC3_MIN||900||2100||1500||1||1||PWM_RC3_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit||
||RC3_MAX||900||2100||1500||1||1||PWM_RC3_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit ||
||RC3_TRIM||900||2100||1500||1||1||PWM_RC3_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit ||
||RC4_MIN||900||2100||1500||1||1||PWM_RC4_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit ||
||RC4_MAX||900||2100||1500||1||1||PWM_RC4_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit ||
||RC4_TRIM||900||2100||1200||1||1||PWM_RC4_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit ||
||RC5_MIN||900||2100||1500||1||1||PWM_CH5_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit ||
||RC5_MAX||900||2100||1500||1||1||PWM_CH5_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit ||
||RC5_MAX||900||2100||1500||1||1||PWM_CH5_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit ||
||RC5_TRIM||900||2100||1500||1||1||PWM_CH5_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit ||
||RC6_MIN||900||2100||1500||1||1||PWM_CH6_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit ||
||RC6_MAX||900||2100||1500||1||1||PWM_CH6_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit ||
||RC6_TRIM||900||2100||1500||1||1||PWM_CH6_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit ||
||RC7_MIN||900||2100||1500||1||1||PWM_CH7_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit ||
||RC7_MAX||900||2100||1500||1||1||PWM_CH7_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit ||
||RC7_TRIM||900||2100||1500||1||1||PWM_CH7_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit ||
||RC8_MIN||900||2100||1500||1||1||PWM_CH8_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit ||
||RC8_MAX||900||2100||1500||1||1||PWM_CH8_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit ||
||RC8_TRIM||900||2100||1500||1||1||PWM_CH8_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit ||
||IMU_OFFSET_0||0||0||0|| || ||IMU_OFFSET_0 - IMU Calibration||
||IMU_OFFSET_1||0||0||0|| || ||IMU_OFFSET_1 - IMU Calibration||
||IMU_OFFSET_2||0||0||0|| || ||IMU_OFFSET_2 - IMU Calibration||
||IMU_OFFSET_3||0||0||0|| || ||IMU_OFFSET_3 - IMU Calibration||
||IMU_OFFSET_4||0||0||0|| || ||IMU_OFFSET_4 - IMU Calibration||
||IMU_OFFSET_5||0||0||0|| || ||IMU_OFFSET_5 - IMU Calibration||
||YAW_MODE|| || ||0|| || ||YAW_MODE||
||WP_MODE|| || ||0|| || ||WP_MODE||
||WP_TOTAL||0||255|| ||0|| ||WP_TOTAL||
||WP_INDEX||0||255|| ||0|| ||WP_INDEX||
||CONFIG|| || ||1|| || ||CONFIG_OPTIONS||
||SWITCH_ENABLE||0||1||1||1||1||REVERS_SWITCH_ENABLE - 0 = Off, 1 = On, Enables/Disables physical reverse switches on APM board||
||FIRMWARE_VER|| || ||0|| || ||FIRMWARE_VER||
||LOG_BITMASK||0||65535||334||1||1||LOG_BITMASK||
||TRIM_ELEVON||900||2100||1500||1||1||TRIM_ELEVON||
||THR_FS_VALUE||850||1000||950||1||1||THROTTLE_FS_VALUE - If the throttle failsafe is enabled, THROTTLE_FS_VALUE sets the channel value below which the failsafe engages. The default is 975ms, which is a very low throttle setting. Most transmitters will let you trim the manual throttle position up so that you cannot engage the failsafe with a regular stick movement. Configure your receiver's failsafe setting for the throttle channel to the absolute minimum, and use the !ArduPilotMega_demo program to check that you cannot reach that value with the throttle control. Leave a margin of at least 50 microseconds between the lowest throttle setting and THROTTLE_FS_VALUE.||
||TRIM_ARSPD_CM||500||5000||1200||100||1||AIRSPEED_CRUISE_CM - The speed in metres per second to maintain during cruise. The default is 10m/s, which is a conservative value suitable for relatively small, light aircraft.||
||GND_TEMP||-10||50||28||1||1||GND_TEMP - Ground Temperature||
||AP_OFFSET|| || ||0|| || ||AP_OFFSET||
||TRIM_PITCH_CD|| || ||0|| || ||TRIM_PITCH_CD||
||ALT_HOLD_RTL||0||20000||10000||100||1||ALT_HOLD_HOME_CM - When the user performs a factory reset on the APM. Sets the flag for weather the current altitude or ALT_HOLD_HOME altitude should be used for Return To Launch. Also sets the value of USE_CURRENT_ALT in meters. This is mainly intended to allow users to start using the APM without programming a mission first.||
||XTRK_ANGLE_CD||0||6000||3000||100||1||XTRACK_ENTRY_ANGLE_DEGREE - Maximum angle used to correct for track following.||
||ROLL_SRV_MAX||0||100||4500||100||0||ROLL_SERVO_MAX_DEGREE||
||PITCH_SRV_MAX||0||100||4500||100||0||PITCH_SERVO_MAX_DEGREE||
||RUDER_SRV_MAX||0||100||4500||100||0||RUDDER_SERVO_MAX_DEGREE||
||LIM_ROLL_CD||0||6000||4500||100||1||HEAD_MAX_DEGREE - The maximum commanded bank angle in either direction. The default is 45 degrees. Decrease this value if your aircraft is not stable or has difficulty maintaining altitude in a steep bank.||
||LIM_PITCH_MAX||0||6000||1500||100||1||PITCH_MAX_DEGREE - The maximum commanded pitch up angle. The default is 15 degrees. Care should be taken not to set this value too large, as the aircraft may stall||
||LIM_PITCH_MIN||-6000||0||-2500||100||1||PITCH_MIN_DEGREE - The maximum commanded pitch down angle. Note that this value must be negative. The default is -25 degrees. Care should be taken not to set this value too large as it may result in overspeeding the aircraft.||
||GND_ALT_CM||0||500000||0||100||1||GND_ALT_CM||
||GND_ABS_PRESS|| || ||0|| || ||GND_ABS_PRESS||
||COMPASS_DEC||-1.57075||1.57075||0||1|| ||COMPASS_DEC - Compass Declination||
||SR0_EXT_STAT||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS||
||SR0_EXTRA1||0||50||10||1||1||TELEMETRY_ENABLE Port 0 - Enable MSG_ATTITUDE||
||SR0_EXTRA2||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable MSG_VFR_HUD||
||SR0_EXTRA3||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Not currently used||
||SR0_POSITION||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages||
||SR0_RAW_CTRL||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT||
||SR0_RAW_SENS||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable IMU_RAW, GPS_RAW, GPS_STATUS packets||
||SR0_RC_CHAN||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW||
||SR3_EXT_STAT||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS||
||SR3_EXTRA1||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable MSG_ATTITUDE||
||SR3_EXTRA2||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable MSG_VFR_HUD||
||SR3_EXTRA3||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Not currently used||
||SR3_POSITION||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages||
||SR3_RAW_CTRL||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT||
||SR3_RAW_SENS||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable IMU_RAW, GPS_RAW, GPS_STATUS packets||
||SR3_RC_CHAN||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW||
||MAG_ENABLE||0||1||0||1||1||MAG_ENABLE - 0 = Off, 1 = On, Magnetometer Enable||
||ARSPD_ENABLE||0||1||0||1||1||AIRSPEED_ENABLE - 0 = Off, 1 = On, Airspeed Sensor Enable||
||BATT_CAPACITY||0||10000||1760||1||1||BATTERY_MAH - Battery capacity in mAh||
||BATT_MONITOR||0||4||0||1||1||BATTERY_MONITOR - The value should be set to 0 to disable battery monitoring, 1 to measure cell voltages for a 3 cell lipo, 2 to measure cell voltages for a 4 cell lipo, 3 to measure the total battery voltage (only) on input 1, or 4 to measure total battery voltage on input 1 and current on input 2. ||
||FS_GCS_ENABL||0||1||0||1||1||FS_GCS_ENABLE - 0 = Off, 1 = On, If the GCS heartbeat is lost for 20 seconds, the plane will Return to Launch||
||FS_LONG_ACTN||0||1||0||1||1||FS_LONG_ACTION - 0 = Off, 1 = On, If heartbeat is lost for 20 srconds, the plane will Return to Launch||
||FS_SHORT_ACTN||0||1||0||1||1||FS_SHORT_ACTION - 0 = Off, 1 = On, If heartbeat is lost for 1.5 seconds, the plane will circle until heartbeat is found again or 20 seconds has passed||
||SYSID_MYGCS||0||255||255||1||1||SYSID_MYGCS - The system ID of the GCS||
||SYSID_THISMAV||0||255||1||1||1||SYSID_THISMAV - The system ID of the MAVlink vehicle||
||AOA|| || ||0|| ||
||ACR_PIT_D|| || ||1|| || ||Description coming soon||
||ACR_PIT_I|| || ||1|| || ||Description coming soon||
||ACR_PIT_IMAX|| || ||1|| || ||Description coming soon||
||ACR_PIT_P|| || ||1|| || ||Description coming soon||
||ACR_RLL_D|| || ||1|| || ||Description coming soon||
||ACR_RLL_I|| || ||1|| || ||Description coming soon||
||ACR_RLL_IMAX|| || ||1|| || ||Description coming soon||
||ACR_RLL_P|| || ||1|| || ||Description coming soon||
||ACR_YAW_D|| || ||1|| || ||Description coming soon||
||ACR_YAW_I|| || ||1|| || ||Description coming soon||
||ACR_YAW_IMAX|| || ||1|| || ||Description coming soon||
||ACR_YAW_P|| || ||1|| || ||Description coming soon||
||ESC|| || ||1|| || ||ESC_CALIBRATE_MODE||
||FRAME|| || ||1|| || ||FRAME_ORIENTATION ||
||LOITER_RADIUS|| || ||1|| || ||Description coming soon||
||NAV_LAT_D|| || ||1|| || ||Description coming soon||
||NAV_LAT_I|| || ||1|| || ||Description coming soon||
||NAV_LAT_IMAX|| || ||1|| || ||Description coming soon||
||NAV_LAT_P|| || ||1|| || ||Description coming soon||
||NAV_LON_D|| || ||1|| || ||Description coming soon||
||NAV_LON_I|| || ||1|| || ||Description coming soon||
||NAV_LON_IMAX|| || ||1|| || ||Description coming soon||
||NAV_LON_P|| || ||1|| || ||Description coming soon||
||NAV_WP_D|| || ||1|| || ||Description coming soon||
||NAV_WP_I|| || ||1|| || ||Description coming soon||
||NAV_WP_IMAX|| || ||1|| || ||Description coming soon||
||NAV_WP_P|| || ||1|| || ||Description coming soon||
||PITCH_MAX|| || ||1|| || ||Description coming soon||
||SONAR_ENABLE||0||1||0||1||1||SONAR_ENABLE - 0 = Off, 1 = On, Sonar Enable||
||STB_PIT_D|| || ||1|| || ||Description coming soon||
||STB_PIT_I|| || ||1|| || ||Description coming soon||
||STB_PIT_IMAX|| || ||1|| || ||Description coming soon||
||STB_PIT_P|| || ||1|| || ||Description coming soon||
||STB_RLL_D|| || ||1|| || ||Description coming soon||
||STB_RLL_I|| || ||1|| || ||Description coming soon||
||STB_RLL_IMAX|| || ||1|| || ||Description coming soon||
||STB_RLL_P|| || ||1|| || ||Description coming soon||
||STB_YAW_D|| || ||1|| || ||Description coming soon||
||STB_YAW_I|| || ||1|| || ||Description coming soon||
||STB_YAW_IMAX|| || ||1|| || ||Description coming soon||
||STB_YAW_P|| || ||1|| || ||Description coming soon||
||THR_BAR_D|| || ||1|| || ||Description coming soon||
||THR_BAR_I|| || ||1|| || ||Description coming soon||
||THR_BAR_IMAX|| || ||1|| || ||Description coming soon||
||THR_BAR_P|| || ||1|| || ||Description coming soo||
||THR_SON_D|| || ||1|| || ||Description coming soon||
||THR_SON_I|| || ||1|| || ||Description coming soon||
||THR_SON_IMAX|| || ||1|| || ||Description coming soon||
||THR_SON_P|| || ||1|| || ||Description coming soon||
||WP_MODE|| || ||1|| || ||Description coming soon||
||WP_MUST_INDEX|| || ||1|| || ||Description coming soon||
||XTRACK_ANGLE|| || ||1|| || ||Description coming soon||
||XTRK_GAIN|| || ||1|| || ||Description coming soon||
||ARSPD_OFFSET|| || ||0|| || ||Description coming soon||
||ELEVON_CH1_REV||0||1||0||1||1||ELEVON_CHANNEL1_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches||
||ELEVON_CH2_REV||0||1||0||1||1||ELEVON_CHANNEL2_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches||
||ELEVON_MIXING||0||1||0||1||1||ELEVON_MIXING - 0 = Disabled, 1 = Enabled||
||ELEVON_REVERSE||0||1||0||1||1||ELEVON_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches||
||INVERTEDFLT_CH||0||8||0||1||1||INVERTED_FLIGHT_CHANNEL - Channel to select inverted flight mode, 0 = Disabled||
||RC1_REV||0||1||1||1||1||RC_CHANNEL1_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches||
||RC2_REV||0||1||1||1||1||RC_CHANNEL2_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches||
||RC3_REV||0||1||1||1||1||RC_CHANNEL3_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches||
||RC4_REV||0||1||1||1||1||RC_CHANNEL4_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches||
||RC5_REV||0||1||1||1||1||RC_CHANNEL5_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches||
||RC6_REV||0||1||1||1||1||RC_CHANNEL6_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches||
||RC7_REV||0||1||1||1||1||RC_CHANNEL7_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches||
||RC8_REV||0||1||1||1||1||RC_CHANNEL8_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches||
||SYSID_SW_MREV|| || ||0|| || ||Description coming soon||
||SYSID_SW_TYPE|| || ||0|| || ||Description coming soon||
||THR_SLEWRATE||0||100||0||1||1||THROTTLE_SLEW_RATE - 0 = Disabled, otherwise it limits throttle movement rate. Units are % per second. This is a test feature and may go away.||
||FLTMODE1||0||20||1||1|| ||FLIGHT_MODE_1 - Mode switch setting 1 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL||
||FLTMODE2||0||20||1||1|| ||FLIGHT_MODE_2 - Mode switch setting 2 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL||
||FLTMODE3||0||20||1||1|| ||FLIGHT_MODE_3 - Mode switch setting 3 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL||
||FLTMODE4||0||20||1||1|| ||FLIGHT_MODE_4 - Mode switch setting 4 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL||
||FLTMODE5||0||20||1||1|| ||FLIGHT_MODE_5 - Mode switch setting 5 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL||
||FLTMODE6||0||20||1||1|| ||FLIGHT_MODE_6 - Mode switch setting 6 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL||

View File

@ -0,0 +1,225 @@
<!DOCTYPE HTML>
<html>
<head>
<script type="application/x-javascript">
<!--
var deg2rad = Math.PI / 180;
var rad2deg = 180 / Math.PI;
var pitch =70;
var roll =20;
var yaw = 200;
var socket;
if (window["WebSocket"]) {
var host = "ws://localhost:56781/websocket/server";
//host = "ws://173.203.100.4:8002/";
try{
socket = new WebSocket(host);
//log('WebSocket - status '+socket.readyState);
socket.onopen = function(msg){ socket.send("onopen"); alert("Welcome - status "+this.readyState); };
socket.onmessage = function(msg){ alert("Received: "+msg.data); };
socket.onerror = function(msg){ alert("Error: "+msg.data); };
socket.onclose = function(msg){ alert("Disconnected - status "+this.readyState); };
}
catch(ex){ alert(ex); }
} else {
alert("This browser doesnt support websockets");
}
function draw() {
pitch -= 1.2;
roll += .75;
if (pitch < -90)
pitch = 90;
if (roll > 180)
roll = -180;
var canvas = document.getElementById("canvas");
if (canvas.getContext) {
var ctx = canvas.getContext("2d");
ctx.save();
ctx.translate(canvas.width/2,canvas.height/2);
ctx.rotate(-roll * deg2rad);
var font = "Arial";
var fontsize = canvas.height/30;
var fontoffset = fontsize - 10;
var halfwidth = canvas.width/2;
var halfheight = canvas.height/2;
var every5deg = -canvas.height / 60;
var pitchoffset = -pitch * every5deg;
var x = Math.sin(-roll * deg2rad);
var y = Math.cos(-roll * deg2rad);
gradObj = ctx.createLinearGradient(0,-halfheight * 2 ,0, halfheight *2);
gradObj.addColorStop(0.0, "Blue");
var offset = 0.5 + pitchoffset / canvas.height / 2 ;
if (offset < 0) {
offset = 0;
}
if (offset > 1) {
offset = 1;
}
gradObj.addColorStop(offset, "LightBlue");
gradObj.addColorStop(offset, "#9bb824");
gradObj.addColorStop(1.0, "#414f07");
ctx.fillStyle = gradObj;
ctx.rect(-halfwidth * 2, -halfheight *2, halfwidth * 4, halfheight * 4);
ctx.fill();
var lengthshort = canvas.width / 12;
var lengthlong = canvas.width / 8;
for (var a = -90; a <= 90; a += 5)
{
// limit to 40 degrees
if (a >= pitch - 34 && a <= pitch + 25)
{
if (a % 10 == 0)
{
if (a == 0)
{
DrawLine(ctx,"White",4, canvas.width / 2 - lengthlong - halfwidth, pitchoffset + a * every5deg, canvas.width / 2 + lengthlong - halfwidth, pitchoffset + a * every5deg);
}
else
{
DrawLine(ctx,"White",4, canvas.width / 2 - lengthlong - halfwidth, pitchoffset + a * every5deg, canvas.width / 2 + lengthlong - halfwidth, pitchoffset + a * every5deg);
}
drawstring(ctx, a, font, fontsize + 2, "White", canvas.width / 2 - lengthlong - 30 - halfwidth - (fontoffset * 1.7), pitchoffset + a * every5deg - 8 - fontoffset);
}
else
{
DrawLine(ctx,"White",4, canvas.width / 2 - lengthshort - halfwidth, pitchoffset + a * every5deg, canvas.width / 2 + lengthshort - halfwidth, pitchoffset + a * every5deg);
}
}
}
ctx.translate(0,canvas.height/14);
lengthlong = canvas.height / 66;
var extra = canvas.height / 15 * 7;
var pointlist = new Array();
pointlist[0] = 0;
pointlist[1] = -lengthlong * 2 - extra;
pointlist[2] = -lengthlong;
pointlist[3] = -lengthlong - extra;
pointlist[4] = lengthlong;
pointlist[5] = -lengthlong - extra;
DrawPolygon(ctx,"RED",4,pointlist)
for (var a = -45; a <= 45; a += 15)
{
ctx.restore();
ctx.save();
ctx.translate(canvas.width / 2, canvas.height / 2 + canvas.height/14);
ctx.rotate(a * deg2rad);
drawstring(ctx, a, font, fontsize, "White", 0 - 6 - fontoffset, -lengthlong * 2 - extra);
DrawLine(ctx,"White",4, 0, -halfheight, 0, -halfheight - 10);
}
ctx.restore();
ctx.save();
DrawEllipse(ctx,"red",4,halfwidth - 10, halfheight - 10, 20, 20);
DrawLine(ctx,"red",4, halfwidth - 10 - 10, halfheight, halfwidth - 10, halfheight);
DrawLine(ctx,"red",4, halfwidth - 10 + 20, halfheight, halfwidth - 10 + 20 + 10, halfheight);
DrawLine(ctx,"red",4, halfwidth - 10 + 20 / 2, halfheight - 10, halfwidth - 10 + 20 / 2, halfheight - 10 - 10);
//DrawLine(ctx,"GREEN",4,-halfwidth,0,halfwidth,0);
}
try {
socket.send("test "+pitch+"\n");
} catch (ex){ }// alert(ex); }
setTimeout ( "draw()", 33 );
}
function DrawEllipse(ctx,color,linewidth,x1,y1,width,height) {
ctx.lineWidth = linewidth;
ctx.strokeStyle = color;
ctx.beginPath();
ctx.moveTo(x1 + width / 2,y1 + height);
var x, y;
for (var i = 0; i <= 360; i += 1)
{
x = Math.sin(i * deg2rad) * width / 2;
y = Math.cos(i * deg2rad) * height / 2;
x = x + x1 + width / 2;
y = y + y1 + height / 2;
ctx.lineTo(x,y);
}
//ctx.moveTo(x1,y1);
ctx.stroke();
ctx.closePath();
}
function DrawLine(ctx,color,width,x1,y1,x2,y2) {
ctx.lineWidth = width;
ctx.strokeStyle = color;
ctx.beginPath();
ctx.moveTo(x1,y1);
ctx.lineTo(x2,y2);
ctx.stroke();
ctx.closePath();
}
function DrawPolygon(ctx,color,width,list) {
ctx.lineWidth = width;
ctx.strokeStyle = color;
ctx.beginPath();
ctx.moveTo(list[0],list[1]);
for ( var i=2, len=list.length; i<len; i+=2 ){
ctx.lineTo(list[i],list[i+1]);
}
ctx.lineTo(list[0],list[1]);
ctx.stroke();
ctx.closePath();
}
function drawstring(ctx,string,font,fontsize,color,x,y) {
ctx.font = fontsize + "pt "+font;
ctx.fillStyle = color;
ctx.fillText(string,x,y + fontsize);
}
-->
</script>
</head>
<body onload="draw();">
<canvas id="canvas" width="640" height="480">
<p>This example requires a browser that supports the
<a href="http://www.w3.org/html/wg/html5/">HTML5</a>
&lt;canvas&gt; feature.</p>
</canvas>
</body>
</html>

View File

@ -0,0 +1,225 @@
<!DOCTYPE HTML>
<html>
<head>
<script type="application/x-javascript">
<!--
var deg2rad = Math.PI / 180;
var rad2deg = 180 / Math.PI;
var pitch =70;
var roll =20;
var yaw = 200;
var socket;
if (window["WebSocket"]) {
var host = "ws://localhost:56781/websocket/server";
//host = "ws://173.203.100.4:8002/";
try{
socket = new WebSocket(host);
//log('WebSocket - status '+socket.readyState);
socket.onopen = function(msg){ socket.send("onopen"); alert("Welcome - status "+this.readyState); };
socket.onmessage = function(msg){ alert("Received: "+msg.data); };
socket.onerror = function(msg){ alert("Error: "+msg.data); };
socket.onclose = function(msg){ alert("Disconnected - status "+this.readyState); };
}
catch(ex){ alert(ex); }
} else {
alert("This browser doesnt support websockets");
}
function draw() {
pitch -= 1.2;
roll += .75;
if (pitch < -90)
pitch = 90;
if (roll > 180)
roll = -180;
var canvas = document.getElementById("canvas");
if (canvas.getContext) {
var ctx = canvas.getContext("2d");
ctx.save();
ctx.translate(canvas.width/2,canvas.height/2);
ctx.rotate(-roll * deg2rad);
var font = "Arial";
var fontsize = canvas.height/30;
var fontoffset = fontsize - 10;
var halfwidth = canvas.width/2;
var halfheight = canvas.height/2;
var every5deg = -canvas.height / 60;
var pitchoffset = -pitch * every5deg;
var x = Math.sin(-roll * deg2rad);
var y = Math.cos(-roll * deg2rad);
gradObj = ctx.createLinearGradient(0,-halfheight * 2 ,0, halfheight *2);
gradObj.addColorStop(0.0, "Blue");
var offset = 0.5 + pitchoffset / canvas.height / 2 ;
if (offset < 0) {
offset = 0;
}
if (offset > 1) {
offset = 1;
}
gradObj.addColorStop(offset, "LightBlue");
gradObj.addColorStop(offset, "#9bb824");
gradObj.addColorStop(1.0, "#414f07");
ctx.fillStyle = gradObj;
ctx.rect(-halfwidth * 2, -halfheight *2, halfwidth * 4, halfheight * 4);
ctx.fill();
var lengthshort = canvas.width / 12;
var lengthlong = canvas.width / 8;
for (var a = -90; a <= 90; a += 5)
{
// limit to 40 degrees
if (a >= pitch - 34 && a <= pitch + 25)
{
if (a % 10 == 0)
{
if (a == 0)
{
DrawLine(ctx,"White",4, canvas.width / 2 - lengthlong - halfwidth, pitchoffset + a * every5deg, canvas.width / 2 + lengthlong - halfwidth, pitchoffset + a * every5deg);
}
else
{
DrawLine(ctx,"White",4, canvas.width / 2 - lengthlong - halfwidth, pitchoffset + a * every5deg, canvas.width / 2 + lengthlong - halfwidth, pitchoffset + a * every5deg);
}
drawstring(ctx, a, font, fontsize + 2, "White", canvas.width / 2 - lengthlong - 30 - halfwidth - (fontoffset * 1.7), pitchoffset + a * every5deg - 8 - fontoffset);
}
else
{
DrawLine(ctx,"White",4, canvas.width / 2 - lengthshort - halfwidth, pitchoffset + a * every5deg, canvas.width / 2 + lengthshort - halfwidth, pitchoffset + a * every5deg);
}
}
}
ctx.translate(0,canvas.height/14);
lengthlong = canvas.height / 66;
var extra = canvas.height / 15 * 7;
var pointlist = new Array();
pointlist[0] = 0;
pointlist[1] = -lengthlong * 2 - extra;
pointlist[2] = -lengthlong;
pointlist[3] = -lengthlong - extra;
pointlist[4] = lengthlong;
pointlist[5] = -lengthlong - extra;
DrawPolygon(ctx,"RED",4,pointlist)
for (var a = -45; a <= 45; a += 15)
{
ctx.restore();
ctx.save();
ctx.translate(canvas.width / 2, canvas.height / 2 + canvas.height/14);
ctx.rotate(a * deg2rad);
drawstring(ctx, a, font, fontsize, "White", 0 - 6 - fontoffset, -lengthlong * 2 - extra);
DrawLine(ctx,"White",4, 0, -halfheight, 0, -halfheight - 10);
}
ctx.restore();
ctx.save();
DrawEllipse(ctx,"red",4,halfwidth - 10, halfheight - 10, 20, 20);
DrawLine(ctx,"red",4, halfwidth - 10 - 10, halfheight, halfwidth - 10, halfheight);
DrawLine(ctx,"red",4, halfwidth - 10 + 20, halfheight, halfwidth - 10 + 20 + 10, halfheight);
DrawLine(ctx,"red",4, halfwidth - 10 + 20 / 2, halfheight - 10, halfwidth - 10 + 20 / 2, halfheight - 10 - 10);
//DrawLine(ctx,"GREEN",4,-halfwidth,0,halfwidth,0);
}
try {
socket.send("test "+pitch+"\n");
} catch (ex){ }// alert(ex); }
setTimeout ( "draw()", 33 );
}
function DrawEllipse(ctx,color,linewidth,x1,y1,width,height) {
ctx.lineWidth = linewidth;
ctx.strokeStyle = color;
ctx.beginPath();
ctx.moveTo(x1 + width / 2,y1 + height);
var x, y;
for (var i = 0; i <= 360; i += 1)
{
x = Math.sin(i * deg2rad) * width / 2;
y = Math.cos(i * deg2rad) * height / 2;
x = x + x1 + width / 2;
y = y + y1 + height / 2;
ctx.lineTo(x,y);
}
//ctx.moveTo(x1,y1);
ctx.stroke();
ctx.closePath();
}
function DrawLine(ctx,color,width,x1,y1,x2,y2) {
ctx.lineWidth = width;
ctx.strokeStyle = color;
ctx.beginPath();
ctx.moveTo(x1,y1);
ctx.lineTo(x2,y2);
ctx.stroke();
ctx.closePath();
}
function DrawPolygon(ctx,color,width,list) {
ctx.lineWidth = width;
ctx.strokeStyle = color;
ctx.beginPath();
ctx.moveTo(list[0],list[1]);
for ( var i=2, len=list.length; i<len; i+=2 ){
ctx.lineTo(list[i],list[i+1]);
}
ctx.lineTo(list[0],list[1]);
ctx.stroke();
ctx.closePath();
}
function drawstring(ctx,string,font,fontsize,color,x,y) {
ctx.font = fontsize + "pt "+font;
ctx.fillStyle = color;
ctx.fillText(string,x,y + fontsize);
}
-->
</script>
</head>
<body onload="draw();">
<canvas id="canvas" width="640" height="480">
<p>This example requires a browser that supports the
<a href="http://www.w3.org/html/wg/html5/">HTML5</a>
&lt;canvas&gt; feature.</p>
</canvas>
</body>
</html>

View File

@ -75,6 +75,8 @@ foreach $file (@files) {
$line =~ s/MAV_CMD_NAV_//;
$line =~ s/MAV_CMD_//;
$line =~ s/\/\/\/</\/\/\//;
$line =~ s/typedef/public/;
$line =~ s/uint8_t/public byte/;

View File

@ -30,14 +30,14 @@
{
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Form1));
this.dataGridView1 = new System.Windows.Forms.DataGridView();
this.colFile = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.colInternal = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.colEnglish = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.colOtherLang = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.button1 = new System.Windows.Forms.Button();
this.button2 = new System.Windows.Forms.Button();
this.comboBox1 = new System.Windows.Forms.ComboBox();
this.richTextBox1 = new System.Windows.Forms.RichTextBox();
this.colFile = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.colInternal = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.colEnglish = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.colOtherLang = new System.Windows.Forms.DataGridViewTextBoxColumn();
((System.ComponentModel.ISupportInitialize)(this.dataGridView1)).BeginInit();
this.SuspendLayout();
//
@ -45,7 +45,6 @@
//
this.dataGridView1.AllowUserToAddRows = false;
this.dataGridView1.AllowUserToDeleteRows = false;
this.dataGridView1.AllowUserToOrderColumns = true;
this.dataGridView1.Anchor = ((System.Windows.Forms.AnchorStyles)((((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Bottom)
| System.Windows.Forms.AnchorStyles.Left)
| System.Windows.Forms.AnchorStyles.Right)));
@ -60,32 +59,6 @@
this.dataGridView1.Size = new System.Drawing.Size(844, 370);
this.dataGridView1.TabIndex = 0;
//
// colFile
//
this.colFile.HeaderText = "File";
this.colFile.Name = "colFile";
this.colFile.ReadOnly = true;
//
// colInternal
//
this.colInternal.HeaderText = "Internal";
this.colInternal.Name = "colInternal";
this.colInternal.ReadOnly = true;
this.colInternal.Width = 150;
//
// colEnglish
//
this.colEnglish.HeaderText = "English";
this.colEnglish.Name = "colEnglish";
this.colEnglish.ReadOnly = true;
this.colEnglish.Width = 150;
//
// colOtherLang
//
this.colOtherLang.HeaderText = "Other Lang";
this.colOtherLang.Name = "colOtherLang";
this.colOtherLang.Width = 150;
//
// button1
//
this.button1.Anchor = System.Windows.Forms.AnchorStyles.Bottom;
@ -125,6 +98,35 @@
this.richTextBox1.TabIndex = 4;
this.richTextBox1.Text = resources.GetString("richTextBox1.Text");
//
// colFile
//
this.colFile.HeaderText = "File";
this.colFile.Name = "colFile";
this.colFile.ReadOnly = true;
//
// colInternal
//
this.colInternal.HeaderText = "Internal";
this.colInternal.Name = "colInternal";
this.colInternal.ReadOnly = true;
this.colInternal.SortMode = System.Windows.Forms.DataGridViewColumnSortMode.NotSortable;
this.colInternal.Width = 150;
//
// colEnglish
//
this.colEnglish.HeaderText = "English";
this.colEnglish.Name = "colEnglish";
this.colEnglish.ReadOnly = true;
this.colEnglish.SortMode = System.Windows.Forms.DataGridViewColumnSortMode.NotSortable;
this.colEnglish.Width = 150;
//
// colOtherLang
//
this.colOtherLang.HeaderText = "Other Lang";
this.colOtherLang.Name = "colOtherLang";
this.colOtherLang.SortMode = System.Windows.Forms.DataGridViewColumnSortMode.NotSortable;
this.colOtherLang.Width = 150;
//
// Form1
//
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
@ -149,11 +151,11 @@
private System.Windows.Forms.Button button1;
private System.Windows.Forms.Button button2;
private System.Windows.Forms.ComboBox comboBox1;
private System.Windows.Forms.RichTextBox richTextBox1;
private System.Windows.Forms.DataGridViewTextBoxColumn colFile;
private System.Windows.Forms.DataGridViewTextBoxColumn colInternal;
private System.Windows.Forms.DataGridViewTextBoxColumn colEnglish;
private System.Windows.Forms.DataGridViewTextBoxColumn colOtherLang;
private System.Windows.Forms.RichTextBox richTextBox1;
}
}

View File

@ -26,7 +26,7 @@ namespace resedit
foreach (CultureInfo cul in temp)
{
list.Add(cul.DisplayName);
list.Add(cul.DisplayName + " " + cul.Name);
}
list.Sort();
@ -55,7 +55,7 @@ namespace resedit
foreach (CultureInfo cul in temp)
{
if (cul.DisplayName == comboBox1.Text)
if ((cul.DisplayName + " " + cul.Name) == comboBox1.Text)
{
Console.WriteLine(cul.Name);
ci = cul.Name;
@ -65,9 +65,15 @@ namespace resedit
foreach (string file in files)
{
// load only file of the slected lang
if (!file.ToLower().Contains(ci.ToString().ToLower() + ".resx"))
continue;
// dont load and tralations if no lang selected
if (file.ToLower().Contains("translation") && comboBox1.Text == "")
continue;
// must be a resx
if (!file.ToLower().EndsWith(".resx"))
continue;
@ -75,10 +81,14 @@ namespace resedit
ResXResourceReader reader = new ResXResourceReader(file);
Console.WriteLine(reader);
reader.BasePath = fbd.SelectedPath + System.IO.Path.DirectorySeparatorChar +"Resources";
try
{
foreach (DictionaryEntry entry in reader)
{
if (entry.Key.ToString().EndsWith(".ToolTip") || entry.Key.ToString().EndsWith(".Text") || entry.Key.ToString().EndsWith("HeaderText") || entry.Key.ToString().EndsWith("ToolTipText"))
{
dataGridView1.Rows.Add();
@ -88,6 +98,7 @@ namespace resedit
dataGridView1.Rows[dataGridView1.RowCount - 1].Cells[colEnglish.Index].Value = entry.Value.ToString();
dataGridView1.Rows[dataGridView1.RowCount - 1].Cells[colOtherLang.Index].Value = entry.Value.ToString();
}
}
}
catch (Exception ex) { Console.WriteLine(ex.ToString()); }

View File

@ -12,7 +12,7 @@ namespace ArdupilotMega
public static int getAltitude(double lat, double lng)
{
short alt = -32768;
short alt = 0;
lat += 0.00083333333333333;
//lng += 0.0008;

View File

@ -789,7 +789,11 @@ namespace ArdupilotMega
FolderBrowserDialog fbd = new FolderBrowserDialog();
fbd.SelectedPath = @"C:\Users\hog\Documents\albany 2011\New folder";
try
{
fbd.SelectedPath = @"C:\Users\hog\Documents\albany 2011\New folder";
}
catch { }
fbd.ShowDialog();