diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.de-DE.resx b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.de-DE.resx
new file mode 100644
index 0000000000..150c38b4a9
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.de-DE.resx
@@ -0,0 +1,189 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Miss using this interface can cause servo damage, use with caution!!!
+
+
+ Winkel
+
+
+ Winkel
+
+
+ Find Trim (3DR Radio)
+
+
+ Winkel
+
+
+ Winkel
+
+
+ Pan
+
+
+ Trim
+
+
+ Interface
+
+
+ Trim
+
+
+ Tilt
+
+
+ Reichweite
+
+
+ Reichweite
+
+
+ Maestro
+
+
+ PWM
+
+
+ PWM
+
+
+ Rev
+
+
+ 1000
+
+
+ Rev
+
+
+ 360
+
+
+ Verbinden
+
+
+ 1000
+
+
+ 90
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
index 3bcce47215..4cd59ed896 100644
--- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
+++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
@@ -381,6 +381,9 @@
ValuesControl.cs
+
+
+
Code
@@ -391,12 +394,6 @@
ConfigFailSafe.cs
-
- UserControl
-
-
- ConfigCameraParams.cs
-
@@ -426,12 +423,6 @@
-
- UserControl
-
-
- ConfigCameraStab.cs
-
UserControl
@@ -684,6 +675,9 @@
+
+ Tracker.cs
+
Tracker.cs
@@ -693,6 +687,9 @@
Tracker.cs
+
+ Camera.cs
+
Camera.cs
@@ -738,21 +735,54 @@
ValuesControl.cs
+
+ FollowMe.cs
+
FollowMe.cs
+
+ ConfigAccelerometerCalibrationPlane.cs
+
+
+ ConfigAccelerometerCalibrationQuad.cs
+
+
+ ConfigAP_Limits.cs
+
ConfigAP_Limits.cs
+
+ ConfigArducopter.cs
+
ConfigArducopter.cs
+
+ ConfigArduplane.cs
+
ConfigArduplane.cs
+
+ ConfigArdurover.cs
+
ConfigArdurover.cs
+
+ ConfigBatteryMonitoring.cs
+
+
+ ConfigFailSafe.cs
+
+
+ ConfigFlightModes.cs
+
+
+ ConfigHardwareOptions.cs
+
ConfigMount.cs
@@ -780,14 +810,53 @@
ConfigFailSafe.cs
+
+ ConfigPlanner.cs
+
ConfigPlanner.cs
+
+ ConfigRadioInput.cs
+
+
+ ConfigRawParams.cs
+
ConfigRawParams.cs
-
- ConfigCameraParams.cs
+
+ ConfigTradHeli.cs
+
+
+ Firmware.cs
+
+
+ FlightData.cs
+
+
+ FlightPlanner.cs
+
+
+ Help.cs
+
+
+ Simulation.cs
+
+
+ Terminal.cs
+
+
+ JoystickSetup.cs
+
+
+ Log.cs
+
+
+ LogBrowse.cs
+
+
+ MavlinkLog.cs
MavlinkLog.cs
@@ -795,9 +864,15 @@
OpenGLtest.cs
+
+ 3DRradio.cs
+
3DRradio.cs
+
+ RAW_Sensor.cs
+
SerialOutput2.cs
@@ -849,9 +924,6 @@
ConfigBatteryMonitoring.cs
-
- ConfigCameraStab.cs
-
ConfigFlightModes.cs
@@ -1313,10 +1385,11 @@
Always
-
+
+
Always
Designer
diff --git a/Tools/ArdupilotMegaPlanner/Camera.de-DE.resx b/Tools/ArdupilotMegaPlanner/Camera.de-DE.resx
new file mode 100644
index 0000000000..f3ae9d3215
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/Camera.de-DE.resx
@@ -0,0 +1,186 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ CM/Pixel
+
+
+ FOV V (m)
+
+
+ Pixel Breite
+
+
+ Flight line distance
+
+
+ Pixel Höhe
+
+
+ Kamera
+
+
+ Sidelap
+
+
+ Höhe m (agl)
+
+
+ Sensor Height
+
+
+ Focal Length
+
+
+ FOV H (m)
+
+
+ Winkel H
+
+
+ Sensor breite
+
+
+ 4608
+
+
+ Überlappen
+
+
+ Winkel V
+
+
+ Across Flight line
+
+
+ 6.16
+
+
+ 4.62
+
+
+ Speichern
+
+
+ 3456
+
+
+ Kamera zeigt nach vorne
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Comms/CommsSerialPort.cs b/Tools/ArdupilotMegaPlanner/Comms/CommsSerialPort.cs
index c296de937f..1ca16abfb9 100644
--- a/Tools/ArdupilotMegaPlanner/Comms/CommsSerialPort.cs
+++ b/Tools/ArdupilotMegaPlanner/Comms/CommsSerialPort.cs
@@ -13,6 +13,15 @@ namespace ArdupilotMega.Comms
{
static bool serialportproblem = false;
+ protected override void Dispose(bool disposing)
+ {
+ try
+ {
+ base.Dispose(disposing);
+ }
+ catch { }
+ }
+
public new void Open()
{
// 500ms write timeout - win32 api default
diff --git a/Tools/ArdupilotMegaPlanner/CurrentState.cs b/Tools/ArdupilotMegaPlanner/CurrentState.cs
index e9631fcc27..eaa3f419fb 100644
--- a/Tools/ArdupilotMegaPlanner/CurrentState.cs
+++ b/Tools/ArdupilotMegaPlanner/CurrentState.cs
@@ -143,7 +143,7 @@ namespace ArdupilotMega
public float wp_dist { get { return (_wpdist * multiplierdist); } set { _wpdist = value; } }
public float alt_error { get { return _alt_error * multiplierdist; } set { if (_alt_error == value) return; _alt_error = value; _targetalt = _targetalt * 0.5f + (float)Math.Round(alt + alt_error, 0) * 0.5f; } }
public float ber_error { get { return (target_bearing - yaw); } set { } }
- public float aspd_error { get { return _aspd_error * multiplierspeed; } set { if (_aspd_error == value) return; _aspd_error = value; _targetairspeed = _targetairspeed * 0.5f + (float)Math.Round(airspeed + aspd_error / 100, 0) * 0.5f; } }
+ public float aspd_error { get { return _aspd_error * multiplierspeed; } set { if (_aspd_error == value) return; _aspd_error = value; _targetairspeed = _targetairspeed * 0.5f + (float)Math.Round(airspeed + aspd_error, 0) * 0.5f; } }
public float xtrack_error { get; set; }
public float wpno { get; set; }
public string mode { get; set; }
@@ -861,7 +861,7 @@ namespace ArdupilotMega
target_bearing = nav.target_bearing;
wp_dist = nav.wp_dist;
alt_error = nav.alt_error;
- aspd_error = nav.aspd_error;
+ aspd_error = nav.aspd_error / 100.0f;
xtrack_error = nav.xtrack_error;
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT] = null;
diff --git a/Tools/ArdupilotMegaPlanner/Driver/arduino.cat b/Tools/ArdupilotMegaPlanner/Driver/arduino.cat
new file mode 100644
index 0000000000..a7e6ad65cf
Binary files /dev/null and b/Tools/ArdupilotMegaPlanner/Driver/arduino.cat differ
diff --git a/Tools/ArdupilotMegaPlanner/Driver/arduino.inf b/Tools/ArdupilotMegaPlanner/Driver/arduino.inf
new file mode 100644
index 0000000000..b05aafe280
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/Driver/arduino.inf
@@ -0,0 +1,81 @@
+
+; Windows USB CDC ACM Setup File
+; Copyright (c) 2000 Microsoft Corporation
+
+
+[Version]
+Signature="$Windows NT$"
+Class=Ports
+ClassGuid={4D36E978-E325-11CE-BFC1-08002BE10318}
+Provider=%MFGNAME%
+DriverVer=01/01/2012,1.0.0.0
+CatalogFile=arduino.cat
+
+[Manufacturer]
+%MFGNAME%=DeviceList,NTamd64
+
+[DestinationDirs]
+FakeModemCopyFileSection=12
+DefaultDestDir=12
+
+[DriverInstall]
+include=mdmcpq.inf
+CopyFiles=FakeModemCopyFileSection
+
+[DriverInstall.HW]
+include=mdmcpq.inf
+AddReg=LowerFilterAddReg
+
+[DriverInstall.Services]
+include = mdmcpq.inf
+AddService=usbser, 0x00000002, LowerFilter_Service_Inst
+
+;------------------------------------------------------------------------------
+; Vendor and Product ID Definitions
+;------------------------------------------------------------------------------
+; When developing your USB device, the VID and PID used in the PC side
+; application program and the firmware on the microcontroller must match.
+; Modify the below line to use your VID and PID. Use the format as shown below.
+; Note: One INF file can be used for multiple devices with different VID and PIDs.
+; For each supported device, append ",USB\VID_xxxx&PID_yyyy" to the end of the line.
+;------------------------------------------------------------------------------
+[DeviceList]
+%DESCRIPTION_UNO%=DriverInstall, USB\VID_2341&PID_0001
+%DESCRIPTION_MEGA%=DriverInstall, USB\VID_2341&PID_0010
+%DESCRIPTION_LEO%=DriverInstall, USB\VID_2341&PID_0032
+%DESCRIPTION_LEO%=DriverInstall, USB\VID_2341&PID_0034&MI_00
+%DESCRIPTION_MICRO%=DriverInstall, USB\VID_2341&PID_0035&MI_00
+%DESCRIPTION_MEGA_ADK%=DriverInstall, USB\VID_2341&PID_003F
+%DESCRIPTION_MEGA_R3%=DriverInstall, USB\VID_2341&PID_0042
+%DESCRIPTION_UNO_R3%=DriverInstall, USB\VID_2341&PID_0043
+%DESCRIPTION_MEGA_ADK_R3%=DriverInstall, USB\VID_2341&PID_0044
+
+
+
+[DeviceList.NTamd64]
+%DESCRIPTION_UNO%=DriverInstall, USB\VID_2341&PID_0001
+%DESCRIPTION_MEGA%=DriverInstall, USB\VID_2341&PID_0010
+%DESCRIPTION_LEO%=DriverInstall, USB\VID_2341&PID_0032
+%DESCRIPTION_LEO%=DriverInstall, USB\VID_2341&PID_0034&MI_00
+%DESCRIPTION_MICRO%=DriverInstall, USB\VID_2341&PID_0035&MI_00
+%DESCRIPTION_MEGA_ADK%=DriverInstall, USB\VID_2341&PID_003F
+%DESCRIPTION_MEGA_R3%=DriverInstall, USB\VID_2341&PID_0042
+%DESCRIPTION_UNO_R3%=DriverInstall, USB\VID_2341&PID_0043
+%DESCRIPTION_MEGA_ADK_R3%=DriverInstall, USB\VID_2341&PID_0044
+
+
+;------------------------------------------------------------------------------
+; String Definitions
+;------------------------------------------------------------------------------
+;Modify these strings to customize your device
+;------------------------------------------------------------------------------
+[Strings]
+MFGNAME="http://www.arduino.cc"
+DESCRIPTION_UNO="Arduino UNO"
+DESCRIPTION_MEGA="Arduino Mega 2560"
+DESCRIPTION_LEO="Arduino Leonardo"
+DESCRIPTION_MICRO="Arduino Micro"
+DESCRIPTION_MEGA_ADK="Arduino Mega ADK"
+DESCRIPTION_MEGA_R3="Arduino Mega 2560 R3"
+DESCRIPTION_UNO_R3="Arduino UNO R3"
+DESCRIPTION_MEGA_ADK_R3="Arduino Mega ADK R3"
diff --git a/Tools/ArdupilotMegaPlanner/Driver/dpinst.xml b/Tools/ArdupilotMegaPlanner/Driver/dpinst.xml
index 6a72acdd75..0bfec75a49 100644
--- a/Tools/ArdupilotMegaPlanner/Driver/dpinst.xml
+++ b/Tools/ArdupilotMegaPlanner/Driver/dpinst.xml
@@ -2,7 +2,7 @@
-
+
diff --git a/Tools/ArdupilotMegaPlanner/Driver/px4fmu.cat b/Tools/ArdupilotMegaPlanner/Driver/px4fmu.cat
new file mode 100644
index 0000000000..48489a0e30
Binary files /dev/null and b/Tools/ArdupilotMegaPlanner/Driver/px4fmu.cat differ
diff --git a/Tools/ArdupilotMegaPlanner/Driver/px4fmu.inf b/Tools/ArdupilotMegaPlanner/Driver/px4fmu.inf
new file mode 100644
index 0000000000..9a34e73bbe
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/Driver/px4fmu.inf
@@ -0,0 +1,57 @@
+
+; Windows USB CDC ACM Setup File
+; Copyright (c) 2000 Microsoft Corporation
+
+
+[Version]
+Signature="$Windows NT$"
+Class=Ports
+ClassGuid={4D36E978-E325-11CE-BFC1-08002BE10318}
+Provider=%MFGNAME%
+DriverVer=01/01/2012,1.0.0.0
+CatalogFile=px4fmu.cat
+
+[Manufacturer]
+%MFGNAME%=DeviceList, NTamd64
+
+[DestinationDirs]
+FakeModemCopyFileSection=12
+DefaultDestDir=12
+
+[DriverInstall]
+include=mdmcpq.inf
+CopyFiles=FakeModemCopyFileSection
+
+[DriverInstall.HW]
+include=mdmcpq.inf
+AddReg=LowerFilterAddReg
+
+[DriverInstall.Services]
+include = mdmcpq.inf
+AddService=usbser, 0x00000002, LowerFilter_Service_Inst
+
+;------------------------------------------------------------------------------
+; Vendor and Product ID Definitions
+;------------------------------------------------------------------------------
+; When developing your USB device, the VID and PID used in the PC side
+; application program and the firmware on the microcontroller must match.
+; Modify the below line to use your VID and PID. Use the format as shown below.
+; Note: One INF file can be used for multiple devices with different VID and PIDs.
+; For each supported device, append ",USB\VID_xxxx&PID_yyyy" to the end of the line.
+;------------------------------------------------------------------------------
+
+[DeviceList]
+%DESCRIPTION%=DriverInstall, USB\VID_26AC&PID_0010
+
+[DeviceList.NTamd64]
+%DESCRIPTION%=DriverInstall, USB\VID_26AC&PID_0010
+
+
+;------------------------------------------------------------------------------
+; String Definitions
+;------------------------------------------------------------------------------
+;Modify these strings to customize your device
+;------------------------------------------------------------------------------
+[Strings]
+MFGNAME="3D Robotics"
+DESCRIPTION="PX4 FMU"
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Driver/signed.cer b/Tools/ArdupilotMegaPlanner/Driver/signed.cer
new file mode 100644
index 0000000000..0cc1ab42b6
Binary files /dev/null and b/Tools/ArdupilotMegaPlanner/Driver/signed.cer differ
diff --git a/Tools/ArdupilotMegaPlanner/FollowMe.de-DE.resx b/Tools/ArdupilotMegaPlanner/FollowMe.de-DE.resx
new file mode 100644
index 0000000000..bb1f84d234
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/FollowMe.de-DE.resx
@@ -0,0 +1,131 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ What this does.
+1. gets the current gps coords from a nmea gps.
+2. sends a guided mode WP to the AP every 2 seconds.
+
+How to use it
+1. connect to ap.
+2. take off, test guided mode is working.
+3. open this and pick your comport, and baud rate for your nmea gps.
+4. it should now be following you.
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAP_Limits.de-DE.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAP_Limits.de-DE.resx
new file mode 100644
index 0000000000..92df74a2ec
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAP_Limits.de-DE.resx
@@ -0,0 +1,175 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ An
+
+
+ Benötigte Limits aktivieren
+
+
+ Enable a simple Fixed Radius from home GeoFence, with the ability to specify Heights and fence arming options
+
+
+
+ RC Kanal
+
+
+ Require Inside Fence
+
+
+ Max Höhe
+
+
+ Radius
+
+
+ Min Höhe
+
+
+ An
+
+
+ Einfacher Zaun
+
+
+ Required Limits - Before Arming
+
+
+ Höhen Limit
+
+
+ GPS Lock Limits
+
+
+ Benötige GPS Lock
+
+
+ GeoFence aktivieren
+
+
+ innerhalb der Höhe
+
+
+ Wiki
+
+
+ An
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.de-DE.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.de-DE.resx
new file mode 100644
index 0000000000..bf970fbe68
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.de-DE.resx
@@ -0,0 +1,143 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ By default your plane will autolevel on every boot.
+To disable this action you need to turn on manual
+ level and preform a level to calibrate the accel offsets.
+
+
+ Nur für fortgeschrittene User
+
+
+ Level your plane to set default accel offsets
+
+
+ Level
+
+
+ Do a accel calibration now.
+
+
+ Disables autolevel and will keep the last done accel calibration
+
+
+ Manuelles leveln
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.de-DE.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.de-DE.resx
new file mode 100644
index 0000000000..7f17bc91f3
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.de-DE.resx
@@ -0,0 +1,138 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ 'Plus'
+
+
+ 'X'
+
+
+ Rahmen Einstellungen
+
+
+ Level den Multicopter um den Beschleunigungsmesser zu Kalibrieren
+
+
+ Beschleunigungsmesser Kalibrieren
+
+
+ Jetzt Kalibrieren
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.de-DE.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.de-DE.resx
new file mode 100644
index 0000000000..25b4f20d09
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.de-DE.resx
@@ -0,0 +1,300 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ D
+
+
+ IMAX
+
+
+ P
+
+
+ D
+
+
+ IMAX
+
+
+ D
+
+
+ IMAX
+
+
+ I
+
+
+ Verstärkung
+
+
+ IMAX
+
+
+ P
+
+
+ I
+
+
+ I
+
+
+ P
+
+
+ I
+
+
+ P
+
+
+ IMAX
+
+
+ IMAX
+
+
+ P
+
+
+ Ch6 Opt
+
+
+ I
+
+
+ Min
+
+
+ D
+
+
+ D
+
+
+ IMAX
+
+
+ Crosstrack Korrektur
+
+
+ Ch7 Opt
+
+
+ D
+
+
+ Höhe halten
+
+
+ Nav WP
+
+
+ P
+
+
+ Throttle Rate
+
+
+ Rate Loiter
+
+
+ m/s
+
+
+ Loiter Speed
+
+
+ I
+
+
+ I
+
+
+ IMAX
+
+
+ P
+
+
+ P
+
+
+ I
+
+
+ IMAX
+
+
+ P
+
+
+ Rate Pitch
+
+
+ Rate Roll
+
+
+ Stabilize Yaw
+
+
+ Stabilize Pitch
+
+
+ Stabilize Roll
+
+
+ Rate Yaw
+
+
+ Stabilize D
+
+
+ I
+
+
+ Lock Pitch and Roll Values
+
+
+ Parameter speichern
+
+
+ P
+
+
+ IMAX
+
+
+ I
+
+
+ P
+
+
+ IMAX
+
+
+ I
+
+
+ Parameter aktualisieren
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.de-DE.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.de-DE.resx
new file mode 100644
index 0000000000..d4c81a9ad9
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.de-DE.resx
@@ -0,0 +1,294 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ INT_MAX
+
+
+ P to T
+
+
+ Gain (cm)
+
+
+ Pitch Comp
+
+
+ P
+
+
+ FBW max
+
+
+ D
+
+
+ FBW min
+
+
+ Servo Roll Pid
+
+
+ INT_MAX
+
+
+ Servo Pitch Pid
+
+
+ P
+
+
+ Ratio
+
+
+ Max
+
+
+ I
+
+
+ D
+
+
+ Min
+
+
+ Cruise
+
+
+ INT_MAX
+
+
+ FS Value
+
+
+ Navigations Winkel
+
+
+ I
+
+
+ Gas 0-100%
+
+
+ Cruise
+
+
+ Geschwindigkeit m/s
+
+
+ D
+
+
+ P
+
+
+ INT_MAX
+
+
+ I
+
+
+ D
+
+
+ I
+
+
+ P
+
+
+ INT_MAX
+
+
+ D
+
+
+ I
+
+
+ Andere Mix's
+
+
+ Energy/Alt Pid
+
+
+ Nav Pitch AS Pid
+
+
+ P
+
+
+ Xtrack Pids
+
+
+ INT_MAX
+
+
+ Servo Yaw Pid
+
+
+ Nav Pitch Alt Pid
+
+
+ Nav Roll Pid
+
+
+ Pitch Max
+
+
+ Bank Max
+
+
+ Pitch Min
+
+
+ D
+
+
+ P
+
+
+ I
+
+
+ D
+
+
+ P
+
+
+ I
+
+
+ INT_MAX
+
+
+ Parameter speichern
+
+
+ Ruder Mix
+
+
+ eingangs Winkel
+
+
+ Parameter aktualisieren
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArdurover.de-DE.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArdurover.de-DE.resx
new file mode 100644
index 0000000000..baaa854eae
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArdurover.de-DE.resx
@@ -0,0 +1,225 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Auto WP Rad
+
+
+ Closed Loop Nav
+
+
+ Sonar Trigger Dist
+
+
+ Booster
+
+
+ Gain (cm)
+
+
+ FBW max
+
+
+ FBW min
+
+
+ Ratio
+
+
+ Max
+
+
+ Min
+
+
+ Rover
+
+
+ Cruise
+
+
+ FS Value
+
+
+ Navigations Winkel
+
+
+ Gas 0-100%
+
+
+ Cruise
+
+
+ Geschwindigkeit m/s
+
+
+ Turn Gain
+
+
+ P
+
+
+ INT_MAX
+
+
+ D
+
+
+ I
+
+
+ Energy/Alt Pid
+
+
+ Xtrack Pids
+
+
+ Nav Roll Pid
+
+
+ Pitch Max
+
+
+ Bank Max
+
+
+ Pitch Min
+
+
+ D
+
+
+ P
+
+
+ I
+
+
+ INT_MAX
+
+
+ Parameter speichern
+
+
+ Entry Angle
+
+
+ Parameter neu laden
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.de-DE.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.de-DE.resx
new file mode 100644
index 0000000000..e717f69adc
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.de-DE.resx
@@ -0,0 +1,156 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Voltage sensor calibration:
+To calibrate your sensor, use a multimeter to measure the voltage coming out of your ESC's battery-elimination circuit (these are black and red wires in the three-wire cable that is powering your APM board).
+Then subtract 0.3v from that value and enter it in field #1 at left.
+
+
+
+ APM Ver
+
+
+ Kapazität
+
+
+ Kalibrierung
+
+
+ Monitor
+
+
+ 2. Gemessene Batteriespannung:
+
+
+ 1. APM Eingangsspannung:
+
+
+ 4. Spannungsteiler (Calced):
+
+
+ 3. Batterie Spannung (Calced):
+
+
+ 5. Amper pro Volt:
+
+
+ Sensor
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.de-DE.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.de-DE.resx
new file mode 100644
index 0000000000..07bc44fc18
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.de-DE.resx
@@ -0,0 +1,172 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Throttle Failsafe Action
+
+
+ Manuell
+
+
+ Off, no Action, On, RTL
+
+
+ Servo/Motor OUT
+
+
+ FailSafe Long (20 sec)
+
+
+ Pwm
+
+
+ Throttle FailSafe
+
+
+ Radio IN
+
+
+ Enable Failsafe on GCS loss of communication
+
+
+ Off, no Action, On, RTL
+
+
+ FailSafe Options
+
+
+ FailSafe Short (1 sec)
+
+
+ Arducopter Auto: Off, no Action, On, RTL
+Arducopter Other: if have gps, RTL, Otherwise Land
+
+
+ Enable Failsafe on low throttle pwm
+
+
+ GCS FailSafe
+
+
+ Trigger Throttle Pwm
+
+
+ Wiki
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.de-DE.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.de-DE.resx
new file mode 100644
index 0000000000..25a2ad5f03
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.de-DE.resx
@@ -0,0 +1,189 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ PWM 0 - 1230
+
+
+ PWM 1621 - 1749
+
+
+ Aktueller Modus
+
+
+ Simple Mode
+
+
+ PWM 1750 +
+
+
+ Current PWM:
+
+
+ Simple Mode
+
+
+ Simple Mode
+
+
+ Simple Mode
+
+
+ Simple Mode
+
+
+ Simple Mode
+
+
+ Manuell
+
+
+ Flugmodus 2
+
+
+ Flugmodus 3
+
+
+ Flugmodus 1
+
+
+ Flugmodus 6
+
+
+ PWM 1231 - 1360
+
+
+ Flugmodus 4
+
+
+ Flugmodus 5
+
+
+ PWM 1361 - 1490
+
+
+ PWM 1491 - 1620
+
+
+ 0
+
+
+ Modus speichern
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.de-DE.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.de-DE.resx
new file mode 100644
index 0000000000..0b8a580229
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.de-DE.resx
@@ -0,0 +1,159 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Log Kalibration
+
+
+ Aktivieren
+
+
+ Aktivieren
+
+
+ Airspeed
+
+
+ Optical Flow
+
+
+ in Grad z.B. 2° 3' W ist -2.3
+
+
+ Sonar
+
+
+ Abweichung
+
+
+ Aktivieren
+
+
+ Kompass
+
+
+ WebSite für die Abweichung
+
+
+ Live Kalibrierung
+
+
+ Aktivieren
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.cs
index 6beb848401..213235dd2c 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.cs
@@ -17,6 +17,8 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
private Transition _NoErrorTransition;
bool startup = true;
+ public string ParamHead = "MNT_";
+
public ConfigMount()
{
InitializeComponent();
@@ -123,6 +125,22 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
updatePitch();
updateRoll();
updateYaw();
+
+ CHK_stab_tilt.setup(1, 0, ParamHead+"STAB_TILT", MainV2.comPort.param);
+ CHK_stab_roll.setup(1, 0, ParamHead+"STAB_ROLL", MainV2.comPort.param);
+ CHK_stab_pan.setup(1, 0, ParamHead+"STAB_PAN", MainV2.comPort.param);
+
+ NUD_CONTROL_x.setup(-180, 180, 100, 1, ParamHead+"CONTROL_X",MainV2.comPort.param);
+ NUD_CONTROL_y.setup(-180, 180, 100, 1, ParamHead+"CONTROL_Y", MainV2.comPort.param);
+ NUD_CONTROL_z.setup(-180, 180, 100, 1, ParamHead+"CONTROL_Z", MainV2.comPort.param);
+
+ NUD_NEUTRAL_x.setup(-180, 180, 100, 1, ParamHead+"NEUTRAL_X", MainV2.comPort.param);
+ NUD_NEUTRAL_y.setup(-180, 180, 100, 1, ParamHead+"NEUTRAL_Y", MainV2.comPort.param);
+ NUD_NEUTRAL_z.setup(-180, 180, 100, 1, ParamHead+"NEUTRAL_Z", MainV2.comPort.param);
+
+ NUD_RETRACT_x.setup(-180, 180, 100, 1, ParamHead+"RETRACT_X", MainV2.comPort.param);
+ NUD_RETRACT_y.setup(-180, 180, 100, 1, ParamHead+"RETRACT_Y", MainV2.comPort.param);
+ NUD_RETRACT_z.setup(-180, 180, 100, 1, ParamHead+"RETRACT_Z", MainV2.comPort.param);
}
catch (Exception ex) { CustomMessageBox.Show("Failed to set Param\n" + ex.ToString()); this.Enabled = false; return; }
}
@@ -154,21 +172,21 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
if (mavlinkComboBoxTilt.Text != "Disable")
{
MainV2.comPort.setParam(mavlinkComboBoxTilt.Text + "_FUNCTION", 7);
- MainV2.comPort.setParam("MNT_STAB_TILT", 1);
+ //MainV2.MainV2.comPort.setParam(ParamHead+"STAB_TILT", 1);
}
else
{
- MainV2.comPort.setParam("MNT_STAB_TILT", 0);
+ //MainV2.comPort.setParam(ParamHead+"STAB_TILT", 0);
ensureDisabled(mavlinkComboBoxTilt, 7);
}
mavlinkNumericUpDownTSM.setup(800, 2200, 1, 1, mavlinkComboBoxTilt.Text +"_MIN", MainV2.comPort.param);
mavlinkNumericUpDownTSMX.setup(800, 2200, 1, 1, mavlinkComboBoxTilt.Text + "_MAX", MainV2.comPort.param);
- mavlinkNumericUpDownTAM.setup(-90, 0, 100, 1, "MNT_ANGMIN_TIL", MainV2.comPort.param);
- mavlinkNumericUpDownTAMX.setup(0, 90, 100, 1, "MNT_ANGMAX_TIL", MainV2.comPort.param);
+ mavlinkNumericUpDownTAM.setup(-90, 0, 100, 1, ParamHead+"ANGMIN_TIL", MainV2.comPort.param);
+ mavlinkNumericUpDownTAMX.setup(0, 90, 100, 1, ParamHead+"ANGMAX_TIL", MainV2.comPort.param);
mavlinkCheckBoxTR.setup(-1, 1, mavlinkComboBoxTilt.Text + "_REV", MainV2.comPort.param);
- CMB_inputch_tilt.setup(typeof(Channelinput), "MNT_RC_IN_TILT", MainV2.comPort.param);
+ CMB_inputch_tilt.setup(typeof(Channelinput), ParamHead+"RC_IN_TILT", MainV2.comPort.param);
}
void updateRoll()
@@ -180,20 +198,20 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
if (mavlinkComboBoxRoll.Text != "Disable")
{
MainV2.comPort.setParam(mavlinkComboBoxRoll.Text + "_FUNCTION", 8);
- MainV2.comPort.setParam("MNT_STAB_ROLL", 1);
+ //MainV2.comPort.setParam(ParamHead+"STAB_ROLL", 1);
}
else
{
- MainV2.comPort.setParam("MNT_STAB_ROLL", 0);
+ //MainV2.comPort.setParam(ParamHead+"STAB_ROLL", 0);
ensureDisabled(mavlinkComboBoxRoll,8);
}
mavlinkNumericUpDownRSM.setup(800, 2200, 1, 1, mavlinkComboBoxRoll.Text +"_MIN", MainV2.comPort.param);
mavlinkNumericUpDownRSMX.setup(800, 2200, 1, 1, mavlinkComboBoxRoll.Text + "_MAX", MainV2.comPort.param);
- mavlinkNumericUpDownRAM.setup(-90, 0, 100, 1, "MNT_ANGMIN_ROL", MainV2.comPort.param);
- mavlinkNumericUpDownRAMX.setup(0, 90, 100, 1, "MNT_ANGMAX_ROL", MainV2.comPort.param);
+ mavlinkNumericUpDownRAM.setup(-90, 0, 100, 1, ParamHead+"ANGMIN_ROL", MainV2.comPort.param);
+ mavlinkNumericUpDownRAMX.setup(0, 90, 100, 1, ParamHead+"ANGMAX_ROL", MainV2.comPort.param);
mavlinkCheckBoxRR.setup(-1, 1, mavlinkComboBoxRoll.Text + "_REV", MainV2.comPort.param);
- CMB_inputch_roll.setup(typeof(Channelinput), "MNT_RC_IN_ROLL", MainV2.comPort.param);
+ CMB_inputch_roll.setup(typeof(Channelinput), ParamHead+"RC_IN_ROLL", MainV2.comPort.param);
}
void updateYaw()
@@ -205,20 +223,20 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
if (mavlinkComboBoxPan.Text != "Disable")
{
MainV2.comPort.setParam(mavlinkComboBoxPan.Text + "_FUNCTION", 6);
- MainV2.comPort.setParam("MNT_STAB_PAN", 1);
+ //MainV2.comPort.setParam(ParamHead+"STAB_PAN", 1);
}
else
{
- MainV2.comPort.setParam("MNT_STAB_PAN", 0);
+ //MainV2.comPort.setParam(ParamHead+"STAB_PAN", 0);
ensureDisabled(mavlinkComboBoxPan,6);
}
mavlinkNumericUpDownPSM.setup(800, 2200, 1, 1, mavlinkComboBoxPan.Text + "_MIN", MainV2.comPort.param);
mavlinkNumericUpDownPSMX.setup(800, 2200, 1, 1, mavlinkComboBoxPan.Text + "_MAX", MainV2.comPort.param);
- mavlinkNumericUpDownPAM.setup(-90, 0, 100, 1, "MNT_ANGMIN_PAN", MainV2.comPort.param);
- mavlinkNumericUpDownPAMX.setup(0, 90, 100, 1, "MNT_ANGMAX_PAN", MainV2.comPort.param);
+ mavlinkNumericUpDownPAM.setup(-90, 0, 100, 1, ParamHead+"ANGMIN_PAN", MainV2.comPort.param);
+ mavlinkNumericUpDownPAMX.setup(0, 90, 100, 1, ParamHead+"ANGMAX_PAN", MainV2.comPort.param);
mavlinkCheckBoxPR.setup(-1, 1, mavlinkComboBoxPan.Text + "_REV", MainV2.comPort.param);
- CMB_inputch_pan.setup(typeof(Channelinput), "MNT_RC_IN_PAN", MainV2.comPort.param);
+ CMB_inputch_pan.setup(typeof(Channelinput), ParamHead+"RC_IN_PAN", MainV2.comPort.param);
}
private void SetErrorMessageOpacity()
@@ -293,8 +311,8 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
ensureDisabled(cmb, 8, mavlinkComboBoxRoll.Text);
// enable 3 axis stabilize
- if (MainV2.comPort.param.ContainsKey("MNT_MODE"))
- MainV2.comPort.setParam("MNT_MODE", 3);
+ if (MainV2.comPort.param.ContainsKey(ParamHead+"MODE"))
+ MainV2.comPort.setParam(ParamHead+"MODE", 3);
updatePitch();
updateRoll();
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.designer.cs
index caa5db207d..849be0d355 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.designer.cs
@@ -86,6 +86,30 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
this.mavlinkCheckBoxRR = new ArdupilotMega.Controls.MavlinkCheckBox();
this.LBL_Error = new ArdupilotMega.Controls.LabelWithPseudoOpacity();
this.PBOX_WarningIcon = new ArdupilotMega.Controls.PictureBoxWithPseudoOpacity();
+ this.groupBox4 = new System.Windows.Forms.GroupBox();
+ this.label27 = new System.Windows.Forms.Label();
+ this.NUD_RETRACT_z = new ArdupilotMega.Controls.MavlinkNumericUpDown();
+ this.label26 = new System.Windows.Forms.Label();
+ this.NUD_RETRACT_y = new ArdupilotMega.Controls.MavlinkNumericUpDown();
+ this.label25 = new System.Windows.Forms.Label();
+ this.NUD_RETRACT_x = new ArdupilotMega.Controls.MavlinkNumericUpDown();
+ this.groupBox5 = new System.Windows.Forms.GroupBox();
+ this.label28 = new System.Windows.Forms.Label();
+ this.NUD_NEUTRAL_z = new ArdupilotMega.Controls.MavlinkNumericUpDown();
+ this.label29 = new System.Windows.Forms.Label();
+ this.NUD_NEUTRAL_y = new ArdupilotMega.Controls.MavlinkNumericUpDown();
+ this.label30 = new System.Windows.Forms.Label();
+ this.NUD_NEUTRAL_x = new ArdupilotMega.Controls.MavlinkNumericUpDown();
+ this.groupBox6 = new System.Windows.Forms.GroupBox();
+ this.label31 = new System.Windows.Forms.Label();
+ this.NUD_CONTROL_z = new ArdupilotMega.Controls.MavlinkNumericUpDown();
+ this.label32 = new System.Windows.Forms.Label();
+ this.NUD_CONTROL_y = new ArdupilotMega.Controls.MavlinkNumericUpDown();
+ this.label33 = new System.Windows.Forms.Label();
+ this.NUD_CONTROL_x = new ArdupilotMega.Controls.MavlinkNumericUpDown();
+ this.CHK_stab_tilt = new ArdupilotMega.Controls.MavlinkCheckBox();
+ this.CHK_stab_roll = new ArdupilotMega.Controls.MavlinkCheckBox();
+ this.CHK_stab_pan = new ArdupilotMega.Controls.MavlinkCheckBox();
((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBox2)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBox3)).BeginInit();
@@ -102,6 +126,18 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownRSM)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownRSMX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.PBOX_WarningIcon)).BeginInit();
+ this.groupBox4.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.NUD_RETRACT_z)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.NUD_RETRACT_y)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.NUD_RETRACT_x)).BeginInit();
+ this.groupBox5.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.NUD_NEUTRAL_z)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.NUD_NEUTRAL_y)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.NUD_NEUTRAL_x)).BeginInit();
+ this.groupBox6.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.NUD_CONTROL_z)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.NUD_CONTROL_y)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.NUD_CONTROL_x)).BeginInit();
this.SuspendLayout();
//
// pictureBox1
@@ -720,9 +756,342 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
this.PBOX_WarningIcon.Opacity = 0.5F;
this.PBOX_WarningIcon.TabStop = false;
//
+ // groupBox4
+ //
+ this.groupBox4.Controls.Add(this.label27);
+ this.groupBox4.Controls.Add(this.NUD_RETRACT_z);
+ this.groupBox4.Controls.Add(this.label26);
+ this.groupBox4.Controls.Add(this.NUD_RETRACT_y);
+ this.groupBox4.Controls.Add(this.label25);
+ this.groupBox4.Controls.Add(this.NUD_RETRACT_x);
+ resources.ApplyResources(this.groupBox4, "groupBox4");
+ this.groupBox4.Name = "groupBox4";
+ this.groupBox4.TabStop = false;
+ //
+ // label27
+ //
+ resources.ApplyResources(this.label27, "label27");
+ this.label27.Name = "label27";
+ //
+ // NUD_RETRACT_z
+ //
+ resources.ApplyResources(this.NUD_RETRACT_z, "NUD_RETRACT_z");
+ this.NUD_RETRACT_z.Increment = new decimal(new int[] {
+ 10,
+ 0,
+ 0,
+ 0});
+ this.NUD_RETRACT_z.Max = 1F;
+ this.NUD_RETRACT_z.Maximum = new decimal(new int[] {
+ 2200,
+ 0,
+ 0,
+ 0});
+ this.NUD_RETRACT_z.Min = 0F;
+ this.NUD_RETRACT_z.Name = "NUD_RETRACT_z";
+ this.NUD_RETRACT_z.param = null;
+ this.NUD_RETRACT_z.ParamName = null;
+ this.NUD_RETRACT_z.Value = new decimal(new int[] {
+ 1000,
+ 0,
+ 0,
+ 0});
+ //
+ // label26
+ //
+ resources.ApplyResources(this.label26, "label26");
+ this.label26.Name = "label26";
+ //
+ // NUD_RETRACT_y
+ //
+ resources.ApplyResources(this.NUD_RETRACT_y, "NUD_RETRACT_y");
+ this.NUD_RETRACT_y.Increment = new decimal(new int[] {
+ 10,
+ 0,
+ 0,
+ 0});
+ this.NUD_RETRACT_y.Max = 1F;
+ this.NUD_RETRACT_y.Maximum = new decimal(new int[] {
+ 2200,
+ 0,
+ 0,
+ 0});
+ this.NUD_RETRACT_y.Min = 0F;
+ this.NUD_RETRACT_y.Name = "NUD_RETRACT_y";
+ this.NUD_RETRACT_y.param = null;
+ this.NUD_RETRACT_y.ParamName = null;
+ this.NUD_RETRACT_y.Value = new decimal(new int[] {
+ 1000,
+ 0,
+ 0,
+ 0});
+ //
+ // label25
+ //
+ resources.ApplyResources(this.label25, "label25");
+ this.label25.Name = "label25";
+ //
+ // NUD_RETRACT_x
+ //
+ resources.ApplyResources(this.NUD_RETRACT_x, "NUD_RETRACT_x");
+ this.NUD_RETRACT_x.Increment = new decimal(new int[] {
+ 10,
+ 0,
+ 0,
+ 0});
+ this.NUD_RETRACT_x.Max = 1F;
+ this.NUD_RETRACT_x.Maximum = new decimal(new int[] {
+ 2200,
+ 0,
+ 0,
+ 0});
+ this.NUD_RETRACT_x.Min = 0F;
+ this.NUD_RETRACT_x.Name = "NUD_RETRACT_x";
+ this.NUD_RETRACT_x.param = null;
+ this.NUD_RETRACT_x.ParamName = null;
+ this.NUD_RETRACT_x.Value = new decimal(new int[] {
+ 1000,
+ 0,
+ 0,
+ 0});
+ //
+ // groupBox5
+ //
+ this.groupBox5.Controls.Add(this.label28);
+ this.groupBox5.Controls.Add(this.NUD_NEUTRAL_z);
+ this.groupBox5.Controls.Add(this.label29);
+ this.groupBox5.Controls.Add(this.NUD_NEUTRAL_y);
+ this.groupBox5.Controls.Add(this.label30);
+ this.groupBox5.Controls.Add(this.NUD_NEUTRAL_x);
+ resources.ApplyResources(this.groupBox5, "groupBox5");
+ this.groupBox5.Name = "groupBox5";
+ this.groupBox5.TabStop = false;
+ //
+ // label28
+ //
+ resources.ApplyResources(this.label28, "label28");
+ this.label28.Name = "label28";
+ //
+ // NUD_NEUTRAL_z
+ //
+ resources.ApplyResources(this.NUD_NEUTRAL_z, "NUD_NEUTRAL_z");
+ this.NUD_NEUTRAL_z.Increment = new decimal(new int[] {
+ 10,
+ 0,
+ 0,
+ 0});
+ this.NUD_NEUTRAL_z.Max = 1F;
+ this.NUD_NEUTRAL_z.Maximum = new decimal(new int[] {
+ 2200,
+ 0,
+ 0,
+ 0});
+ this.NUD_NEUTRAL_z.Min = 0F;
+ this.NUD_NEUTRAL_z.Name = "NUD_NEUTRAL_z";
+ this.NUD_NEUTRAL_z.param = null;
+ this.NUD_NEUTRAL_z.ParamName = null;
+ this.NUD_NEUTRAL_z.Value = new decimal(new int[] {
+ 1000,
+ 0,
+ 0,
+ 0});
+ //
+ // label29
+ //
+ resources.ApplyResources(this.label29, "label29");
+ this.label29.Name = "label29";
+ //
+ // NUD_NEUTRAL_y
+ //
+ resources.ApplyResources(this.NUD_NEUTRAL_y, "NUD_NEUTRAL_y");
+ this.NUD_NEUTRAL_y.Increment = new decimal(new int[] {
+ 10,
+ 0,
+ 0,
+ 0});
+ this.NUD_NEUTRAL_y.Max = 1F;
+ this.NUD_NEUTRAL_y.Maximum = new decimal(new int[] {
+ 2200,
+ 0,
+ 0,
+ 0});
+ this.NUD_NEUTRAL_y.Min = 0F;
+ this.NUD_NEUTRAL_y.Name = "NUD_NEUTRAL_y";
+ this.NUD_NEUTRAL_y.param = null;
+ this.NUD_NEUTRAL_y.ParamName = null;
+ this.NUD_NEUTRAL_y.Value = new decimal(new int[] {
+ 1000,
+ 0,
+ 0,
+ 0});
+ //
+ // label30
+ //
+ resources.ApplyResources(this.label30, "label30");
+ this.label30.Name = "label30";
+ //
+ // NUD_NEUTRAL_x
+ //
+ resources.ApplyResources(this.NUD_NEUTRAL_x, "NUD_NEUTRAL_x");
+ this.NUD_NEUTRAL_x.Increment = new decimal(new int[] {
+ 10,
+ 0,
+ 0,
+ 0});
+ this.NUD_NEUTRAL_x.Max = 1F;
+ this.NUD_NEUTRAL_x.Maximum = new decimal(new int[] {
+ 2200,
+ 0,
+ 0,
+ 0});
+ this.NUD_NEUTRAL_x.Min = 0F;
+ this.NUD_NEUTRAL_x.Name = "NUD_NEUTRAL_x";
+ this.NUD_NEUTRAL_x.param = null;
+ this.NUD_NEUTRAL_x.ParamName = null;
+ this.NUD_NEUTRAL_x.Value = new decimal(new int[] {
+ 1000,
+ 0,
+ 0,
+ 0});
+ //
+ // groupBox6
+ //
+ this.groupBox6.Controls.Add(this.label31);
+ this.groupBox6.Controls.Add(this.NUD_CONTROL_z);
+ this.groupBox6.Controls.Add(this.label32);
+ this.groupBox6.Controls.Add(this.NUD_CONTROL_y);
+ this.groupBox6.Controls.Add(this.label33);
+ this.groupBox6.Controls.Add(this.NUD_CONTROL_x);
+ resources.ApplyResources(this.groupBox6, "groupBox6");
+ this.groupBox6.Name = "groupBox6";
+ this.groupBox6.TabStop = false;
+ //
+ // label31
+ //
+ resources.ApplyResources(this.label31, "label31");
+ this.label31.Name = "label31";
+ //
+ // NUD_CONTROL_z
+ //
+ resources.ApplyResources(this.NUD_CONTROL_z, "NUD_CONTROL_z");
+ this.NUD_CONTROL_z.Increment = new decimal(new int[] {
+ 10,
+ 0,
+ 0,
+ 0});
+ this.NUD_CONTROL_z.Max = 1F;
+ this.NUD_CONTROL_z.Maximum = new decimal(new int[] {
+ 2200,
+ 0,
+ 0,
+ 0});
+ this.NUD_CONTROL_z.Min = 0F;
+ this.NUD_CONTROL_z.Name = "NUD_CONTROL_z";
+ this.NUD_CONTROL_z.param = null;
+ this.NUD_CONTROL_z.ParamName = null;
+ this.NUD_CONTROL_z.Value = new decimal(new int[] {
+ 1000,
+ 0,
+ 0,
+ 0});
+ //
+ // label32
+ //
+ resources.ApplyResources(this.label32, "label32");
+ this.label32.Name = "label32";
+ //
+ // NUD_CONTROL_y
+ //
+ resources.ApplyResources(this.NUD_CONTROL_y, "NUD_CONTROL_y");
+ this.NUD_CONTROL_y.Increment = new decimal(new int[] {
+ 10,
+ 0,
+ 0,
+ 0});
+ this.NUD_CONTROL_y.Max = 1F;
+ this.NUD_CONTROL_y.Maximum = new decimal(new int[] {
+ 2200,
+ 0,
+ 0,
+ 0});
+ this.NUD_CONTROL_y.Min = 0F;
+ this.NUD_CONTROL_y.Name = "NUD_CONTROL_y";
+ this.NUD_CONTROL_y.param = null;
+ this.NUD_CONTROL_y.ParamName = null;
+ this.NUD_CONTROL_y.Value = new decimal(new int[] {
+ 1000,
+ 0,
+ 0,
+ 0});
+ //
+ // label33
+ //
+ resources.ApplyResources(this.label33, "label33");
+ this.label33.Name = "label33";
+ //
+ // NUD_CONTROL_x
+ //
+ resources.ApplyResources(this.NUD_CONTROL_x, "NUD_CONTROL_x");
+ this.NUD_CONTROL_x.Increment = new decimal(new int[] {
+ 10,
+ 0,
+ 0,
+ 0});
+ this.NUD_CONTROL_x.Max = 1F;
+ this.NUD_CONTROL_x.Maximum = new decimal(new int[] {
+ 2200,
+ 0,
+ 0,
+ 0});
+ this.NUD_CONTROL_x.Min = 0F;
+ this.NUD_CONTROL_x.Name = "NUD_CONTROL_x";
+ this.NUD_CONTROL_x.param = null;
+ this.NUD_CONTROL_x.ParamName = null;
+ this.NUD_CONTROL_x.Value = new decimal(new int[] {
+ 1000,
+ 0,
+ 0,
+ 0});
+ //
+ // CHK_stab_tilt
+ //
+ resources.ApplyResources(this.CHK_stab_tilt, "CHK_stab_tilt");
+ this.CHK_stab_tilt.Name = "CHK_stab_tilt";
+ this.CHK_stab_tilt.OffValue = 0F;
+ this.CHK_stab_tilt.OnValue = 1F;
+ this.CHK_stab_tilt.param = null;
+ this.CHK_stab_tilt.ParamName = null;
+ this.CHK_stab_tilt.UseVisualStyleBackColor = true;
+ //
+ // CHK_stab_roll
+ //
+ resources.ApplyResources(this.CHK_stab_roll, "CHK_stab_roll");
+ this.CHK_stab_roll.Name = "CHK_stab_roll";
+ this.CHK_stab_roll.OffValue = 0F;
+ this.CHK_stab_roll.OnValue = 1F;
+ this.CHK_stab_roll.param = null;
+ this.CHK_stab_roll.ParamName = null;
+ this.CHK_stab_roll.UseVisualStyleBackColor = true;
+ //
+ // CHK_stab_pan
+ //
+ resources.ApplyResources(this.CHK_stab_pan, "CHK_stab_pan");
+ this.CHK_stab_pan.Name = "CHK_stab_pan";
+ this.CHK_stab_pan.OffValue = 0F;
+ this.CHK_stab_pan.OnValue = 1F;
+ this.CHK_stab_pan.param = null;
+ this.CHK_stab_pan.ParamName = null;
+ this.CHK_stab_pan.UseVisualStyleBackColor = true;
+ //
// ConfigMount
//
- this.BackColor = System.Drawing.Color.FromArgb(((int)(((byte)(38)))), ((int)(((byte)(39)))), ((int)(((byte)(40)))));
+ this.BackColor = System.Drawing.Color.FromArgb(((int)(((byte)(43)))), ((int)(((byte)(44)))), ((int)(((byte)(45)))));
+ this.Controls.Add(this.CHK_stab_pan);
+ this.Controls.Add(this.CHK_stab_roll);
+ this.Controls.Add(this.CHK_stab_tilt);
+ this.Controls.Add(this.groupBox6);
+ this.Controls.Add(this.groupBox5);
+ this.Controls.Add(this.groupBox4);
this.Controls.Add(this.label24);
this.Controls.Add(this.CMB_inputch_pan);
this.Controls.Add(this.label23);
@@ -795,6 +1164,21 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownRSM)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownRSMX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.PBOX_WarningIcon)).EndInit();
+ this.groupBox4.ResumeLayout(false);
+ this.groupBox4.PerformLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.NUD_RETRACT_z)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.NUD_RETRACT_y)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.NUD_RETRACT_x)).EndInit();
+ this.groupBox5.ResumeLayout(false);
+ this.groupBox5.PerformLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.NUD_NEUTRAL_z)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.NUD_NEUTRAL_y)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.NUD_NEUTRAL_x)).EndInit();
+ this.groupBox6.ResumeLayout(false);
+ this.groupBox6.PerformLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.NUD_CONTROL_z)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.NUD_CONTROL_y)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.NUD_CONTROL_x)).EndInit();
this.ResumeLayout(false);
this.PerformLayout();
@@ -856,6 +1240,30 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
private MavlinkComboBox CMB_inputch_roll;
private System.Windows.Forms.Label label24;
private MavlinkComboBox CMB_inputch_pan;
+ private System.Windows.Forms.GroupBox groupBox4;
+ private System.Windows.Forms.Label label27;
+ private MavlinkNumericUpDown NUD_RETRACT_z;
+ private System.Windows.Forms.Label label26;
+ private MavlinkNumericUpDown NUD_RETRACT_y;
+ private System.Windows.Forms.Label label25;
+ private MavlinkNumericUpDown NUD_RETRACT_x;
+ private System.Windows.Forms.GroupBox groupBox5;
+ private System.Windows.Forms.Label label28;
+ private MavlinkNumericUpDown NUD_NEUTRAL_z;
+ private System.Windows.Forms.Label label29;
+ private MavlinkNumericUpDown NUD_NEUTRAL_y;
+ private System.Windows.Forms.Label label30;
+ private MavlinkNumericUpDown NUD_NEUTRAL_x;
+ private System.Windows.Forms.GroupBox groupBox6;
+ private System.Windows.Forms.Label label31;
+ private MavlinkNumericUpDown NUD_CONTROL_z;
+ private System.Windows.Forms.Label label32;
+ private MavlinkNumericUpDown NUD_CONTROL_y;
+ private System.Windows.Forms.Label label33;
+ private MavlinkNumericUpDown NUD_CONTROL_x;
+ private MavlinkCheckBox CHK_stab_tilt;
+ private MavlinkCheckBox CHK_stab_roll;
+ private MavlinkCheckBox CHK_stab_pan;
}
}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.resx
index 061ee327f4..70b940b08d 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.resx
@@ -145,10 +145,7 @@
$this
- 53
-
-
- Top, Left, Right
+ 59
17, 150
@@ -169,7 +166,7 @@
$this
- 51
+ 57
Zoom
@@ -196,10 +193,7 @@
$this
- 52
-
-
- Top, Left, Right
+ 58
17, 23
@@ -220,7 +214,7 @@
$this
- 50
+ 56
True
@@ -253,7 +247,7 @@
$this
- 49
+ 55
True
@@ -286,7 +280,7 @@
$this
- 48
+ 54
Top, Right
@@ -319,7 +313,7 @@
$this
- 45
+ 51
True
@@ -352,10 +346,7 @@
$this
- 42
-
-
- Top, Left, Right
+ 48
17, 274
@@ -376,7 +367,7 @@
$this
- 43
+ 49
Zoom
@@ -403,7 +394,7 @@
$this
- 44
+ 50
True
@@ -436,7 +427,7 @@
$this
- 31
+ 37
True
@@ -469,7 +460,7 @@
$this
- 32
+ 38
True
@@ -499,7 +490,7 @@
$this
- 33
+ 39
True
@@ -529,7 +520,7 @@
$this
- 34
+ 40
True
@@ -559,7 +550,7 @@
$this
- 37
+ 43
True
@@ -589,7 +580,7 @@
$this
- 38
+ 44
True
@@ -622,7 +613,7 @@
$this
- 20
+ 26
True
@@ -655,7 +646,7 @@
$this
- 21
+ 27
True
@@ -685,7 +676,7 @@
$this
- 22
+ 28
True
@@ -715,7 +706,7 @@
$this
- 23
+ 29
True
@@ -745,7 +736,7 @@
$this
- 26
+ 32
True
@@ -775,7 +766,7 @@
$this
- 27
+ 33
True
@@ -808,7 +799,7 @@
$this
- 9
+ 15
True
@@ -841,7 +832,7 @@
$this
- 10
+ 16
True
@@ -871,7 +862,7 @@
$this
- 11
+ 17
True
@@ -901,7 +892,7 @@
$this
- 12
+ 18
True
@@ -931,7 +922,7 @@
$this
- 15
+ 21
True
@@ -961,7 +952,7 @@
$this
- 16
+ 22
71, 3
@@ -982,7 +973,7 @@
$this
- 8
+ 14
71, 131
@@ -1003,7 +994,7 @@
$this
- 7
+ 13
71, 255
@@ -1024,7 +1015,7 @@
$this
- 6
+ 12
True
@@ -1057,7 +1048,7 @@
$this
- 4
+ 10
True
@@ -1090,7 +1081,7 @@
$this
- 2
+ 8
True
@@ -1123,7 +1114,7 @@
$this
- 0
+ 6
False
@@ -1141,13 +1132,13 @@
CMB_inputch_pan
- ArdupilotMega.Controls.MavlinkComboBox, ArdupilotMegaPlanner10, Version=1.1.4695.13950, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkComboBox, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
$this
- 1
+ 7
False
@@ -1165,13 +1156,13 @@
CMB_inputch_roll
- ArdupilotMega.Controls.MavlinkComboBox, ArdupilotMegaPlanner10, Version=1.1.4695.13950, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkComboBox, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
$this
- 3
+ 9
False
@@ -1189,13 +1180,13 @@
CMB_inputch_tilt
- ArdupilotMega.Controls.MavlinkComboBox, ArdupilotMegaPlanner10, Version=1.1.4695.13950, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkComboBox, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
$this
- 5
+ 11
False
@@ -1213,13 +1204,13 @@
mavlinkNumericUpDownTAM
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4695.13950, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
$this
- 13
+ 19
False
@@ -1237,13 +1228,13 @@
mavlinkNumericUpDownTAMX
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4695.13950, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
$this
- 14
+ 20
False
@@ -1261,13 +1252,13 @@
mavlinkNumericUpDownTSM
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4695.13950, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
$this
- 17
+ 23
False
@@ -1285,13 +1276,13 @@
mavlinkNumericUpDownTSMX
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4695.13950, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
$this
- 18
+ 24
True
@@ -1318,13 +1309,13 @@
mavlinkCheckBoxTR
- ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4695.13950, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
$this
- 19
+ 25
False
@@ -1342,13 +1333,13 @@
mavlinkNumericUpDownPAM
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4695.13950, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
$this
- 24
+ 30
False
@@ -1366,13 +1357,13 @@
mavlinkNumericUpDownPAMX
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4695.13950, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
$this
- 25
+ 31
False
@@ -1390,13 +1381,13 @@
mavlinkNumericUpDownPSM
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4695.13950, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
$this
- 28
+ 34
False
@@ -1414,13 +1405,13 @@
mavlinkNumericUpDownPSMX
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4695.13950, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
$this
- 29
+ 35
True
@@ -1447,13 +1438,13 @@
mavlinkCheckBoxPR
- ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4695.13950, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
$this
- 30
+ 36
False
@@ -1471,13 +1462,13 @@
mavlinkNumericUpDownRAM
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4695.13950, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
$this
- 35
+ 41
False
@@ -1495,13 +1486,13 @@
mavlinkNumericUpDownRAMX
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4695.13950, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
$this
- 36
+ 42
False
@@ -1519,13 +1510,13 @@
mavlinkNumericUpDownRSM
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4695.13950, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
$this
- 39
+ 45
False
@@ -1543,13 +1534,13 @@
mavlinkNumericUpDownRSMX
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4695.13950, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
$this
- 40
+ 46
True
@@ -1576,13 +1567,13 @@
mavlinkCheckBoxRR
- ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4695.13950, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
$this
- 41
+ 47
Bottom, Left, Right
@@ -1609,13 +1600,13 @@
LBL_Error
- ArdupilotMega.Controls.LabelWithPseudoOpacity, ArdupilotMegaPlanner10, Version=1.1.4695.13950, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.LabelWithPseudoOpacity, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
$this
- 46
+ 52
Bottom, Left, Right
@@ -1636,13 +1627,880 @@
PBOX_WarningIcon
- ArdupilotMega.Controls.PictureBoxWithPseudoOpacity, ArdupilotMegaPlanner10, Version=1.1.4695.13950, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.PictureBoxWithPseudoOpacity, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
$this
- 47
+ 53
+
+
+ label27
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox4
+
+
+ 0
+
+
+ NUD_RETRACT_z
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+
+
+ groupBox4
+
+
+ 1
+
+
+ label26
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox4
+
+
+ 2
+
+
+ NUD_RETRACT_y
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+
+
+ groupBox4
+
+
+ 3
+
+
+ label25
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox4
+
+
+ 4
+
+
+ NUD_RETRACT_x
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+
+
+ groupBox4
+
+
+ 5
+
+
+ 551, 66
+
+
+ 119, 97
+
+
+ 137
+
+
+ Retract Angles
+
+
+ groupBox4
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ $this
+
+
+ 5
+
+
+ True
+
+
+ NoControl
+
+
+ 7, 72
+
+
+ 14, 13
+
+
+ 129
+
+
+ Z
+
+
+ label27
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox4
+
+
+ 0
+
+
+ False
+
+
+ 54, 70
+
+
+ 59, 20
+
+
+ 128
+
+
+ NUD_RETRACT_z
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+
+
+ groupBox4
+
+
+ 1
+
+
+ True
+
+
+ NoControl
+
+
+ 7, 46
+
+
+ 14, 13
+
+
+ 127
+
+
+ Y
+
+
+ label26
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox4
+
+
+ 2
+
+
+ False
+
+
+ 54, 44
+
+
+ 59, 20
+
+
+ 126
+
+
+ NUD_RETRACT_y
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+
+
+ groupBox4
+
+
+ 3
+
+
+ True
+
+
+ 7, 20
+
+
+ 14, 13
+
+
+ 125
+
+
+ X
+
+
+ label25
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox4
+
+
+ 4
+
+
+ False
+
+
+ 54, 18
+
+
+ 59, 20
+
+
+ 124
+
+
+ NUD_RETRACT_x
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+
+
+ groupBox4
+
+
+ 5
+
+
+ label28
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox5
+
+
+ 0
+
+
+ NUD_NEUTRAL_z
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+
+
+ groupBox5
+
+
+ 1
+
+
+ label29
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox5
+
+
+ 2
+
+
+ NUD_NEUTRAL_y
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+
+
+ groupBox5
+
+
+ 3
+
+
+ label30
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox5
+
+
+ 4
+
+
+ NUD_NEUTRAL_x
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+
+
+ groupBox5
+
+
+ 5
+
+
+ 551, 169
+
+
+ 119, 97
+
+
+ 138
+
+
+ Neutral Angles
+
+
+ groupBox5
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ $this
+
+
+ 4
+
+
+ True
+
+
+ NoControl
+
+
+ 7, 72
+
+
+ 14, 13
+
+
+ 129
+
+
+ Z
+
+
+ label28
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox5
+
+
+ 0
+
+
+ False
+
+
+ 54, 70
+
+
+ 59, 20
+
+
+ 128
+
+
+ NUD_NEUTRAL_z
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+
+
+ groupBox5
+
+
+ 1
+
+
+ True
+
+
+ NoControl
+
+
+ 7, 46
+
+
+ 14, 13
+
+
+ 127
+
+
+ Y
+
+
+ label29
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox5
+
+
+ 2
+
+
+ False
+
+
+ 54, 44
+
+
+ 59, 20
+
+
+ 126
+
+
+ NUD_NEUTRAL_y
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+
+
+ groupBox5
+
+
+ 3
+
+
+ True
+
+
+ NoControl
+
+
+ 7, 20
+
+
+ 14, 13
+
+
+ 125
+
+
+ X
+
+
+ label30
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox5
+
+
+ 4
+
+
+ False
+
+
+ 54, 18
+
+
+ 59, 20
+
+
+ 124
+
+
+ NUD_NEUTRAL_x
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+
+
+ groupBox5
+
+
+ 5
+
+
+ label31
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox6
+
+
+ 0
+
+
+ NUD_CONTROL_z
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+
+
+ groupBox6
+
+
+ 1
+
+
+ label32
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox6
+
+
+ 2
+
+
+ NUD_CONTROL_y
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+
+
+ groupBox6
+
+
+ 3
+
+
+ label33
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox6
+
+
+ 4
+
+
+ NUD_CONTROL_x
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+
+
+ groupBox6
+
+
+ 5
+
+
+ 551, 272
+
+
+ 119, 97
+
+
+ 138
+
+
+ Control Angles
+
+
+ groupBox6
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ $this
+
+
+ 3
+
+
+ True
+
+
+ NoControl
+
+
+ 7, 72
+
+
+ 14, 13
+
+
+ 129
+
+
+ Z
+
+
+ label31
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox6
+
+
+ 0
+
+
+ False
+
+
+ 54, 70
+
+
+ 59, 20
+
+
+ 128
+
+
+ NUD_CONTROL_z
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+
+
+ groupBox6
+
+
+ 1
+
+
+ True
+
+
+ NoControl
+
+
+ 7, 46
+
+
+ 14, 13
+
+
+ 127
+
+
+ Y
+
+
+ label32
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox6
+
+
+ 2
+
+
+ False
+
+
+ 54, 44
+
+
+ 59, 20
+
+
+ 126
+
+
+ NUD_CONTROL_y
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+
+
+ groupBox6
+
+
+ 3
+
+
+ True
+
+
+ NoControl
+
+
+ 7, 20
+
+
+ 14, 13
+
+
+ 125
+
+
+ X
+
+
+ label33
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox6
+
+
+ 4
+
+
+ False
+
+
+ 54, 18
+
+
+ 59, 20
+
+
+ 124
+
+
+ NUD_CONTROL_x
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+
+
+ groupBox6
+
+
+ 5
+
+
+ True
+
+
+ False
+
+
+ 249, 5
+
+
+ 86, 17
+
+
+ 139
+
+
+ Stabalise Tilt
+
+
+ CHK_stab_tilt
+
+
+ ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+
+
+ $this
+
+
+ 2
+
+
+ True
+
+
+ False
+
+
+ NoControl
+
+
+ 249, 133
+
+
+ 90, 17
+
+
+ 140
+
+
+ Stabalise Roll
+
+
+ CHK_stab_roll
+
+
+ ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+
+
+ $this
+
+
+ 1
+
+
+ True
+
+
+ False
+
+
+ NoControl
+
+
+ 249, 257
+
+
+ 91, 17
+
+
+ 141
+
+
+ Stabalise Pan
+
+
+ CHK_stab_pan
+
+
+ ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+
+
+ $this
+
+
+ 0
True
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs
index 0a1375e4fb..6a0dc83658 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs
@@ -492,7 +492,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
CMB_speedunits.DataSource = Enum.GetNames(typeof(Common.speeds));
// setup language selection
- var cultureCodes = new[] { "en-US", "zh-Hans", "zh-TW", "ru-RU", "Fr", "Pl", "it-IT", "es-ES" };
+ var cultureCodes = new[] { "en-US", "zh-Hans", "zh-TW", "ru-RU", "Fr", "Pl", "it-IT", "es-ES","de-DE" };
_languages = cultureCodes
.Select(CultureInfoEx.GetCultureInfo)
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.de-DE.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.de-DE.resx
new file mode 100644
index 0000000000..8c24b32338
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.de-DE.resx
@@ -0,0 +1,232 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Map is rotated to follow the plane
+
+
+ Höhen Warnung
+
+
+ HUD
+
+
+ Stop
+
+
+ Batterie Warnung
+
+
+ Sprache einschalten
+
+
+ Track Length
+
+
+ Wegpunkte
+
+
+ Zeit Interval
+
+
+ Dist to Home
+
+
+ Video Format
+
+
+ Position
+
+
+ Attitude
+
+
+ Map Follow
+
+
+ Telemetry Rates
+
+
+ RC
+
+
+ Modus/Status
+
+
+ Aktivieren HUD Overlay
+
+
+ APM Reset
+
+
+ Wegpunkte beim Verninden laden?
+
+
+ Geschwindigkeits Einheiten
+
+
+ Wegpunkt
+
+
+ NOTE: The Configuration Tab will NOT display these units, as those are raw values.
+
+
+
+ Video Device
+
+
+ UI Sprache
+
+
+ Joystick
+
+
+ GDI+ (old type)
+
+
+ OSD Color
+
+
+ Sensor
+
+
+ Entfernungs Einheiten
+
+
+ Sprache
+
+
+ Joystick Setup
+
+
+ Flugdaten Anzeige
+
+
+ Mavlink Message Debug
+
+
+ Reset APM on USB Connect
+
+
+ Modus
+
+
+ Start
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.de-DE.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.de-DE.resx
new file mode 100644
index 0000000000..47a1cd6a3e
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.de-DE.resx
@@ -0,0 +1,150 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Elevons CH1 Rev
+
+
+ Sender Kalibrieren
+
+
+ Elevons CH2 Rev
+
+
+ Elevon Config
+
+
+ Elevons Rev
+
+
+ Elevons
+
+
+ Umkehren
+
+
+ Umkehren
+
+
+ Umkehren
+
+
+ Umkehren
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.de-DE.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.de-DE.resx
new file mode 100644
index 0000000000..390598ddeb
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.de-DE.resx
@@ -0,0 +1,150 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Wert
+
+
+ Laden
+
+
+ Komando
+
+
+ Grundeinstellung
+
+
+ Speichern
+
+
+ Parameter speichern
+
+
+ mavScale
+
+
+ RawValue
+
+
+ Parameter vergleichen
+
+
+ Parameter aktualisieren
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.de-DE.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.de-DE.resx
new file mode 100644
index 0000000000..7add5a95b3
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.de-DE.resx
@@ -0,0 +1,237 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Manuell
+
+
+ 180
+
+
+ Swash-Servo position
+
+
+ 1
+
+
+ 2
+
+
+ 3
+
+
+ Oben
+
+
+ Swash Travel
+
+
+ Rudder Travel
+
+
+ Max
+
+
+ Max
+
+
+ Roll Max
+
+
+ Pitch Max
+
+
+ Min
+
+
+ 1000
+
+
+ 1500
+
+
+ Swash Type
+
+
+ Externen Kreisel
+
+
+ 1500
+
+
+ Null
+
+
+ Servo
+
+
+ 60
+
+
+ Rev
+
+
+ Position
+
+
+ Trim
+
+
+ 1500
+
+
+ CCPM
+
+
+ -60
+
+
+ H1
+
+
+ 1500
+
+
+ 1500
+
+
+ Verstärkung
+
+
+ Trim
+
+
+ Aktivieren
+
+
+ Manuell
+
+
+ Ruder
+
+
+ Rev
+
+
+ Min
+
+
+ Basis
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/GCSViews.ConfigurationView.ConfigMount.de-DE.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/GCSViews.ConfigurationView.ConfigMount.de-DE.resx
new file mode 100644
index 0000000000..c2eb63e341
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/GCSViews.ConfigurationView.ConfigMount.de-DE.resx
@@ -0,0 +1,207 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Min
+
+
+ Servo Limits
+
+
+ Max
+
+
+ Angle Limits
+
+
+ Max
+
+
+ Min
+
+
+ Servo Limits
+
+
+ Error Message of some kind
+
+
+ Pan
+
+
+ Max
+
+
+ Min
+
+
+ Max
+
+
+ Min
+
+
+ Input Ch
+
+
+ Input Ch
+
+
+ Input Ch
+
+
+ Servo Limits
+
+
+ Max
+
+
+ Angle Limits
+
+
+ Roll
+
+
+ Max
+
+
+ Min
+
+
+ Tilt
+
+
+ Min
+
+
+ Angle Limits
+
+
+ Reverse
+
+
+ Reverse
+
+
+ Reverse
+
+
+ Wiki
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.de-DE.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.de-DE.resx
new file mode 100644
index 0000000000..2710538529
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.de-DE.resx
@@ -0,0 +1,138 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Vorgänger Firmware auswählen
+
+
+ Images by Max Levine and Marooned
+
+
+ Bitte klicken Sie die Bilder oben für "Flug Versionen"
+
+
+ Status
+
+
+ APM Setup (Plane and Quad)
+
+
+ Eigene firmware laden
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs
index add015f395..ca8bdf2418 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs
@@ -30,7 +30,6 @@ namespace ArdupilotMega.GCSViews
{
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
- ArdupilotMega.MAVLink comPort = MainV2.comPort;
public static int threadrun = 0;
StreamWriter swlog;
int tickStart = 0;
@@ -457,10 +456,10 @@ namespace ArdupilotMega.GCSViews
System.Threading.Thread.Sleep(50);
continue;
}
- if (!comPort.BaseStream.IsOpen)
+ if (!MainV2.comPort.BaseStream.IsOpen)
lastdata = DateTime.Now;
// re-request servo data
- if (!(lastdata.AddSeconds(8) > DateTime.Now) && comPort.BaseStream.IsOpen)
+ if (!(lastdata.AddSeconds(8) > DateTime.Now) && MainV2.comPort.BaseStream.IsOpen)
{
//Console.WriteLine("REQ streams - flightdata");
try
@@ -468,13 +467,13 @@ namespace ArdupilotMega.GCSViews
//System.Threading.Thread.Sleep(1000);
//comPort.requestDatastream((byte)ArdupilotMega.MAVLink09.MAV_DATA_STREAM.RAW_CONTROLLER, 0); // request servoout
- comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTENDED_STATUS, MainV2.cs.ratestatus); // mode
- comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.POSITION, MainV2.cs.rateposition); // request gps
- comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA1, MainV2.cs.rateattitude); // request attitude
- comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA2, MainV2.cs.rateattitude); // request vfr
- comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA3, MainV2.cs.ratesensors); // request extra stuff - tridge
- comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RAW_SENSORS, MainV2.cs.ratesensors); // request raw sensor
- comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RC_CHANNELS, MainV2.cs.raterc); // request rc info
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTENDED_STATUS, MainV2.cs.ratestatus); // mode
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.POSITION, MainV2.cs.rateposition); // request gps
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA1, MainV2.cs.rateattitude); // request attitude
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA2, MainV2.cs.rateattitude); // request vfr
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA3, MainV2.cs.ratesensors); // request extra stuff - tridge
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RAW_SENSORS, MainV2.cs.ratesensors); // request raw sensor
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RC_CHANNELS, MainV2.cs.raterc); // request rc info
}
catch { log.Error("Failed to request rates"); }
lastdata = DateTime.Now.AddSeconds(120); // prevent flooding
@@ -504,7 +503,7 @@ namespace ArdupilotMega.GCSViews
{
if (threadrun == 0) { return; }
- if (comPort.BaseStream.IsOpen)
+ if (MainV2.comPort.BaseStream.IsOpen)
{
MainV2.comPort.logreadmode = false;
try
@@ -589,12 +588,14 @@ namespace ArdupilotMega.GCSViews
tunning = DateTime.Now;
}
-
-
- if (MainV2.comPort.logplaybackfile != null && MainV2.comPort.logplaybackfile.BaseStream.Position == MainV2.comPort.logplaybackfile.BaseStream.Length)
+ try
{
- MainV2.comPort.logreadmode = false;
+ if (MainV2.comPort.logplaybackfile != null && MainV2.comPort.logplaybackfile.BaseStream.Position == MainV2.comPort.logplaybackfile.BaseStream.Length)
+ {
+ MainV2.comPort.logreadmode = false;
+ }
}
+ catch { }
}
else
{
@@ -1106,9 +1107,9 @@ namespace ArdupilotMega.GCSViews
threadrun = 0;
try
{
- if (comPort.BaseStream.IsOpen)
+ if (MainV2.comPort.BaseStream.IsOpen)
{
- comPort.Close();
+ MainV2.comPort.Close();
}
}
catch { }
@@ -1140,7 +1141,7 @@ namespace ArdupilotMega.GCSViews
{
((Button)sender).Enabled = false;
#if MAVLINK10
- comPort.doCommand((MAVLink.MAV_CMD)Enum.Parse(typeof(MAVLink.MAV_CMD), CMB_action.Text), 1, 0, 1, 0, 0, 0, 0);
+ MainV2.comPort.doCommand((MAVLink.MAV_CMD)Enum.Parse(typeof(MAVLink.MAV_CMD), CMB_action.Text), 1, 0, 1, 0, 0, 0, 0);
#else
comPort.doAction((MAVLink.MAV_ACTION)Enum.Parse(typeof(MAVLink.MAV_ACTION), "MAV_ACTION_" + CMB_action.Text));
#endif
@@ -1157,7 +1158,7 @@ namespace ArdupilotMega.GCSViews
//comPort.doAction(MAVLink09.MAV_ACTION.MAV_ACTION_RETURN); // set nav from
//System.Threading.Thread.Sleep(100);
- comPort.setWPCurrent(1); // set nav to
+ MainV2.comPort.setWPCurrent(1); // set nav to
//System.Threading.Thread.Sleep(100);
//comPort.doAction(MAVLink09.MAV_ACTION.MAV_ACTION_SET_AUTO); // set auto
}
@@ -1324,7 +1325,7 @@ namespace ArdupilotMega.GCSViews
modifyandSetSpeed.Value = (decimal)(float)MainV2.comPort.param["TRIM_THROTTLE"];
}
- comPort.ParamListChanged += FlightData_ParentChanged;
+ MainV2.comPort.ParamListChanged += FlightData_ParentChanged;
}
void cam_camimage(Image camimage)
@@ -1506,7 +1507,7 @@ namespace ArdupilotMega.GCSViews
try
{
((Button)sender).Enabled = false;
- comPort.setWPCurrent((ushort)CMB_setwp.SelectedIndex); // set nav to
+ MainV2.comPort.setWPCurrent((ushort)CMB_setwp.SelectedIndex); // set nav to
}
catch { CustomMessageBox.Show("The command failed to execute"); }
((Button)sender).Enabled = true;
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.de-DE.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.de-DE.resx
new file mode 100644
index 0000000000..9ca70257c9
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.de-DE.resx
@@ -0,0 +1,324 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Point Camera Here
+
+
+ Changes to the Mode on the left
+
+
+ &Manual
+
+
+ Play/Pause
+
+
+ Changes the current target waypoint
+
+
+ In der Auto Modus wechseln
+
+
+ Fliege hier hin
+
+
+ Double Click me to change
+
+
+ Geschätzte Windbeschleunigung
+
+
+ Ansicht der Senosrrohdaten
+
+
+ Neustart der Mission
+
+
+ 0
+
+
+ Aufgenomene Pfade auf der Karte löschen
+
+
+ Geschätzte Windrichtung
+
+
+ Vel: 0
+
+
+ Show the tunning graph, chowing target attitudes vs actual
+
+
+ 0
+
+
+ Batterie Info zeigen
+
+
+ hdop: 0
+
+
+ Arm the Mav
+
+
+ Tlog > Kml oder Diagramm
+
+
+ Vergrößern
+
+
+ Track löschen
+
+
+ Aktiv/Inaktiv
+
+
+ Hoch
+
+
+ User Items
+
+
+ Makes the map autopan based on current location
+
+
+ Script
+
+
+ In den RTL Modus wechseln
+
+
+ Instrumente
+
+
+ Auto Pan
+
+
+ Set MJPEG source
+
+
+ Joystick
+
+
+ Change Zoom Level
+
+
+ Reset
+
+
+ Tuning
+
+
+ Runter
+
+
+ Sats: 0
+
+
+ Do Action
+
+
+ Restart Mission
+
+
+ Change Mode to Manual/Stabalize
+
+
+ View raw Gyro and Accel values, and Raw Radio ins/outs
+
+
+ Set Aspect Ratio
+
+
+ Double click me to change Max
+
+
+ 0
+
+
+ Actions
+
+
+ Preform the action ot the left
+
+
+ Set Home Alt
+
+
+ Quick
+
+
+ Dir: 0
+
+
+ Load Log
+
+
+ Setup and enable your joystick
+
+
+ Set the current display alt as 0, ie home alt is shown as 0
+
+
+ Record Hud to AVI
+
+
+ Status
+
+
+ &Auto
+
+
+ Set WP
+
+
+ Telemetry Logs
+
+
+ 0.00 %
+
+
+ Flight Planner
+
+
+ Modus setzen
+
+
+ x 1.0
+
+
+ Abspielgechwindigkeit
+
+
+ Aufzeichnung stoppen
+
+
+ &RTL
+
+
+ Fly To Here Alt
+
+
+ Anzahl Satelliten
+
+
+ gps hdop
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.de-DE.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.de-DE.resx
new file mode 100644
index 0000000000..17e38141bd
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.de-DE.resx
@@ -0,0 +1,393 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Elevation Graph
+
+
+ Fly To Here
+
+
+ Höhe prüfen
+
+
+ Home
+
+
+ Grid
+
+
+ Tracker Home
+
+
+ Lat
+
+
+ Download
+
+
+ Prev
+
+
+ Load and Append
+
+
+ Vergrößern
+
+
+ 45
+
+
+ Change the current map type
+
+
+ P4
+
+
+ Zeit
+
+
+ Absolute Höhe
+
+
+ Bezugshöhe
+
+
+ P2
+
+
+ Kamera
+
+
+ Karte drehen
+
+
+ KML Overlay
+
+
+ Lat
+
+
+ Auto WP
+
+
+ Long
+
+
+ Alt (abs)
+
+
+ Map Tool
+
+
+ Forever
+
+
+ Höhe
+
+
+ ROI setzen
+
+
+ Mouse Location
+
+
+ hoch
+
+
+ Heimatlokation
+
+
+ Loiter Radius
+
+
+ Load WP File
+
+
+ Start
+
+
+ Read WPs
+
+
+ Polygon laden
+
+
+ Prefetch
+
+
+ Hochladen
+
+
+ Höhe
+
+
+ WP Radius
+
+
+ Zoom To
+
+
+ Long
+
+
+ Command
+
+
+ Lat
+
+
+ Status
+
+
+ Set Return Location
+
+
+ panel6
+
+
+ Polygon löschen
+
+
+ Action
+
+
+ P1
+
+
+ Zeile löschen
+
+
+ Takeoff
+
+
+ Polygon punkt hinzugügen
+
+
+ Loiter
+
+
+ APM Command
+
+
+ Add Below
+
+
+ Entfernung
+
+
+ Reihe nach unten verschieben
+
+
+ WPs speichern
+
+
+ Runter
+
+
+ Lon
+
+
+ Polygon zeichnen
+
+
+ GridV2
+
+
+ Springen
+
+
+ Landen
+
+
+ Datei laden/speichern
+
+
+ 100
+
+
+ Geo-Fence
+
+
+ WP Datei speichern
+
+
+ Datei speichern
+
+
+ 30
+
+
+ Die Reihe aufwärts bewegen
+
+
+ Aufwärts
+
+
+ Löschen
+
+
+ Kreise
+
+
+ WP #
+
+
+ WP löschen
+
+
+ Wegpunkte
+
+
+ Datei laden
+
+
+ RTL
+
+
+ Voreingestellte Höhe halten
+
+
+ Mission löschen
+
+
+ Linie unterhalb des Gitters hinzufügen
+
+
+ P3
+
+
+ Komplex
+
+
+ Polygon speichern
+
+
+ Wp Kreis erstellen
+
+
+ Entfernungsmessung
+
+
+ Abwärts
+
+
+ Reverse WPs
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Help.de-DE.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Help.de-DE.resx
new file mode 100644
index 0000000000..8b8ca815de
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Help.de-DE.resx
@@ -0,0 +1,129 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+
+
+
+ Eingabe Fenster zeigen (Neustart)
+
+
+ Auf Updates prüfen
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.de-DE.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.de-DE.resx
new file mode 100644
index 0000000000..ee94dde49f
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.de-DE.resx
@@ -0,0 +1,303 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Roll
+
+
+ Höhen Fehler
+
+
+ Reverse Roll
+
+
+ Heli
+
+
+ Pitch
+
+
+ Ardupilot Ausgabe
+
+
+ Plane IMU
+
+
+ Yaw
+
+
+ Can do Plane/Heli/Quads
+
+
+ GPS Refresh Rate
+
+
+ Gas
+
+
+ Autopilot Status
+
+
+ WP
+
+
+ Show Roll
+
+
+ Mode
+
+
+ Simulator Authority - For diff planes
+
+
+ Start FG Quad
+
+
+ Roll Gain
+
+
+ Pitch Gain
+
+
+ Quad
+
+
+ Ruder Gain
+
+
+ Längengrad
+
+
+ Throttle Gain
+
+
+ Höhe
+
+
+ These
+
+
+ are
+
+
+ Breitengrad
+
+
+ SIM only
+
+
+ Erweiterte IP einstellungen
+
+
+ Pitch
+
+
+ NOTE:
+
+
+ Heading
+
+
+ Plane GPS
+
+
+ 10000
+
+
+ Roll
+
+
+ Sim Link Start/Stop
+
+
+ WPDist
+
+
+ Bearing ERR
+
+
+ Alles anzeigen
+
+
+ Sensor
+
+
+ Einstellungen speichern
+
+
+ Start FG Plane
+
+
+ Show Rudder
+
+
+ Yaw
+
+
+ Reverse Rudder
+
+
+ 10000
+
+
+ Can do Plane and Quad with model
+
+
+ Reverse Pitch
+
+
+ Show Throttle
+
+
+ Xplane 10
+
+
+ AeroSimRC
+
+
+ Show Pitch
+
+
+
+
+
+ FlightGear
+
+
+ 10000
+
+
+ X-plane
+
+
+ JSBSim
+
+
+ 10000
+
+
+ Can do Plane/Heli/Quads
+
+
+ Start Xplane
+
+
+ Can Do Plane/Quad with plugin
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs
index fedee1f109..083fac9a24 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs
@@ -260,6 +260,8 @@ namespace ArdupilotMega.GCSViews
comPort.PortName = MainV2.comPortName;
+ comPort.BaudRate = int.Parse(MainV2._connectionControl.CMB_baudrate.Text);
+
comPort.Open();
comPort.toggleDTR();
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.de-DE.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.de-DE.resx
new file mode 100644
index 0000000000..37cc97eb38
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.de-DE.resx
@@ -0,0 +1,139 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Tests
+
+
+ Log Download
+
+
+ Sendereinstellung
+
+
+ *NOTE* CLI Works over USB only
+
+
+
+ Log Browse
+
+
+ Show Settings
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/JoystickSetup.de-DE.resx b/Tools/ArdupilotMegaPlanner/JoystickSetup.de-DE.resx
new file mode 100644
index 0000000000..5fef0744d9
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/JoystickSetup.de-DE.resx
@@ -0,0 +1,219 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ CH 7
+
+
+ CH 5
+
+
+ CH 8
+
+
+ CH 6
+
+
+ Joystick
+
+
+ Pitch
+
+
+ Gas
+
+
+ 0
+
+
+ Roll
+
+
+ Expo
+
+
+ 30
+
+
+ Output
+
+
+ 30
+
+
+ Rudder
+
+
+ 0
+
+
+ Joystick
+
+
+ 0
+
+
+ Controller Axis
+
+
+ 0
+
+
+ Reverse
+
+
+ 30
+
+
+ 0
+
+
+ Speichern
+
+
+ Auto Detect
+
+
+ Elevons
+
+
+ Auto Detect
+
+
+ Auto Detect
+
+
+ Auto Detect
+
+
+ Auto Detect
+
+
+ Auto Detect
+
+
+ Auto Detect
+
+
+ Auto Detect
+
+
+ Aktivieren
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Log.de-DE.resx b/Tools/ArdupilotMegaPlanner/Log.de-DE.resx
new file mode 100644
index 0000000000..bd063ac8a4
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/Log.de-DE.resx
@@ -0,0 +1,141 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Log
+
+
+ Alle Log Dateien laden
+
+
+ KML wiederherstellen
+
+
+ Dieses Log herunterladen
+
+
+ Logs löschen
+
+
+ First Person KML
+
+
+ (adv) Dump All DF
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/LogBrowse.de-DE.resx b/Tools/ArdupilotMegaPlanner/LogBrowse.de-DE.resx
new file mode 100644
index 0000000000..a10d79e944
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/LogBrowse.de-DE.resx
@@ -0,0 +1,141 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Log laden
+
+
+ Log durchsuchen
+
+
+ Diagramm
+
+
+ Diagramm aus markirtem Bereich
+
+
+ andere log Datei laden
+
+
+ Daten des Diagrammes löschen
+
+
+ Diagramm löschen
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/MainV2.cs b/Tools/ArdupilotMegaPlanner/MainV2.cs
index 5776aa5bb5..359dd7f64d 100644
--- a/Tools/ArdupilotMegaPlanner/MainV2.cs
+++ b/Tools/ArdupilotMegaPlanner/MainV2.cs
@@ -145,7 +145,7 @@ namespace ArdupilotMega
/// Otiginally seperate controls, each hosted in a toolstip sqaure, combined into this custom
/// control for layout reasons.
///
- private readonly ConnectionControl _connectionControl;
+ static internal ConnectionControl _connectionControl;
public MainV2()
{
@@ -545,7 +545,7 @@ namespace ArdupilotMega
}
// Tell the connection UI that we are now connected.
- this._connectionControl.IsConnected(true);
+ _connectionControl.IsConnected(true);
// Here we want to reset the connection stats counter etc.
this.ResetConnectionStats();
diff --git a/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs b/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs
index 726afafc94..6bce105a00 100644
--- a/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs
+++ b/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs
@@ -912,7 +912,7 @@ namespace ArdupilotMega
public static void modifyParamForDisplay(bool fromapm, string paramname, ref float value)
{
- if (paramname.ToUpper().EndsWith("_IMAX") || paramname.ToUpper().EndsWith("ALT_HOLD_RTL") || paramname.ToUpper().EndsWith("APPROACH_ALT") || paramname.ToUpper().EndsWith("TRIM_ARSPD_CM")
+ if (paramname.ToUpper().EndsWith("_IMAX") || paramname.ToUpper().EndsWith("ALT_HOLD_RTL") || paramname.ToUpper().EndsWith("APPROACH_ALT") || paramname.ToUpper().EndsWith("TRIM_ARSPD_CM") || paramname.ToUpper().EndsWith("MIN_GNDSPD_CM")
|| paramname.ToUpper().EndsWith("XTRK_ANGLE_CD") || paramname.ToUpper().EndsWith("LIM_PITCH_MAX") || paramname.ToUpper().EndsWith("LIM_PITCH_MIN")
|| paramname.ToUpper().EndsWith("LIM_ROLL_CD") || paramname.ToUpper().EndsWith("PITCH_MAX") || paramname.ToUpper().EndsWith("WP_SPEED_MAX"))
{
diff --git a/Tools/ArdupilotMegaPlanner/MavlinkLog.de-DE.resx b/Tools/ArdupilotMegaPlanner/MavlinkLog.de-DE.resx
new file mode 100644
index 0000000000..95b52c766f
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/MavlinkLog.de-DE.resx
@@ -0,0 +1,141 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Parameter entpacken
+
+
+ Log
+
+
+ KML + GPX erzeugen
+
+
+ WPs entpacken
+
+
+ zu CSV Konvertieren
+
+
+ Graph Log
+
+
+ in Text Konvertieren
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Msi/installer.wxs b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs
index eb0dd597af..e8b773e48f 100644
--- a/Tools/ArdupilotMegaPlanner/Msi/installer.wxs
+++ b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs
@@ -1,15 +1,15 @@
-
+
-
+
-
-
+
+
@@ -31,7 +31,7 @@
-
+
@@ -108,11 +108,11 @@
-
+
-
+
@@ -123,20 +123,20 @@
-
+
-
+
-
+
@@ -150,7 +150,7 @@
-
+
@@ -162,13 +162,13 @@
-
+
-
+
@@ -179,7 +179,7 @@
-
+
@@ -189,97 +189,111 @@
-
-
-
-
+
+
+
-
-
-
-
+
+
+
+
-
-
-
-
+
+
+
+
-
-
-
-
+
+
+
+
-
-
-
-
-
-
-
+
+
+
+
-
-
-
-
+
+
+
+
+
+
+
-
-
-
-
+
+
+
+
-
-
-
-
+
+
+
+
-
-
-
-
+
+
+
+
-
-
-
-
+
+
+
+
+
+
+
+
+
+
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
-
-
+
+
- NOT
+ NOT
Installed AND NOT VersionNT64
- NOT
+ NOT
Installed AND VersionNT64
@@ -308,15 +322,16 @@
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
diff --git a/Tools/ArdupilotMegaPlanner/Program.cs b/Tools/ArdupilotMegaPlanner/Program.cs
index 746d7f18c3..908367927d 100644
--- a/Tools/ArdupilotMegaPlanner/Program.cs
+++ b/Tools/ArdupilotMegaPlanner/Program.cs
@@ -196,13 +196,23 @@ namespace ArdupilotMega
{
try
{
+ string data = "";
+ foreach (System.Collections.DictionaryEntry de in ex.Data)
+ data += String.Format("-> {0}: {1}", de.Key, de.Value);
+
+
// Create a request using a URL that can receive a post.
WebRequest request = WebRequest.Create("http://vps.oborne.me/mail.php");
request.Timeout = 10000; // 10 sec
// Set the Method property of the request to POST.
request.Method = "POST";
// Create POST data and convert it to a byte array.
- string postData = "message=" + Environment.OSVersion.VersionString + " " + System.Reflection.Assembly.GetExecutingAssembly().GetName().Version.ToString() + " " + Application.ProductVersion + " Exception " + ex.ToString().Replace('&', ' ').Replace('=', ' ') + " Stack: " + ex.StackTrace.ToString().Replace('&', ' ').Replace('=', ' ');
+ string postData = "message=" + Environment.OSVersion.VersionString + " " + System.Reflection.Assembly.GetExecutingAssembly().GetName().Version.ToString()
+ + " " + Application.ProductVersion
+ + "\nException " + ex.ToString().Replace('&', ' ').Replace('=', ' ')
+ + "\nStack: " + ex.StackTrace.ToString().Replace('&', ' ').Replace('=', ' ')
+ + "\nTargetSite " + ex.TargetSite + " " + ex.TargetSite.DeclaringType
+ + "\ndata " + data;
byte[] byteArray = Encoding.ASCII.GetBytes(postData);
// Set the ContentType property of the WebRequest.
request.ContentType = "application/x-www-form-urlencoded";
diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs
index 5683076bcb..e697705ba2 100644
--- a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs
+++ b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs
@@ -34,5 +34,5 @@ using System.Resources;
// by using the '*' as shown below:
// [assembly: AssemblyVersion("1.0.*")]
[assembly: AssemblyVersion("1.1.*")]
-[assembly: AssemblyFileVersion("1.2.19")]
+[assembly: AssemblyFileVersion("1.2.20")]
[assembly: NeutralResourcesLanguageAttribute("")]
diff --git a/Tools/ArdupilotMegaPlanner/RAW_Sensor.de-DE.resx b/Tools/ArdupilotMegaPlanner/RAW_Sensor.de-DE.resx
new file mode 100644
index 0000000000..42ad2e20fb
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/RAW_Sensor.de-DE.resx
@@ -0,0 +1,167 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Raw Sensor
+
+
+ RAW Sensor
+
+
+ Update Speed
+
+
+ Servo/Motor OUT
+
+
+ Note: There is a delay
+when viewing via Xbee
+@ 50hz
+
+
+ Radio IN
+
+
+ Accel X
+
+
+ Accel Z
+
+
+ Accel Y
+
+
+ Radio
+
+
+ Flight Data
+
+
+ Save CSV
+
+
+ Gyro Z
+
+
+ Gyro X
+
+
+ Gyro Y
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.de-DE.resx b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.de-DE.resx
new file mode 100644
index 0000000000..4cf9c3c1eb
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.de-DE.resx
@@ -0,0 +1,333 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands.
+
+
+
+ The 3DR Radios have 2 status LEDs, one red and one green.
+green LED blinking - searching for another radio
+green LED solid - link is established with another radio
+red LED flashing - transmitting data
+red LED solid - in firmware update mode
+
+
+ RSSI
+
+
+ MAVLINK enables/disables MAVLink packet framing. This tries to align radio packets to MAVLink packet boundaries, which makes a big difference to what happens to the MAVLink stream when you lose a packet.
+
+
+
+ Min Freq
+
+
+ Duty Cycle
+
+
+ Version
+
+
+ AIR_SPEED is the inter-radio data rate in rounded kbps. So 128 means 128kbps. Max is 192, min is 2. I would not recommend values below 16 as the frequency hopping and tdm sync times get too long.
+
+
+ Copy Required Items to Remote
+
+
+ Max Freq
+
+
+ LBT Rssi
+
+
+ # of Channels
+
+
+ Einstellungen speichern
+
+
+ the percentage of time to allow transmit
+
+
+ NETID is a 16 bit 'network ID'. This is used to seed the frequency hopping sequence and to identify packets as coming from the right radio. Make sure you use a different NETID from anyone else running the same sort of radio in the area.
+
+
+ LBT Rssi
+
+
+ Duty Cycle
+
+
+ # of Channels
+
+
+ Max Freq
+
+
+ Min Freq
+
+
+ Format
+
+
+ Op Resend
+
+
+ Geschwindigkeit
+
+
+ Mavlink
+
+
+ ECC
+
+
+ Baud
+
+
+ Tx Leistung
+
+
+ ECC
+
+
+ Net ID
+
+
+ Mavlink
+
+
+ Serial baud rate in rounded kbps. So 57 means 57600.
+
+
+
+ Net ID
+
+
+ Tx Power
+
+
+ maximale Frequenz in kHz
+
+
+ Remote
+
+
+ Reset to Defaults
+
+
+ Op Resend
+
+
+ Local
+
+
+ Version
+
+
+ MAVLINK enables/disables MAVLink packet framing. This tries to align radio packets to MAVLink packet boundaries, which makes a big difference to what happens to the MAVLink stream when you lose a packet.
+
+
+
+ number of frequency hopping channels
+
+
+ Status Leds
+
+
+ Serial baud rate in rounded kbps. So 57 means 57600.
+
+
+
+ maximale Frequenz in kHz
+
+
+ Erweiterte Optionen
+
+
+ OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands.
+
+
+
+ minimale Frequenz in kHz
+
+
+ Air Speed
+
+
+ Baud
+
+
+ Format
+
+
+ ECC is to enable/disable the golay error correcting code. It defaults to off. If you enable it then you packets take twice as many bytes to send, so you lose half your air bandwidth, but it can correct up to 3 bit errors per 12 bits of data. Use this for long range, usually in combination with a lower air data rate. The golay decode takes 20 microsecond per transmitted byte (40 microseconds per user data byte) which means you will also be a bit CPU constrained at the highest air data rates. So you usually use golay at 128kbps or less.
+
+
+
+ minimale Frequenz in kHz
+
+
+ ECC is to enable/disable the golay error correcting code. It defaults to off. If you enable it then you packets take twice as many bytes to send, so you lose half your air bandwidth, but it can correct up to 3 bit errors per 12 bits of data. Use this for long range, usually in combination with a lower air data rate. The golay decode takes 20 microsecond per transmitted byte (40 microseconds per user data byte) which means you will also be a bit CPU constrained at the highest air data rates. So you usually use golay at 128kbps or less.
+
+
+
+ TXPOWER is the transmit power in dBm. 20dBm is 100mW. It is useful to set this to lower levels for short range testing.
+
+
+
+ Upload Firmware (Local)
+
+
+ Load Settings
+
+
+ TXPOWER is the transmit power in dBm. 20dBm is 100mW. It is useful to set this to lower levels for short range testing.
+
+
+
+ NETID is a 16 bit 'network ID'. This is used to seed the frequency hopping sequence and to identify packets as coming from the right radio. Make sure you use a different NETID from anyone else running the same sort of radio in the area.
+
+
+ number of frequency hopping channels
+
+
+ AIR_SPEED is the inter-radio data rate in rounded kbps. So 128 means 128kbps. Max is 192, min is 2. I would not recommend values below 16 as the frequency hopping and tdm sync times get too long.
+
+
+ see the spec for a RSSI to dBm graph. The numbers at the end are:
+txe: number of transmit errors (eg. transmit timeouts)
+rxe: number of receive errors (crc error, framing error etc)
+stx: number of serial transmit overflows
+rrx: number of serial receive overflows
+ecc: number of 12 bit words successfully corrected by the golay code
+which result in a valid packet CRC
+
+
+
+ Listen Before Talk threshold
+
+
+ Listen Before Talk threshold
+
+
+ the percentage of time to allow transmit
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.fr.resx b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.fr.resx
new file mode 100644
index 0000000000..7d3b78f760
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.fr.resx
@@ -0,0 +1,330 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands.
+
+
+
+ The 3DR Radios have 2 status LEDs, one red and one green.
+green LED blinking - searching for another radio
+green LED solid - link is established with another radio
+red LED flashing - transmitting data
+red LED solid - in firmware update mode
+
+
+ RSSI
+
+
+ MAVLINK enables/disables MAVLink packet framing. This tries to align radio packets to MAVLink packet boundaries, which makes a big difference to what happens to the MAVLink stream when you lose a packet.
+
+
+
+ Min Freq
+
+
+ Duty Cycle
+
+
+ Version
+
+
+ AIR_SPEED is the inter-radio data rate in rounded kbps. So 128 means 128kbps. Max is 192, min is 2. I would not recommend values below 16 as the frequency hopping and tdm sync times get too long.
+
+
+ Copy Required Items to Remote
+
+
+ Max Freq
+
+
+ LBT Rssi
+
+
+ # of Channels
+
+
+ Save Settings
+
+
+ the percentage of time to allow transmit
+
+
+ NETID is a 16 bit 'network ID'. This is used to seed the frequency hopping sequence and to identify packets as coming from the right radio. Make sure you use a different NETID from anyone else running the same sort of radio in the area.
+
+
+ LBT Rssi
+
+
+ Duty Cycle
+
+
+ # of Channels
+
+
+ Max Freq
+
+
+ Min Freq
+
+
+ Format
+
+
+ Op Resend
+
+
+ Air Speed
+
+
+ Mavlink
+
+
+ ECC
+
+
+ Baud
+
+
+ Tx Power
+
+
+ ECC
+
+
+ Net ID
+
+
+ Mavlink
+
+
+ Serial baud rate in rounded kbps. So 57 means 57600.
+
+
+
+ Net ID
+
+
+ Tx Power
+
+
+ maximum frequency in kHz
+
+
+ Remote
+
+
+ Op Resend
+
+
+ Local
+
+
+ Version
+
+
+ MAVLINK enables/disables MAVLink packet framing. This tries to align radio packets to MAVLink packet boundaries, which makes a big difference to what happens to the MAVLink stream when you lose a packet.
+
+
+
+ number of frequency hopping channels
+
+
+ Status Leds
+
+
+ Serial baud rate in rounded kbps. So 57 means 57600.
+
+
+
+ maximum frequency in kHz
+
+
+ Advanced Options
+
+
+ OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands.
+
+
+
+ minimum frequency in kHz
+
+
+ Air Speed
+
+
+ Baud
+
+
+ Format
+
+
+ ECC is to enable/disable the golay error correcting code. It defaults to off. If you enable it then you packets take twice as many bytes to send, so you lose half your air bandwidth, but it can correct up to 3 bit errors per 12 bits of data. Use this for long range, usually in combination with a lower air data rate. The golay decode takes 20 microsecond per transmitted byte (40 microseconds per user data byte) which means you will also be a bit CPU constrained at the highest air data rates. So you usually use golay at 128kbps or less.
+
+
+
+ minimum frequency in kHz
+
+
+ ECC is to enable/disable the golay error correcting code. It defaults to off. If you enable it then you packets take twice as many bytes to send, so you lose half your air bandwidth, but it can correct up to 3 bit errors per 12 bits of data. Use this for long range, usually in combination with a lower air data rate. The golay decode takes 20 microsecond per transmitted byte (40 microseconds per user data byte) which means you will also be a bit CPU constrained at the highest air data rates. So you usually use golay at 128kbps or less.
+
+
+
+ TXPOWER is the transmit power in dBm. 20dBm is 100mW. It is useful to set this to lower levels for short range testing.
+
+
+
+ Upload Firmware (Local)
+
+
+ Load Settings
+
+
+ TXPOWER is the transmit power in dBm. 20dBm is 100mW. It is useful to set this to lower levels for short range testing.
+
+
+
+ NETID is a 16 bit 'network ID'. This is used to seed the frequency hopping sequence and to identify packets as coming from the right radio. Make sure you use a different NETID from anyone else running the same sort of radio in the area.
+
+
+ number of frequency hopping channels
+
+
+ AIR_SPEED is the inter-radio data rate in rounded kbps. So 128 means 128kbps. Max is 192, min is 2. I would not recommend values below 16 as the frequency hopping and tdm sync times get too long.
+
+
+ see the spec for a RSSI to dBm graph. The numbers at the end are:
+txe: number of transmit errors (eg. transmit timeouts)
+rxe: number of receive errors (crc error, framing error etc)
+stx: number of serial transmit overflows
+rrx: number of serial receive overflows
+ecc: number of 12 bit words successfully corrected by the golay code
+which result in a valid packet CRC
+
+
+
+ Listen Before Talk threshold
+
+
+ Listen Before Talk threshold
+
+
+ the percentage of time to allow transmit
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Utilities/ThemeManager.cs b/Tools/ArdupilotMegaPlanner/Utilities/ThemeManager.cs
index 3050e78f09..c0412e5f80 100644
--- a/Tools/ArdupilotMegaPlanner/Utilities/ThemeManager.cs
+++ b/Tools/ArdupilotMegaPlanner/Utilities/ThemeManager.cs
@@ -205,7 +205,7 @@ namespace ArdupilotMega.Utilities
ctl.BackColor = BGColor;
ctl.ForeColor = TextColor;
CheckBox CHK = (CheckBox)ctl;
- CHK.FlatStyle = FlatStyle.Flat;
+ // CHK.FlatStyle = FlatStyle.Flat;
}
else if (ctl.GetType() == typeof(ComboBox) || ctl.GetType() == typeof(MavlinkComboBox))
{
diff --git a/Tools/ArdupilotMegaPlanner/resedit.Form1.de-DE.resx b/Tools/ArdupilotMegaPlanner/resedit.Form1.de-DE.resx
new file mode 100644
index 0000000000..8314f236f3
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/resedit.Form1.de-DE.resx
@@ -0,0 +1,131 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ How to use:
+First time, if this is the first load, just pick your language down the bottom and edit. click save.
+
+More uses, Pick your language, and it will autoload, existing for that language
+
+if you get halfway though, click the load trans button
+
+NOTE, the autoload only works after Michael has added it to the planner. otherwise you will need to use load trans
+
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/wix/Program.cs b/Tools/ArdupilotMegaPlanner/wix/Program.cs
index e418b5757c..99b57a88d8 100644
--- a/Tools/ArdupilotMegaPlanner/wix/Program.cs
+++ b/Tools/ArdupilotMegaPlanner/wix/Program.cs
@@ -121,11 +121,11 @@ namespace wix
st.WriteLine("del installer.wixobj");
- st.WriteLine(@"""%wix%\bin\candle"" installer.wxs -ext WiXNetFxExtension -ext WixDifxAppExtension -ext WixUIExtension.dll -ext WixUtilExtension");
+ st.WriteLine(@"""%wix%\bin\candle"" installer.wxs -ext WiXNetFxExtension -ext WixDifxAppExtension -ext WixUIExtension.dll -ext WixUtilExtension -ext WixIisExtension");
- st.WriteLine(@"""%wix%\bin\light"" installer.wixobj ""%wix%\bin\difxapp_x86.wixlib"" -o MissionPlanner32-" + fvi.FileVersion + ".msi -ext WiXNetFxExtension -ext WixDifxAppExtension -ext WixUIExtension.dll -ext WixUtilExtension");
+ st.WriteLine(@"""%wix%\bin\light"" installer.wixobj ""%wix%\bin\difxapp_x86.wixlib"" -o MissionPlanner-" + fvi.FileVersion + ".msi -ext WiXNetFxExtension -ext WixDifxAppExtension -ext WixUIExtension.dll -ext WixUtilExtension -ext WixIisExtension");
- st.WriteLine(@"""%wix%\bin\light"" installer.wixobj ""%wix%\bin\difxapp_x64.wixlib"" -o MissionPlanner64-" + fvi.FileVersion + ".msi -ext WiXNetFxExtension -ext WixDifxAppExtension -ext WixUIExtension.dll -ext WixUtilExtension");
+ //st.WriteLine(@"""%wix%\bin\light"" installer.wixobj ""%wix%\bin\difxapp_x64.wixlib"" -o MissionPlanner64-" + fvi.FileVersion + ".msi -ext WiXNetFxExtension -ext WixDifxAppExtension -ext WixUIExtension.dll -ext WixUtilExtension -ext WixIisExtension");
st.WriteLine(@"""C:\Program Files\7-Zip\7z.exe"" a -tzip -xr!*.log -xr!ArdupilotPlanner.log* -xr!*.tlog -xr!config.xml -xr!gmapcache -xr!eeprom.bin -xr!dataflash.bin -xr!*.new ""Mission Planner " + fvi.FileVersion + @".zip"" ..\bin\release\*");
@@ -133,8 +133,8 @@ namespace wix
st.WriteLine("googlecode_upload.py -s \"Mission Planner zip file, " + fvi.FileVersion + "\" -p ardupilot-mega \"Mission Planner " + fvi.FileVersion + @".zip""");
- st.WriteLine("googlecode_upload.py -s \"Mission Planner installer (32-bit)\" -p ardupilot-mega MissionPlanner32-" + fvi.FileVersion + ".msi");
- st.WriteLine("googlecode_upload.py -s \"Mission Planner installer (64-bit)\" -p ardupilot-mega MissionPlanner64-" + fvi.FileVersion + ".msi");
+ st.WriteLine("googlecode_upload.py -s \"Mission Planner installer\" -p ardupilot-mega MissionPlanner-" + fvi.FileVersion + ".msi");
+ //st.WriteLine("googlecode_upload.py -s \"Mission Planner installer (64-bit)\" -p ardupilot-mega MissionPlanner64-" + fvi.FileVersion + ".msi");
st.Close();
@@ -176,7 +176,7 @@ namespace wix
sr.Close();
string data = @"
-
+
@@ -212,30 +212,39 @@ namespace wix
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
-
-
+
+
- NOT
+ NOT
Installed AND NOT VersionNT64
- NOT
+ NOT
Installed AND VersionNT64