diff --git a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml
index 586c44657ec6bbf6cdc9d4187e7e2534a24f8096..1505fcd241dbb268d257cdcb0186febe9f8b9c85 100644
--- a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml
+++ b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml
@@ -535,18 +535,6 @@
-
-
- Plane
- Friedrich Beckmann <friedrich.beckmann@hs-augsburg.de>
- Plane V-Tail
-
-
-
-
-
-
-
Plane
diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
index 8ffa73bc89caebc331478a147303358a6845fcb5..77acd1a73d1845a3ab4ff36d3d7e1e1fb9452c69 100644
--- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
+++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
@@ -3885,6 +3885,18 @@ Used to calculate increased terrain random walk nosie due to movement
modules/mavlink
+
+ Parameter hash check
+ Disabling the parameter hash check functionality will make the mavlink instance stream parameters continuously.
+
+ modules/mavlink
+
+
+ Hearbeat message forwarding
+ The mavlink hearbeat message will not be forwarded if this parameter is set to 'disabled'. The main reason for disabling heartbeats to be forwarded is because they confuse dronekit.
+
+ modules/mavlink
+
MAVLink protocol version
modules/mavlink
@@ -5333,6 +5345,78 @@ the setpoint will be capped to MPC_XY_VEL_MAX
true
modules/sensors
+
+ Set the max PWM value for the auxiliary 1 output
+ This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the max PWM value for the auxiliary 2 output
+ This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the max PWM value for the auxiliary 3 output
+ This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the max PWM value for the auxiliary 4 output
+ This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the max PWM value for the auxiliary 5 output
+ This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the max PWM value for the auxiliary 6 output
+ This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the max PWM value for the auxiliary 7 output
+ This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the max PWM value for the auxiliary 8 output
+ This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
Set the minimum PWM for the auxiliary outputs
Set to 1000 for industry default or 900 to increase servo travel.
@@ -5342,6 +5426,78 @@ the setpoint will be capped to MPC_XY_VEL_MAX
true
modules/sensors
+
+ Set the min PWM value for the auxiliary 1 output
+ This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the min PWM value for the auxiliary 2 output
+ This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the min PWM value for the auxiliary 3 output
+ This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the min PWM value for the auxiliary 4 output
+ This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the min PWM value for the auxiliary 5 output
+ This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the min PWM value for the auxiliary 6 output
+ This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the min PWM value for the auxiliary 7 output
+ This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the min PWM value for the auxiliary 8 output
+ This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
Set the PWM output frequency for the auxiliary outputs
Set to 400 for industry default or 1000 for high frequency ESCs. Set to 0 for Oneshot125.
@@ -5616,6 +5772,150 @@ the setpoint will be capped to MPC_XY_VEL_MAX
true
modules/sensors
+
+ Set the max PWM value for the main 1 output
+ This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAX will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the max PWM value for the main 2 output
+ This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAX will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the max PWM value for the main 3 output
+ This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAX will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the max PWM value for the main 4 output
+ This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAX will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the max PWM value for the main 5 output
+ This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAX will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the max PWM value for the main 6 output
+ This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAX will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the max PWM value for the main 7 output
+ This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAX will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the max PWM value for the main 8 output
+ This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAX will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the min PWM value for the main 1 output
+ This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MIN will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the min PWM value for the main 2 output
+ This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MIN will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the min PWM value for the main 3 output
+ This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MIN will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the min PWM value for the main 4 output
+ This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MIN will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the min PWM value for the main 5 output
+ This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MIN will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the min PWM value for the main 6 output
+ This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MIN will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the min PWM value for the main 7 output
+ This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MIN will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
+
+ Set the min PWM value for the main 8 output
+ This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MIN will be used
+ -1
+ 2200
+ us
+ true
+ modules/sensors
+
Invert direction of main output channel 1
Enable to invert the channel.
@@ -8909,6 +9209,13 @@ is less than 50% of this value
true
modules/systemlib
+
+ Bootloader update
+ If enabled, update the bootloader on the next boot. WARNING: do not cut the power during an update process, otherwise you will have to recover using some alternative method (e.g. JTAG). Instructions: - Insert an SD card - Enable this parameter - Reboot the board (plug the power or send a reboot command) - Wait until the board comes back up (or at least 2 minutes) - If it does not come back, check the file bootlog.txt on the SD card
+
+ true
+ modules/systemlib
+
Enable auto start of accelerometer thermal calibration at the next power up
0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the the temperature calibration starts. default (0, no calibration)