diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index b801d2b9664668c680034a2ebf03c527caeed94f..857639a73ec85c933b002e93ec4e5633f3fe6998 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -270,18 +270,33 @@ velocity 100000 modules/sensors - - Scaling factor for battery voltage sensor on FMU v2 + + Scaling from ADC counts to volt on the ADC input (battery voltage) + This is not the battery voltage, but the intermediate ADC voltage. A value of -1 signifies that the board defaults are used, which is highly recommended. 8 modules/sensors - - Scaling factor for battery current sensor + + Scaling from ADC counts to volt on the ADC input (battery current) + This is not the battery current, but the intermediate ADC voltage. A value of -1 signifies that the board defaults are used, which is highly recommended. 8 modules/sensors - - Offset for battery current sensor + + Offset in volt as seen by the ADC input of the current sensor + This offset will be subtracted before calculating the battery current based on the voltage. + 8 + modules/sensors + + + Battery voltage divider (V divider) + This is the divider from battery voltage to 3.3V ADC voltage. If using e.g. Mauch power modules the value from the datasheet can be applied straight here. A value of -1 means to use the board default. + 8 + modules/sensors + + + Battery current per volt (A/V) + The voltage seen by the 3.3V ADC multiplied by this factor will determine the battery current. A value of -1 means to use the board default. 8 modules/sensors @@ -477,7 +492,7 @@ velocity true modules/systemlib - + Circuit breaker for GPS failure detection Setting this parameter to 240024 will disable the GPS failure detection. If this check is enabled, then the sensor check will fail if the GPS module is missing. It will also check for excessive signal noise on the GPS receiver and warn the user if detected. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK 0 @@ -618,6 +633,17 @@ velocity 1 modules/commander + + Allow arming without GPS + The default allows to arm the vehicle without GPS signal. + 0 + 1 + modules/commander + + Allow arming without GPS + Don't allow arming without GPS + + Battery failsafe mode Action the system takes on low battery. Defaults to off @@ -630,6 +656,15 @@ velocity Land at current position + + Time-out to wait when offboard connection is lost before triggering offboard lost action. +See COM_OBL_ACT and COM_OBL_RC_ACT to configure action + 0 + 60 + second + 1 + modules/commander + @@ -767,6 +802,14 @@ Assumes measurement is timestamped at trailing edge of integration period1 modules/ekf2 + + Vision Position Estimator delay relative to IMU measurements + 0 + 300 + ms + 1 + modules/ekf2 + 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 @@ -1013,9 +1056,9 @@ Assumes measurement is timestamped at trailing edge of integration period Integer bitmask controlling data fusion and aiding methods - Set bits in the following positions to enable: 0 : Set to true to use GPS data if available 1 : Set to true to use optical flow data if available 2 : Set to true to inhibit IMU bias estimation + Set bits in the following positions to enable: 0 : Set to true to use GPS data if available 1 : Set to true to use optical flow data if available 2 : Set to true to inhibit IMU bias estimation 3 : Set to true to enable vision position fusion 4 : Set to true to enable vision yaw fusion * 0 - 15 + 28 modules/ekf2 @@ -1023,8 +1066,9 @@ Assumes measurement is timestamped at trailing edge of integration periodThe range sensor option should only be used when for operation over a flat surface as the local NED origin will move up and down with ground level. modules/ekf2 - Reserved (GPS) + GPS Barometric pressure + Vision Range sensor @@ -1049,6 +1093,34 @@ Assumes measurement is timestamped at trailing edge of integration period2 modules/ekf2 + + Measurement noise for vision position observations used when the vision system does not supply error estimates + 0.01 + m + 2 + modules/ekf2 + + + Measurement noise for vision angle observations used when the vision system does not supply error estimates + 0.01 + rad + 2 + modules/ekf2 + + + Gate size for vision estimate fusion + 1.0 + SD + 1 + modules/ekf2 + + + Minimum valid range for the vision estimate + 0.01 + m + 2 + modules/ekf2 + Measurement noise for the optical flow sensor when it's reported quality metric is at the maximum 0.05 @@ -1170,8 +1242,34 @@ Assumes measurement is timestamped at trailing edge of integration period3 modules/ekf2 + + X position of VI sensor focal point in body frame + m + 3 + modules/ekf2 + + + Y position of VI sensor focal point in body frame + m + 3 + modules/ekf2 + + + Z position of VI sensor focal point in body frame + m + 3 + modules/ekf2 + + + Airspeed fusion threshold. A value of zero will deactivate airspeed fusion. Any other positive +value will determine the minimum airspeed which will still be fused + 0.0 + m/s + 1 + modules/ekf2 + - Time constant of the velocity output prediction and smoothing filter. Controls how tightly the velocity output tracks the EKF states. Set to a negative number to disable the EKF velocity state tracking. This will cause the output velocity to track the output position time derivative + Time constant of the velocity output prediction and smoothing filter 1.0 s 2 @@ -1616,7 +1714,7 @@ Assumes measurement is timestamped at trailing edge of integration period Throttle limit value before flare - This throttle value will be set as throttle limit at FW_LND_TLALT, before arcraft will flare. + This throttle value will be set as throttle limit at FW_LND_TLALT, before aircraft will flare. 0.0 1.0 norm @@ -2271,7 +2369,7 @@ but also ignore less noise 4 modules/local_position_estimator - + Barometric presssure altitude z standard deviation 0.01 3 @@ -2280,7 +2378,7 @@ but also ignore less noise modules/local_position_estimator - GPS + Enables GPS data, also forces alt init with GPS modules/local_position_estimator @@ -2332,6 +2430,14 @@ but also ignore less noise 3 modules/local_position_estimator + + GPS max epv + 1.0 + 5.0 + m + 3 + modules/local_position_estimator + Vision xy standard deviation 0.01 @@ -2361,7 +2467,7 @@ but also ignore less noise 3 modules/local_position_estimator - + Position propagation noise density 0 1 @@ -2369,7 +2475,7 @@ but also ignore less noise 8 modules/local_position_estimator - + Velocity propagation noise density 0 1 @@ -2385,8 +2491,8 @@ but also ignore less noise 8 modules/local_position_estimator - - Terrain random walk noise density + + Terrain random walk noise density, hilly/outdoor (1e-1), flat/Indoor (1e-3) 0 1 m/s/sqrt(Hz) @@ -2464,6 +2570,15 @@ but also ignore less noise modules/mavlink + + Broadcast heartbeats on local network + This allows a ground control station to automatically find the drone on the local network. + modules/mavlink + + Always broadcast + Never broadcast + + Test parameter This parameter is not actively used by the system. Its purpose is to allow testing the parameter interface on the communication level. @@ -2520,6 +2635,28 @@ but also ignore less noise + + Set offboard loss failsafe mode + The offboard loss failsafe will only be entered after a timeout, set by COM_OF_LOSS_T in seconds. + modules/commander + + Loiter + Land at current position + Return to Land + + + + Set offboard loss failsafe mode when RC is available + The offboard loss failsafe will only be entered after a timeout, set by COM_OF_LOSS_T in seconds. + modules/commander + + Altitude control + Position control + Return to Land + Manual + Land at current position + + Take-off altitude This is the minimum altitude the system will take off to. @@ -2640,7 +2777,7 @@ but also ignore less noise Return to Land - + Set RC loss failsafe mode The RC loss failsafe will only be entered after a timeout, set by COM_RC_LOSS_T in seconds. If RC input checks have been disabled by setting the COM_RC_IN_MODE param it will not be triggered. Setting this parameter to 4 will enable CASA Outback Challenge rules, which are only recommended to participants of that competition. modules/navigator @@ -6487,6 +6624,13 @@ to accelerate forward if necessary 2.0 modules/vtol_att_control + + QuadChute + 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 + Position of tilt servo in mc mode 0.0 @@ -7073,7 +7217,7 @@ Maps the change of airspeed error to the acceleration setpoint - Fift flightmode slot (1640-1800) + Fifth flightmode slot (1640-1800) If the main switch channel is in this range the selected flight mode will be applied. modules/commander