diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
index ab8a91425e06fa54056dbb5e763b8452792501ae..0d565d3d541c2862b1c3059a2ff43d7b47c9d0ff 100644
--- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
+++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
@@ -286,7 +286,7 @@ velocity
8
modules/sensors
-
+
Empty cell voltage (5C load)
Defines the voltage where a single cell of the battery is considered empty. The voltage should be chosen before the steep dropoff to 2.8V. A typical lithium battery can only be discharged down to 10% before it drops off to a voltage level damaging the cells.
V
@@ -294,7 +294,7 @@ velocity
0.01
modules/systemlib
-
+
Full cell voltage (5C load)
Defines the voltage where a single cell of the battery is considered full under a mild load. This will never be the nominal voltage of 4.2V
V
@@ -322,7 +322,7 @@ velocity
0.01
modules/systemlib
-
+
Voltage drop per cell on full throttle
This implicitely defines the internal resistance to maximum current ratio and assumes linearity. A good value to use is the difference between the 5C and 20-25C load.
0.07
@@ -2153,7 +2153,7 @@ Assumes measurement is timestamped at trailing edge of integration period240
modules/mavlink
-
+
MAVLink airframe type
1
modules/mavlink
@@ -2707,6 +2707,7 @@ Assumes measurement is timestamped at trailing edge of integration period0.95
norm
2
+ 0.01
modules/mc_pos_control
@@ -2716,6 +2717,7 @@ Assumes measurement is timestamped at trailing edge of integration period1.0
norm
2
+ 0.01
modules/mc_pos_control
@@ -2725,30 +2727,35 @@ Assumes measurement is timestamped at trailing edge of integration period1.0
norm
2
+ 0.01
modules/mc_pos_control
Proportional gain for vertical position error
0.0
+ 1.5
2
modules/mc_pos_control
Proportional gain for vertical velocity error
- 0.0
+ 0.1
+ 0.4
2
modules/mc_pos_control
Integral gain for vertical velocity error
Non zero value allows hovering thrust estimation on stabilized or autonomous takeoff.
- 0.0
+ 0.01
+ 0.1
3
modules/mc_pos_control
Differential gain for vertical velocity error
0.0
+ 0.1
3
modules/mc_pos_control
@@ -2772,12 +2779,14 @@ Assumes measurement is timestamped at trailing edge of integration period
Proportional gain for horizontal position error
0.0
+ 2.0
2
modules/mc_pos_control
-
+
Proportional gain for horizontal velocity error
- 0.0
+ 0.06
+ 0.15
2
modules/mc_pos_control
@@ -2785,21 +2794,25 @@ Assumes measurement is timestamped at trailing edge of integration periodIntegral gain for horizontal velocity error
Non-zero value allows to resist wind.
0.0
+ 0.1
3
modules/mc_pos_control
Differential gain for horizontal velocity error. Small values help reduce fast oscillations. If value is too big oscillations will appear again
- 0.0
+ 0.005
+ 0.1
3
modules/mc_pos_control
Nominal horizontal velocity
Normal horizontal velocity in AUTO modes (includes also RTL / hold / etc.) and endpoint for position stabilized mode (POSCTRL).
- 0.0
+ 3.0
+ 20.0
m/s
2
+ 1
modules/mc_pos_control
@@ -2840,14 +2853,15 @@ Assumes measurement is timestamped at trailing edge of integration period
Landing descend rate
- 0.0
+ 0.2
m/s
1
modules/mc_pos_control
Takeoff climb rate
- 0.0
+ 1
+ 5
m/s
2
modules/mc_pos_control
@@ -2871,6 +2885,7 @@ Assumes measurement is timestamped at trailing edge of integration period
Max manual yaw rate
0.0
+ 400
deg/s
1
modules/mc_pos_control
@@ -2885,6 +2900,7 @@ Assumes measurement is timestamped at trailing edge of integration period
Maximum horizontal velocity for which position hold is enabled (use 0 to disable check)
0.0
+ 3.0
m/s
2
modules/mc_pos_control
@@ -2892,6 +2908,7 @@ Assumes measurement is timestamped at trailing edge of integration period
Maximum vertical velocity for which position hold is enabled (use 0 to disable check)
0.0
+ 3.0
m/s
2
modules/mc_pos_control
@@ -2899,6 +2916,7 @@ Assumes measurement is timestamped at trailing edge of integration period
Low pass filter cut freq. for numerical velocity derivative
0.0
+ 10
Hz
2
modules/mc_pos_control
@@ -5673,6 +5691,18 @@ This is used for gathering replay logs for the ekf2 module
Primary mag ID
modules/sensors
+
+ Bitfield selecting mag sides for calibration
+ DETECT_ORIENTATION_TAIL_DOWN = 1 DETECT_ORIENTATION_NOSE_DOWN = 2 DETECT_ORIENTATION_LEFT = 4 DETECT_ORIENTATION_RIGHT = 8 DETECT_ORIENTATION_UPSIDE_DOWN = 16 DETECT_ORIENTATION_RIGHTSIDE_UP = 32
+ 34
+ 63
+ modules/sensors
+
+ Two side calibration
+ Six side calibration
+ Three side calibration
+
+
Primary baro ID
modules/sensors