diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 86afb3ff2361f94cc280969d02c53ed273522bb2..f4b4c362c8c176bf9fffe312abf7a1076c8064a5 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -221,7 +221,7 @@ Set to 2 to use heading from motion capture 0 50 true - modules/systemlib + lib/battery Scaling from ADC counts to volt on the ADC input (battery current) @@ -244,7 +244,7 @@ Set to 2 to use heading from motion capture 2 0.01 true - modules/systemlib + lib/battery Emergency threshold @@ -255,7 +255,7 @@ Set to 2 to use heading from motion capture 2 0.01 true - modules/systemlib + lib/battery Low threshold @@ -266,14 +266,14 @@ Set to 2 to use heading from motion capture 2 0.01 true - modules/systemlib + lib/battery Number of cells Defines the number of cells the attached battery consists of. S true - modules/systemlib + lib/battery Unconfigured 2S Battery @@ -300,7 +300,7 @@ Set to 2 to use heading from motion capture 0.2 Ohms true - modules/systemlib + lib/battery Battery monitoring source @@ -320,7 +320,7 @@ Set to 2 to use heading from motion capture 2 0.01 true - modules/systemlib + lib/battery Battery voltage divider (V divider) @@ -335,7 +335,7 @@ Set to 2 to use heading from motion capture 2 0.01 true - modules/systemlib + lib/battery Voltage drop per cell on full throttle @@ -346,7 +346,7 @@ Set to 2 to use heading from motion capture 2 0.01 true - modules/systemlib + lib/battery Offset in volt as seen by the ADC input of the current sensor @@ -895,10 +895,24 @@ See COM_OBL_ACT and COM_OBL_RC_ACT to configure action Loss of position failsafe activation delay This sets number of seconds that the position checks need to be failed before the failsafe will activate. The default value has been optimised for rotary wing applications. For fixed wing applications, a larger value between 5 and 10 should be used. + 1 + 100 sec true modules/commander + + Horizontal position error threshold + This is the horizontal position error (EPV) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. + m + modules/commander + + + Vertical position error threshold + This is the vertical position error (EPV) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. + m + modules/commander + Loss of position probation gain factor This sets the rate that the loss of position probation time grows when position checks are failing. The default value has been optimised for rotary wing applications. For fixed wing applications a value of 0 should be used. @@ -908,6 +922,8 @@ See COM_OBL_ACT and COM_OBL_RC_ACT to configure action Loss of position probation delay at takeoff The probation delay is the number of seconds that the EKF innovation checks need to pass for the position to be declared good after it has been declared bad. The probation delay will be reset to this parameter value when takeoff is detected. After takeoff, if position checks are passing, the probation delay will reduce by one second for every lapsed second of valid position down to a minimum of 1 second. If position checks are failing, the probation delay will increase by COM_POS_FS_GAIN seconds for every lapsed second up to a maximum of 100 seconds. The default value has been optimised for rotary wing applications. For fixed wing applications, a value of 1 should be used. + 1 + 100 sec true modules/commander @@ -956,6 +972,12 @@ See COM_OBL_ACT and COM_OBL_RC_ACT to configure action 0.05 modules/commander + + Horizontal velocity error threshold + This is the horizontal velocity error (EVH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. + m + modules/commander + @@ -1613,6 +1635,13 @@ Baro and Magnetometer data will be averaged before downsampling, other data will 1 modules/ekf2 + + Maximum lapsed time from last fusion of measurements that constrain velocity drift before the EKF will report the horizontal nav solution as invalid + 500000 + 10000000 + uSec + modules/ekf2 + Optical flow measurement delay relative to IMU measurements Assumes measurement is timestamped at trailing edge of integration period @@ -4239,9 +4268,16 @@ if required by the gimbal (only in AUX output mode) - Acro Expo factor -applied to input of all axis: roll, pitch, yaw - 0 Purely linear input curve 1 Purely cubic input curve + Acro mode Expo factor for Roll and Pitch + Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve + 0 + 1 + 2 + modules/mc_att_control + + + Acro mode Expo factor for Yaw + Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve 0 1 2 @@ -4251,7 +4287,7 @@ applied to input of all axis: roll, pitch, yaw Max acro pitch rate default: 2 turns per second 0.0 - 1000.0 + 1800.0 deg/s 1 5 @@ -4261,16 +4297,23 @@ default: 2 turns per second Max acro roll rate default: 2 turns per second 0.0 - 1000.0 + 1800.0 deg/s 1 5 modules/mc_att_control - Acro SuperExpo factor -applied to input of all axis: roll, pitch, yaw - 0 Pure Expo function 0.7 resonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect + Acro mode SuperExpo factor for Roll and Pitch + SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO. 0 Pure Expo function 0.7 resonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect + 0 + 0.95 + 2 + modules/mc_att_control + + + Acro mode SuperExpo factor for Yaw + SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y. 0 Pure Expo function 0.7 resonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect 0 0.95 2 @@ -4280,7 +4323,7 @@ applied to input of all axis: roll, pitch, yaw Max acro yaw rate default 1.5 turns per second 0.0 - 1000.0 + 1800.0 deg/s 1 5 @@ -4732,9 +4775,9 @@ towards MPC_ACC_HOR_MAX/MPC_ACC_UP_MAX with jerk limit 1 modules/mc_pos_control - + Maximum manual thrust - 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. + Limit max allowed thrust for Manual mode. 0.0 1.0 norm @@ -4744,7 +4787,7 @@ towards MPC_ACC_HOR_MAX/MPC_ACC_UP_MAX with jerk limit Minimum manual thrust - Minimum vertical thrust. It's recommended to set it > 0 to avoid free fall with zero thrust. + Minimum vertical thrust. It's recommended to set it > 0 to avoid free fall with zero thrust. With MC_AIRMODE set to 1, this can safely be set to 0. 0.0 1.0 norm @@ -4778,11 +4821,11 @@ towards MPC_ACC_HOR_MAX/MPC_ACC_UP_MAX with jerk limit 0.01 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. + Limit max allowed thrust 0.0 - 0.95 + 1.0 norm 2 0.01 @@ -9471,7 +9514,7 @@ to accelerate forward if necessary Adaptive QuadChute - Maximum negative altitude error, when in fixed wing the altitude drops below this copared to the altitude setpoint the vehicle will transition back to MC mode and enter failsafe RTL + 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 modules/vtol_att_control