diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
index beda149..41962b2 100644
--- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
+++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
@@ -1687,7 +1687,7 @@
X-axis ballistic coefficient used for multi-rotor wind estimation
- This parameter controls the prediction of drag produced by bluff body drag along the forward/reverse axis when flying a multi-copter which enables estimation of wind drift when enabled by the EKF2_AID_MASK parameter. The EKF2_BCOEF_X paraemter should be set initially to the ratio of mass / projected frontal area and adjusted together with EKF2_MCOEF to minimise variance of the X-axis drag specific force innovation sequence. The drag produced by this effect scales with speed squared. Set this parameter to zero to turn off the bluff body drag model for this axis. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter.
+ This parameter controls the prediction of drag produced by bluff body drag along the forward/reverse axis when flying a multi-copter which enables estimation of wind drift when enabled by the EKF2_AID_MASK parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis.
0.0
200.0
kg/m^2
@@ -1695,7 +1695,7 @@
Y-axis ballistic coefficient used for multi-rotor wind estimation
- This parameter controls the prediction of drag produced by bluff body drag along the right/left axis when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_AID_MASK parameter. The EKF2_BCOEF_Y paraemter should be set initially to the ratio of mass / projected side area and adjusted together with EKF2_MCOEF to minimise variance of the Y-axis drag specific force innovation sequence. The drag produced by this effect scales with speed squared. et this parameter to zero to turn off the bluff body drag model for this axis. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter.
+ This parameter controls the prediction of drag produced by bluff body drag along the right/left axis when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_AID_MASK parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis.
0.0
200.0
kg/m^2
@@ -1940,6 +1940,14 @@
m/s
1
+
+ Gyro bias learning limit
+ The ekf delta angle bias states will be limited to within a range equivalent to +- of this value.
+ 0.0
+ 0.4
+ rad/s
+ 3
+
Process noise for IMU rate gyro bias prediction
0.0
@@ -2069,8 +2077,8 @@
2
- propeller momentum drag coefficient used for multi-rotor wind estimation
- This parameter controls the prediction of drag produced by the propellers when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_AID_MASK parameter. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the propeller axis of rotation is lost when passing through the rotor disc. This changes the momentum of the flow which creates a drag reaction force. When comparing un-ducted propellers of the same diameter, the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with propeller selection. Momentum drag is significantly higher for ducted rotors. For example, if flying at 10 m/s at sea level conditions produces a rotor induced drag deceleration of 1.5 m/s/s when the multi-copter levelled to zero roll/pitch, then EKF2_MCOEF would be set to 0.15 = (1.5/10.0). Set EKF2_MCOEF to a positive value to enable wind estimation using this drag effect. To account for the drag produced by the body which scales with speed squared, see documentation for the EKF2_BCOEF_X and EKF2_BCOEF_Y parameters. The EKF2_MCOEF parameter should be adjusted together with EKF2_BCOEF_X and EKF2_BCOEF_Y to minimise variance of the X and y axis drag specific force innovation sequences.
+ Propeller momentum drag coefficient used for multi-rotor wind estimation
+ This parameter controls the prediction of drag produced by the propellers when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_AID_MASK parameter. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the propeller axis of rotation is lost when passing through the rotor disc. This changes the momentum of the flow which creates a drag reaction force. When comparing un-ducted propellers of the same diameter, the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with propeller selection. Momentum drag is significantly higher for ducted rotors. To account for the drag produced by the body which scales with speed squared, see documentation for the EKF2_BCOEF_X and EKF2_BCOEF_Y parameters. Set this parameter to zero to turn off the momentum drag model for both axis.
0
1.0
1/s
@@ -2457,33 +2465,6 @@
-
- Acro body x max rate
- This is the rate the controller is trying to achieve if the user applies full roll stick input in acro mode.
- 45
- 720
- deg/s
- 1
- 5
-
-
- Acro body y max rate
- This is the body y rate the controller is trying to achieve if the user applies full pitch stick input in acro mode.
- 45
- 720
- deg/s
- 1
- 5
-
-
- Acro body z max rate
- This is the body z rate the controller is trying to achieve if the user applies full yaw stick input in acro mode.
- 10
- 180
- deg/s
- 1
- 5
-
Airspeed mode
For small wings or VTOL without airspeed sensor this parameter can be used to enable flying without an airspeed reading
@@ -2492,104 +2473,6 @@
Airspeed disabled
-
- Enable airspeed scaling
- This enables a logic that automatically adjusts the output of the rate controller to take into account the real torque produced by an aerodynamic control surface given the current deviation from the trim airspeed (FW_AIRSPD_TRIM). Enable when using aerodynamic control surfaces (e.g.: plane) Disable when using rotor wings (e.g.: autogyro)
-
-
- Whether to scale throttle by battery power level
- This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The fixed wing should constantly behave as if it was fully charged with reduced max thrust at lower battery percentages. i.e. if cruise speed is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery.
-
-
- Pitch trim increment for flaps configuration
- This increment is added to the pitch trim whenever flaps are fully deployed.
- -0.25
- 0.25
- 2
- 0.01
-
-
- Pitch trim increment for spoiler configuration
- This increment is added to the pitch trim whenever spoilers are fully deployed.
- -0.25
- 0.25
- 2
- 0.01
-
-
- Pitch trim increment at maximum airspeed
- This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MAX.
- -0.25
- 0.25
- 2
- 0.01
-
-
- Pitch trim increment at minimum airspeed
- This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MIN.
- -0.25
- 0.25
- 2
- 0.01
-
-
- Roll trim increment for flaps configuration
- This increment is added to TRIM_ROLL whenever flaps are fully deployed.
- -0.25
- 0.25
- 2
- 0.01
-
-
- Roll trim increment at maximum airspeed
- This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MAX.
- -0.25
- 0.25
- 2
- 0.01
-
-
- Roll trim increment at minimum airspeed
- This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MIN.
- -0.25
- 0.25
- 2
- 0.01
-
-
- Yaw trim increment at maximum airspeed
- This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MAX.
- -0.25
- 0.25
- 2
- 0.01
-
-
- Yaw trim increment at minimum airspeed
- This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN.
- -0.25
- 0.25
- 2
- 0.01
-
-
- Flaps setting during landing
- Sets a fraction of full flaps during landing.
- 0.0
- 1.0
- norm
- 2
- 0.01
-
-
- Flaps setting during take-off
- Sets a fraction of full flaps during take-off.
- 0.0
- 1.0
- norm
- 2
- 0.01
-
Maximum manual pitch angle
Maximum manual pitch angle setpoint (positive & negative) in manual attitude-only stabilized mode
@@ -2641,50 +2524,6 @@
2
0.01
-
- Pitch rate derivative gain
- Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.
- 0.0
- 1.0
- %/rad/s
- 3
- 0.005
-
-
- Pitch rate feed forward
- Direct feed forward from rate setpoint to control surface output
- 0.0
- 1.0
- %/rad/s
- 2
- 0.05
-
-
- Pitch 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
- 1
- %/rad
- 3
- 0.005
-
-
- Pitch rate integrator limit
- The portion of the integrator part in the control surface deflection is limited to this value
- 0.0
- 1.0
- 2
- 0.05
-
-
- Pitch rate proportional gain
- Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s.
- 0.0
- 2.0
- %/rad/s
- 3
- 0.005
-
Pitch setpoint offset (pitch at level flight)
An airframe specific offset of the pitch setpoint in degrees, the value is added to the pitch setpoint and should correspond to the pitch at typical cruise speed of the airframe.
@@ -2728,50 +2567,6 @@
1
0.01
-
- Roll rate derivative Gain
- Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.
- 0.0
- 1.0
- %/rad/s
- 3
- 0.005
-
-
- 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.
- 0.0
- 1
- %/rad/s
- 2
- 0.05
-
-
- Roll 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
- 1
- %/rad
- 3
- 0.005
-
-
- Roll integrator anti-windup
- The portion of the integrator part in the control surface deflection is limited to this value.
- 0.0
- 1.0
- 2
- 0.05
-
-
- Roll rate proportional Gain
- Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s.
- 0.0
- 2.0
- %/rad/s
- 3
- 0.005
-
Maximum roll rate
This limits the maximum roll rate the controller will output (in degrees per second).
@@ -2863,50 +2658,6 @@
1
0.5
-
- Yaw rate derivative gain
- Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.
- 0.0
- 1.0
- %/rad/s
- 3
- 0.005
-
-
- Yaw rate feed forward
- Direct feed forward from rate setpoint to control surface output
- 0.0
- 1.0
- %/rad/s
- 2
- 0.05
-
-
- Yaw 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
- 1
- %/rad
- 1
- 0.5
-
-
- Yaw rate integrator limit
- The portion of the integrator part in the control surface deflection is limited to this value
- 0.0
- 1.0
- 2
- 0.05
-
-
- Yaw rate proportional gain
- Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s.
- 0.0
- 2.0
- %/rad/s
- 3
- 0.005
-
Maximum yaw rate
This limits the maximum yaw rate the controller will output (in degrees per second).
@@ -3200,24 +2951,277 @@
2
0.05
-
- NPFG switch distance multiplier
- Multiplied by the track error boundary to determine when the aircraft switches to the next waypoint and/or path segment. Should be less than 1. 1/pi (0.32) sets the switch distance equivalent to that of the L1 controller.
- 0.1
+
+ NPFG switch distance multiplier
+ Multiplied by the track error boundary to determine when the aircraft switches to the next waypoint and/or path segment. Should be less than 1. 1/pi (0.32) sets the switch distance equivalent to that of the L1 controller.
+ 0.1
+ 1.0
+ 2
+ 0.01
+
+
+ Enable track keeping excess wind handling logic
+
+
+ Enable automatic upper bound on the NPFG period
+ Adapts period to maintain track keeping in variable winds and path curvature.
+
+
+ Enable wind excess regulation
+ Disabling this parameter further disables all other airspeed incrementation options.
+
+
+
+
+ Acro body x max rate
+ This is the rate the controller is trying to achieve if the user applies full roll stick input in acro mode.
+ 45
+ 720
+ deg
+
+
+ Acro body y max rate
+ This is the body y rate the controller is trying to achieve if the user applies full pitch stick input in acro mode.
+ 45
+ 720
+ deg
+
+
+ Acro body z max rate
+ This is the body z rate the controller is trying to achieve if the user applies full yaw stick input in acro mode.
+ 10
+ 180
+ deg
+
+
+ Enable airspeed scaling
+ This enables a logic that automatically adjusts the output of the rate controller to take into account the real torque produced by an aerodynamic control surface given the current deviation from the trim airspeed (FW_AIRSPD_TRIM). Enable when using aerodynamic control surfaces (e.g.: plane) Disable when using rotor wings (e.g.: autogyro)
+
+
+ Whether to scale throttle by battery power level
+ This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The fixed wing should constantly behave as if it was fully charged with reduced max thrust at lower battery percentages. i.e. if cruise speed is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery.
+
+
+ Pitch trim increment for flaps configuration
+ This increment is added to the pitch trim whenever flaps are fully deployed.
+ -0.25
+ 0.25
+ 2
+ 0.01
+
+
+ Pitch trim increment for spoiler configuration
+ This increment is added to the pitch trim whenever spoilers are fully deployed.
+ -0.25
+ 0.25
+ 2
+ 0.01
+
+
+ Pitch trim increment at maximum airspeed
+ This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MAX.
+ -0.25
+ 0.25
+ 2
+ 0.01
+
+
+ Pitch trim increment at minimum airspeed
+ This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MIN.
+ -0.25
+ 0.25
+ 2
+ 0.01
+
+
+ Roll trim increment for flaps configuration
+ This increment is added to TRIM_ROLL whenever flaps are fully deployed.
+ -0.25
+ 0.25
+ 2
+ 0.01
+
+
+ Roll trim increment at maximum airspeed
+ This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MAX.
+ -0.25
+ 0.25
+ 2
+ 0.01
+
+
+ Roll trim increment at minimum airspeed
+ This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MIN.
+ -0.25
+ 0.25
+ 2
+ 0.01
+
+
+ Yaw trim increment at maximum airspeed
+ This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MAX.
+ -0.25
+ 0.25
+ 2
+ 0.01
+
+
+ Yaw trim increment at minimum airspeed
+ This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN.
+ -0.25
+ 0.25
+ 2
+ 0.01
+
+
+ Flaps setting during landing
+ Sets a fraction of full flaps during landing. Also applies to flaperons if enabled in the mixer/allocation.
+ 0.0
+ 1.0
+ norm
+ 2
+ 0.01
+
+
+ Flaps setting during take-off
+ Sets a fraction of full flaps during take-off. Also applies to flaperons if enabled in the mixer/allocation.
+ 0.0
+ 1.0
+ norm
+ 2
+ 0.01
+
+
+ Pitch rate derivative gain
+ Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.
+ 0.0
+ 1.0
+ %/rad/s
+ 3
+ 0.005
+
+
+ Pitch rate feed forward
+ Direct feed forward from rate setpoint to control surface output
+ 0.0
+ 10.0
+ %/rad/s
+ 2
+ 0.05
+
+
+ Pitch 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
+ 0.5
+ %/rad
+ 3
+ 0.005
+
+
+ Pitch rate integrator limit
+ The portion of the integrator part in the control surface deflection is limited to this value
+ 0.0
+ 1.0
+ 2
+ 0.05
+
+
+ Pitch rate proportional gain
+ Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s.
+ 0.0
+ 1.0
+ %/rad/s
+ 3
+ 0.005
+
+
+ Roll rate derivative Gain
+ Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.
+ 0.0
+ 1.0
+ %/rad/s
+ 3
+ 0.005
+
+
+ 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.
+ 0.0
+ 10.0
+ %/rad/s
+ 2
+ 0.05
+
+
+ Roll 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
+ 0.2
+ %/rad
+ 3
+ 0.005
+
+
+ Roll integrator anti-windup
+ The portion of the integrator part in the control surface deflection is limited to this value.
+ 0.0
+ 1.0
+ 2
+ 0.05
+
+
+ Roll rate proportional Gain
+ Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s.
+ 0.0
+ 1.0
+ %/rad/s
+ 3
+ 0.005
+
+
+ Yaw rate derivative gain
+ Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.
+ 0.0
1.0
+ %/rad/s
+ 3
+ 0.005
+
+
+ Yaw rate feed forward
+ Direct feed forward from rate setpoint to control surface output
+ 0.0
+ 10.0
+ %/rad/s
2
- 0.01
+ 0.05
-
- Enable track keeping excess wind handling logic
+
+ Yaw 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
+ %/rad
+ 1
+ 0.5
-
- Enable automatic upper bound on the NPFG period
- Adapts period to maintain track keeping in variable winds and path curvature.
+
+ Yaw rate integrator limit
+ The portion of the integrator part in the control surface deflection is limited to this value
+ 0.0
+ 1.0
+ 2
+ 0.05
-
- Enable wind excess regulation
- Disabling this parameter further disables all other airspeed incrementation options.
+
+ Yaw rate proportional gain
+ Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s.
+ 0.0
+ 1.0
+ %/rad/s
+ 3
+ 0.005
@@ -4467,6 +4471,108 @@
If set to 1 incoming HIL GPS messages are parsed.
+
+
+ UART ESC baud rate
+ Default rate is 250Kbps, which is used in off-the-shelf MoadalAI ESC products.
+ bit/s
+
+
+ UART ESC configuration
+ Selects what type of UART ESC, if any, is being used.
+ 0
+ 1
+ true
+
+ - Disabled
+ - VOXL ESC
+
+
+
+ UART ESC Mode
+ Selects what type of mode is enabled, if any
+ 0
+ 2
+ true
+
+ - None
+ - Turtle Mode enabled via AUX1
+ - Turtle Mode enabled via AUX2
+ - UART Passthrough Mode
+
+
+
+ UART ESC RPM Max
+ Maximum RPM for ESC
+
+
+ UART ESC RPM Min
+ Minimum RPM for ESC
+
+
+ UART ESC ID 1 Spin Direction Flag
+
+ - Default
+ - Reverse
+
+
+
+ UART ESC ID 2 Spin Direction Flag
+
+ - Default
+ - Reverse
+
+
+
+ UART ESC ID 3 Spin Direction Flag
+
+ - Default
+ - Reverse
+
+
+
+ UART ESC ID 4 Spin Direction Flag
+
+ - Default
+ - Reverse
+
+
+
+ UART ESC Turtle Mode Cosphi
+ 0.000
+ 1.000
+ 10
+ 0.001
+
+
+ UART ESC Turtle Mode Crash Flip Motor Deadband
+ 0
+ 100
+ 10
+ 1
+
+
+ UART ESC Turtle Mode Crash Flip Motor expo
+ 0
+ 100
+ 10
+ 1
+
+
+ UART ESC Turtle Mode Crash Flip Motor STICK_MINF
+ 0.0
+ 100.0
+ 10
+ 1.0
+
+
+ UART ESC Turtle Mode Crash Flip Motor Percent
+ 1
+ 100
+ 10
+ 1
+
+
Enable online mag bias calibration
@@ -4563,7 +4669,7 @@
Require a takeoff
Require a landing
Require a takeoff and a landing
- Require a takeoff and a landing, or neither of both
+ Require both a takeoff and a landing, or neither
@@ -7765,6 +7871,7 @@
from boot until disarm
from boot until shutdown
depending on AUX1 RC channel
+ from 1st armed until shutdown
@@ -7920,20 +8027,9 @@
2.00
m
-
- Automatically set external rotations
- During calibration attempt to automatically determine the rotation of external magnetometers.
-
-
- Bitfield selecting mag sides for calibration
- If set to two side calibration, only the offsets are estimated, the scale calibration is left unchanged. Thus an initial six side calibration is recommended. Bits: ORIENTATION_TAIL_DOWN = 1 ORIENTATION_NOSE_DOWN = 2 ORIENTATION_LEFT = 4 ORIENTATION_RIGHT = 8 ORIENTATION_UPSIDE_DOWN = 16 ORIENTATION_RIGHTSIDE_UP = 32
- 34
- 63
-
- Two side calibration
- Three side calibration
- Six side calibration
-
+
+ For legacy QGC support only
+ Use SENS_MAG_SIDES instead
Low pass filter cutoff frequency for accel
@@ -8428,6 +8524,10 @@
HY-SRF05 / HC-SR05
true
+
+ TF02 Pro Distance Sensor (i2c)
+ true
+
Thermal control of sensor temperature
@@ -8450,6 +8550,10 @@
TREvo3m
+
+ VL53L0X Distance Sensor
+ true
+
VL53L1X Distance Sensor
true
@@ -8554,6 +8658,10 @@
Magnetometer auto calibration
Automatically initialize magnetometer calibration from bias estimate if available.
+
+ Automatically set external rotations
+ During calibration attempt to automatically determine the rotation of external magnetometers.
+
Sensors hub mag mode
true
@@ -8570,6 +8678,17 @@
Hz
true
+
+ Bitfield selecting mag sides for calibration
+ If set to two side calibration, only the offsets are estimated, the scale calibration is left unchanged. Thus an initial six side calibration is recommended. Bits: ORIENTATION_TAIL_DOWN = 1 ORIENTATION_NOSE_DOWN = 2 ORIENTATION_LEFT = 4 ORIENTATION_RIGHT = 8 ORIENTATION_UPSIDE_DOWN = 16 ORIENTATION_RIGHTSIDE_UP = 32
+ 34
+ 63
+
+ Two side calibration
+ Three side calibration
+ Six side calibration
+
+
MaxBotix MB12XX Sensor 0 Rotation
This parameter defines the rotation of the sensor relative to the platform.
@@ -9975,100 +10094,6 @@
-
-
- UART ESC baud rate
- Default rate is 250Kbps, which is used in off-the-shelf MoadalAI ESC products.
- bit/s
-
-
- UART ESC configuration
- Selects what type of UART ESC, if any, is being used.
- 0
- 1
- true
-
- - Disabled
- - VOXL ESC
-
-
-
- UART ESC Mode
- Selects what type of mode is enabled, if any
- 0
- 2
- true
-
- - None
- - Turtle Mode enabled via AUX1
- - Turtle Mode enabled via AUX2
- - UART Passthrough Mode
-
-
-
- UART ESC Motor 1 Mapping. 1-4 (negative for reversal)
- -4
- 4
-
-
- UART ESC Motor 2 Mapping. 1-4 (negative for reversal)
- -4
- 4
-
-
- UART ESC Motor 3 Mapping. 1-4 (negative for reversal)
- -4
- 4
-
-
- UART ESC Motor 4 Mapping. 1-4 (negative for reversal)
- -4
- 4
-
-
- UART ESC RPM Max
- Maximum RPM for ESC
-
-
- UART ESC RPM Min
- Minimum RPM for ESC
-
-
- UART ESC Turtle Mode Cosphi
- 0.000
- 1.000
- 10
- 0.001
-
-
- UART ESC Turtle Mode Crash Flip Motor Deadband
- 0
- 100
- 10
- 1
-
-
- UART ESC Turtle Mode Crash Flip Motor expo
- 0
- 100
- 10
- 1
-
-
- UART ESC Turtle Mode Crash Flip Motor STICK_MINF
- 0.0
- 100.0
- 10
- 1.0
-
-
- UART ESC Turtle Mode Crash Flip Motor Percent
- 1
- 100
- 10
- 1
-
-
UAVCAN CAN bus bitrate
@@ -10098,6 +10123,10 @@
CAN built-in bus termination
1
+
+ Simulator Gazebo bridge enable
+ true
+
UAVCAN CAN bus bitrate
20000
@@ -10445,15 +10474,6 @@
0.0
2.0
-
- Adaptive QuadChute
- Maximum negative altitude error for fixed wing flight. If the altitude drops below this value below the altitude setpoint the vehicle will transition back to MC mode and enter failsafe RTL.
- 0.0
- 200.0
- m
- 1
- 1
-
Differential thrust in forwards flight
Enable differential thrust seperately for roll, pitch, yaw in forward (fixed-wing) mode. The effectiveness of differential thrust around the corresponding axis can be tuned by setting VT_FW_DIFTHR_S_R / VT_FW_DIFTHR_S_P / VT_FW_DIFTHR_S_Y.
@@ -10499,23 +10519,25 @@
1
- Quadchute maximum height
- Maximum height above the ground (if available, otherwhise above home if available, otherwise above the local origin) where triggering a quadchute is possible. Triggering a quadchute always means transitioning the vehicle to hover flight in which generally a lot of energy is consumed. At high altitudes there is therefore a big risk to deplete the battery and therefore crash. Currently, there is no automated re-transition to fixed wing mode implemented and therefore this parameter serves and an intermediate measure to increase safety. Setting this value to 0 deactivates the behavior.
+ Quad-chute maximum height
+ Maximum height above the ground (if available, otherwhise above home if available, otherwise above the local origin) where triggering a quadchute is possible. Triggering a quadchute always means transitioning the vehicle to hover flight in which generally a lot of energy is consumed. At high altitudes there is therefore a big risk to deplete the battery and therefore crash. Currently, there is no automated re-transition to fixed wing mode implemented and therefore this parameter serves and an intermediate measure to increase safety. Setting this value to 0 deactivates the behavior (always enable quad-chute independently of altitude).
0
m
1
- QuadChute Max Pitch
- Maximum pitch angle before QuadChute engages Above this the vehicle will transition back to MC mode and enter failsafe RTL
+ Quad-chute max pitch threshold
+ Absolute pitch threshold for quad-chute triggering in FW mode. Above this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold.
0
180
+ deg
- QuadChute Max Roll
- Maximum roll angle before QuadChute engages Above this the vehicle will transition back to MC mode and enter failsafe RTL
+ Quad-chute max roll threshold
+ Absolute roll threshold for quad-chute triggering in FW mode. Above this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold.
0
180
+ deg
Duration of a front transition
@@ -10569,6 +10591,24 @@
2
0.01
+
+ Quad-chute uncommanded descent threshold
+ Threshold for integrated height rate error to trigger a uncommanded-descent quad-chute. Only checked in altitude-controlled fixed-wing flight. Additional conditions that have to be met for uncommanded descent detection are a positive (climbing) height rate setpoint and a negative (sinking) current height rate estimate. Set to 0 do disable this threshold.
+ 0.0
+ 200.0
+ m
+ 1
+ 1
+
+
+ Quad-chute transition altitude loss threshold
+ Altitude loss threshold for quad-chute triggering during VTOL transition to fixed-wing flight. If the current altitude is more than this value below the altitude at the beginning of the transition, it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold.
+ 0
+ 50
+ m
+ 1
+ 1
+
Spoiler setting while landing (hover)
-1