diff --git a/src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml b/src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml
index d4b602f2e8cbcde5215b55fd89347458a224636c..864f58a0bab0ed26d20d4fd333fd752eff5d88bc 100644
--- a/src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml
+++ b/src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml
@@ -55,7 +55,7 @@
Extended status ID
Extended status ID
1
- 100000
+ 1000000
Extended status interval (µs)
@@ -89,7 +89,6 @@
specification sheet; accuracy will help control performance but
some deviation from the specified value is acceptable.
RPM/v
- 0
0
4000
@@ -244,17 +243,21 @@ velocity
Empty cell voltage
Defines the voltage where a single cell of the battery is considered empty.
V
+ 2
Full cell voltage
Defines the voltage where a single cell of the battery is considered full.
V
+ 2
Voltage drop per cell on 100% load
This implicitely defines the internal resistance to maximum current ratio and assumes linearity.
0.0
+ 1.5
V
+ 2
Number of cells
@@ -267,6 +270,7 @@ velocity
Battery capacity
Defines the capacity of the attached battery.
mA
+ 0
Scaling factor for battery voltage sensor on PX4IO
@@ -276,7 +280,7 @@ velocity
Scaling factor for battery voltage sensor on FMU v2
-
+
Scaling factor for battery current sensor
@@ -304,6 +308,7 @@ velocity
0 disables the trigger, 1 sets it to enabled on command, 2 always on
0
2
+ true
Camera trigger pin
@@ -361,6 +366,12 @@ velocity
0
782097
+
+ Circuit breaker for USB link check
+ Setting this parameter to 197848 will disable the USB connected checks in the commander. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK
+ 0
+ 197848
+
@@ -388,6 +399,7 @@ velocity
Engine failure triggers only above this throttle value
0.0
1.0
+ 1
Engine Failure Current/Throttle Threshold
@@ -395,6 +407,7 @@ velocity
0.0
30.0
ampere
+ 2
Engine Failure Time Threshold
@@ -402,6 +415,7 @@ velocity
0.0
60.0
second
+ 1
RC loss time threshold
@@ -409,6 +423,7 @@ velocity
0
35
second
+ 1
Home set horizontal threshold
@@ -416,6 +431,7 @@ velocity
2
15
meter
+ 2
Home set vertical threshold
@@ -423,6 +439,7 @@ velocity
5
25
meter
+ 2
Autosaving of params
@@ -509,14 +526,211 @@ velocity
m
+
+
+ Magnetometer measurement delay relative to IMU measurements
+ 0
+ 300
+ ms
+
+
+ Barometer measurement delay relative to IMU measurements
+ 0
+ 300
+ ms
+
+
+ GPS measurement delay relative to IMU measurements
+ 0
+ 300
+ ms
+
+
+ Airspeed measurement delay relative to IMU measurements
+ 0
+ 300
+ ms
+
+
+ Integer bitmask controlling GPS checks. Set bits to 1 to enable checks. Checks enabled by the following bit positions
+0 : Minimum required sat count set by EKF2_REQ_NSATS
+1 : Minimum required GDoP set by EKF2_REQ_GDOP
+2 : Maximum allowed horizontal position error set by EKF2_REQ_EPH
+3 : Maximum allowed vertical position error set by EKF2_REQ_EPV
+4 : Maximum allowed speed error set by EKF2_REQ_SACC
+5 : Maximum allowed horizontal position rate set by EKF2_REQ_HDRIFT. This check can only be used if the vehciel is stationary during alignment.
+6 : Maximum allowed vertical position rate set by EKF2_REQ_VDRIFT. This check can only be used if the vehciel is stationary during alignment.
+7 : Maximum allowed horizontal speed set by EKF2_REQ_HDRIFT. This check can only be used if the vehciel is stationary during alignment.
+8 : Maximum allowed vertical velocity discrepancy set by EKF2_REQ_VDRIFT
+ 0
+ 511
+
+
+
+ Required EPH to use GPS
+ 2
+ 100
+ m
+
+
+ Required EPV to use GPS
+ 2
+ 100
+ m
+
+
+ Required speed accuracy to use GPS
+ 0.5
+ 5.0
+ m/s
+
+
+ Required satellite count to use GPS
+ 4
+ 12
+
+
+
+ Required GDoP to use GPS
+ 1.5
+ 5.0
+
+
+
+ Maximum horizontal drift speed to use GPS
+ 0.1
+ 1.0
+ m/s
+
+
+ Maximum vertical drift speed to use GPS
+ 0.1
+ 1.5
+ m/s
+
+
+ Rate gyro noise for covariance prediction
+ 0.0001
+ 0.01
+ rad/s
+
+
+ Accelerometer noise for covariance prediction
+ 0.01
+ 1.0
+ m/s/s
+
+
+ Process noise for delta angle bias prediction
+ 0.0
+ 0.0001
+ rad/s
+
+
+ Process noise for delta velocity z bias prediction
+ 0.0
+ 0.01
+ m/s/s
+
+
+ Process noise for delta angle scale factor prediction
+ 0.0
+ 0.01
+ None
+
+
+ Process noise for sensor bias and earth magnetic field prediction
+ 0.0
+ 0.1
+ Gauss/s
+
+
+ Process noise for wind velocity prediction
+ 0.0
+ 1.0
+ m/s/s
+
+
+ Measurement noise for gps horizontal velocity
+ 0.01
+ 5.0
+ m/s
+
+
+ Measurement noise for gps position
+ 0.01
+ 10.0
+ m
+
+
+ Measurement noise for non-aiding position hold
+ 0.5
+ 50.0
+ m
+
+
+ Measurement noise for barometric altitude
+ 0.01
+ 15.0
+ m
+
+
+ Measurement noise for magnetic heading fusion
+ 0.01
+ 1.0
+ rad
+
+
+ Measurement noise for magnetometer 3-axis fusion
+ 0.001
+ 1.0
+ Gauss
+
+
+ Magnetic declination
+ degrees
+
+
+ Gate size for magnetic heading fusion
+ 1.0
+ SD
+
+
+ Gate size for magnetometer XYZ component fusion
+ 1.0
+ SD
+
+
+ Gate size for barometric height fusion
+ 1.0
+ SD
+
+
+ Gate size for GPS horizontal position fusion
+ 1.0
+ SD
+
+
+ Gate size for GPS velocity fusion
+ 1.0
+ SD
+
+
-
- Attitude Time Constant
- This defines the latency between a step input and the achieved setpoint (inverse to a P gain). Half a second is a good start value and fits for most average systems. Smaller systems may require smaller values, but as this will wear out servos faster, the value should only be decreased as needed.
+
+ Attitude Roll Time Constant
+ This defines the latency between a roll step input and the achieved setpoint (inverse to a P gain). Half a second is a good start value and fits for most average systems. Smaller systems may require smaller values, but as this will wear out servos faster, the value should only be decreased as needed.
0.4
1.0
seconds
+
+ Attitude Pitch Time Constant
+ This defines the latency between a pitch step input and the achieved setpoint (inverse to a P gain). Half a second is a good start value and fits for most average systems. Smaller systems may require smaller values, but as this will wear out servos faster, the value should only be decreased as needed.
+ 0.2
+ 1.0
+ seconds
+
Pitch rate proportional gain
This defines how much the elevator input will be commanded depending on the current body angular rate error.
@@ -599,6 +813,31 @@ velocity
90.0
deg/s
+
+ Wheel steering rate proportional gain
+ This defines how much the wheel steering input will be commanded depending on the current body angular rate error.
+ 0.005
+ 1.0
+
+
+ Wheel steering rate integrator gain
+ This gain defines how much control response will result out of a steady state error. It trims any constant error.
+ 0.0
+ 50.0
+
+
+ Wheel steering rate integrator limit
+ The portion of the integrator part in the control surface deflection is limited to this value
+ 0.0
+ 1.0
+
+
+ Maximum wheel steering rate
+ This limits the maximum wheel steering rate the controller will output (in degrees per second). Setting a value of zero disables the limit.
+ 0.0
+ 90.0
+ deg/s
+
Roll rate feed forward
Direct feed forward from rate setpoint to control surface output. Use this to obtain a tigher response of the controller without introducing noise amplification.
@@ -617,6 +856,12 @@ velocity
0.0
10.0
+
+ Wheel steering rate feed forward
+ Direct feed forward from rate setpoint to control surface output
+ 0.0
+ 10.0
+
Minimal speed for yaw coordination
For airspeeds above this value, the yaw rate is calculated for a coordinated turn. Set to a very high value to disable.
@@ -678,6 +923,16 @@ velocity
90.0
deg
+
+ Scale factor for flaps
+ 0.0
+ 1.0
+
+
+ Scale factor for flaperons
+ 0.0
+ 1.0
+
@@ -794,18 +1049,36 @@ velocity
Max horizontal distance in meters
Set to > 0 to activate a geofence action if horizontal distance to home exceeds this value.
+ -1
+ meters
Max vertical distance in meters
Set to > 0 to activate a geofence action if vertical distance to home exceeds this value.
+ -1
+ meters
+
+
+
+
+ Consider mount operation mode
+ If set to 1, mount mode will be enforced.
+ 0
+ 1
+
+
+ Auxiliary switch to set mount operation mode
+ Set to 0 to disable manual mode control. If set to an auxiliary switch: Switch off means the gimbal is put into safe/locked position. Switch on means the gimbal can move freely, and landing gear will be retracted if applicable.
+ 0
+ 3
L1 period
This is the L1 distance and defines the tracking point ahead of the aircraft its following. A value of 25 meters works for most aircraft. Shorten slowly during tuning until response is sharp without oscillation.
- 1.0
- 100.0
+ 12.0
+ 50.0
L1 damping
@@ -896,6 +1169,12 @@ velocity
Enable or disable usage of terrain estimate during landing
0: disabled, 1: enabled
+
+ Takeoff and landing airspeed scale factor
+ Multiplying this factor with the minimum airspeed of the plane gives the target airspeed for takeoff and landing approach.
+ 1.0
+ 1.5
+
@@ -933,6 +1212,13 @@ velocity
20
m/s
+
+ Fixedwing max short-term velocity
+ Maximum velocity integral in flight direction allowed in the landed state (m/s)
+ 2
+ 10
+ m/s
+
Airspeed max
Maximum airspeed allowed in the landed state (m/s)
@@ -1144,7 +1430,7 @@ velocity
-
+
Take-off altitude
Even if first waypoint has altitude less then MIS_TAKEOFF_ALT above home position, system will climb to MIS_TAKEOFF_ALT on takeoff, then go to waypoint.
meters
@@ -1201,6 +1487,18 @@ velocity
+
+ Roll time constant
+ Reduce if the system is too twitchy, increase if the response is too slow and sluggish.
+ 0.15
+ 0.25
+
+
+ Pitch time constant
+ Reduce if the system is too twitchy, increase if the response is too slow and sluggish.
+ 0.15
+ 0.25
+
Roll P gain
Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad.
@@ -1298,13 +1596,20 @@ velocity
360.0
deg/s
-
+
Max yaw rate
- Limit for yaw rate, has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. A value of significantly over 60 degrees per second can already lead to mixer saturation.
+ A value of significantly over 120 degrees per second can already lead to mixer saturation.
0.0
360.0
deg/s
+
+ Max yaw rate in auto mode
+ Limit for yaw rate, has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. A value of significantly over 60 degrees per second can already lead to mixer saturation. A value of 30 degrees / second is recommended to avoid very audible twitches.
+ 0.0
+ 120.0
+ deg/s
+
Max acro roll rate
0.0
@@ -1452,7 +1757,7 @@ velocity
0.0
0.95
-
+
Minimum manual thrust
Minimum vertical thrust. It's recommended to set it > 0 to avoid free fall with zero thrust.
0.0
@@ -1530,18 +1835,23 @@ velocity
90.0
degree
-
+
Maximum tilt during landing
Limits maximum tilt angle on landing.
0.0
90.0
degree
-
+
Landing descend rate
0.0
m/s
+
+ Takeoff climb rate
+ 0.0
+ m/s
+
Max manual roll
0.0
@@ -1586,6 +1896,12 @@ velocity
0.0
Hz
+
+ Maximum horizonal acceleration in velocity controlled modes
+ 2.0
+ 10.0
+ m/s/s
+
Minimum thrust
Minimum vertical thrust. It's recommended to set it > 0 to avoid free fall with zero thrust.
@@ -1682,84 +1998,98 @@ velocity
Set to 1 to invert the channel, 0 for default direction.
0
1
+ true
Invert direction of aux output channel 2
Set to 1 to invert the channel, 0 for default direction.
0
1
+ true
Invert direction of aux output channel 3
Set to 1 to invert the channel, 0 for default direction.
0
1
+ true
Invert direction of aux output channel 4
Set to 1 to invert the channel, 0 for default direction.
0
1
+ true
Invert direction of aux output channel 5
Set to 1 to invert the channel, 0 for default direction.
0
1
+ true
Invert direction of aux output channel 6
Set to 1 to invert the channel, 0 for default direction.
0
1
+ true
Invert direction of main output channel 1
Set to 1 to invert the channel, 0 for default direction.
0
1
+ true
Invert direction of main output channel 2
Set to 1 to invert the channel, 0 for default direction.
0
1
+ true
Invert direction of main output channel 3
Set to 1 to invert the channel, 0 for default direction.
0
1
+ true
Invert direction of main output channel 4
Set to 1 to invert the channel, 0 for default direction.
0
1
+ true
Invert direction of main output channel 5
Set to 1 to invert the channel, 0 for default direction.
0
1
+ true
Invert direction of main output channel 6
Set to 1 to invert the channel, 0 for default direction.
0
1
+ true
Invert direction of main output channel 7
Set to 1 to invert the channel, 0 for default direction.
0
1
+ true
Invert direction of main output channel 8
Set to 1 to invert the channel, 0 for default direction.
0
1
+ true
Enable S.BUS out
@@ -1773,6 +2103,7 @@ velocity
800
1400
microseconds
+ true
Set the maximum PWM for the MAIN outputs
@@ -1780,6 +2111,7 @@ velocity
1600
2200
microseconds
+ true
Set the disarmed PWM for MAIN outputs
@@ -1787,6 +2119,7 @@ velocity
0
2200
microseconds
+ true
Set the minimum PWM for the MAIN outputs
@@ -1794,6 +2127,7 @@ velocity
800
1400
microseconds
+ true
Set the maximum PWM for the MAIN outputs
@@ -1801,6 +2135,7 @@ velocity
1600
2200
microseconds
+ true
Set the disarmed PWM for AUX outputs
@@ -1808,6 +2143,7 @@ velocity
0
2200
microseconds
+ true
@@ -1933,7 +2269,7 @@ velocity
0.001
0.05
-
+
Accelerometer process noise
Generic defaults: 0.25, multicopters: 0.25, ground vehicles: 0.25. Increasing this value makes the filter trust the accelerometer less and other sensors more.
0.05
@@ -2049,11 +2385,11 @@ velocity
0.0
10.0
-
+
XY axis weight for optical flow
Weight (cutoff frequency) for optical flow (velocity) measurements.
0.0
- 30.0
+ 10.0
XY axis weight for resetting velocity
@@ -2140,6 +2476,12 @@ velocity
1.0
m
+
+ Disable mocap (set 0 if using fake gps)
+ Disable mocap
+ 0
+ 1
+
Disable vision input
Set to the appropriate key (328754) to disable vision input.
@@ -2159,18 +2501,21 @@ velocity
The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS.
-0.25
0.25
+ 2
Pitch trim
The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS.
-0.25
0.25
+ 2
Yaw trim
The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS.
-0.25
0.25
+ 2
RC Channel 1 Minimum
@@ -2920,6 +3265,11 @@ velocity
0
18
+
+ Kill switch channel mapping
+ 0
+ 18
+
Flaps channel mapping
0
@@ -2973,6 +3323,12 @@ velocity
-1
1
+
+ Threshold for the kill switch
+ 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th
+ -1
+ 1
+
@@ -2997,6 +3353,67 @@ velocity
seconds
+
+
+ Enable or disable runway takeoff with landing gear
+ 0: disabled, 1: enabled
+ 0
+ 1
+
+
+ Specifies which heading should be held during runnway takeoff
+ 0: airframe heading, 1: heading towards takeoff waypoint
+ 0
+ 1
+
+
+ Altitude AGL at which we have enough ground clearance to allow some roll.
+Until RWTO_NAV_ALT is reached the plane is held level and only
+rudder is used to keep the heading (see RWTO_HDG). This should be below
+FW_CLMBOUT_DIFF if FW_CLMBOUT_DIFF > 0
+ 0.0
+ 100.0
+ m
+
+
+ Max throttle during runway takeoff.
+(Can be used to test taxi on runway)
+ 0.0
+ 1.0
+
+
+ Pitch setpoint during taxi / before takeoff airspeed is reached.
+A taildragger with stearable wheel might need to pitch up
+a little to keep it's wheel on the ground before airspeed
+to takeoff is reached
+ 0.0
+ 20.0
+ deg
+
+
+ Max pitch during takeoff.
+Fixed-wing settings are used if set to 0. Note that there is also a minimum
+pitch of 10 degrees during takeoff, so this must be larger if set
+ 0.0
+ 60.0
+ deg
+
+
+ Max roll during climbout.
+Roll is limited during climbout to ensure enough lift and prevents aggressive
+navigation before we're on a safe height
+ 0.0
+ 60.0
+ deg
+
+
+ Min. airspeed scaling factor for takeoff.
+Pitch up will be commanded when the following airspeed is reached:
+FW_AIRSPD_MIN * RWTO_AIRSPD_SCL
+ 0.0
+ 2.0
+
+
Logging rate
@@ -3380,11 +3797,17 @@ velocity
0
2
-
+
Companion computer interface
CHANGING THIS VALUE REQUIRES A RESTART. Configures the baud rate of the companion computer interface. Set to zero to disable, set to these values to enable (NO OTHER VALUES SUPPORTED!) 921600: enables onboard mode at 921600 baud, 8N1. 57600: enables onboard mode at 57600 baud, 8N1. 157600: enables OSD mode at 57600 baud, 8N1.
0
921600
+ true
+
+ Companion Link (57600 baud, 8N1)
+ Companion Link (921600 baud, 8N1)
+ OSD (57600 baud, 8N1)
+
Parameter version
@@ -3441,10 +3864,10 @@ velocity
0.1
2
-
+
The channel number of motors that must be turned off in fixed wing mode
0
- 123456
+ 12345678
VTOL number of engines
@@ -3533,6 +3956,11 @@ velocity
1.0
20
+
+ Enable optimal recovery strategy for pitch-weak tailsitters
+ 0
+ 1
+
@@ -3803,126 +4231,6 @@ Maps the change of airspeed error to the acceleration setpoint
TEST_DEV
-
- FWB_P_LP
-
-
- FWB_Q_LP
-
-
- FWB_R_LP
-
-
- FWB_R_HP
-
-
- FWB_P2AIL
-
-
- FWB_Q2ELV
-
-
- FWB_R2RDR
-
-
- FWB_PSI2PHI
-
-
- FWB_PHI2P
-
-
- FWB_PHI_LIM_MAX
-
-
- FWB_V2THE_P
-
-
- FWB_V2THE_I
-
-
- FWB_V2THE_D
-
-
- FWB_V2THE_D_LP
-
-
- FWB_V2THE_I_MAX
-
-
- FWB_THE_MIN
-
-
- FWB_THE_MAX
-
-
- FWB_THE2Q_P
-
-
- FWB_THE2Q_I
-
-
- FWB_THE2Q_D
-
-
- FWB_THE2Q_D_LP
-
-
- FWB_THE2Q_I_MAX
-
-
- FWB_H2THR_P
-
-
- FWB_H2THR_I
-
-
- FWB_H2THR_D
-
-
- FWB_H2THR_D_LP
-
-
- FWB_H2THR_I_MAX
-
-
- FWB_XT2YAW_MAX
-
-
- FWB_XT2YAW
-
-
- FWB_V_MIN
-
-
- FWB_V_CMD
-
-
- FWB_V_MAX
-
-
- FWB_CR_MAX
-
-
- FWB_CR2THR_P
-
-
- FWB_CR2THR_I
-
-
- FWB_CR2THR_D
-
-
- FWB_CR2THR_D_LP
-
-
- FWB_CR2THR_I_MAX
-
-
- FWB_TRIM_THR
-
-
- FWB_TRIM_V
-
Flare, minimum pitch
Minimum pitch during flare, a positive sign means nose up Applied once FW_LND_TLALT is reached