diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
index 782fefd9208fe6268be5837227b358dc4b129f4b..88b39f7f24e9915909620ec68aaf0abcbcbe6d66 100644
--- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
+++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
@@ -259,6 +259,7 @@ velocity
V
2
0.01
+ true
modules/systemlib
@@ -267,6 +268,7 @@ velocity
V
2
0.01
+ true
modules/systemlib
@@ -277,6 +279,7 @@ velocity
norm
2
0.01
+ true
modules/systemlib
@@ -287,6 +290,7 @@ velocity
norm
2
0.01
+ true
modules/systemlib
@@ -297,6 +301,7 @@ velocity
norm
2
0.01
+ true
modules/systemlib
@@ -307,6 +312,7 @@ velocity
V
2
0.01
+ true
modules/systemlib
@@ -315,12 +321,14 @@ velocity
-1.0
0.2
Ohms
+ true
modules/systemlib
Number of cells
Defines the number of cells the attached battery consists of.
S
+ true
modules/systemlib
11S Battery
@@ -349,6 +357,7 @@ velocity
mA
0
50
+ true
modules/systemlib
@@ -581,12 +590,6 @@ velocity
0.5
modules/commander
-
- Autosaving of params
- If not equal to zero the commander will automatically save parameters to persistent storage once changed. Default is on, as the interoperability with currently deployed GCS solutions depends on parameters being sticky. Developers can default it to off.
-
- modules/commander
-
RC control input mode
The default value of 0 requires a valid RC transmitter setup. Setting this to 1 allows joystick control and disables RC input handling and the associated checks. A value of 2 will generate RC control data from manual input received via MAVLink instead of directly forwarding the manual input data.
@@ -1584,6 +1587,11 @@ value will determine the minimum airspeed which will still be fused
0.01
modules/fw_att_control
+
+ Enable wheel steering controller
+
+ modules/fw_att_control
+
Wheel steering rate proportional gain
This defines how much the wheel steering input will be commanded depending on the current body angular rate error.
@@ -2178,17 +2186,17 @@ value will determine the minimum airspeed which will still be fused
modules/fw_pos_control_l1
- Height rate P factor
+ Height rate proportional factor
0.0
- 2.0
+ 1.0
2
0.05
modules/fw_pos_control_l1
-
- Height rate FF factor
+
+ Height rate feed forward
0.0
- 2.0
+ 1.0
2
0.05
modules/fw_pos_control_l1
@@ -2365,7 +2373,7 @@ but also ignore less noise
-
+
Multicopter max climb rate
Maximum vertical velocity allowed in the landed state (m/s up and down)
m/s
@@ -2417,6 +2425,16 @@ but also ignore less noise
When controlling manually the throttle stick value (0 to 1) has to be bellow this threshold in order to pass the check for landing. So if set to 1 it's allowed to land with any stick position.
0
1
+ norm
+ 2
+ modules/land_detector
+
+
+ Manual position flight stick up threshold for taking off
+ When controlling manually in position mode the throttle stick value (0 to 1) has to get above this threshold after arming in order to take off.
+ 0
+ 1
+ norm
2
modules/land_detector
@@ -2468,6 +2486,14 @@ but also ignore less noise
0
modules/land_detector
+
+ Maximum altitude that can be reached prior to subconditions
+ 10
+ 150
+ m
+ 2
+ modules/land_detector
+
@@ -2592,7 +2618,7 @@ but also ignore less noise
Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) Larger than data sheet to account for tilt error.
0.00001
2
- m/s^2/srqt(Hz)
+ m/s^2/sqrt(Hz)
4
modules/local_position_estimator
@@ -2601,7 +2627,7 @@ but also ignore less noise
Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz)
0.00001
2
- m/s^2/srqt(Hz)
+ m/s^2/sqrt(Hz)
4
modules/local_position_estimator
@@ -2754,7 +2780,7 @@ Used to calculate increased terrain random walk nosie due to movement3
modules/local_position_estimator
-
+
Enable publishing of a fake global position (e.g for AUTO missions using Optical Flow)
by initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable
0
@@ -2817,9 +2843,9 @@ by initializing the estimator to the LPE_LAT/LON parameters when global informat
3
modules/local_position_estimator
-
+
Integer bitmask controlling data fusion
- Set bits in the following positions to enable: 0 : Set to true to fuse GPS data if available, also requires GPS for altitude init 1 : Set to true to fuse optical flow data if available 2 : Set to true to fuse vision position 3 : Set to true to fuse vision yaw 4 : Set to true to fuse land detector 5 : Set to true to publish AGL as local position down component 6 : Set to true to enable flow gyro compensation 7 : Set to true to enable baro fusion default (247, no vision yaw)
+ Set bits in the following positions to enable: 0 : Set to true to fuse GPS data if available, also requires GPS for altitude init 1 : Set to true to fuse optical flow data if available 2 : Set to true to fuse vision position 3 : Set to true to fuse vision yaw 4 : Set to true to fuse land detector 5 : Set to true to publish AGL as local position down component 6 : Set to true to enable flow gyro compensation 7 : Set to true to enable baro fusion default (145 - GPS only)
0
255
modules/local_position_estimator
@@ -3052,7 +3078,7 @@ by initializing the estimator to the LPE_LAT/LON parameters when global informat
0.5
modules/navigator
-
+
MC Altitude Acceptance Radius
Acceptance radius for multicopter altitude.
0.05
@@ -3538,24 +3564,6 @@ if required for the gimbal (only in AUX output mode)
0.01
modules/mc_pos_control
-
- ALTCTL throttle curve breakpoint
- Halfwidth of deadband or reduced sensitivity center portion of curve. This is the halfwidth of the center region of the ALTCTL throttle curve. It extends from center-dz to center+dz.
- 0.0
- 0.2
- norm
- 2
- 0.05
- modules/mc_pos_control
-
-
- ALTCTL throttle curve breakpoint height
- Controls the slope of the reduced sensitivity region. This is the height of the ALTCTL throttle curve at center-dz and center+dz.
- 0.0
- 0.2
- 2
- modules/mc_pos_control
-
Maximum thrust in auto thrust control
Limit max allowed thrust. Setting a value of one can put the system into actuator saturation as no spread between the motors is possible any more. A value of 0.8 - 0.9 is recommended.
@@ -3624,7 +3632,7 @@ if required for the gimbal (only in AUX output mode)
1
modules/mc_pos_control
-
+
Maximum vertical descent velocity
Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL, POSCTRL).
0.5
@@ -3632,13 +3640,6 @@ if required for the gimbal (only in AUX output mode)
m/s
modules/mc_pos_control
-
- Transitional support, do not change / use
- 0.5
- 4.0
- m/s
- modules/mc_pos_control
-
Vertical velocity feed forward
Feed forward weight for altitude control in stabilized modes (ALTCTRL, POSCTRL). 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
@@ -3677,7 +3678,7 @@ if required for the gimbal (only in AUX output mode)
modules/mc_pos_control
- Nominal horizontal velocity
+ Nominal horizontal velocity in mission
Normal horizontal velocity in AUTO modes (includes also RTL / hold / etc.) and endpoint for position stabilized mode (POSCTRL).
3.0
20.0
@@ -3686,6 +3687,25 @@ if required for the gimbal (only in AUX output mode)
1
modules/mc_pos_control
+
+ Nominal horizontal velocity for manual controlled mode
+ 3.0
+ 20.0
+ m/s
+ 2
+ 1
+ modules/mc_pos_control
+
+
+ Distance Threshold Horizontal Auto
+ The distance defines at which point the vehicle has to slow down to reach target if no direct passing to the next target is desired
+ 1.0
+ 50.0
+ m
+ 2
+ 1
+ modules/mc_pos_control
+
Maximum horizontal velocity
Maximum horizontal velocity in AUTO mode. If higher speeds are commanded in a mission they will be capped to this velocity.
@@ -3761,15 +3781,8 @@ if required for the gimbal (only in AUX output mode)
1
modules/mc_pos_control
-
- Deadzone of X,Y sticks where position hold is enabled
- 0.0
- 1.0
- 2
- modules/mc_pos_control
-
-
- Deadzone of Z stick where altitude hold is enabled
+
+ Deadzone of sticks where position hold is enabled
0.0
1.0
2
@@ -3808,6 +3821,15 @@ if required for the gimbal (only in AUX output mode)
1
modules/mc_pos_control
+
+ Maximum horizonal braking deceleration in velocity controlled modes
+ 2.0
+ 15.0
+ m/s/s
+ 2
+ 1
+ modules/mc_pos_control
+
Maximum vertical acceleration in velocity controlled modes upward
2.0
@@ -3838,15 +3860,37 @@ if required for the gimbal (only in AUX output mode)
Manual control stick exponential curve sensitivity attenuation with small velocity setpoints
- The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection.
+ The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve
0
1
2
modules/mc_pos_control
-
- Purely cubic input curve
- Purely linear input curve (default)
-
+
+
+ Manual control stick vertical exponential curve
+ The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve
+ 0
+ 1
+ 2
+ modules/mc_pos_control
+
+
+ Altitude for 1. step of slow landing (descend)
+ Below this altitude descending velocity gets limited to a value between "MPC_Z_VEL_MAX" and "MPC_LAND_SPEED" to enable a smooth descent experience Value needs to be higher than "MPC_LAND_ALT2"
+ 0
+ 122
+ m
+ 1
+ modules/mc_pos_control
+
+
+ Altitude for 2. step of slow landing (landing)
+ Below this altitude descending velocity gets limited to "MPC_LAND_SPEED" Value needs to be lower than "MPC_LAND_ALT1"
+ 0
+ 122
+ m
+ 1
+ modules/mc_pos_control
@@ -3940,6 +3984,132 @@ if required for the gimbal (only in AUX output mode)
2
drivers/px4fmu
+
+ Invert direction of main output channel 1
+ Set to 1 to invert the channel, 0 for default direction.
+
+ true
+ drivers/px4io
+
+
+ Invert direction of main output channel 2
+ Set to 1 to invert the channel, 0 for default direction.
+
+ true
+ drivers/px4io
+
+
+ Invert direction of main output channel 3
+ Set to 1 to invert the channel, 0 for default direction.
+
+ true
+ drivers/px4io
+
+
+ Invert direction of main output channel 4
+ Set to 1 to invert the channel, 0 for default direction.
+
+ true
+ drivers/px4io
+
+
+ Invert direction of main output channel 5
+ Set to 1 to invert the channel, 0 for default direction.
+
+ true
+ drivers/px4io
+
+
+ Invert direction of main output channel 6
+ Set to 1 to invert the channel, 0 for default direction.
+
+ true
+ drivers/px4io
+
+
+ Invert direction of main output channel 7
+ Set to 1 to invert the channel, 0 for default direction.
+
+ true
+ drivers/px4io
+
+
+ Invert direction of main output channel 8
+ Set to 1 to invert the channel, 0 for default direction.
+
+ true
+ drivers/px4io
+
+
+ Trim value for main output channel 1
+ Set to normalized offset
+ -0.2
+ 0.2
+ 2
+ drivers/px4io
+
+
+ Trim value for main output channel 2
+ Set to normalized offset
+ -0.2
+ 0.2
+ 2
+ drivers/px4io
+
+
+ Trim value for main output channel 3
+ Set to normalized offset
+ -0.2
+ 0.2
+ 2
+ drivers/px4io
+
+
+ Trim value for main output channel 4
+ Set to normalized offset
+ -0.2
+ 0.2
+ 2
+ drivers/px4io
+
+
+ Trim value for main output channel 5
+ Set to normalized offset
+ -0.2
+ 0.2
+ 2
+ drivers/px4io
+
+
+ Trim value for main output channel 6
+ Set to normalized offset
+ -0.2
+ 0.2
+ 2
+ drivers/px4io
+
+
+ Trim value for main output channel 7
+ Set to normalized offset
+ -0.2
+ 0.2
+ 2
+ drivers/px4io
+
+
+ Trim value for main output channel 8
+ Set to normalized offset
+ -0.2
+ 0.2
+ 2
+ drivers/px4io
+
+
+ S.BUS out
+ Set to 1 to enable S.BUS version 1 output instead of RSSI.
+
+ drivers/px4io
+
Set the PWM output frequency for the main outputs
IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. Set to 400 for industry default or 1000 for high frequency ESCs.
@@ -6221,6 +6391,42 @@ FW_AIRSPD_MIN * RWTO_AIRSPD_SCL
+
+ UTC offset (unit: min)
+ the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets
+ -1000
+ 1000
+ min
+ modules/logger
+
+
+ Logging Mode
+ Determines when to start and stop logging. By default, logging is started when arming the system, and stopped when disarming. This parameter is only for the new logger (SYS_LOGGER=1).
+ 0
+ 3
+ true
+ modules/logger
+
+ from boot until disarm
+ when armed until disarm (default)
+ from boot until shutdown - IMU and Baro data only (used for thermal calibration)
+ from boot until shutdown
+
+
+
+ Maximum number of log directories to keep
+ If there are more log directories than this value, the system will delete the oldest directories during startup. In addition, the system will delete old logs if there is not enough free space left. The minimum amount is 300 MB. If this is set to 0, old directories will only be removed if the free space falls below the minimum.
+ 0
+ 1000
+ true
+ modules/logger
+
+
+ Log UUID
+ If set to 1, add an ID to the log, which uniquely identifies the vehicle
+
+ modules/logger
+
Logging rate
A value of -1 indicates the commandline argument should be obeyed. A value of 0 sets the minimum rate, any other value is interpreted as rate in Hertz. This parameter is only read out before logging starts (which commonly is before arming).
@@ -6261,34 +6467,6 @@ This is used for gathering replay logs for the ekf2 module
Medium priority
-
- UTC offset (unit: min)
- the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets
- -1000
- 1000
- min
- modules/logger
-
-
- Logging Mode
- Determines when to start and stop logging. By default, logging is started when arming the system, and stopped when disarming. This parameter is only for the new logger (SYS_LOGGER=1).
- 0
- 3
- true
- modules/logger
-
- from boot until disarm
- when armed until disarm (default)
- from boot until shutdown - IMU and Baro data only (used for thermal calibration)
- from boot until shutdown
-
-
-
- Log UUID
- If set to 1, add an ID to the log, which uniquely identifies the vehicle
-
- modules/logger
-
@@ -7771,29 +7949,6 @@ This is used for gathering replay logs for the ekf2 module
-
- Target throttle value for pusher/puller motor during the transition to fw mode
- 0.0
- 1.0
- 3
- 0.01
- modules/vtol_att_control
-
-
- Maximum allowed down-pitch the controller is able to demand. This prevents large, negative
-lift values being created when facing strong winds. The vehicle will use the pusher motor
-to accelerate forward if necessary
- 0.0
- 45.0
- modules/vtol_att_control
-
-
- Fixed wing thrust scale for hover forward flight
- Scale applied to fixed wing thrust being used as source for forward acceleration in multirotor mode. This technique can be used to avoid the plane having to pitch down a lot in order to move forward. Setting this value to 0 (default) will disable this strategy.
- 0.0
- 2.0
- modules/vtol_att_control
-
Position of tilt servo in mc mode
0.0
@@ -7961,21 +8116,21 @@ to accelerate forward if necessary
modules/vtol_att_control
-
+
Duration of a front transition
Time in seconds used for a transition
0.00
- 10.00
+ 20.00
s
2
1
modules/vtol_att_control
-
+
Duration of a back transition
Time in seconds used for a back transition
0.00
- 10.00
+ 20.00
s
2
1
@@ -8034,12 +8189,26 @@ to accelerate forward if necessary
modules/vtol_att_control
- QuadChute
+ QuadChute Altitude
Minimum altitude for fixed wing flight, when in fixed wing the altitude drops below this altitude the vehicle will transition back to MC mode and enter failsafe RTL
0.0
200.0
modules/vtol_att_control
+
+ QuadChute Max Pith
+ Maximum pitch angle before QuadChute engages Above this the vehicle will transition back to MC mode and enter failsafe RTL
+ 0
+ 180
+ modules/vtol_att_control
+
+
+ QuadChute Max Roll
+ Maximum roll angle before QuadChute engages Above this the vehicle will transition back to MC mode and enter failsafe RTL
+ 0
+ 180
+ modules/vtol_att_control
+
Airspeed less front transition time (open loop)
The duration of the front transition when there is no airspeed feedback available.
@@ -8048,6 +8217,29 @@ to accelerate forward if necessary
seconds
modules/vtol_att_control
+
+ Target throttle value for pusher/puller motor during the transition to fw mode
+ 0.0
+ 1.0
+ 3
+ 0.01
+ modules/vtol_att_control
+
+
+ Maximum allowed down-pitch the controller is able to demand. This prevents large, negative
+lift values being created when facing strong winds. The vehicle will use the pusher motor
+to accelerate forward if necessary
+ 0.0
+ 45.0
+ modules/vtol_att_control
+
+
+ Fixed wing thrust scale for hover forward flight
+ Scale applied to fixed wing thrust being used as source for forward acceleration in multirotor mode. This technique can be used to avoid the plane having to pitch down a lot in order to move forward. Setting this value to 0 (default) will disable this strategy.
+ 0.0
+ 2.0
+ modules/vtol_att_control
+
@@ -8467,6 +8659,22 @@ Maps the change of airspeed error to the acceleration setpoint
RV_YAW_P
examples/rover_steering_control
+
+ SEG_TH2V_P
+ examples/segway
+
+
+ SEG_TH2V_I
+ examples/segway
+
+
+ SEG_TH2V_I_MAX
+ examples/segway
+
+
+ SEG_Q2V
+ examples/segway
+
EXFW_HDNG_P
examples/fixedwing_control