From 276b19e48552360159c33e93a59d824b3876a33b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 28 May 2016 14:37:21 +0200 Subject: [PATCH] Update PX4 param meta --- .../PX4/AirframeFactMetaData.xml | 2 +- .../PX4/PX4ParameterFactMetaData.xml | 800 ++++++++++++++---- 2 files changed, 622 insertions(+), 180 deletions(-) diff --git a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml index 1a10d7268..ebc825caa 100644 --- a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml +++ b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml @@ -4,7 +4,7 @@ 1 1 - + Emmanuel Roussel Coaxial Helicopter Left swashplate servomotor, pitch axis diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 0d565d3d5..b801d2b96 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -184,8 +184,7 @@ Moment of inertia enabled in estimator If set to != 0 the moment of inertia will be used in the estimator - 0 - 1 + modules/attitude_estimator_ekf @@ -225,7 +224,7 @@ modules/attitude_estimator_q - Enable automatic GPS based declination compensation + Automatic GPS based declination compensation modules/attitude_estimator_q @@ -243,7 +242,7 @@ Set to 2 to use heading from motion capture - Enable acceleration compensation based on GPS + Acceleration compensation based on GPS velocity modules/attitude_estimator_q @@ -398,13 +397,12 @@ velocity Camera trigger mode - 0 disables the trigger, 1 sets it to enabled on command, 2 time based and always on, 3 distance based and always on, 4 distance based and started / stopped via mission or command. 0 4 true drivers/camera_trigger - On invididual commands + On individual commands Disable Distance based, always on Time based, always on @@ -530,8 +528,9 @@ velocity Engine failure triggers only above this throttle value 0.0 1.0 - 1 - 0.05 + norm + 2 + 0.01 modules/commander @@ -539,7 +538,7 @@ velocity Engine failure triggers only below this current value 0.0 50.0 - A + A/% 2 1 modules/commander @@ -602,6 +601,13 @@ velocity Virtual RC by Joystick + + RC input arm/disarm command duration + The default value of 1000 requires the stick to be held in the arm or disarm position for 1 second. + 100 + 1500 + modules/commander + 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. @@ -630,7 +636,10 @@ velocity Comms hold wait time The amount of time in seconds the system should wait at the comms hold waypoint 0.0 + 3600.0 s + 0 + 1 modules/navigator @@ -655,13 +664,18 @@ velocity -50 30000 m + 1 + 0.5 modules/navigator - Airfield hole wait time + Airfield home wait time The amount of time in seconds the system should wait at the airfield home waypoint 0.0 + 3600.0 s + 0 + 1 modules/navigator @@ -698,6 +712,8 @@ velocity Altitude of airfield home waypoint -50 m + 1 + 0.5 modules/navigator @@ -811,7 +827,7 @@ Assumes measurement is timestamped at trailing edge of integration period2 modules/ekf2 - + Rate gyro noise for covariance prediction 0.0001 0.1 @@ -819,7 +835,7 @@ Assumes measurement is timestamped at trailing edge of integration period4 modules/ekf2 - + Accelerometer noise for covariance prediction 0.01 1.0 @@ -827,30 +843,23 @@ Assumes measurement is timestamped at trailing edge of integration period2 modules/ekf2 - - Process noise for delta angle bias prediction - 0.0 - 0.0001 - rad/s - 8 - modules/ekf2 - - - Process noise for delta velocity z bias prediction + + Process noise for IMU rate gyro bias prediction 0.0 0.01 - m/s/s - 7 + rad/s**2 + 6 modules/ekf2 - - Process noise for delta angle scale factor prediction + + Process noise for IMU accelerometer bias prediction 0.0 0.01 + m/s**3 6 modules/ekf2 - + Process noise for body magnetic field prediction 0.0 0.1 @@ -858,7 +867,7 @@ Assumes measurement is timestamped at trailing edge of integration period6 modules/ekf2 - + Process noise for earth magnetic field prediction 0.0 0.1 @@ -898,7 +907,7 @@ Assumes measurement is timestamped at trailing edge of integration period1 modules/ekf2 - + Measurement noise for barometric altitude 0.01 15.0 @@ -964,9 +973,8 @@ Assumes measurement is timestamped at trailing edge of integration period Magnetic heading Automatic - 2-D projection + None 3-axis fusion - None @@ -990,6 +998,13 @@ Assumes measurement is timestamped at trailing edge of integration period1 modules/ekf2 + + Gate size for TAS fusion + 1.0 + SD + 1 + modules/ekf2 + Replay mode A value of 1 indicates that the ekf2 module will publish replay messages for logging. @@ -997,10 +1012,10 @@ Assumes measurement is timestamped at trailing edge of integration periodmodules/ekf2 - Integer bitmask controlling which external aiding sources will be used - 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 + 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 0 - 3 + 15 modules/ekf2 @@ -1155,6 +1170,45 @@ Assumes measurement is timestamped at trailing edge of integration period3 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 + 1.0 + s + 2 + modules/ekf2 + + + Time constant of the position output prediction and smoothing filter. Controls how tightly the output track the EKF states + 0.1 + 1.0 + s + 2 + modules/ekf2 + + + 1-sigma IMU gyro switch-on bias + 0.0 + 0.2 + rad/sec + 2 + modules/ekf2 + + + 1-sigma IMU accelerometer switch-on bias + 0.0 + 0.5 + m/s/s + 2 + modules/ekf2 + + + 1-sigma tilt angle uncertainty after gravity vector alignment + 0.0 + 0.5 + rad + 3 + modules/ekf2 + @@ -1163,6 +1217,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.4 1.0 s + 2 + 0.05 modules/fw_att_control @@ -1171,6 +1227,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.2 1.0 s + 2 + 0.05 modules/fw_att_control @@ -1179,6 +1237,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.005 1.0 %/rad/s + 3 + 0.005 modules/fw_att_control @@ -1187,6 +1247,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.005 0.5 %/rad + 3 + 0.005 modules/fw_att_control @@ -1195,6 +1257,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.0 90.0 deg/s + 1 + 0.5 modules/fw_att_control @@ -1203,6 +1267,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.0 90.0 deg/s + 1 + 0.5 modules/fw_att_control @@ -1210,7 +1276,8 @@ Assumes measurement is timestamped at trailing edge of integration periodThe portion of the integrator part in the control surface deflection is limited to this value 0.0 1.0 - % + 2 + 0.05 modules/fw_att_control @@ -1219,6 +1286,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.005 1.0 %/rad/s + 3 + 0.005 modules/fw_att_control @@ -1227,6 +1296,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.005 0.2 %/rad + 3 + 0.005 modules/fw_att_control @@ -1234,7 +1305,8 @@ Assumes measurement is timestamped at trailing edge of integration periodThe portion of the integrator part in the control surface deflection is limited to this value. 0.0 1.0 - % + 2 + 0.05 modules/fw_att_control @@ -1243,6 +1315,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.0 90.0 deg/s + 1 + 0.5 modules/fw_att_control @@ -1251,6 +1325,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.005 1.0 %/rad/s + 3 + 0.005 modules/fw_att_control @@ -1259,6 +1335,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.0 50.0 %/rad + 1 + 0.5 modules/fw_att_control @@ -1266,7 +1344,8 @@ Assumes measurement is timestamped at trailing edge of integration periodThe portion of the integrator part in the control surface deflection is limited to this value 0.0 1.0 - % + 2 + 0.05 modules/fw_att_control @@ -1275,6 +1354,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.0 90.0 deg/s + 1 + 0.5 modules/fw_att_control @@ -1283,14 +1364,18 @@ Assumes measurement is timestamped at trailing edge of integration period0.005 1.0 %/rad/s + 3 + 0.005 modules/fw_att_control Wheel steering rate integrator gain This gain defines how much control response will result out of a steady state error. It trims any constant error. - 0.0 - 50.0 + 0.005 + 0.5 %/rad + 3 + 0.005 modules/fw_att_control @@ -1298,7 +1383,8 @@ Assumes measurement is timestamped at trailing edge of integration periodThe portion of the integrator part in the control surface deflection is limited to this value 0.0 1.0 - % + 2 + 0.05 modules/fw_att_control @@ -1307,6 +1393,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.0 90.0 deg/s + 1 + 0.5 modules/fw_att_control @@ -1315,6 +1403,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.0 10.0 %/rad/s + 2 + 0.05 modules/fw_att_control @@ -1323,6 +1413,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.0 10.0 %/rad/s + 2 + 0.05 modules/fw_att_control @@ -1331,6 +1423,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.0 10.0 %/rad/s + 2 + 0.05 modules/fw_att_control @@ -1339,12 +1433,18 @@ Assumes measurement is timestamped at trailing edge of integration period0.0 10.0 %/rad/s + 2 + 0.05 modules/fw_att_control Minimal speed for yaw coordination For airspeeds above this value, the yaw rate is calculated for a coordinated turn. Set to a very high value to disable. + 0.0 + 1000.0 m/s + 1 + 0.5 modules/fw_att_control @@ -1358,36 +1458,14 @@ Assumes measurement is timestamped at trailing edge of integration periodopen-loop - - Minimum Airspeed - If the airspeed falls below this value, the TECS controller will try to increase airspeed more aggressively. - 0.0 - 40 - m/s - modules/fw_att_control - - - Trim Airspeed - The TECS controller tries to fly at this airspeed. - 0.0 - 40 - m/s - modules/fw_att_control - - - Maximum Airspeed - If the airspeed is above this value, the TECS controller will try to decrease airspeed more aggressively. - 0.0 - 40 - m/s - modules/fw_att_control - Roll Setpoint Offset An airframe specific offset of the roll setpoint in degrees, the value is added to the roll setpoint and should correspond to the typical cruise speed of the airframe. -90.0 90.0 deg + 1 + 0.5 modules/fw_att_control @@ -1396,6 +1474,8 @@ Assumes measurement is timestamped at trailing edge of integration period-90.0 90.0 deg + 1 + 0.5 modules/fw_att_control @@ -1404,6 +1484,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.0 90.0 deg + 1 + 0.5 modules/fw_att_control @@ -1412,18 +1494,26 @@ Assumes measurement is timestamped at trailing edge of integration period0.0 90.0 deg + 1 + 0.5 modules/fw_att_control Scale factor for flaps 0.0 1.0 + norm + 2 + 0.01 modules/fw_att_control Scale factor for flaperons 0.0 1.0 + norm + 2 + 0.01 modules/fw_att_control @@ -1434,6 +1524,8 @@ Assumes measurement is timestamped at trailing edge of integration period12.0 50.0 m + 1 + 0.5 modules/fw_pos_control_l1 @@ -1441,6 +1533,8 @@ Assumes measurement is timestamped at trailing edge of integration periodDamping factor for L1 control. 0.6 0.9 + 2 + 0.05 modules/fw_pos_control_l1 @@ -1449,6 +1543,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.0 1.0 norm + 2 + 0.01 modules/fw_pos_control_l1 @@ -1464,6 +1560,8 @@ Assumes measurement is timestamped at trailing edge of integration period-60.0 0.0 deg + 1 + 0.5 modules/fw_pos_control_l1 @@ -1472,6 +1570,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.0 60.0 deg + 1 + 0.5 modules/fw_pos_control_l1 @@ -1480,6 +1580,8 @@ Assumes measurement is timestamped at trailing edge of integration period35.0 65.0 deg + 1 + 0.5 modules/fw_pos_control_l1 @@ -1488,6 +1590,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.0 1.0 norm + 2 + 0.01 modules/fw_pos_control_l1 @@ -1496,6 +1600,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.0 1.0 norm + 2 + 0.01 modules/fw_pos_control_l1 @@ -1504,6 +1610,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.0 0.4 norm + 2 + 0.01 modules/fw_pos_control_l1 @@ -1512,6 +1620,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.0 1.0 norm + 2 + 0.01 modules/fw_pos_control_l1 @@ -1520,6 +1630,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.0 150.0 m + 1 + 0.5 modules/fw_pos_control_l1 @@ -1527,11 +1639,17 @@ Assumes measurement is timestamped at trailing edge of integration period1.0 15.0 deg + 1 + 0.5 modules/fw_pos_control_l1 FW_LND_HVIRT + 1.0 + 15.0 m + 1 + 0.5 modules/fw_pos_control_l1 @@ -1539,6 +1657,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.0 25.0 m + 1 + 0.5 modules/fw_pos_control_l1 @@ -1547,6 +1667,8 @@ Assumes measurement is timestamped at trailing edge of integration period-1.0 30.0 m + 1 + 0.5 modules/fw_pos_control_l1 @@ -1554,11 +1676,12 @@ Assumes measurement is timestamped at trailing edge of integration period0 30.0 m + 1 + 0.5 modules/fw_pos_control_l1 - Enable or disable usage of terrain estimate during landing - 0: disabled, 1: enabled + Use terrain estimate during landing modules/fw_pos_control_l1 @@ -1568,6 +1691,8 @@ Assumes measurement is timestamped at trailing edge of integration period0 15.0 deg + 1 + 0.5 modules/fw_pos_control_l1 @@ -1576,80 +1701,147 @@ Assumes measurement is timestamped at trailing edge of integration period0 45.0 deg + 1 + 0.5 modules/fw_pos_control_l1 - Landing airspeed scale factor - Multiplying this factor with the minimum airspeed of the plane gives the target airspeed the landing approach. + Min. airspeed scaling factor for landing + Multiplying this factor with the minimum airspeed of the plane gives the target airspeed the landing approach. FW_AIRSPD_MIN * FW_LND_AIRSPD_SC 1.0 1.5 + norm + 2 + 0.01 modules/fw_pos_control_l1 + + Minimum Airspeed + If the airspeed falls below this value, the TECS controller will try to increase airspeed more aggressively. + 0.0 + 40 + m/s + 1 + 0.5 + modules/fw_pos_control_l1 + + + Maximum Airspeed + If the airspeed is above this value, the TECS controller will try to decrease airspeed more aggressively. + 0.0 + 40 + m/s + 1 + 0.5 + modules/fw_pos_control_l1 + Maximum climb rate This is the best climb rate that the aircraft can achieve with the throttle set to THR_MAX and the airspeed set to the default value. For electric aircraft make sure this number can be achieved towards the end of flight when the battery voltage has reduced. The setting of this parameter can be checked by commanding a positive altitude change of 100m in loiter, RTL or guided mode. If the throttle required to climb is close to THR_MAX and the aircraft is maintaining airspeed, then this parameter is set correctly. If the airspeed starts to reduce, then the parameter is set to high, and if the throttle demand required to climb and maintain speed is noticeably less than FW_THR_MAX, then either FW_T_CLMB_MAX should be increased or FW_THR_MAX reduced. - 2.0 - 10.0 + 1.0 + 15.0 m/s + 1 + 0.5 modules/fw_pos_control_l1 Minimum descent rate This is the sink rate of the aircraft with the throttle set to THR_MIN and flown at the same airspeed as used to measure FW_T_CLMB_MAX. + 1.0 + 5.0 m/s + 1 + 0.5 modules/fw_pos_control_l1 Maximum descent rate This sets the maximum descent rate that the controller will use. If this value is too large, the aircraft can over-speed on descent. This should be set to a value that can be achieved without exceeding the lower pitch angle limit and without over-speeding the aircraft. + 2.0 + 15.0 m/s + 1 + 0.5 modules/fw_pos_control_l1 TECS time constant This is the time constant of the TECS control algorithm (in seconds). Smaller values make it faster to respond, larger values make it slower to respond. + 1.0 + 10.0 s + 1 + 0.5 modules/fw_pos_control_l1 TECS Throttle time constant This is the time constant of the TECS throttle control algorithm (in seconds). Smaller values make it faster to respond, larger values make it slower to respond. + 1.0 + 10.0 s + 1 + 0.5 modules/fw_pos_control_l1 Throttle damping factor This is the damping gain for the throttle demand loop. Increase to add damping to correct for oscillations in speed and height. + 0.0 + 2.0 + 1 + 0.1 modules/fw_pos_control_l1 Integrator gain This is the integrator gain on the control loop. Increasing this gain increases the speed at which speed and height offsets are trimmed out, but reduces damping and increases overshoot. + 0.0 + 2.0 + 2 + 0.05 modules/fw_pos_control_l1 Maximum vertical acceleration This is the maximum vertical acceleration (in m/s/s) either up or down that the controller will use to correct speed or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g) allows for reasonably aggressive pitch changes if required to recover from under-speed conditions. + 1.0 + 10.0 m/s/s + 1 + 0.5 modules/fw_pos_control_l1 Complementary filter "omega" parameter for height This is the cross-over frequency (in radians/second) of the complementary filter used to fuse vertical acceleration and barometric height to obtain an estimate of height rate and height. Increasing this frequency weights the solution more towards use of the barometer, whilst reducing it weights the solution more towards use of the accelerometer data. + 1.0 + 10.0 rad/s + 1 + 0.5 modules/fw_pos_control_l1 Complementary filter "omega" parameter for speed - This is the cross-over frequency (in radians/second) of the complementary filter used to fuse longitudinal acceleration and airspeed to obtain an improved airspeed estimate. Increasing this frequency weights the solution more towards use of the arispeed sensor, whilst reducing it weights the solution more towards use of the accelerometer data. + This is the cross-over frequency (in radians/second) of the complementary filter used to fuse longitudinal acceleration and airspeed to obtain an improved airspeed estimate. Increasing this frequency weights the solution more towards use of the airspeed sensor, whilst reducing it weights the solution more towards use of the accelerometer data. + 1.0 + 10.0 rad/s + 1 + 0.5 modules/fw_pos_control_l1 Roll -> Throttle feedforward Increasing this gain turn increases the amount of throttle that will be used to compensate for the additional drag created by turning. Ideally this should be set to approximately 10 x the extra sink rate in m/s created by a 45 degree bank turn. Increase this gain if the aircraft initially loses energy in turns and reduce if the aircraft initially gains energy in turns. Efficient high aspect-ratio aircraft (eg powered sailplanes) can use a lower value, whereas inefficient low aspect-ratio models (eg delta wings) can use a higher value. + 0.0 + 20.0 + 1 + 0.5 modules/fw_pos_control_l1 @@ -1657,24 +1849,99 @@ Assumes measurement is timestamped at trailing edge of integration periodThis parameter adjusts the amount of weighting that the pitch control applies to speed vs height errors. Setting it to 0.0 will cause the pitch control to control height and ignore speed errors. This will normally improve height accuracy but give larger airspeed errors. Setting it to 2.0 will cause the pitch control loop to control speed and ignore height errors. This will normally reduce airspeed errors, but give larger height errors. The default value of 1.0 allows the pitch control to simultaneously control height and speed. Note to Glider Pilots - set this parameter to 2.0 (The glider will adjust its pitch angle to maintain airspeed, ignoring changes in height). 0.0 2.0 + 1 + 1.0 modules/fw_pos_control_l1 Pitch damping factor This is the damping gain for the pitch demand loop. Increase to add damping to correct for oscillations in height. The default value of 0.0 will work well provided the pitch to servo controller has been tuned properly. + 0.0 + 2.0 + 1 + 0.1 modules/fw_pos_control_l1 Height rate P factor + 0.0 + 2.0 + 2 + 0.05 modules/fw_pos_control_l1 Height rate FF factor + 0.0 + 2.0 + 2 + 0.05 modules/fw_pos_control_l1 - - Speed rate P factor - modules/fw_pos_control_l1 + + Speed rate P factor + 0.0 + 2.0 + 2 + 0.01 + modules/fw_pos_control_l1 + + + Cruise Airspeed + The fixed wing controller tries to fly at this airspeed. + 0.0 + 40 + m/s + 1 + 0.5 + modules/navigator + + + + + Minimum follow target altitude + The minimum height in meters relative to home for following a target + 8.0 + meters + modules/navigator + + + Distance to follow target from + The distance in meters to follow the target at + 1.0 + meters + modules/navigator + + + Side to follow target from + The side to follow the target from (front right = 0, behind = 1, front = 2, front left = 3) + 0 + 3 + n/a + modules/navigator + + + Dynamic filtering algorithm responsiveness to target movement +lower numbers increase the responsiveness to changing long lat +but also ignore less noise + 0.0 + 1.0 + n/a + 2 + modules/navigator + + + + + Dump GPS communication to a file + If this is set to 1, all GPS communication data will be written to a file. Two files will be created, for reading and writing. All communication from startup until device disarm will be dumped. + 0 + 1 + drivers/gps + + Enable + Disable + @@ -1682,7 +1949,10 @@ Assumes measurement is timestamped at trailing edge of integration periodLoiter time The amount of time in seconds the system should do open loop loiter and wait for gps recovery before it goes into flight termination. 0.0 + 3600.0 s + 0 + 1 modules/navigator @@ -1691,6 +1961,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.0 30.0 deg + 1 + 0.5 modules/navigator @@ -1699,6 +1971,8 @@ Assumes measurement is timestamped at trailing edge of integration period-30.0 30.0 deg + 1 + 0.5 modules/navigator @@ -1706,6 +1980,9 @@ Assumes measurement is timestamped at trailing edge of integration periodThrust value which is set during the open loop loiter 0.0 1.0 + norm + 2 + 0.05 modules/navigator @@ -1871,9 +2148,7 @@ Assumes measurement is timestamped at trailing edge of integration period - Enable launch detection - 0 - 1 + Launch detection lib/launchdetection @@ -1882,34 +2157,44 @@ Assumes measurement is timestamped at trailing edge of integration periodLAUN_CAT_A for LAUN_CAT_T serves as threshold to trigger launch detection. 0 m/s/s + 1 + 0.5 lib/launchdetection Catapult time threshold LAUN_CAT_A for LAUN_CAT_T serves as threshold to trigger launch detection. - 0 + 0.0 + 5.0 s + 2 + 0.05 lib/launchdetection Motor delay Delay between starting attitude control and powering up the throttle (giving throttle control to the controller) Before this timespan is up the throttle will be set to FW_THR_IDLE, set to 0 to deactivate - 0 + 0.0 + 10.0 s + 1 + 0.5 lib/launchdetection Maximum pitch before the throttle is powered up (during motor delay phase) This is an extra limit for the maximum pitch which is imposed in the phase before the throttle turns on. This allows to limit the maximum pitch angle during a bungee launch (make the launch less steep). - 0 - 45 + 0.0 + 45.0 deg + 1 + 0.5 lib/launchdetection - Enable accelerometer integration for prediction + Accelerometer integration for prediction modules/local_position_estimator @@ -1995,7 +2280,7 @@ Assumes measurement is timestamped at trailing edge of integration periodmodules/local_position_estimator - Enable GPS + GPS modules/local_position_estimator @@ -2064,7 +2349,7 @@ Assumes measurement is timestamped at trailing edge of integration periodmodules/local_position_estimator - Enabled vision correction + Vision correction modules/local_position_estimator @@ -2146,6 +2431,15 @@ Assumes measurement is timestamped at trailing edge of integration period250 modules/mavlink + + MAVLink protocol version + modules/mavlink + + Always use version 1 + Default to 1, switch to 2 if GCS sends version 2 + Always use version 2 + + MAVLink Radio ID When non-zero the MAVLink app will attempt to configure the radio to this ID and re-set the parameter to 0. If the value is negative it will reset the complete radio config to factory defaults. @@ -2180,13 +2474,48 @@ Assumes measurement is timestamped at trailing edge of integration period - Enables testmode (Identify) of MKBLCTRL Driver - 0 - 1 + Test mode (Identify) of MKBLCTRL Driver + drivers/mkblctrl + + + + + Low pass filter frequency for Gyro + platforms/qurt/fc_addon/mpu_spi - Enabled - Disabled + MPU9X50_GYRO_LPF_184HZ + MPU9X50_GYRO_LPF_250HZ + MPU9X50_GYRO_LPF_41HZ + MPU9X50_GYRO_LPF_92HZ + MPU9X50_GYRO_LPF_10HZ + MPU9X50_GYRO_LPF_20HZ + MPU9X50_GYRO_LPF_3600HZ_NOLPF + MPU9X50_GYRO_LPF_5HZ + + + + Low pass filter frequency for Accelerometer + platforms/qurt/fc_addon/mpu_spi + + MPU9X50_ACC_LPF_184HZ + MPU9X50_ACC_LPF_460HZ + MPU9X50_ACC_LPF_41HZ + MPU9X50_ACC_LPF_92HZ + MPU9X50_ACC_LPF_10HZ + MPU9X50_ACC_LPF_20HZ + MPU9X50_ACC_LPF_460HZ_NOLPF + MPU9X50_ACC_LPF_5HZ + + + + Sample rate in Hz + platforms/qurt/fc_addon/mpu_spi + + MPU9x50_SAMPLE_RATE_200HZ + MPU9x50_SAMPLE_RATE_100HZ + MPU9x50_SAMPLE_RATE_1000HZ + MPU9x50_SAMPLE_RATE_500HZ @@ -2197,6 +2526,8 @@ Assumes measurement is timestamped at trailing edge of integration period0 80 m + 1 + 0.5 modules/navigator @@ -2205,10 +2536,12 @@ Assumes measurement is timestamped at trailing edge of integration period0 80 m + 1 + 0.5 modules/navigator - Enable persistent onboard mission storage + Persistent onboard mission storage When enabled, missions that have been uploaded by the GCS are stored and reloaded after reboot persistently. modules/navigator @@ -2219,6 +2552,8 @@ Assumes measurement is timestamped at trailing edge of integration period0 1000 m + 1 + 0.5 modules/navigator @@ -2251,23 +2586,37 @@ Assumes measurement is timestamped at trailing edge of integration period-1 20 s + 1 1 modules/navigator - Max yaw error in degree needed for waypoint heading acceptance + Max yaw error in degrees needed for waypoint heading acceptance 0 90 deg + 1 1 modules/navigator + + Weather-vane mode landings for missions + + modules/navigator + + + Weather-vane mode for loiter mode + + modules/navigator + Loiter radius (FW only) Default value of loiter radius for missions, loiter, RTL, etc. (fixedwing only). 25 1000 m + 1 + 0.5 modules/navigator @@ -2276,6 +2625,8 @@ Assumes measurement is timestamped at trailing edge of integration period0.05 200.0 m + 1 + 0.5 modules/navigator @@ -2672,6 +3023,7 @@ Assumes measurement is timestamped at trailing edge of integration period1.0 norm 2 + 0.01 modules/mc_pos_control @@ -2681,6 +3033,7 @@ Assumes measurement is timestamped at trailing edge of integration period0.8 norm 2 + 0.01 modules/mc_pos_control @@ -2690,6 +3043,7 @@ Assumes measurement is timestamped at trailing edge of integration period0.2 norm 2 + 0.05 modules/mc_pos_control @@ -2759,15 +3113,30 @@ Assumes measurement is timestamped at trailing edge of integration period3 modules/mc_pos_control - - Maximum vertical velocity + + Maximum vertical ascent velocity Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL, POSCTRL). - 0.0 + 0.5 8.0 m/s 1 modules/mc_pos_control + + Maximum vertical descent velocity + Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL, POSCTRL). + 0.5 + 4.0 + 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. @@ -3147,7 +3516,7 @@ Assumes measurement is timestamped at trailing edge of integration perioddrivers/px4io - Enable S.BUS out + S.BUS out Set to 1 to enable S.BUS version 1 output instead of RSSI. drivers/px4io @@ -3585,14 +3954,16 @@ Assumes measurement is timestamped at trailing edge of integration periodmodules/position_estimator_inav - Disable mocap (set 0 if using fake gps) - Disable mocap - + Mo-cap + Set to 0 if using fake GPS modules/position_estimator_inav + + Mo-cap disabled + Mo-cap enabled + - Enable LIDAR for altitude estimation - Enable LIDAR for altitude estimation + LIDAR for altitude estimation modules/position_estimator_inav @@ -3613,6 +3984,13 @@ Assumes measurement is timestamped at trailing edge of integration periodmodules/position_estimator_inav + + + RC receiver type + Acceptable values: - RC_RECEIVER_SPEKTRUM = 1, - RC_RECEIVER_LEMONRX = 2, + platforms/qurt/fc_addon/rc_receiver + + Roll trim @@ -4330,7 +4708,7 @@ Assumes measurement is timestamped at trailing edge of integration periodmodules/sensors - Enable relay control of relay 1 mapped to the Spektrum receiver power supply + Relay control of relay 1 mapped to the Spektrum receiver power supply 0 1 modules/sensors @@ -5140,8 +5518,7 @@ Assumes measurement is timestamped at trailing edge of integration period - Enable or disable runway takeoff with landing gear - 0: disabled, 1: enabled + Runway takeoff with landing gear lib/runway_takeoff @@ -5164,6 +5541,8 @@ FW_CLMBOUT_DIFF if FW_CLMBOUT_DIFF > 0 0.0 100.0 m + 1 + 1 lib/runway_takeoff @@ -5171,6 +5550,9 @@ FW_CLMBOUT_DIFF if FW_CLMBOUT_DIFF > 0 (Can be used to test taxi on runway) 0.0 1.0 + norm + 2 + 0.01 lib/runway_takeoff @@ -5181,6 +5563,8 @@ to takeoff is reached 0.0 20.0 deg + 1 + 0.5 lib/runway_takeoff @@ -5190,6 +5574,8 @@ pitch of 10 degrees during takeoff, so this must be larger if set 0.0 60.0 deg + 1 + 0.5 lib/runway_takeoff @@ -5199,6 +5585,8 @@ navigation before we're on a safe height 0.0 60.0 deg + 1 + 0.5 lib/runway_takeoff @@ -5207,10 +5595,21 @@ Pitch up will be commanded when the following airspeed is reached: FW_AIRSPD_MIN * RWTO_AIRSPD_SCL 0.0 2.0 + norm + 2 + 0.01 lib/runway_takeoff + + 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 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). @@ -5220,7 +5619,7 @@ FW_AIRSPD_MIN * RWTO_AIRSPD_SCL modules/sdlog2 - Enable extended logging mode + Extended logging mode A value of -1 indicates the command line argument should be obeyed. A value of 0 disables extended logging mode, a value of 1 enables it. This parameter is only read out before logging starts (which commonly is before arming). -1 1 @@ -5233,18 +5632,10 @@ FW_AIRSPD_MIN * RWTO_AIRSPD_SCL Use timestamps only if GPS 3D fix is available - A value of 1 constrains the log folder creation to only use the time stamp if a 3D GPS lock is present. + Constrain the log folder creation to only use the time stamp if a 3D GPS lock is present. modules/sdlog2 - - 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/sdlog2 - Give logging app higher thread priority to avoid data loss. This is used for gathering replay logs for the ekf2 module @@ -5837,18 +6228,51 @@ This is used for gathering replay logs for the ekf2 module - Enable Lidar-Lite (LL40LS) pwm driver + Lidar-Lite (LL40LS) PWM true modules/sensors - Enable sf0x driver + Lightware SF0x laser rangefinder true modules/sensors + + + ESC model + See esc_model_t enum definition in uart_esc_dev.h for all supported ESC model enum values. + platforms/qurt/fc_addon/uart_esc + + ESC_350QX + ESC_200QX + ESC_210QC + + + + ESC UART baud rate + Default rate is 250Kbps, whic is used in off-the-shelf QRP ESC products. + platforms/qurt/fc_addon/uart_esc + + + Motor 1 Mapping + platforms/qurt/fc_addon/uart_esc + + + Motor 2 Mapping + platforms/qurt/fc_addon/uart_esc + + + Motor 3 Mapping + platforms/qurt/fc_addon/uart_esc + + + Motor 4 Mapping + platforms/qurt/fc_addon/uart_esc + + Interval of one subscriber in the example in ms @@ -5871,6 +6295,8 @@ This is used for gathering replay logs for the ekf2 module Auto-start script index CHANGING THIS VALUE REQUIRES A RESTART. Defines the auto-start script used to bootstrap the system. + 0 + 99999 true modules/systemlib @@ -5880,12 +6306,17 @@ This is used for gathering replay logs for the ekf2 module 0 1 modules/systemlib + + Reset parameters + Keep parameters + Set usage of IO board Can be used to use a standard startup script but with a FMU only set-up. Set to 0 to force the FMU only set-up. 0 1 + modules/systemlib @@ -5894,6 +6325,11 @@ This is used for gathering replay logs for the ekf2 module 0 2 modules/systemlib + + Data survives in-flight resets only + Data survives resets + Data does not survive reset + Set multicopter estimator group @@ -5909,8 +6345,8 @@ This is used for gathering replay logs for the ekf2 module - Enable TELEM2 as companion computer link - CHANGING THIS VALUE REQUIRES A RESTART. Configures the baud rate of the TELEM2 connector as companion computer interface. Set to zero to disable, set to these values to enable (NO OTHER VALUES SUPPORTED!). + TELEM2 as companion computer link + CHANGING THIS VALUE REQUIRES A RESTART. Configures the baud rate of the TELEM2 connector as companion computer interface. 0 1921600 true @@ -5932,11 +6368,76 @@ This is used for gathering replay logs for the ekf2 module 0 modules/systemlib + + SD logger + 0 + 1 + true + modules/systemlib + + new logger (experimental) + sdlog2 (default) + + + + + + TEST_MIN + modules/controllib_test + + + TEST_MAX + modules/controllib_test + + + TEST_TRIM + modules/controllib_test + + + TEST_HP + modules/controllib_test + + + TEST_LP + modules/controllib_test + + + TEST_P + modules/controllib_test + + + TEST_I + modules/controllib_test + + + TEST_I_MAX + modules/controllib_test + + + TEST_D + modules/controllib_test + + + TEST_D_LP + modules/controllib_test + + + TEST_MEAN + modules/controllib_test + + + TEST_DEV + modules/controllib_test + + + TEST_PARAMS + systemcmds/tests + - 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. 3 - Sets the motor control outputs to UAVCAN and enables support for dynamic node ID allocation and firmware update. + UAVCAN mode + 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 3 modules/uavcan @@ -6177,12 +6678,7 @@ to accelerate forward if necessary modules/vtol_att_control - Enable optimal recovery strategy for pitch-weak tailsitters - - modules/vtol_att_control - - - Enable weather-vane mode landings for missions + Optimal recovery strategy for pitch-weak tailsitters modules/vtol_att_control @@ -6195,11 +6691,6 @@ to accelerate forward if necessary 0.01 modules/vtol_att_control - - Enable weather-vane mode for loiter - - modules/vtol_att_control - Front transition timeout Time in seconds after which transition will be cancelled. Disabled if set to 0. @@ -6228,7 +6719,6 @@ to accelerate forward if necessary mTECS enabled - Set to 1 to enable mTECS modules/fw_pos_control_l1/mtecs @@ -6624,54 +7114,6 @@ Maps the change of airspeed error to the acceleration setpoint Stabilized - - TEST_MIN - modules/controllib_test - - - TEST_MAX - modules/controllib_test - - - TEST_TRIM - modules/controllib_test - - - TEST_HP - modules/controllib_test - - - TEST_LP - modules/controllib_test - - - TEST_P - modules/controllib_test - - - TEST_I - modules/controllib_test - - - TEST_I_MAX - modules/controllib_test - - - TEST_D - modules/controllib_test - - - TEST_D_LP - modules/controllib_test - - - TEST_MEAN - modules/controllib_test - - - TEST_DEV - modules/controllib_test - SEG_TH2V_P modules/segway -- 2.22.0