diff --git a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml index 67345da1a905c41374539111e2ab866b6b29c8c8..6b9ebade819a74b93c9e0bba644902e68655c3ae 100644 --- a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml +++ b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml @@ -102,6 +102,12 @@ feed-through of RC AUX3 channel + + + Simon Wilks <simon@uaventure.com> + Octo Coax Wide + + Anton Babushkin <anton@px4.io> @@ -349,9 +355,13 @@ - + Roman Bapst <roman@px4.io> VTOL Duo Tailsitter + motor left + motor right + elevon left + elevon right diff --git a/src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml b/src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml index 864f58a0bab0ed26d20d4fd333fd752eff5d88bc..cbeae445e2ebbebe1bdf194cbc5256e358c8e27c 100644 --- a/src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml +++ b/src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml @@ -262,9 +262,20 @@ velocity Number of cells Defines the number of cells the attached battery consists of. - 1 + 2 10 S + + 10S Battery + 3S Battery + 2S Battery + 5S Battery + 4S Battery + 7S Battery + 6S Battery + 9S Battery + 8S Battery + Battery capacity @@ -379,6 +390,10 @@ velocity Set to 1 to enable actions triggered when the datalink is lost. 0 1 + + ON: Datalink failse + OFF: No Datalink failsafe + Datalink loss time threshold @@ -452,6 +467,11 @@ velocity The default value of 0 requires a valid RC transmitter setup. Setting this to 1 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. 0 2 + + Disable RC Input Checks + RC Transmitter + Virtual RC by Joystick + Time-out for auto disarm after landing @@ -1076,7 +1096,7 @@ velocity L1 period - This is the L1 distance and defines the tracking point ahead of the aircraft its following. A value of 25 meters works for most aircraft. Shorten slowly during tuning until response is sharp without oscillation. + This is the L1 distance and defines the tracking point ahead of the aircraft its following. A value of 18-25 meters works for most aircraft. Shorten slowly during tuning until response is sharp without oscillation. 12.0 50.0 @@ -1170,8 +1190,8 @@ velocity 0: disabled, 1: enabled - Takeoff and landing airspeed scale factor - Multiplying this factor with the minimum airspeed of the plane gives the target airspeed for takeoff and landing approach. + Landing airspeed scale factor + Multiplying this factor with the minimum airspeed of the plane gives the target airspeed the landing approach. 1.0 1.5 @@ -1492,22 +1512,26 @@ velocity Reduce if the system is too twitchy, increase if the response is too slow and sluggish. 0.15 0.25 + 2 Pitch time constant Reduce if the system is too twitchy, increase if the response is too slow and sluggish. 0.15 0.25 + 2 Roll P gain Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad. 0.0 + 2 Roll rate P gain Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s. 0.0 + 3 Roll rate I gain @@ -1518,69 +1542,82 @@ velocity Roll rate D gain Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. 0.0 + 4 Roll rate feedforward Improves tracking performance. 0.0 + 4 Pitch P gain Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad. 0.0 1/s + 2 Pitch rate P gain Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s. 0.0 + 3 Pitch rate I gain Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset. 0.0 + 2 Pitch rate D gain Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. 0.0 + 4 Pitch rate feedforward Improves tracking performance. 0.0 + 4 Yaw P gain Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad. 0.0 1/s + 2 Yaw rate P gain Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s. 0.0 + 2 Yaw rate I gain Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset. 0.0 + 2 Yaw rate D gain Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. 0.0 + 2 Yaw rate feedforward Improves tracking performance. 0.0 + 4 Yaw feed forward Feed forward weight for manual yaw control. 0 will give slow responce and no overshot, 1 - fast responce and big overshot. 0.0 1.0 + 2 Max roll rate @@ -1588,6 +1625,7 @@ velocity 0.0 360.0 deg/s + 1 Max pitch rate @@ -1595,6 +1633,7 @@ velocity 0.0 360.0 deg/s + 1 Max yaw rate @@ -1602,6 +1641,7 @@ velocity 0.0 360.0 deg/s + 1 Max yaw rate in auto mode @@ -1609,23 +1649,27 @@ velocity 0.0 120.0 deg/s + 1 Max acro roll rate 0.0 360.0 deg/s + 1 Max acro pitch rate 0.0 360.0 deg/s + 1 Max acro yaw rate 0.0 deg/s + 1 Threshold for Rattitude mode @@ -1633,6 +1677,7 @@ velocity 0.0 1.0 + 2 Roll P gain @@ -1750,41 +1795,49 @@ velocity It's recommended to set it > 0 to avoid free fall with zero thrust. 0.05 1.0 + 3 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. 0.0 0.95 + 2 Minimum manual thrust Minimum vertical thrust. It's recommended to set it > 0 to avoid free fall with zero thrust. 0.0 1.0 + 3 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. 0.0 1.0 + 2 Proportional gain for vertical position error 0.0 + 2 Proportional gain for vertical velocity error 0.0 + 2 Integral gain for vertical velocity error Non zero value allows hovering thrust estimation on stabilized or autonomous takeoff. 0.0 + 3 Differential gain for vertical velocity error 0.0 + 3 Maximum vertical velocity @@ -1792,41 +1845,49 @@ velocity 0.0 8.0 m/s + 1 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. 0.0 1.0 + 2 Proportional gain for horizontal position error 0.0 + 2 Proportional gain for horizontal velocity error 0.0 + 2 Integral gain for horizontal velocity error Non-zero value allows to resist wind. 0.0 + 3 Differential gain for horizontal velocity error. Small values help reduce fast oscillations. If value is too big oscillations will appear again 0.0 + 3 Maximum horizontal velocity Maximum horizontal velocity in AUTO mode and endpoint for position stabilized mode (POSCTRL). 0.0 m/s + 2 Horizontal velocity feed forward Feed forward weight for position control in position control mode (POSCTRL). 0 will give slow responce and no overshot, 1 - fast responce and big overshot. 0.0 1.0 + 2 Maximum tilt angle in air @@ -1834,6 +1895,7 @@ velocity 0.0 90.0 degree + 1 Maximum tilt during landing @@ -1841,66 +1903,78 @@ velocity 0.0 90.0 degree + 1 Landing descend rate 0.0 m/s + 1 Takeoff climb rate 0.0 m/s + 2 Max manual roll 0.0 90.0 degree + 1 Max manual pitch 0.0 90.0 degree + 1 Max manual yaw rate 0.0 degree / s + 1 Deadzone of X,Y sticks where position hold is enabled 0.0 1.0 % + 2 Deadzone of Z stick where altitude hold is enabled 0.0 1.0 % + 2 Maximum horizontal velocity for which position hold is enabled (use 0 to disable check) 0.0 m/s + 2 Maximum vertical velocity for which position hold is enabled (use 0 to disable check) 0.0 m/s + 2 Low pass filter cut freq. for numerical velocity derivative 0.0 Hz + 2 Maximum horizonal acceleration in velocity controlled modes 2.0 10.0 m/s/s + 2 Minimum thrust @@ -2385,7 +2459,7 @@ velocity 0.0 10.0 - + XY axis weight for optical flow Weight (cutoff frequency) for optical flow (velocity) measurements. 0.0 @@ -2409,12 +2483,11 @@ velocity 0.0 0.1 - + Optical flow scale factor - Factor to convert raw optical flow (in pixels) to radians [rad/px]. + Factor to scale optical flow 0.0 - 1.0 - rad/px + 10.0 Minimal acceptable optical flow quality @@ -2422,13 +2495,7 @@ velocity 0.0 1.0 - - 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 @@ -2482,6 +2549,19 @@ velocity 0 1 + + Enable LIDAR for altitude estimation + Enable LIDAR for altitude estimation + 0 + 1 + + + LIDAR calibration offset + LIDAR calibration offset. Value will be added to the measured distance + -20 + 20 + m + Disable vision input Set to the appropriate key (328754) to disable vision input. @@ -3961,6 +4041,12 @@ FW_AIRSPD_MIN * RWTO_AIRSPD_SCL 0 1 + + Front transition timeout + Time in seconds after which transition will be cancelled. Disabled if set to 0. + 0.0 + 30.0 +