diff --git a/src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml b/src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml index b1b6a2b7b199a3475da3077d5459c5113b96ea5b..fcaa9d1421f640f8dd1d3b8f2c9361e8c2d7fe7c 100644 --- a/src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml +++ b/src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml @@ -1,6 +1,148 @@ 3 + + + Speed controller bandwidth + Speed controller bandwidth, in Hz. Higher values result in faster speed and current rise times, but may result in overshoot and higher current consumption. For fixed-wing aircraft, this value should be less than 50 Hz; for multirotors, values up to 100 Hz may provide improvements in responsiveness. + Hertz + 10 + 250 + + + Reverse direction + Motor spin direction as detected during initial enumeration. Use 0 or 1 to reverse direction. + 0 + 1 + + + Speed (RPM) controller gain + Speed (RPM) controller gain. Determines controller + aggressiveness; units are amp-seconds per radian. Systems with + higher rotational inertia (large props) will need gain increased; + systems with low rotational inertia (small props) may need gain + decreased. Higher values result in faster response, but may result + in oscillation and excessive overshoot. Lower values result in a + slower, smoother response. + amp-seconds per radian + 3 + 0.00 + 1.00 + + + Idle speed (e Hz) + Idle speed (e Hz) + Hertz + 3 + 0.0 + 100.0 + + + Spin-up rate (e Hz/s) + Spin-up rate (e Hz/s) + Hz/s + + 5 + 1000 + + + Index of this ESC in throttle command messages. + Index of this ESC in throttle command messages. + Index + + 0 + 15 + + + Extended status ID + Extended status ID + + + 1 + 1023 + + + Extended status interval (µs) + Extended status interval (µs) + µs + + 0 + 1000000 + + + ESC status interval (µs) + ESC status interval (µs) + µs + + 1000000 + + + Motor current limit in amps + Motor current limit in amps. This determines the maximum + current controller setpoint, as well as the maximum allowable + current setpoint slew rate. This value should generally be set to + the continuous current rating listed in the motor’s specification + sheet, or set equal to the motor’s specified continuous power + divided by the motor voltage limit. + Amps + 3 + 1 + 80 + + + Motor Kv in RPM per volt + Motor Kv in RPM per volt. This can be taken from the motor’s + specification sheet; accuracy will help control performance but + some deviation from the specified value is acceptable. + RPM/v + 0 + 0 + 100 + + + READ ONLY: Motor inductance in henries. + READ ONLY: Motor inductance in henries. This is measured on start-up. + henries + 3 + + + Number of motor poles. + Number of motor poles. Used to convert mechanical speeds to + electrical speeds. This number should be taken from the motor’s + specification sheet. + Poles + + 2 + 40 + + + READ ONLY: Motor resistance in ohms + READ ONLY: Motor resistance in ohms. This is measured on start-up. When + tuning a new motor, check that this value is approximately equal + to the value shown in the motor’s specification sheet. + Ohms + 3 + + + Acceleration limit (V) + Acceleration limit (V) + Volts + 3 + 0.01 + 1.00 + + + Motor voltage limit in volts + Motor voltage limit in volts. The current controller’s + commanded voltage will never exceed this value. Note that this may + safely be above the nominal voltage of the motor; to determine the + actual motor voltage limit, divide the motor’s rated power by the + motor current limit. + Volts + 3 + 0 + + Body angular rate process noise @@ -23,12 +165,6 @@ Mag measurement noise - - EKF attitude estimator enabled - If enabled, it uses the older EKF filter. However users can enable the new quaternion based complimentary filter by setting EKF_ATT_ENABLED = 0. - 0 - 1 - Moment of inertia matrix diagonal entry (1, 1) kg*m^2 @@ -53,27 +189,43 @@ Complimentary filter accelerometer weight 0 1 + 2 Complimentary filter magnetometer weight 0 1 + 2 + + + Complimentary filter external heading weight + 0 + 1 Complimentary filter gyroscope bias weight 0 1 + 2 Magnetic declination, in degrees This parameter is not used in normal operation, as the declination is looked up based on the GPS coordinates of the vehicle. degrees + 2 Enable automatic GPS based declination compensation 0 1 + + External heading usage mode (from Motion capture/Vision) +Set to 1 to use heading estimate from vision. +Set to 2 to use heading from motion capture + 0 + 2 + Enable acceleration compensation based on GPS velocity @@ -85,11 +237,13 @@ velocity 0 2 rad/s + 3 Threshold (of RMS) to warn about high vibration levels - 0.001 - 100 + 0.01 + 10 + 2 @@ -126,8 +280,7 @@ velocity 1 100000 - - CONFIG_ARCH_BOARD_PX4FMU_V2 + Scaling factor for battery voltage sensor on FMU v2 @@ -209,6 +362,12 @@ velocity 0 240024 + + Circuit breaker for disabling buzzer + Setting this parameter to 782097 will disable the buzzer audio notification. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK + 0 + 782097 + @@ -284,6 +443,11 @@ velocity 0 2 + + Time-out for auto disarm after landing + A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be automatically disarmed in case a landing situation has been detected during this period. A value of zero means that automatic disarming is disabled. + 0 + @@ -610,11 +774,11 @@ velocity - - Geofence mode - 0 = disabled, 1 = geofence file only, 2 = max horizontal (GF_MAX_HOR_DIST) and vertical (GF_MAX_VER_DIST) distances, 3 = both + + Geofence violation action + 0 = none, 1 = warning (default), 2 = loiter, 3 = return to launch, 4 = fight termination 0 - 3 + 4 Geofence altitude mode @@ -636,11 +800,11 @@ velocity Max horizontal distance in meters - Set to > 0 to activate RTL if horizontal distance to home exceeds this value. + Set to > 0 to activate a geofence action if horizontal distance to home exceeds this value. Max vertical distance in meters - Set to > 0 to activate RTL if vertical distance to home exceeds this value. + Set to > 0 to activate a geofence action if vertical distance to home exceeds this value. @@ -705,7 +869,7 @@ velocity 0.0 1.0 - + Climbout Altitude difference If the altitude error exceeds this parameter, the system will climb out with maximum throttle and minimum airspeed until it is closer than this distance to the desired altitude. Mostly used for takeoff waypoints / modes. Set to zero to disable climbout mode (not recommended). 0.0 @@ -820,6 +984,131 @@ velocity 1 + + + Enable local position estimator + + + Enable accelerometer integration for prediction + + + Optical flow xy standard deviation + 0.01 + 1 + m + + + Sonar z standard deviation + 0.01 + 1 + m + + + Lidar z standard deviation + 0.01 + 1 + m + + + Accelerometer xy standard deviation + Data sheet sqrt(Noise power) = 150ug/sqrt(Hz) std dev = (150*9.8*1e-6)*sqrt(1000 Hz) m/s^2 Since accels sampled at 1000 Hz. should be 0.0464 + 0.00001 + 2 + m/s^2 + + + Accelerometer z standard deviation + (see Accel x comments) + 0.00001 + 2 + m/s^2 + + + Barometric presssure altitude z standard deviation + 0.01 + 3 + m + + + GPS xy standard deviation + 0.01 + 5 + m + + + GPS z standard deviation + 0.01 + 20 + m + + + GPS xy velocity standard deviation + 0.01 + 2 + m/s + + + GPS z velocity standard deviation + 0.01 + 2 + m/s + + + GPS max eph + 1.0 + 5.0 + m + + + Vision xy standard deviation + 0.01 + 1 + m + + + Vision z standard deviation + 0.01 + 2 + m + + + Circuit breaker to disable vision input + Set to the appropriate key (328754) to disable vision input. + 0 + 1 + + + Vicon position standard deviation + 0.01 + 1 + m + + + Position propagation process noise power (variance*sampling rate) + 0 + 1 + (m/s^2)-s + + + Velocity propagation process noise power (variance*sampling rate) + 0 + 5 + (m/s)-s + + + Accel bias propagation process noise power (variance*sampling rate) + 0 + 1 + (m/s)-s + + + Fault detection threshold, for chi-squared dist + TODO add separate params for 1 dof, 3 dof, and 6 dof beta or false alarm rate in false alarms/hr + 3 + 1000 + + + MAVLink system ID @@ -1023,23 +1312,30 @@ velocity 360.0 deg/s - + Max acro roll rate 0.0 360.0 deg/s - + Max acro pitch rate 0.0 360.0 deg/s - + Max acro yaw rate 0.0 deg/s + + Threshold for Rattitude mode + Manual input needed in order to override attitude control rate setpoints and instead pass manual stick inputs as rate setpoints + 0.0 + 1.0 + + Roll P gain Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad. @@ -1270,6 +1566,33 @@ velocity 0.0 degree / s + + Deadzone of X,Y sticks where position hold is enabled + 0.0 + 1.0 + % + + + Deadzone of Z stick where altitude hold is enabled + 0.0 + 1.0 + % + + + Maximum horizontal velocity for which position hold is enabled (use 0 to disable check) + 0.0 + m/s + + + Maximum vertical velocity for which position hold is enabled (use 0 to disable check) + 0.0 + m/s + + + Low pass filter cut freq. for numerical velocity derivative + 0.0 + Hz + Minimum thrust Minimum vertical thrust. It's recommended to set it > 0 to avoid free fall with zero thrust. @@ -1697,9 +2020,9 @@ velocity 0.0 10.0 - - Z axis weight for sonar - Weight (cutoff frequency) for sonar measurements. + + Z axis weight for lidar + Weight (cutoff frequency) for lidar measurements. 0.0 10.0 @@ -1733,11 +2056,11 @@ velocity 0.0 10.0 - + XY axis weight for optical flow Weight (cutoff frequency) for optical flow (velocity) measurements. 0.0 - 10.0 + 30.0 XY axis weight for resetting velocity @@ -1764,19 +2087,19 @@ velocity 1.0 rad/px - + Minimal acceptable optical flow quality 0 - lowest quality, 1 - best quality. 0.0 1.0 - - Weight for sonar filter - Sonar filter detects spikes on sonar measurements and used to detect new surface level. + + Weight for lidar filter + Lidar filter detects spikes on lidar measurements and used to detect new surface level. 0.0 1.0 - + Sonar maximal error for new surface If sonar measurement error is larger than this value it skiped (spike) or accepted as new surface level (if offset is stable). 0.0 @@ -1810,6 +2133,20 @@ velocity 1.0 s + + Flow module offset (center of rotation) in X direction + Yaw X flow compensation + -1.0 + 1.0 + m + + + Flow module offset (center of rotation) in Y direction + Yaw Y flow compensation + -1.0 + 1.0 + m + Disable vision input Set to the appropriate key (328754) to disable vision input. @@ -2565,6 +2902,11 @@ velocity 0 18 + + Rattitude switch channel mapping + 0 + 18 + Posctl switch channel mapping 0 @@ -2602,6 +2944,12 @@ velocity -1 1 + + Threshold for selecting rattitude mode + 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 + Threshold for selecting posctl mode 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 @@ -2661,7 +3009,7 @@ velocity 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). -1 - 1 + 100 Enable extended logging mode @@ -2941,6 +3289,18 @@ velocity Accelerometer Z-axis scaling factor + + Primary accel ID + + + Primary gyro ID + + + Primary mag ID + + + Primary baro ID + Differential pressure sensor offset The offset (zero-reading) in Pascal @@ -3007,7 +3367,7 @@ velocity Auto-start script index - Defines the auto-start script used to bootstrap the system. + CHANGING THIS VALUE REQUIRES A RESTART. Defines the auto-start script used to bootstrap the system. Automatically configure default values @@ -3029,7 +3389,7 @@ velocity Companion computer interface - 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. + 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 @@ -3042,9 +3402,9 @@ velocity Enable UAVCAN - Allowed values: 0 - UAVCAN disabled. 1 - Enabled support for UAVCAN actuators and sensors. 2 - Enabled support for dynamic node ID allocation and firmware update. + Allowed values: 0 - UAVCAN disabled. 1 - Enabled support for UAVCAN actuators and sensors. 2 - Enabled support for dynamic node ID allocation and firmware update. 3 - Sets the motor control outputs to UAVCAN and enables support for dynamic node ID allocation and firmware update. 0 - 2 + 3 UAVCAN Node ID @@ -3411,18 +3771,6 @@ Maps the change of airspeed error to the acceleration setpoint EXFW_PITCH_P - - FPE_LO_THRUST - - - FPE_SONAR_LP_U - - - FPE_SONAR_LP_L - - - FPE_DEBUG - RV_YAW_P diff --git a/src/AutoPilotPlugins/PX4/PowerComponent.qml b/src/AutoPilotPlugins/PX4/PowerComponent.qml index f6bd6ce76ecd88560da8eb70f666a64f5f3eb2df..fed17d5a654a665e9664241c712f434d7eb55d27 100644 --- a/src/AutoPilotPlugins/PX4/PowerComponent.qml +++ b/src/AutoPilotPlugins/PX4/PowerComponent.qml @@ -281,7 +281,7 @@ QGCView { fact: controller.getParameterFact(-1, "UAVCAN_ENABLE") checkedValue: 3 uncheckedValue: 0 - text: "Enable UAVCAN as the default MAIN output bus (requires restart)" + text: "Enable UAVCAN as the default MAIN output bus (requires autopilot restart)" } } }