You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
3741 lines
164 KiB
3741 lines
164 KiB
<?xml version='1.0' encoding='UTF-8'?> |
|
<parameters> |
|
<version>3</version> |
|
<group name="Attitude EKF estimator"> |
|
<parameter default="1e-4" name="EKF_ATT_V3_Q0" type="FLOAT"> |
|
<short_desc>Body angular rate process noise</short_desc> |
|
</parameter> |
|
<parameter default="0.08" name="EKF_ATT_V3_Q1" type="FLOAT"> |
|
<short_desc>Body angular acceleration process noise</short_desc> |
|
</parameter> |
|
<parameter default="0.009" name="EKF_ATT_V3_Q2" type="FLOAT"> |
|
<short_desc>Acceleration process noise</short_desc> |
|
</parameter> |
|
<parameter default="0.005" name="EKF_ATT_V3_Q3" type="FLOAT"> |
|
<short_desc>Magnet field vector process noise</short_desc> |
|
</parameter> |
|
<parameter default="0.0008" name="EKF_ATT_V4_R0" type="FLOAT"> |
|
<short_desc>Gyro measurement noise</short_desc> |
|
</parameter> |
|
<parameter default="10000.0" name="EKF_ATT_V4_R1" type="FLOAT"> |
|
<short_desc>Accel measurement noise</short_desc> |
|
</parameter> |
|
<parameter default="100.0" name="EKF_ATT_V4_R2" type="FLOAT"> |
|
<short_desc>Mag measurement noise</short_desc> |
|
</parameter> |
|
<parameter default="1" name="EKF_ATT_ENABLED" type="INT32"> |
|
<short_desc>EKF attitude estimator enabled</short_desc> |
|
<long_desc>If enabled, it uses the older EKF filter. |
|
However users can enable the new quaternion |
|
based complimentary filter by setting EKF_ATT_ENABLED = 0.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0.0018" name="ATT_J11" type="FLOAT"> |
|
<short_desc>Moment of inertia matrix diagonal entry (1, 1)</short_desc> |
|
<unit>kg*m^2</unit> |
|
</parameter> |
|
<parameter default="0.0018" name="ATT_J22" type="FLOAT"> |
|
<short_desc>Moment of inertia matrix diagonal entry (2, 2)</short_desc> |
|
<unit>kg*m^2</unit> |
|
</parameter> |
|
<parameter default="0.0037" name="ATT_J33" type="FLOAT"> |
|
<short_desc>Moment of inertia matrix diagonal entry (3, 3)</short_desc> |
|
<unit>kg*m^2</unit> |
|
</parameter> |
|
<parameter default="0" name="ATT_J_EN" type="INT32"> |
|
<short_desc>Moment of inertia enabled in estimator</short_desc> |
|
<long_desc>If set to != 0 the moment of inertia will be used in the estimator</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
</group> |
|
<group name="Attitude Q estimator"> |
|
<parameter default="0.2" name="ATT_W_ACC" type="FLOAT"> |
|
<short_desc>Complimentary filter accelerometer weight</short_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0.1" name="ATT_W_MAG" type="FLOAT"> |
|
<short_desc>Complimentary filter magnetometer weight</short_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0.1" name="ATT_W_GYRO_BIAS" type="FLOAT"> |
|
<short_desc>Complimentary filter gyroscope bias weight</short_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0.0" name="ATT_MAG_DECL" type="FLOAT"> |
|
<short_desc>Magnetic declination, in degrees</short_desc> |
|
<long_desc>This parameter is not used in normal operation, |
|
as the declination is looked up based on the |
|
GPS coordinates of the vehicle.</long_desc> |
|
<unit>degrees</unit> |
|
</parameter> |
|
<parameter default="1" name="ATT_MAG_DECL_A" type="INT32"> |
|
<short_desc>Enable automatic GPS based declination compensation</short_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="2" name="ATT_ACC_COMP" type="INT32"> |
|
<short_desc>Enable acceleration compensation based on GPS |
|
velocity</short_desc> |
|
<min>1</min> |
|
<max>2</max> |
|
</parameter> |
|
<parameter default="0.05" name="ATT_BIAS_MAX" type="FLOAT"> |
|
<short_desc>Gyro bias limit</short_desc> |
|
<min>0</min> |
|
<max>2</max> |
|
<unit>rad/s</unit> |
|
</parameter> |
|
</group> |
|
<group name="Battery Calibration"> |
|
<parameter default="10000" name="BAT_V_SCALE_IO" type="INT32"> |
|
<short_desc>Scaling factor for battery voltage sensor on PX4IO</short_desc> |
|
</parameter> |
|
<parameter default="0.0082" name="BAT_V_SCALING" type="FLOAT"> |
|
<board>CONFIG_ARCH_BOARD_PX4FMU_V2</board> |
|
<short_desc>Scaling factor for battery voltage sensor on FMU v2</short_desc> |
|
</parameter> |
|
<parameter default="0.0124" name="BAT_C_SCALING" type="FLOAT"> |
|
<short_desc>Scaling factor for battery current sensor</short_desc> |
|
</parameter> |
|
<parameter default="3.4" name="BAT_V_EMPTY" type="FLOAT"> |
|
<short_desc>Empty cell voltage</short_desc> |
|
<long_desc>Defines the voltage where a single cell of the battery is considered empty.</long_desc> |
|
<unit>V</unit> |
|
</parameter> |
|
<parameter default="4.2" name="BAT_V_CHARGED" type="FLOAT"> |
|
<short_desc>Full cell voltage</short_desc> |
|
<long_desc>Defines the voltage where a single cell of the battery is considered full.</long_desc> |
|
<unit>V</unit> |
|
</parameter> |
|
<parameter default="0.07" name="BAT_V_LOAD_DROP" type="FLOAT"> |
|
<short_desc>Voltage drop per cell on 100% load</short_desc> |
|
<long_desc>This implicitely defines the internal resistance |
|
to maximum current ratio and assumes linearity.</long_desc> |
|
<unit>V</unit> |
|
</parameter> |
|
<parameter default="3" name="BAT_N_CELLS" type="INT32"> |
|
<short_desc>Number of cells</short_desc> |
|
<long_desc>Defines the number of cells the attached battery consists of.</long_desc> |
|
<unit>S</unit> |
|
</parameter> |
|
<parameter default="-1.0" name="BAT_CAPACITY" type="FLOAT"> |
|
<short_desc>Battery capacity</short_desc> |
|
<long_desc>Defines the capacity of the attached battery.</long_desc> |
|
<unit>mA</unit> |
|
</parameter> |
|
</group> |
|
<group name="Circuit Breaker"> |
|
<parameter default="0" name="CBRK_SUPPLY_CHK" type="INT32"> |
|
<short_desc>Circuit breaker for power supply check</short_desc> |
|
<long_desc>Setting this parameter to 894281 will disable the power valid |
|
checks in the commander. |
|
WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK</long_desc> |
|
<min>0</min> |
|
<max>894281</max> |
|
</parameter> |
|
<parameter default="0" name="CBRK_RATE_CTRL" type="INT32"> |
|
<short_desc>Circuit breaker for rate controller output</short_desc> |
|
<long_desc>Setting this parameter to 140253 will disable the rate |
|
controller uORB publication. |
|
WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK</long_desc> |
|
<min>0</min> |
|
<max>140253</max> |
|
</parameter> |
|
<parameter default="0" name="CBRK_IO_SAFETY" type="INT32"> |
|
<short_desc>Circuit breaker for IO safety</short_desc> |
|
<long_desc>Setting this parameter to 894281 will disable IO safety. |
|
WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK</long_desc> |
|
<min>0</min> |
|
<max>22027</max> |
|
</parameter> |
|
<parameter default="0" name="CBRK_AIRSPD_CHK" type="INT32"> |
|
<short_desc>Circuit breaker for airspeed sensor</short_desc> |
|
<long_desc>Setting this parameter to 162128 will disable the check for an airspeed sensor. |
|
WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK</long_desc> |
|
<min>0</min> |
|
<max>162128</max> |
|
</parameter> |
|
<parameter default="121212" name="CBRK_FLIGHTTERM" type="INT32"> |
|
<short_desc>Circuit breaker for flight termination</short_desc> |
|
<long_desc>Setting this parameter to 121212 will disable the flight termination action. |
|
--> The IO driver will not do flight termination if requested by the FMU |
|
WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK</long_desc> |
|
<min>0</min> |
|
<max>121212</max> |
|
</parameter> |
|
<parameter default="284953" name="CBRK_ENGINEFAIL" type="INT32"> |
|
<short_desc>Circuit breaker for engine failure detection</short_desc> |
|
<long_desc>Setting this parameter to 284953 will disable the engine failure detection. |
|
If the aircraft is in engine failure mode the enine failure flag will be |
|
set to healthy |
|
WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK</long_desc> |
|
<min>0</min> |
|
<max>284953</max> |
|
</parameter> |
|
<parameter default="240024" name="CBRK_GPSFAIL" type="INT32"> |
|
<short_desc>Circuit breaker for GPS failure detection</short_desc> |
|
<long_desc>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</long_desc> |
|
<min>0</min> |
|
<max>240024</max> |
|
</parameter> |
|
</group> |
|
<group name="Commander"> |
|
<parameter default="0" name="COM_DL_LOSS_EN" type="INT32"> |
|
<short_desc>Datalink loss mode enabled</short_desc> |
|
<long_desc>Set to 1 to enable actions triggered when the datalink is lost.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="10" name="COM_DL_LOSS_T" type="INT32"> |
|
<short_desc>Datalink loss time threshold</short_desc> |
|
<long_desc>After this amount of seconds without datalink the data link lost mode triggers</long_desc> |
|
<min>0</min> |
|
<max>30</max> |
|
<unit>second</unit> |
|
</parameter> |
|
<parameter default="0" name="COM_DL_REG_T" type="INT32"> |
|
<short_desc>Datalink regain time threshold</short_desc> |
|
<long_desc>After a data link loss: after this this amount of seconds with a healthy datalink the 'datalink loss' |
|
flag is set back to false</long_desc> |
|
<min>0</min> |
|
<max>30</max> |
|
<unit>second</unit> |
|
</parameter> |
|
<parameter default="0.5" name="COM_EF_THROT" type="FLOAT"> |
|
<short_desc>Engine Failure Throttle Threshold</short_desc> |
|
<long_desc>Engine failure triggers only above this throttle value</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="5.0" name="COM_EF_C2T" type="FLOAT"> |
|
<short_desc>Engine Failure Current/Throttle Threshold</short_desc> |
|
<long_desc>Engine failure triggers only below this current/throttle value</long_desc> |
|
<min>0.0</min> |
|
<max>7.0</max> |
|
</parameter> |
|
<parameter default="10.0" name="COM_EF_TIME" type="FLOAT"> |
|
<short_desc>Engine Failure Time Threshold</short_desc> |
|
<long_desc>Engine failure triggers only if the throttle threshold and the |
|
current to throttle threshold are violated for this time</long_desc> |
|
<min>0.0</min> |
|
<max>7.0</max> |
|
<unit>second</unit> |
|
</parameter> |
|
<parameter default="0.5" name="COM_RC_LOSS_T" type="FLOAT"> |
|
<short_desc>RC loss time threshold</short_desc> |
|
<long_desc>After this amount of seconds without RC connection the rc lost flag is set to true</long_desc> |
|
<min>0</min> |
|
<max>35</max> |
|
<unit>second</unit> |
|
</parameter> |
|
<parameter default="1" name="COM_AUTOS_PAR" type="INT32"> |
|
<short_desc>Autosaving of params</short_desc> |
|
<long_desc>If not equal to zero the commander will automatically save parameters to persistent storage once changed. |
|
Default is on, as the interoperability with currently deployed GCS solutions depends on parameters |
|
being sticky. Developers can default it to off.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0" name="COM_RC_IN_MODE" type="INT32"> |
|
<short_desc>RC control input mode</short_desc> |
|
<long_desc>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.</long_desc> |
|
<min>0</min> |
|
<max>2</max> |
|
</parameter> |
|
</group> |
|
<group name="Data Link Loss"> |
|
<parameter default="-265847810" name="NAV_AH_LAT" type="INT32"> |
|
<short_desc>Airfield home Lat</short_desc> |
|
<long_desc>Latitude of airfield home waypoint</long_desc> |
|
<min>0</min> |
|
<unit>degrees * 1e7</unit> |
|
</parameter> |
|
<parameter default="1518423250" name="NAV_AH_LON" type="INT32"> |
|
<short_desc>Airfield home Lon</short_desc> |
|
<long_desc>Longitude of airfield home waypoint</long_desc> |
|
<min>0</min> |
|
<unit>degrees * 1e7</unit> |
|
</parameter> |
|
<parameter default="600.0" name="NAV_AH_ALT" type="FLOAT"> |
|
<short_desc>Airfield home alt</short_desc> |
|
<long_desc>Altitude of airfield home waypoint</long_desc> |
|
<min>0.0</min> |
|
<unit>m</unit> |
|
</parameter> |
|
<parameter default="120.0" name="NAV_DLL_CH_T" type="FLOAT"> |
|
<short_desc>Comms hold wait time</short_desc> |
|
<long_desc>The amount of time in seconds the system should wait at the comms hold waypoint</long_desc> |
|
<min>0.0</min> |
|
<unit>seconds</unit> |
|
</parameter> |
|
<parameter default="-266072120" name="NAV_DLL_CH_LAT" type="INT32"> |
|
<short_desc>Comms hold Lat</short_desc> |
|
<long_desc>Latitude of comms hold waypoint</long_desc> |
|
<min>0</min> |
|
<unit>degrees * 1e7</unit> |
|
</parameter> |
|
<parameter default="1518453890" name="NAV_DLL_CH_LON" type="INT32"> |
|
<short_desc>Comms hold Lon</short_desc> |
|
<long_desc>Longitude of comms hold waypoint</long_desc> |
|
<min>0</min> |
|
<unit>degrees * 1e7</unit> |
|
</parameter> |
|
<parameter default="600.0" name="NAV_DLL_CH_ALT" type="FLOAT"> |
|
<short_desc>Comms hold alt</short_desc> |
|
<long_desc>Altitude of comms hold waypoint</long_desc> |
|
<min>0.0</min> |
|
<unit>m</unit> |
|
</parameter> |
|
<parameter default="120.0" name="NAV_DLL_AH_T" type="FLOAT"> |
|
<short_desc>Aifield hole wait time</short_desc> |
|
<long_desc>The amount of time in seconds the system should wait at the airfield home waypoint</long_desc> |
|
<min>0.0</min> |
|
<unit>seconds</unit> |
|
</parameter> |
|
<parameter default="2" name="NAV_DLL_N" type="INT32"> |
|
<short_desc>Number of allowed Datalink timeouts</short_desc> |
|
<long_desc>After more than this number of data link timeouts the aircraft returns home directly</long_desc> |
|
<min>0</min> |
|
<max>1000</max> |
|
</parameter> |
|
<parameter default="0" name="NAV_DLL_CHSK" type="INT32"> |
|
<short_desc>Skip comms hold wp</short_desc> |
|
<long_desc>If set to 1 the system will skip the comms hold wp on data link loss and will directly fly to |
|
airfield home</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
</group> |
|
<group name="FW Attitude Control"> |
|
<parameter default="0.5" name="FW_ATT_TC" type="FLOAT"> |
|
<short_desc>Attitude Time Constant</short_desc> |
|
<long_desc>This defines the latency between a step input and the achieved setpoint |
|
(inverse to a P gain). Half a second is a good start value and fits for |
|
most average systems. Smaller systems may require smaller values, but as |
|
this will wear out servos faster, the value should only be decreased as |
|
needed.</long_desc> |
|
<min>0.4</min> |
|
<max>1.0</max> |
|
<unit>seconds</unit> |
|
</parameter> |
|
<parameter default="0.05" name="FW_PR_P" type="FLOAT"> |
|
<short_desc>Pitch rate proportional gain</short_desc> |
|
<long_desc>This defines how much the elevator input will be commanded depending on the |
|
current body angular rate error.</long_desc> |
|
<min>0.005</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="FW_PR_I" type="FLOAT"> |
|
<short_desc>Pitch rate integrator gain</short_desc> |
|
<long_desc>This gain defines how much control response will result out of a steady |
|
state error. It trims any constant error.</long_desc> |
|
<min>0.0</min> |
|
<max>50.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="FW_P_RMAX_POS" type="FLOAT"> |
|
<short_desc>Maximum positive / up pitch rate</short_desc> |
|
<long_desc>This limits the maximum pitch up angular rate the controller will output (in |
|
degrees per second). Setting a value of zero disables the limit.</long_desc> |
|
<min>0.0</min> |
|
<max>90.0</max> |
|
<unit>deg/s</unit> |
|
</parameter> |
|
<parameter default="0.0" name="FW_P_RMAX_NEG" type="FLOAT"> |
|
<short_desc>Maximum negative / down pitch rate</short_desc> |
|
<long_desc>This limits the maximum pitch down up angular rate the controller will |
|
output (in degrees per second). Setting a value of zero disables the limit.</long_desc> |
|
<min>0.0</min> |
|
<max>90.0</max> |
|
<unit>deg/s</unit> |
|
</parameter> |
|
<parameter default="0.2" name="FW_PR_IMAX" type="FLOAT"> |
|
<short_desc>Pitch rate integrator limit</short_desc> |
|
<long_desc>The portion of the integrator part in the control surface deflection is |
|
limited to this value</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="FW_P_ROLLFF" type="FLOAT"> |
|
<short_desc>Roll to Pitch feedforward gain</short_desc> |
|
<long_desc>This compensates during turns and ensures the nose stays level.</long_desc> |
|
<min>0.0</min> |
|
<max>2.0</max> |
|
</parameter> |
|
<parameter default="0.05" name="FW_RR_P" type="FLOAT"> |
|
<short_desc>Roll rate proportional Gain</short_desc> |
|
<long_desc>This defines how much the aileron input will be commanded depending on the |
|
current body angular rate error.</long_desc> |
|
<min>0.005</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="FW_RR_I" type="FLOAT"> |
|
<short_desc>Roll rate integrator Gain</short_desc> |
|
<long_desc>This gain defines how much control response will result out of a steady |
|
state error. It trims any constant error.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="0.2" name="FW_RR_IMAX" type="FLOAT"> |
|
<short_desc>Roll Integrator Anti-Windup</short_desc> |
|
<long_desc>The portion of the integrator part in the control surface deflection is limited to this value.</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="FW_R_RMAX" type="FLOAT"> |
|
<short_desc>Maximum Roll Rate</short_desc> |
|
<long_desc>This limits the maximum roll rate the controller will output (in degrees per |
|
second). Setting a value of zero disables the limit.</long_desc> |
|
<min>0.0</min> |
|
<max>90.0</max> |
|
<unit>deg/s</unit> |
|
</parameter> |
|
<parameter default="0.05" name="FW_YR_P" type="FLOAT"> |
|
<short_desc>Yaw rate proportional gain</short_desc> |
|
<long_desc>This defines how much the rudder input will be commanded depending on the |
|
current body angular rate error.</long_desc> |
|
<min>0.005</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="FW_YR_I" type="FLOAT"> |
|
<short_desc>Yaw rate integrator gain</short_desc> |
|
<long_desc>This gain defines how much control response will result out of a steady |
|
state error. It trims any constant error.</long_desc> |
|
<min>0.0</min> |
|
<max>50.0</max> |
|
</parameter> |
|
<parameter default="0.2" name="FW_YR_IMAX" type="FLOAT"> |
|
<short_desc>Yaw rate integrator limit</short_desc> |
|
<long_desc>The portion of the integrator part in the control surface deflection is |
|
limited to this value</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="FW_Y_RMAX" type="FLOAT"> |
|
<short_desc>Maximum Yaw Rate</short_desc> |
|
<long_desc>This limits the maximum yaw rate the controller will output (in degrees per |
|
second). Setting a value of zero disables the limit.</long_desc> |
|
<min>0.0</min> |
|
<max>90.0</max> |
|
<unit>deg/s</unit> |
|
</parameter> |
|
<parameter default="0.3" name="FW_RR_FF" type="FLOAT"> |
|
<short_desc>Roll rate feed forward</short_desc> |
|
<long_desc>Direct feed forward from rate setpoint to control surface output. Use this |
|
to obtain a tigher response of the controller without introducing |
|
noise amplification.</long_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.4" name="FW_PR_FF" type="FLOAT"> |
|
<short_desc>Pitch rate feed forward</short_desc> |
|
<long_desc>Direct feed forward from rate setpoint to control surface output</long_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.3" name="FW_YR_FF" type="FLOAT"> |
|
<short_desc>Yaw rate feed forward</short_desc> |
|
<long_desc>Direct feed forward from rate setpoint to control surface output</long_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="1000.0" name="FW_YCO_VMIN" type="FLOAT"> |
|
<short_desc>Minimal speed for yaw coordination</short_desc> |
|
<long_desc>For airspeeds above this value, the yaw rate is calculated for a coordinated |
|
turn. Set to a very high value to disable.</long_desc> |
|
<unit>m/s</unit> |
|
</parameter> |
|
<parameter default="0" name="FW_YCO_METHOD" type="INT32"> |
|
<short_desc>Method used for yaw coordination</short_desc> |
|
<long_desc>The param value sets the method used to calculate the yaw rate |
|
0: open-loop zero lateral acceleration based on kinematic constraints |
|
1: closed-loop: try to reduce lateral acceleration to 0 by measuring the acceleration</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
<unit>m/s</unit> |
|
</parameter> |
|
<parameter default="10.0" name="FW_AIRSPD_MIN" type="FLOAT"> |
|
<short_desc>Minimum Airspeed</short_desc> |
|
<long_desc>If the airspeed falls below this value, the TECS controller will try to |
|
increase airspeed more aggressively.</long_desc> |
|
<min>0.0</min> |
|
<max>40</max> |
|
<unit>m/s</unit> |
|
</parameter> |
|
<parameter default="15.0" name="FW_AIRSPD_TRIM" type="FLOAT"> |
|
<short_desc>Trim Airspeed</short_desc> |
|
<long_desc>The TECS controller tries to fly at this airspeed.</long_desc> |
|
<min>0.0</min> |
|
<max>40</max> |
|
<unit>m/s</unit> |
|
</parameter> |
|
<parameter default="20.0" name="FW_AIRSPD_MAX" type="FLOAT"> |
|
<short_desc>Maximum Airspeed</short_desc> |
|
<long_desc>If the airspeed is above this value, the TECS controller will try to decrease |
|
airspeed more aggressively.</long_desc> |
|
<min>0.0</min> |
|
<max>40</max> |
|
<unit>m/s</unit> |
|
</parameter> |
|
<parameter default="0.0" name="FW_RSP_OFF" type="FLOAT"> |
|
<short_desc>Roll Setpoint Offset</short_desc> |
|
<long_desc>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.</long_desc> |
|
<min>-90.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="0.0" name="FW_PSP_OFF" type="FLOAT"> |
|
<short_desc>Pitch Setpoint Offset</short_desc> |
|
<long_desc>An airframe specific offset of the pitch setpoint in degrees, the value is |
|
added to the pitch setpoint and should correspond to the typical cruise |
|
speed of the airframe.</long_desc> |
|
<min>-90.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="45.0" name="FW_MAN_R_MAX" type="FLOAT"> |
|
<short_desc>Max Manual Roll</short_desc> |
|
<long_desc>Max roll for manual control in attitude stabilized mode</long_desc> |
|
<min>0.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="45.0" name="FW_MAN_P_MAX" type="FLOAT"> |
|
<short_desc>Max Manual Pitch</short_desc> |
|
<long_desc>Max pitch for manual control in attitude stabilized mode</long_desc> |
|
<min>0.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
</group> |
|
<group name="Fixed Wing TECS"> |
|
<parameter default="2.0" name="FW_T_SINK_MIN" type="FLOAT"> |
|
<short_desc>Minimum descent rate</short_desc> |
|
<long_desc>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.</long_desc> |
|
</parameter> |
|
<parameter default="5.0" name="FW_T_SINK_MAX" type="FLOAT"> |
|
<short_desc>Maximum descent rate</short_desc> |
|
<long_desc>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.</long_desc> |
|
</parameter> |
|
<parameter default="5.0" name="FW_T_TIME_CONST" type="FLOAT"> |
|
<short_desc>TECS time constant</short_desc> |
|
<long_desc>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.</long_desc> |
|
</parameter> |
|
<parameter default="8.0" name="FW_T_THRO_CONST" type="FLOAT"> |
|
<short_desc>TECS Throttle time constant</short_desc> |
|
<long_desc>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.</long_desc> |
|
</parameter> |
|
<parameter default="0.5" name="FW_T_THR_DAMP" type="FLOAT"> |
|
<short_desc>Throttle damping factor</short_desc> |
|
<long_desc>This is the damping gain for the throttle demand loop. |
|
Increase to add damping to correct for oscillations in speed and height.</long_desc> |
|
</parameter> |
|
<parameter default="0.1" name="FW_T_INTEG_GAIN" type="FLOAT"> |
|
<short_desc>Integrator gain</short_desc> |
|
<long_desc>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.</long_desc> |
|
</parameter> |
|
<parameter default="7.0" name="FW_T_VERT_ACC" type="FLOAT"> |
|
<short_desc>Maximum vertical acceleration</short_desc> |
|
<long_desc>This is the maximum vertical acceleration (in metres/second square) |
|
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.</long_desc> |
|
</parameter> |
|
<parameter default="3.0" name="FW_T_HGT_OMEGA" type="FLOAT"> |
|
<short_desc>Complementary filter "omega" parameter for height</short_desc> |
|
<long_desc>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.</long_desc> |
|
</parameter> |
|
<parameter default="2.0" name="FW_T_SPD_OMEGA" type="FLOAT"> |
|
<short_desc>Complementary filter "omega" parameter for speed</short_desc> |
|
<long_desc>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.</long_desc> |
|
</parameter> |
|
<parameter default="10.0" name="FW_T_RLL2THR" type="FLOAT"> |
|
<short_desc>Roll -> Throttle feedforward</short_desc> |
|
<long_desc>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.</long_desc> |
|
</parameter> |
|
<parameter default="1.0" name="FW_T_SPDWEIGHT" type="FLOAT"> |
|
<short_desc>Speed <--> Altitude priority</short_desc> |
|
<long_desc>This 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).</long_desc> |
|
</parameter> |
|
<parameter default="0.0" name="FW_T_PTCH_DAMP" type="FLOAT"> |
|
<short_desc>Pitch damping factor</short_desc> |
|
<long_desc>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.</long_desc> |
|
</parameter> |
|
<parameter default="0.05" name="FW_T_HRATE_P" type="FLOAT"> |
|
<short_desc>Height rate P factor</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="FW_T_HRATE_FF" type="FLOAT"> |
|
<short_desc>Height rate FF factor</short_desc> |
|
</parameter> |
|
<parameter default="0.05" name="FW_T_SRATE_P" type="FLOAT"> |
|
<short_desc>Speed rate P factor</short_desc> |
|
</parameter> |
|
</group> |
|
<group name="GPS Failure Navigation"> |
|
<parameter default="30.0" name="NAV_GPSF_LT" type="FLOAT"> |
|
<short_desc>Loiter time</short_desc> |
|
<long_desc>The amount of time in seconds the system should do open loop loiter and wait for gps recovery |
|
before it goes into flight termination.</long_desc> |
|
<min>0.0</min> |
|
<unit>seconds</unit> |
|
</parameter> |
|
<parameter default="15.0" name="NAV_GPSF_R" type="FLOAT"> |
|
<short_desc>Open loop loiter roll</short_desc> |
|
<long_desc>Roll in degrees during the open loop loiter</long_desc> |
|
<min>0.0</min> |
|
<max>30.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="0.0" name="NAV_GPSF_P" type="FLOAT"> |
|
<short_desc>Open loop loiter pitch</short_desc> |
|
<long_desc>Pitch in degrees during the open loop loiter</long_desc> |
|
<min>-30.0</min> |
|
<max>30.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="0.7" name="NAV_GPSF_TR" type="FLOAT"> |
|
<short_desc>Open loop loiter thrust</short_desc> |
|
<long_desc>Thrust value which is set during the open loop loiter</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
</group> |
|
<group name="Geofence"> |
|
<parameter default="0" name="GF_MODE" type="INT32"> |
|
<short_desc>Geofence mode</short_desc> |
|
<long_desc>0 = disabled, 1 = geofence file only, 2 = max horizontal (GF_MAX_HOR_DIST) and vertical (GF_MAX_VER_DIST) distances, 3 = both</long_desc> |
|
<min>0</min> |
|
<max>3</max> |
|
</parameter> |
|
<parameter default="0" name="GF_ALTMODE" type="INT32"> |
|
<short_desc>Geofence altitude mode</short_desc> |
|
<long_desc>Select which altitude reference should be used |
|
0 = WGS84, 1 = AMSL</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0" name="GF_SOURCE" type="INT32"> |
|
<short_desc>Geofence source</short_desc> |
|
<long_desc>Select which position source should be used. Selecting GPS instead of global position makes sure that there is |
|
no dependence on the position estimator |
|
0 = global position, 1 = GPS</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="-1" name="GF_COUNT" type="INT32"> |
|
<short_desc>Geofence counter limit</short_desc> |
|
<long_desc>Set how many subsequent position measurements outside of the fence are needed before geofence violation is triggered</long_desc> |
|
<min>-1</min> |
|
<max>10</max> |
|
</parameter> |
|
<parameter default="-1" name="GF_MAX_HOR_DIST" type="INT32"> |
|
<short_desc>Max horizontal distance in meters</short_desc> |
|
<long_desc>Set to > 0 to activate RTL if horizontal distance to home exceeds this value.</long_desc> |
|
</parameter> |
|
<parameter default="-1" name="GF_MAX_VER_DIST" type="INT32"> |
|
<short_desc>Max vertical distance in meters</short_desc> |
|
<long_desc>Set to > 0 to activate RTL if vertical distance to home exceeds this value.</long_desc> |
|
</parameter> |
|
</group> |
|
<group name="L1 Control"> |
|
<parameter default="25.0" name="FW_L1_PERIOD" type="FLOAT"> |
|
<short_desc>L1 period</short_desc> |
|
<long_desc>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.</long_desc> |
|
<min>1.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="0.75" name="FW_L1_DAMPING" type="FLOAT"> |
|
<short_desc>L1 damping</short_desc> |
|
<long_desc>Damping factor for L1 control.</long_desc> |
|
<min>0.6</min> |
|
<max>0.9</max> |
|
</parameter> |
|
<parameter default="0.7" name="FW_THR_CRUISE" type="FLOAT"> |
|
<short_desc>Cruise throttle</short_desc> |
|
<long_desc>This is the throttle setting required to achieve the desired cruise speed. Most airframes have a value of 0.5-0.7.</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="FW_THR_SLEW_MAX" type="FLOAT"> |
|
<short_desc>Throttle max slew rate</short_desc> |
|
<long_desc>Maximum slew rate for the commanded throttle</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="-45.0" name="FW_P_LIM_MIN" type="FLOAT"> |
|
<short_desc>Negative pitch limit</short_desc> |
|
<long_desc>The minimum negative pitch the controller will output.</long_desc> |
|
<min>-60.0</min> |
|
<max>0.0</max> |
|
<unit>degrees</unit> |
|
</parameter> |
|
<parameter default="45.0" name="FW_P_LIM_MAX" type="FLOAT"> |
|
<short_desc>Positive pitch limit</short_desc> |
|
<long_desc>The maximum positive pitch the controller will output.</long_desc> |
|
<min>0.0</min> |
|
<max>60.0</max> |
|
<unit>degrees</unit> |
|
</parameter> |
|
<parameter default="45.0" name="FW_R_LIM" type="FLOAT"> |
|
<short_desc>Controller roll limit</short_desc> |
|
<long_desc>The maximum roll the controller will output.</long_desc> |
|
<min>0.0</min> |
|
<unit>degrees</unit> |
|
</parameter> |
|
<parameter default="1.0" name="FW_THR_MAX" type="FLOAT"> |
|
<short_desc>Throttle limit max</short_desc> |
|
<long_desc>This is the maximum throttle % that can be used by the controller. |
|
For overpowered aircraft, this should be reduced to a value that |
|
provides sufficient thrust to climb at the maximum pitch angle PTCH_MAX.</long_desc> |
|
</parameter> |
|
<parameter default="0.0" name="FW_THR_MIN" type="FLOAT"> |
|
<short_desc>Throttle limit min</short_desc> |
|
<long_desc>This is the minimum throttle % that can be used by the controller. |
|
For electric aircraft this will normally be set to zero, but can be set |
|
to a small non-zero value if a folding prop is fitted to prevent the |
|
prop from folding and unfolding repeatedly in-flight or to provide |
|
some aerodynamic drag from a turning prop to improve the descent rate. |
|
For aircraft with internal combustion engine this parameter should be set |
|
for desired idle rpm.</long_desc> |
|
</parameter> |
|
<parameter default="1.0" name="FW_THR_LND_MAX" type="FLOAT"> |
|
<short_desc>Throttle limit value before flare</short_desc> |
|
<long_desc>This throttle value will be set as throttle limit at FW_LND_TLALT, |
|
before arcraft will flare.</long_desc> |
|
</parameter> |
|
<parameter default="25.0" name="FW_CLMBOUT_DIFF" type="FLOAT"> |
|
<short_desc>Climbout Altitude difference</short_desc> |
|
<long_desc>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).</long_desc> |
|
</parameter> |
|
<parameter default="5.0" name="FW_T_CLMB_MAX" type="FLOAT"> |
|
<short_desc>Maximum climb rate</short_desc> |
|
<long_desc>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.</long_desc> |
|
</parameter> |
|
<parameter default="5.0" name="FW_LND_ANG" type="FLOAT"> |
|
<short_desc>Landing slope angle</short_desc> |
|
</parameter> |
|
<parameter default="10.0" name="FW_LND_HVIRT" type="FLOAT"> |
|
<short_desc>FW_LND_HVIRT</short_desc> |
|
</parameter> |
|
<parameter default="8.0" name="FW_LND_FLALT" type="FLOAT"> |
|
<short_desc>Landing flare altitude (relative to landing altitude)</short_desc> |
|
<unit>meter</unit> |
|
</parameter> |
|
<parameter default="-1.0" name="FW_LND_TLALT" type="FLOAT"> |
|
<short_desc>Landing throttle limit altitude (relative landing altitude)</short_desc> |
|
<long_desc>Default of -1.0f lets the system default to applying throttle |
|
limiting at 2/3 of the flare altitude.</long_desc> |
|
<unit>meter</unit> |
|
</parameter> |
|
<parameter default="15.0" name="FW_LND_HHDIST" type="FLOAT"> |
|
<short_desc>Landing heading hold horizontal distance</short_desc> |
|
</parameter> |
|
<parameter default="0" name="FW_LND_USETER" type="INT32"> |
|
<short_desc>Enable or disable usage of terrain estimate during landing</short_desc> |
|
<long_desc>0: disabled, 1: enabled</long_desc> |
|
</parameter> |
|
</group> |
|
<group name="Land Detector"> |
|
<parameter default="0.30" name="LNDMC_Z_VEL_MAX" type="FLOAT"> |
|
<short_desc>Multicopter max climb rate</short_desc> |
|
<long_desc>Maximum vertical velocity allowed to trigger a land (m/s up and down)</long_desc> |
|
</parameter> |
|
<parameter default="1.00" name="LNDMC_XY_VEL_MAX" type="FLOAT"> |
|
<short_desc>Multicopter max horizontal velocity</short_desc> |
|
<long_desc>Maximum horizontal velocity allowed to trigger a land (m/s)</long_desc> |
|
</parameter> |
|
<parameter default="20.0" name="LNDMC_ROT_MAX" type="FLOAT"> |
|
<short_desc>Multicopter max rotation</short_desc> |
|
<long_desc>Maximum allowed around each axis to trigger a land (degrees per second)</long_desc> |
|
</parameter> |
|
<parameter default="0.20" name="LNDMC_THR_MAX" type="FLOAT"> |
|
<short_desc>Multicopter max throttle</short_desc> |
|
<long_desc>Maximum actuator output on throttle before triggering a land</long_desc> |
|
</parameter> |
|
<parameter default="0.40" name="LNDFW_VEL_XY_MAX" type="FLOAT"> |
|
<short_desc>Fixedwing max horizontal velocity</short_desc> |
|
<long_desc>Maximum horizontal velocity allowed to trigger a land (m/s)</long_desc> |
|
</parameter> |
|
<parameter default="10.00" name="LNDFW_VEL_Z_MAX" type="FLOAT"> |
|
<short_desc>Fixedwing max climb rate</short_desc> |
|
<long_desc>Maximum vertical velocity allowed to trigger a land (m/s up and down)</long_desc> |
|
</parameter> |
|
<parameter default="10.00" name="LNDFW_AIRSPD_MAX" type="FLOAT"> |
|
<short_desc>Airspeed max</short_desc> |
|
<long_desc>Maximum airspeed allowed to trigger a land (m/s)</long_desc> |
|
</parameter> |
|
</group> |
|
<group name="Launch detection"> |
|
<parameter default="0" name="LAUN_ALL_ON" type="INT32"> |
|
<short_desc>Enable launch detection</short_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="30.0" name="LAUN_CAT_A" type="FLOAT"> |
|
<short_desc>Catapult accelerometer theshold</short_desc> |
|
<long_desc>LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection.</long_desc> |
|
<min>0</min> |
|
</parameter> |
|
<parameter default="0.05" name="LAUN_CAT_T" type="FLOAT"> |
|
<short_desc>Catapult time theshold</short_desc> |
|
<long_desc>LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection.</long_desc> |
|
<min>0</min> |
|
</parameter> |
|
<parameter default="0.0" name="LAUN_CAT_MDEL" type="FLOAT"> |
|
<short_desc>Motor delay</short_desc> |
|
<long_desc>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 LAUN_THR_PRE, set to 0 to deactivate</long_desc> |
|
<min>0</min> |
|
<unit>seconds</unit> |
|
</parameter> |
|
<parameter default="30.0" name="LAUN_CAT_PMAX" type="FLOAT"> |
|
<short_desc>Maximum pitch before the throttle is powered up (during motor delay phase)</short_desc> |
|
<long_desc>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).</long_desc> |
|
<min>0</min> |
|
<max>45</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="0.0" name="LAUN_THR_PRE" type="FLOAT"> |
|
<short_desc>Throttle setting while detecting launch</short_desc> |
|
<long_desc>The throttle is set to this value while the system is waiting for the take-off.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
</group> |
|
<group name="Local Position Estimator"> |
|
<parameter default="1" name="LPE_ENABLED" type="INT32"> |
|
<short_desc>Enable local position estimator</short_desc> |
|
</parameter> |
|
<parameter default="1" name="LPE_INTEGRATE" type="INT32"> |
|
<short_desc>Enable accelerometer integration for prediction</short_desc> |
|
</parameter> |
|
<parameter default="0.01" name="LPE_FLW_XY" type="FLOAT"> |
|
<short_desc>Optical flow xy standard deviation</short_desc> |
|
<min>0.01</min> |
|
<max>1</max> |
|
<unit>m</unit> |
|
</parameter> |
|
<parameter default="0.2" name="LPE_SNR_Z" type="FLOAT"> |
|
<short_desc>Sonar z standard deviation</short_desc> |
|
<min>0.01</min> |
|
<max>1</max> |
|
<unit>m</unit> |
|
</parameter> |
|
<parameter default="0.1" name="LPE_LDR_Z" type="FLOAT"> |
|
<short_desc>Lidar z standard deviation</short_desc> |
|
<min>0.01</min> |
|
<max>1</max> |
|
<unit>m</unit> |
|
</parameter> |
|
<parameter default="1.0" name="LPE_ACC_XY" type="FLOAT"> |
|
<short_desc>Accelerometer xy standard deviation</short_desc> |
|
<min>0.01</min> |
|
<max>2</max> |
|
<unit>m/s^2</unit> |
|
</parameter> |
|
<parameter default="0.1" name="LPE_ACC_Z" type="FLOAT"> |
|
<short_desc>Accelerometer xy standard deviation</short_desc> |
|
<min>0.01</min> |
|
<max>2</max> |
|
<unit>m/s^2</unit> |
|
</parameter> |
|
<parameter default="3.0" name="LPE_BAR_Z" type="FLOAT"> |
|
<short_desc>Barometric presssure altitude z standard deviation</short_desc> |
|
<min>0.01</min> |
|
<max>3</max> |
|
<unit>m</unit> |
|
</parameter> |
|
<parameter default="2.0" name="LPE_GPS_XY" type="FLOAT"> |
|
<short_desc>GPS xy standard deviation</short_desc> |
|
<min>0.01</min> |
|
<max>5</max> |
|
<unit>m</unit> |
|
</parameter> |
|
<parameter default="3.0" name="LPE_GPS_Z" type="FLOAT"> |
|
<short_desc>GPS z standard deviation</short_desc> |
|
<min>0.01</min> |
|
<max>5</max> |
|
<unit>m</unit> |
|
</parameter> |
|
<parameter default="1.0" name="LPE_GPS_VXY" type="FLOAT"> |
|
<short_desc>GPS xy velocity standard deviation</short_desc> |
|
<min>0.01</min> |
|
<max>2</max> |
|
<unit>m/s</unit> |
|
</parameter> |
|
<parameter default="1.0" name="LPE_GPS_VZ" type="FLOAT"> |
|
<short_desc>GPS z velocity standard deviation</short_desc> |
|
<min>0.01</min> |
|
<max>2</max> |
|
<unit>m/s</unit> |
|
</parameter> |
|
<parameter default="0.5" name="LPE_VIS_XY" type="FLOAT"> |
|
<short_desc>Vision xy standard deviation</short_desc> |
|
<min>0.01</min> |
|
<max>1</max> |
|
<unit>m</unit> |
|
</parameter> |
|
<parameter default="0.5" name="LPE_VIS_Z" type="FLOAT"> |
|
<short_desc>Vision z standard deviation</short_desc> |
|
<min>0.01</min> |
|
<max>2</max> |
|
<unit>m</unit> |
|
</parameter> |
|
<parameter default="1.0" name="LPE_VIS_VXY" type="FLOAT"> |
|
<short_desc>Vision xy velocity standard deviation</short_desc> |
|
<min>0.01</min> |
|
<max>2</max> |
|
<unit>m/s</unit> |
|
</parameter> |
|
<parameter default="1.0" name="LPE_VIS_VZ" type="FLOAT"> |
|
<short_desc>Vision z velocity standard deviation</short_desc> |
|
<min>0.01</min> |
|
<max>2</max> |
|
<unit>m/s</unit> |
|
</parameter> |
|
<parameter default="0" name="LPE_NO_VISION" type="INT32"> |
|
<short_desc>Circuit breaker to disable vision input</short_desc> |
|
<long_desc>Set to the appropriate key (328754) to disable vision input.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0.05" name="LPE_VIC_P" type="FLOAT"> |
|
<short_desc>Vicon position standard deviation</short_desc> |
|
<min>0.01</min> |
|
<max>1</max> |
|
<unit>m</unit> |
|
</parameter> |
|
<parameter default="1.0" name="LPE_PN_P" type="FLOAT"> |
|
<short_desc>Position propagation process noise</short_desc> |
|
<min>0.01</min> |
|
<max>1</max> |
|
<unit>m</unit> |
|
</parameter> |
|
<parameter default="0.1" name="LPE_PN_V" type="FLOAT"> |
|
<short_desc>Velocity propagation process noise</short_desc> |
|
<min>0.01</min> |
|
<max>5</max> |
|
<unit>m/s</unit> |
|
</parameter> |
|
</group> |
|
<group name="MAVLink"> |
|
<parameter default="1" name="MAV_SYS_ID" type="INT32"> |
|
<short_desc>MAVLink system ID</short_desc> |
|
<min>1</min> |
|
<max>250</max> |
|
</parameter> |
|
<parameter default="50" name="MAV_COMP_ID" type="INT32"> |
|
<short_desc>MAVLink component ID</short_desc> |
|
<min>1</min> |
|
<max>50</max> |
|
</parameter> |
|
<parameter default="MAV_TYPE_FIXED_WING" name="MAV_TYPE" type="INT32"> |
|
<short_desc>MAVLink type</short_desc> |
|
</parameter> |
|
<parameter default="0" name="MAV_USEHILGPS" type="INT32"> |
|
<short_desc>Use/Accept HIL GPS message (even if not in HIL mode)</short_desc> |
|
<long_desc>If set to 1 incomming HIL GPS messages are parsed.</long_desc> |
|
</parameter> |
|
<parameter default="1" name="MAV_FWDEXTSP" type="INT32"> |
|
<short_desc>Forward external setpoint messages</short_desc> |
|
<long_desc>If set to 1 incomming external setpoint messages will be directly forwarded to the controllers if in offboard |
|
control mode</long_desc> |
|
</parameter> |
|
<parameter default="1" name="MAV_TEST_PAR" type="INT32"> |
|
<short_desc>Test parameter</short_desc> |
|
<long_desc>This parameter is not actively used by the system. Its purpose is to allow |
|
testing the parameter interface on the communication level.</long_desc> |
|
<min>-1000</min> |
|
<max>1000</max> |
|
</parameter> |
|
</group> |
|
<group name="MKBLCTRL Testmode"> |
|
<parameter default="0" name="MKBLCTRL_TEST" type="INT32"> |
|
<short_desc>Enables testmode (Identify) of MKBLCTRL Driver</short_desc> |
|
</parameter> |
|
</group> |
|
<group name="Mission"> |
|
<parameter default="50.0" name="NAV_LOITER_RAD" type="FLOAT"> |
|
<short_desc>Loiter radius (FW only)</short_desc> |
|
<long_desc>Default value of loiter radius for missions, loiter, RTL, etc. (fixedwing only).</long_desc> |
|
<min>20</min> |
|
<max>200</max> |
|
<unit>meters</unit> |
|
</parameter> |
|
<parameter default="10.0" name="NAV_ACC_RAD" type="FLOAT"> |
|
<short_desc>Acceptance Radius</short_desc> |
|
<long_desc>Default acceptance radius, overridden by acceptance radius of waypoint if set.</long_desc> |
|
<min>0.05</min> |
|
<max>200</max> |
|
<unit>meters</unit> |
|
</parameter> |
|
<parameter default="0" name="NAV_DLL_OBC" type="INT32"> |
|
<short_desc>Set OBC mode for data link loss</short_desc> |
|
<long_desc>If set to 1 the behaviour on data link loss is set to a mode according to the OBC rules</long_desc> |
|
<min>0</min> |
|
</parameter> |
|
<parameter default="0" name="NAV_RCL_OBC" type="INT32"> |
|
<short_desc>Set OBC mode for rc loss</short_desc> |
|
<long_desc>If set to 1 the behaviour on data link loss is set to a mode according to the OBC rules</long_desc> |
|
<min>0</min> |
|
</parameter> |
|
<parameter default="10.0" name="MIS_TAKEOFF_ALT" type="FLOAT"> |
|
<short_desc>Take-off altitude</short_desc> |
|
<long_desc>Even if first waypoint has altitude less then MIS_TAKEOFF_ALT above home position, system will climb to |
|
MIS_TAKEOFF_ALT on takeoff, then go to waypoint.</long_desc> |
|
<unit>meters</unit> |
|
</parameter> |
|
<parameter default="1" name="MIS_ONBOARD_EN" type="INT32"> |
|
<short_desc>Enable persistent onboard mission storage</short_desc> |
|
<long_desc>When enabled, missions that have been uploaded by the GCS are stored |
|
and reloaded after reboot persistently.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="500" name="MIS_DIST_1WP" type="FLOAT"> |
|
<short_desc>Maximal horizontal distance from home to first waypoint</short_desc> |
|
<long_desc>Failsafe check to prevent running mission stored from previous flight at a new takeoff location. |
|
Set a value of zero or less to disable. The mission will not be started if the current |
|
waypoint is more distant than MIS_DIS_1WP from the current position.</long_desc> |
|
<min>0</min> |
|
<max>1000</max> |
|
</parameter> |
|
<parameter default="0" name="MIS_ALTMODE" type="INT32"> |
|
<short_desc>Altitude setpoint mode</short_desc> |
|
<long_desc>0: the system will follow a zero order hold altitude setpoint |
|
1: the system will follow a first order hold altitude setpoint |
|
values follow the definition in enum mission_altitude_mode</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="1" name="MIS_YAWMODE" type="INT32"> |
|
<short_desc>Multirotor only. Yaw setpoint mode</short_desc> |
|
<long_desc>0: Set the yaw heading to the yaw value specified for the destination waypoint. |
|
1: Maintain a yaw heading pointing towards the next waypoint. |
|
2: Maintain a yaw heading that always points to the home location. |
|
3: Maintain a yaw heading that always points away from the home location (ie: back always faces home). |
|
The values are defined in the enum mission_altitude_mode</long_desc> |
|
<min>0</min> |
|
<max>3</max> |
|
</parameter> |
|
</group> |
|
<group name="Multicopter Attitude Control"> |
|
<parameter default="" name="MPP_MAN_R_MAX" type="FLOAT"> |
|
<short_desc>Max manual roll</short_desc> |
|
<min>0.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="" name="MPP_MAN_P_MAX" type="FLOAT"> |
|
<short_desc>Max manual pitch</short_desc> |
|
<min>0.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="" name="MPP_MAN_Y_MAX" type="FLOAT"> |
|
<short_desc>Max manual yaw rate</short_desc> |
|
<min>0.0</min> |
|
<unit>deg/s</unit> |
|
</parameter> |
|
<parameter default="" name="MP_ROLL_P" type="FLOAT"> |
|
<short_desc>Roll P gain</short_desc> |
|
<long_desc>Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="" name="MP_ROLLRATE_P" type="FLOAT"> |
|
<short_desc>Roll rate P gain</short_desc> |
|
<long_desc>Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="" name="MP_ROLLRATE_I" type="FLOAT"> |
|
<short_desc>Roll rate I gain</short_desc> |
|
<long_desc>Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="" name="MP_ROLLRATE_D" type="FLOAT"> |
|
<short_desc>Roll rate D gain</short_desc> |
|
<long_desc>Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="" name="MP_PITCH_P" type="FLOAT"> |
|
<short_desc>Pitch P gain</short_desc> |
|
<long_desc>Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad.</long_desc> |
|
<min>0.0</min> |
|
<unit>1/s</unit> |
|
</parameter> |
|
<parameter default="" name="MP_PITCHRATE_P" type="FLOAT"> |
|
<short_desc>Pitch rate P gain</short_desc> |
|
<long_desc>Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="" name="MP_PITCHRATE_I" type="FLOAT"> |
|
<short_desc>Pitch rate I gain</short_desc> |
|
<long_desc>Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="" name="MP_PITCHRATE_D" type="FLOAT"> |
|
<short_desc>Pitch rate D gain</short_desc> |
|
<long_desc>Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="" name="MP_YAW_P" type="FLOAT"> |
|
<short_desc>Yaw P gain</short_desc> |
|
<long_desc>Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad.</long_desc> |
|
<min>0.0</min> |
|
<unit>1/s</unit> |
|
</parameter> |
|
<parameter default="" name="MP_YAWRATE_P" type="FLOAT"> |
|
<short_desc>Yaw rate P gain</short_desc> |
|
<long_desc>Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="" name="MP_YAWRATE_I" type="FLOAT"> |
|
<short_desc>Yaw rate I gain</short_desc> |
|
<long_desc>Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="" name="MP_YAWRATE_D" type="FLOAT"> |
|
<short_desc>Yaw rate D gain</short_desc> |
|
<long_desc>Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="" name="MP_YAW_FF" type="FLOAT"> |
|
<short_desc>Yaw feed forward</short_desc> |
|
<long_desc>Feed forward weight for manual yaw control. 0 will give slow responce and no overshot, 1 - fast responce and big overshot.</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="" name="MP_YAWRATE_MAX" type="FLOAT"> |
|
<short_desc>Max yaw rate</short_desc> |
|
<long_desc>Limit for yaw rate, has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation.</long_desc> |
|
<min>0.0</min> |
|
<max>360.0</max> |
|
<unit>deg/s</unit> |
|
</parameter> |
|
<parameter default="" name="MP_ACRO_R_MAX" type="FLOAT"> |
|
<short_desc>Max acro roll rate</short_desc> |
|
<min>0.0</min> |
|
<max>360.0</max> |
|
<unit>deg/s</unit> |
|
</parameter> |
|
<parameter default="" name="MP_ACRO_P_MAX" type="FLOAT"> |
|
<short_desc>Max acro pitch rate</short_desc> |
|
<min>0.0</min> |
|
<max>360.0</max> |
|
<unit>deg/s</unit> |
|
</parameter> |
|
<parameter default="" name="MP_ACRO_Y_MAX" type="FLOAT"> |
|
<short_desc>Max acro yaw rate</short_desc> |
|
<min>0.0</min> |
|
<unit>deg/s</unit> |
|
</parameter> |
|
<parameter default="6.0" name="MC_ROLL_P" type="FLOAT"> |
|
<short_desc>Roll P gain</short_desc> |
|
<long_desc>Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="0.1" name="MC_ROLLRATE_P" type="FLOAT"> |
|
<short_desc>Roll rate P gain</short_desc> |
|
<long_desc>Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="0.0" name="MC_ROLLRATE_I" type="FLOAT"> |
|
<short_desc>Roll rate I gain</short_desc> |
|
<long_desc>Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="0.002" name="MC_ROLLRATE_D" type="FLOAT"> |
|
<short_desc>Roll rate D gain</short_desc> |
|
<long_desc>Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="0.0" name="MC_ROLLRATE_FF" type="FLOAT"> |
|
<short_desc>Roll rate feedforward</short_desc> |
|
<long_desc>Improves tracking performance.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="6.0" name="MC_PITCH_P" type="FLOAT"> |
|
<short_desc>Pitch P gain</short_desc> |
|
<long_desc>Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad.</long_desc> |
|
<min>0.0</min> |
|
<unit>1/s</unit> |
|
</parameter> |
|
<parameter default="0.1" name="MC_PITCHRATE_P" type="FLOAT"> |
|
<short_desc>Pitch rate P gain</short_desc> |
|
<long_desc>Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="0.0" name="MC_PITCHRATE_I" type="FLOAT"> |
|
<short_desc>Pitch rate I gain</short_desc> |
|
<long_desc>Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="0.002" name="MC_PITCHRATE_D" type="FLOAT"> |
|
<short_desc>Pitch rate D gain</short_desc> |
|
<long_desc>Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="0.0" name="MC_PITCHRATE_FF" type="FLOAT"> |
|
<short_desc>Pitch rate feedforward</short_desc> |
|
<long_desc>Improves tracking performance.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="2.0" name="MC_YAW_P" type="FLOAT"> |
|
<short_desc>Yaw P gain</short_desc> |
|
<long_desc>Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad.</long_desc> |
|
<min>0.0</min> |
|
<unit>1/s</unit> |
|
</parameter> |
|
<parameter default="0.3" name="MC_YAWRATE_P" type="FLOAT"> |
|
<short_desc>Yaw rate P gain</short_desc> |
|
<long_desc>Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="0.0" name="MC_YAWRATE_I" type="FLOAT"> |
|
<short_desc>Yaw rate I gain</short_desc> |
|
<long_desc>Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="0.0" name="MC_YAWRATE_D" type="FLOAT"> |
|
<short_desc>Yaw rate D gain</short_desc> |
|
<long_desc>Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="0.0" name="MC_YAWRATE_FF" type="FLOAT"> |
|
<short_desc>Yaw rate feedforward</short_desc> |
|
<long_desc>Improves tracking performance.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="0.5" name="MC_YAW_FF" type="FLOAT"> |
|
<short_desc>Yaw feed forward</short_desc> |
|
<long_desc>Feed forward weight for manual yaw control. 0 will give slow responce and no overshot, 1 - fast responce and big overshot.</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="360.0" name="MC_ROLLRATE_MAX" type="FLOAT"> |
|
<short_desc>Max roll rate</short_desc> |
|
<long_desc>Limit for roll rate, has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation.</long_desc> |
|
<min>0.0</min> |
|
<max>360.0</max> |
|
<unit>deg/s</unit> |
|
</parameter> |
|
<parameter default="360.0" name="MC_PITCHRATE_MAX" type="FLOAT"> |
|
<short_desc>Max pitch rate</short_desc> |
|
<long_desc>Limit for pitch rate, has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation.</long_desc> |
|
<min>0.0</min> |
|
<max>360.0</max> |
|
<unit>deg/s</unit> |
|
</parameter> |
|
<parameter default="120.0" name="MC_YAWRATE_MAX" type="FLOAT"> |
|
<short_desc>Max yaw rate</short_desc> |
|
<long_desc>Limit for yaw rate, has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation.</long_desc> |
|
<min>0.0</min> |
|
<max>360.0</max> |
|
<unit>deg/s</unit> |
|
</parameter> |
|
<parameter default="90.0" name="MC_ACRO_R_MAX" type="FLOAT"> |
|
<short_desc>Max acro roll rate</short_desc> |
|
<min>0.0</min> |
|
<max>360.0</max> |
|
<unit>deg/s</unit> |
|
</parameter> |
|
<parameter default="90.0" name="MC_ACRO_P_MAX" type="FLOAT"> |
|
<short_desc>Max acro pitch rate</short_desc> |
|
<min>0.0</min> |
|
<max>360.0</max> |
|
<unit>deg/s</unit> |
|
</parameter> |
|
<parameter default="120.0" name="MC_ACRO_Y_MAX" type="FLOAT"> |
|
<short_desc>Max acro yaw rate</short_desc> |
|
<min>0.0</min> |
|
<unit>deg/s</unit> |
|
</parameter> |
|
</group> |
|
<group name="Multicopter Position Control"> |
|
<parameter default="" name="MPP_THR_MIN" type="FLOAT"> |
|
<short_desc>Minimum thrust</short_desc> |
|
<long_desc>Minimum vertical thrust. It's recommended to set it > 0 to avoid free fall with zero thrust.</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="" name="MPP_THR_MAX" type="FLOAT"> |
|
<short_desc>Maximum thrust</short_desc> |
|
<long_desc>Limit max allowed thrust.</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="" name="MPP_Z_P" type="FLOAT"> |
|
<short_desc>Proportional gain for vertical position error</short_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="" name="MPP_Z_VEL_P" type="FLOAT"> |
|
<short_desc>Proportional gain for vertical velocity error</short_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="" name="MPP_Z_VEL_I" type="FLOAT"> |
|
<short_desc>Integral gain for vertical velocity error</short_desc> |
|
<long_desc>Non zero value allows hovering thrust estimation on stabilized or autonomous takeoff.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="" name="MPP_Z_VEL_D" type="FLOAT"> |
|
<short_desc>Differential gain for vertical velocity error</short_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="" name="MPP_Z_VEL_MAX" type="FLOAT"> |
|
<short_desc>Maximum vertical velocity</short_desc> |
|
<long_desc>Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL).</long_desc> |
|
<min>0.0</min> |
|
<unit>m/s</unit> |
|
</parameter> |
|
<parameter default="" name="MPP_Z_FF" type="FLOAT"> |
|
<short_desc>Vertical velocity feed forward</short_desc> |
|
<long_desc>Feed forward weight for altitude control in stabilized modes (ALTCTRL). 0 will give slow responce and no overshot, 1 - fast responce and big overshot.</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="" name="MPP_XY_P" type="FLOAT"> |
|
<short_desc>Proportional gain for horizontal position error</short_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="" name="MPP_XY_VEL_P" type="FLOAT"> |
|
<short_desc>Proportional gain for horizontal velocity error</short_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="" name="MPP_XY_VEL_I" type="FLOAT"> |
|
<short_desc>Integral gain for horizontal velocity error</short_desc> |
|
<long_desc>Non-zero value allows to resist wind.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="" name="MPP_XY_VEL_D" type="FLOAT"> |
|
<short_desc>Differential gain for horizontal velocity error. Small values help reduce fast oscillations. If value is too big oscillations will appear again</short_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="" name="MPP_XY_VEL_MAX" type="FLOAT"> |
|
<short_desc>Maximum horizontal velocity</short_desc> |
|
<long_desc>Maximum horizontal velocity in AUTO mode and endpoint for position stabilized mode (POSCTRL).</long_desc> |
|
<min>0.0</min> |
|
<unit>m/s</unit> |
|
</parameter> |
|
<parameter default="" name="MPP_XY_FF" type="FLOAT"> |
|
<short_desc>Horizontal velocity feed forward</short_desc> |
|
<long_desc>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.</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="" name="MPP_TILTMAX_AIR" type="FLOAT"> |
|
<short_desc>Maximum tilt angle in air</short_desc> |
|
<long_desc>Limits maximum tilt in AUTO and POSCTRL modes during flight.</long_desc> |
|
<min>0.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="" name="MPP_TILTMAX_LND" type="FLOAT"> |
|
<short_desc>Maximum tilt during landing</short_desc> |
|
<long_desc>Limits maximum tilt angle on landing.</long_desc> |
|
<min>0.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="" name="MPP_LAND_SPEED" type="FLOAT"> |
|
<short_desc>Landing descend rate</short_desc> |
|
<min>0.0</min> |
|
<unit>m/s</unit> |
|
</parameter> |
|
<parameter default="0.1" name="MPC_THR_MIN" type="FLOAT"> |
|
<short_desc>Minimum thrust</short_desc> |
|
<long_desc>Minimum vertical thrust. It's recommended to set it > 0 to avoid free fall with zero thrust.</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="MPC_THR_MAX" type="FLOAT"> |
|
<short_desc>Maximum thrust</short_desc> |
|
<long_desc>Limit max allowed thrust.</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="MPC_Z_P" type="FLOAT"> |
|
<short_desc>Proportional gain for vertical position error</short_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="0.1" name="MPC_Z_VEL_P" type="FLOAT"> |
|
<short_desc>Proportional gain for vertical velocity error</short_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="0.02" name="MPC_Z_VEL_I" type="FLOAT"> |
|
<short_desc>Integral gain for vertical velocity error</short_desc> |
|
<long_desc>Non zero value allows hovering thrust estimation on stabilized or autonomous takeoff.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="0.0" name="MPC_Z_VEL_D" type="FLOAT"> |
|
<short_desc>Differential gain for vertical velocity error</short_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="5.0" name="MPC_Z_VEL_MAX" type="FLOAT"> |
|
<short_desc>Maximum vertical velocity</short_desc> |
|
<long_desc>Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL, POSCTRL).</long_desc> |
|
<min>0.0</min> |
|
<unit>m/s</unit> |
|
</parameter> |
|
<parameter default="0.5" name="MPC_Z_FF" type="FLOAT"> |
|
<short_desc>Vertical velocity feed forward</short_desc> |
|
<long_desc>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.</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="MPC_XY_P" type="FLOAT"> |
|
<short_desc>Proportional gain for horizontal position error</short_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="0.1" name="MPC_XY_VEL_P" type="FLOAT"> |
|
<short_desc>Proportional gain for horizontal velocity error</short_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="0.02" name="MPC_XY_VEL_I" type="FLOAT"> |
|
<short_desc>Integral gain for horizontal velocity error</short_desc> |
|
<long_desc>Non-zero value allows to resist wind.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="0.01" name="MPC_XY_VEL_D" type="FLOAT"> |
|
<short_desc>Differential gain for horizontal velocity error. Small values help reduce fast oscillations. If value is too big oscillations will appear again</short_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="5.0" name="MPC_XY_VEL_MAX" type="FLOAT"> |
|
<short_desc>Maximum horizontal velocity</short_desc> |
|
<long_desc>Maximum horizontal velocity in AUTO mode and endpoint for position stabilized mode (POSCTRL).</long_desc> |
|
<min>0.0</min> |
|
<unit>m/s</unit> |
|
</parameter> |
|
<parameter default="0.5" name="MPC_XY_FF" type="FLOAT"> |
|
<short_desc>Horizontal velocity feed forward</short_desc> |
|
<long_desc>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.</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="45.0" name="MPC_TILTMAX_AIR" type="FLOAT"> |
|
<short_desc>Maximum tilt angle in air</short_desc> |
|
<long_desc>Limits maximum tilt in AUTO and POSCTRL modes during flight.</long_desc> |
|
<min>0.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="15.0" name="MPC_TILTMAX_LND" type="FLOAT"> |
|
<short_desc>Maximum tilt during landing</short_desc> |
|
<long_desc>Limits maximum tilt angle on landing.</long_desc> |
|
<min>0.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="1.0" name="MPC_LAND_SPEED" type="FLOAT"> |
|
<short_desc>Landing descend rate</short_desc> |
|
<min>0.0</min> |
|
<unit>m/s</unit> |
|
</parameter> |
|
<parameter default="35.0" name="MPC_MAN_R_MAX" type="FLOAT"> |
|
<short_desc>Max manual roll</short_desc> |
|
<min>0.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="35.0" name="MPC_MAN_P_MAX" type="FLOAT"> |
|
<short_desc>Max manual pitch</short_desc> |
|
<min>0.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="120.0" name="MPC_MAN_Y_MAX" type="FLOAT"> |
|
<short_desc>Max manual yaw rate</short_desc> |
|
<min>0.0</min> |
|
<unit>deg/s</unit> |
|
</parameter> |
|
</group> |
|
<group name="PWM Outputs"> |
|
<parameter default="0" name="PWM_AUX_REV1" type="INT32"> |
|
<short_desc>Invert direction of aux output channel 1</short_desc> |
|
<long_desc>Set to 1 to invert the channel, 0 for default direction.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0" name="PWM_AUX_REV2" type="INT32"> |
|
<short_desc>Invert direction of aux output channel 2</short_desc> |
|
<long_desc>Set to 1 to invert the channel, 0 for default direction.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0" name="PWM_AUX_REV3" type="INT32"> |
|
<short_desc>Invert direction of aux output channel 3</short_desc> |
|
<long_desc>Set to 1 to invert the channel, 0 for default direction.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0" name="PWM_AUX_REV4" type="INT32"> |
|
<short_desc>Invert direction of aux output channel 4</short_desc> |
|
<long_desc>Set to 1 to invert the channel, 0 for default direction.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0" name="PWM_AUX_REV5" type="INT32"> |
|
<short_desc>Invert direction of aux output channel 5</short_desc> |
|
<long_desc>Set to 1 to invert the channel, 0 for default direction.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0" name="PWM_AUX_REV6" type="INT32"> |
|
<short_desc>Invert direction of aux output channel 6</short_desc> |
|
<long_desc>Set to 1 to invert the channel, 0 for default direction.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0" name="PWM_MAIN_REV1" type="INT32"> |
|
<short_desc>Invert direction of main output channel 1</short_desc> |
|
<long_desc>Set to 1 to invert the channel, 0 for default direction.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0" name="PWM_MAIN_REV2" type="INT32"> |
|
<short_desc>Invert direction of main output channel 2</short_desc> |
|
<long_desc>Set to 1 to invert the channel, 0 for default direction.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0" name="PWM_MAIN_REV3" type="INT32"> |
|
<short_desc>Invert direction of main output channel 3</short_desc> |
|
<long_desc>Set to 1 to invert the channel, 0 for default direction.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0" name="PWM_MAIN_REV4" type="INT32"> |
|
<short_desc>Invert direction of main output channel 4</short_desc> |
|
<long_desc>Set to 1 to invert the channel, 0 for default direction.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0" name="PWM_MAIN_REV5" type="INT32"> |
|
<short_desc>Invert direction of main output channel 5</short_desc> |
|
<long_desc>Set to 1 to invert the channel, 0 for default direction.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0" name="PWM_MAIN_REV6" type="INT32"> |
|
<short_desc>Invert direction of main output channel 6</short_desc> |
|
<long_desc>Set to 1 to invert the channel, 0 for default direction.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0" name="PWM_MAIN_REV7" type="INT32"> |
|
<short_desc>Invert direction of main output channel 7</short_desc> |
|
<long_desc>Set to 1 to invert the channel, 0 for default direction.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0" name="PWM_MAIN_REV8" type="INT32"> |
|
<short_desc>Invert direction of main output channel 8</short_desc> |
|
<long_desc>Set to 1 to invert the channel, 0 for default direction.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
</group> |
|
<group name="Payload drop"> |
|
<parameter default="0.03" name="BD_GPROPERTIES" type="FLOAT"> |
|
<short_desc>Ground drag property</short_desc> |
|
<long_desc>This parameter encodes the ground drag coefficient and the corresponding |
|
decrease in wind speed from the plane altitude to ground altitude.</long_desc> |
|
<min>0.001</min> |
|
<max>0.1</max> |
|
<unit>unknown</unit> |
|
</parameter> |
|
<parameter default="120.0" name="BD_TURNRADIUS" type="FLOAT"> |
|
<short_desc>Plane turn radius</short_desc> |
|
<long_desc>The planes known minimal turn radius - use a higher value |
|
to make the plane maneuver more distant from the actual drop |
|
position. This is to ensure the wings are level during the drop.</long_desc> |
|
<min>30.0</min> |
|
<max>500.0</max> |
|
<unit>meter</unit> |
|
</parameter> |
|
<parameter default="30.0" name="BD_PRECISION" type="FLOAT"> |
|
<short_desc>Drop precision</short_desc> |
|
<long_desc>If the system is closer than this distance on passing over the |
|
drop position, it will release the payload. This is a safeguard |
|
to prevent a drop out of the required accuracy.</long_desc> |
|
<min>1.0</min> |
|
<max>80.0</max> |
|
<unit>meter</unit> |
|
</parameter> |
|
<parameter default="0.1" name="BD_OBJ_CD" type="FLOAT"> |
|
<short_desc>Payload drag coefficient of the dropped object</short_desc> |
|
<long_desc>The drag coefficient (cd) is the typical drag |
|
constant for air. It is in general object specific, |
|
but the closest primitive shape to the actual object |
|
should give good results: |
|
http://en.wikipedia.org/wiki/Drag_coefficient</long_desc> |
|
<min>0.08</min> |
|
<max>1.5</max> |
|
<unit>meter</unit> |
|
</parameter> |
|
<parameter default="0.6" name="BD_OBJ_MASS" type="FLOAT"> |
|
<short_desc>Payload mass</short_desc> |
|
<long_desc>A typical small toy ball: |
|
0.025 kg |
|
OBC water bottle: |
|
0.6 kg</long_desc> |
|
<min>0.001</min> |
|
<max>5.0</max> |
|
<unit>kilogram</unit> |
|
</parameter> |
|
<parameter default="0.00311724531" name="BD_OBJ_SURFACE" type="FLOAT"> |
|
<short_desc>Payload front surface area</short_desc> |
|
<long_desc>A typical small toy ball: |
|
(0.045 * 0.045) / 4.0 * pi = 0.001590 m^2 |
|
OBC water bottle: |
|
(0.063 * 0.063) / 4.0 * pi = 0.003117 m^2</long_desc> |
|
<min>0.001</min> |
|
<max>0.5</max> |
|
<unit>m^2</unit> |
|
</parameter> |
|
</group> |
|
<group name="Position Estimator"> |
|
<parameter default="230" name="PE_VEL_DELAY_MS" type="INT32"> |
|
<short_desc>Velocity estimate delay</short_desc> |
|
<long_desc>The delay in milliseconds of the velocity estimate from GPS.</long_desc> |
|
<min>0</min> |
|
<max>1000</max> |
|
</parameter> |
|
<parameter default="210" name="PE_POS_DELAY_MS" type="INT32"> |
|
<short_desc>Position estimate delay</short_desc> |
|
<long_desc>The delay in milliseconds of the position estimate from GPS.</long_desc> |
|
<min>0</min> |
|
<max>1000</max> |
|
</parameter> |
|
<parameter default="350" name="PE_HGT_DELAY_MS" type="INT32"> |
|
<short_desc>Height estimate delay</short_desc> |
|
<long_desc>The delay in milliseconds of the height estimate from the barometer.</long_desc> |
|
<min>0</min> |
|
<max>1000</max> |
|
</parameter> |
|
<parameter default="30" name="PE_MAG_DELAY_MS" type="INT32"> |
|
<short_desc>Mag estimate delay</short_desc> |
|
<long_desc>The delay in milliseconds of the magnetic field estimate from |
|
the magnetometer.</long_desc> |
|
<min>0</min> |
|
<max>1000</max> |
|
</parameter> |
|
<parameter default="210" name="PE_TAS_DELAY_MS" type="INT32"> |
|
<short_desc>True airspeeed estimate delay</short_desc> |
|
<long_desc>The delay in milliseconds of the airspeed estimate.</long_desc> |
|
<min>0</min> |
|
<max>1000</max> |
|
</parameter> |
|
<parameter default="0.9" name="PE_GPS_ALT_WGT" type="FLOAT"> |
|
<short_desc>GPS vs. barometric altitude update weight</short_desc> |
|
<long_desc>RE-CHECK this.</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="1.4" name="PE_EAS_NOISE" type="FLOAT"> |
|
<short_desc>Airspeed measurement noise</short_desc> |
|
<long_desc>Increasing this value will make the filter trust this sensor |
|
less and trust other sensors more.</long_desc> |
|
<min>0.5</min> |
|
<max>5.0</max> |
|
</parameter> |
|
<parameter default="0.3" name="PE_VELNE_NOISE" type="FLOAT"> |
|
<short_desc>Velocity measurement noise in north-east (horizontal) direction</short_desc> |
|
<long_desc>Generic default: 0.3, multicopters: 0.5, ground vehicles: 0.5</long_desc> |
|
<min>0.05</min> |
|
<max>5.0</max> |
|
</parameter> |
|
<parameter default="0.5" name="PE_VELD_NOISE" type="FLOAT"> |
|
<short_desc>Velocity noise in down (vertical) direction</short_desc> |
|
<long_desc>Generic default: 0.5, multicopters: 0.7, ground vehicles: 0.7</long_desc> |
|
<min>0.05</min> |
|
<max>5.0</max> |
|
</parameter> |
|
<parameter default="0.5" name="PE_POSNE_NOISE" type="FLOAT"> |
|
<short_desc>Position noise in north-east (horizontal) direction</short_desc> |
|
<long_desc>Generic defaults: 0.5, multicopters: 0.5, ground vehicles: 0.5</long_desc> |
|
<min>0.1</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.5" name="PE_POSD_NOISE" type="FLOAT"> |
|
<short_desc>Position noise in down (vertical) direction</short_desc> |
|
<long_desc>Generic defaults: 0.5, multicopters: 1.0, ground vehicles: 1.0</long_desc> |
|
<min>0.1</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.05" name="PE_MAG_NOISE" type="FLOAT"> |
|
<short_desc>Magnetometer measurement noise</short_desc> |
|
<long_desc>Generic defaults: 0.05, multicopters: 0.05, ground vehicles: 0.05</long_desc> |
|
<min>0.1</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.015" name="PE_GYRO_PNOISE" type="FLOAT"> |
|
<short_desc>Gyro process noise</short_desc> |
|
<long_desc>Generic defaults: 0.015, multicopters: 0.015, ground vehicles: 0.015. |
|
This noise controls how much the filter trusts the gyro measurements. |
|
Increasing it makes the filter trust the gyro less and other sensors more.</long_desc> |
|
<min>0.001</min> |
|
<max>0.05</max> |
|
</parameter> |
|
<parameter default="0.25" name="PE_ACC_PNOISE" type="FLOAT"> |
|
<short_desc>Accelerometer process noise</short_desc> |
|
<long_desc>Generic defaults: 0.25, multicopters: 0.25, ground vehicles: 0.25. |
|
Increasing this value makes the filter trust the accelerometer less |
|
and other sensors more.</long_desc> |
|
<min>0.05</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="1e-06" name="PE_GBIAS_PNOISE" type="FLOAT"> |
|
<short_desc>Gyro bias estimate process noise</short_desc> |
|
<long_desc>Generic defaults: 1e-07f, multicopters: 1e-07f, ground vehicles: 1e-07f. |
|
Increasing this value will make the gyro bias converge faster but noisier.</long_desc> |
|
<min>0.0000001</min> |
|
<max>0.00001</max> |
|
</parameter> |
|
<parameter default="0.0002" name="PE_ABIAS_PNOISE" type="FLOAT"> |
|
<short_desc>Accelerometer bias estimate process noise</short_desc> |
|
<long_desc>Generic defaults: 0.0001f, multicopters: 0.0001f, ground vehicles: 0.0001f. |
|
Increasing this value makes the bias estimation faster and noisier.</long_desc> |
|
<min>0.00001</min> |
|
<max>0.001</max> |
|
</parameter> |
|
<parameter default="0.0003" name="PE_MAGE_PNOISE" type="FLOAT"> |
|
<short_desc>Magnetometer earth frame offsets process noise</short_desc> |
|
<long_desc>Generic defaults: 0.0001, multicopters: 0.0001, ground vehicles: 0.0001. |
|
Increasing this value makes the magnetometer earth bias estimate converge |
|
faster but also noisier.</long_desc> |
|
<min>0.0001</min> |
|
<max>0.01</max> |
|
</parameter> |
|
<parameter default="0.0003" name="PE_MAGB_PNOISE" type="FLOAT"> |
|
<short_desc>Magnetometer body frame offsets process noise</short_desc> |
|
<long_desc>Generic defaults: 0.0003, multicopters: 0.0003, ground vehicles: 0.0003. |
|
Increasing this value makes the magnetometer body bias estimate converge faster |
|
but also noisier.</long_desc> |
|
<min>0.0001</min> |
|
<max>0.01</max> |
|
</parameter> |
|
<parameter default="5.0" name="PE_POSDEV_INIT" type="FLOAT"> |
|
<short_desc>Threshold for filter initialization</short_desc> |
|
<long_desc>If the standard deviation of the GPS position estimate is below this threshold |
|
in meters, the filter will initialize.</long_desc> |
|
<min>0.3</min> |
|
<max>10.0</max> |
|
</parameter> |
|
</group> |
|
<group name="Position Estimator INAV"> |
|
<parameter default="0.5" name="INAV_W_Z_BARO" type="FLOAT"> |
|
<short_desc>Z axis weight for barometer</short_desc> |
|
<long_desc>Weight (cutoff frequency) for barometer altitude measurements.</long_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.005" name="INAV_W_Z_GPS_P" type="FLOAT"> |
|
<short_desc>Z axis weight for GPS</short_desc> |
|
<long_desc>Weight (cutoff frequency) for GPS altitude measurements. GPS altitude data is very noisy and should be used only as slow correction for baro offset.</long_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="INAV_W_Z_GPS_V" type="FLOAT"> |
|
<short_desc>Z velocity weight for GPS</short_desc> |
|
<long_desc>Weight (cutoff frequency) for GPS altitude velocity measurements.</long_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="5.0" name="INAV_W_Z_VIS_P" type="FLOAT"> |
|
<short_desc>Z axis weight for vision</short_desc> |
|
<long_desc>Weight (cutoff frequency) for vision altitude measurements. vision altitude data is very noisy and should be used only as slow correction for baro offset.</long_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="INAV_W_Z_VIS_V" type="FLOAT"> |
|
<short_desc>Z velocity weight for vision</short_desc> |
|
<long_desc>Weight (cutoff frequency) for vision altitude velocity measurements.</long_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="3.0" name="INAV_W_Z_SONAR" type="FLOAT"> |
|
<short_desc>Z axis weight for sonar</short_desc> |
|
<long_desc>Weight (cutoff frequency) for sonar measurements.</long_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="INAV_W_XY_GPS_P" type="FLOAT"> |
|
<short_desc>XY axis weight for GPS position</short_desc> |
|
<long_desc>Weight (cutoff frequency) for GPS position measurements.</long_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="2.0" name="INAV_W_XY_GPS_V" type="FLOAT"> |
|
<short_desc>XY axis weight for GPS velocity</short_desc> |
|
<long_desc>Weight (cutoff frequency) for GPS velocity measurements.</long_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="7.0" name="INAV_W_XY_VIS_P" type="FLOAT"> |
|
<short_desc>XY axis weight for vision position</short_desc> |
|
<long_desc>Weight (cutoff frequency) for vision position measurements.</long_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="INAV_W_XY_VIS_V" type="FLOAT"> |
|
<short_desc>XY axis weight for vision velocity</short_desc> |
|
<long_desc>Weight (cutoff frequency) for vision velocity measurements.</long_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="5.0" name="INAV_W_XY_FLOW" type="FLOAT"> |
|
<short_desc>XY axis weight for optical flow</short_desc> |
|
<long_desc>Weight (cutoff frequency) for optical flow (velocity) measurements.</long_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.5" name="INAV_W_XY_RES_V" type="FLOAT"> |
|
<short_desc>XY axis weight for resetting velocity</short_desc> |
|
<long_desc>When velocity sources lost slowly decrease estimated horizontal velocity with this weight.</long_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.1" name="INAV_W_GPS_FLOW" type="FLOAT"> |
|
<short_desc>XY axis weight factor for GPS when optical flow available</short_desc> |
|
<long_desc>When optical flow data available, multiply GPS weights (for position and velocity) by this factor.</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="0.05" name="INAV_W_ACC_BIAS" type="FLOAT"> |
|
<short_desc>Accelerometer bias estimation weight</short_desc> |
|
<long_desc>Weight (cutoff frequency) for accelerometer bias estimation. 0 to disable.</long_desc> |
|
<min>0.0</min> |
|
<max>0.1</max> |
|
</parameter> |
|
<parameter default="0.15" name="INAV_FLOW_K" type="FLOAT"> |
|
<short_desc>Optical flow scale factor</short_desc> |
|
<long_desc>Factor to convert raw optical flow (in pixels) to radians [rad/px].</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
<unit>rad/px</unit> |
|
</parameter> |
|
<parameter default="0.5" name="INAV_FLOW_Q_MIN" type="FLOAT"> |
|
<short_desc>Minimal acceptable optical flow quality</short_desc> |
|
<long_desc>0 - lowest quality, 1 - best quality.</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="0.05" name="INAV_SONAR_FILT" type="FLOAT"> |
|
<short_desc>Weight for sonar filter</short_desc> |
|
<long_desc>Sonar filter detects spikes on sonar measurements and used to detect new surface level.</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="0.5" name="INAV_SONAR_ERR" type="FLOAT"> |
|
<short_desc>Sonar maximal error for new surface</short_desc> |
|
<long_desc>If sonar measurement error is larger than this value it skiped (spike) or accepted as new surface level (if offset is stable).</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
<unit>m</unit> |
|
</parameter> |
|
<parameter default="3.0" name="INAV_LAND_T" type="FLOAT"> |
|
<short_desc>Land detector time</short_desc> |
|
<long_desc>Vehicle assumed landed if no altitude changes happened during this time on low throttle.</long_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
<unit>s</unit> |
|
</parameter> |
|
<parameter default="0.7" name="INAV_LAND_DISP" type="FLOAT"> |
|
<short_desc>Land detector altitude dispersion threshold</short_desc> |
|
<long_desc>Dispersion threshold for triggering land detector.</long_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
<unit>m</unit> |
|
</parameter> |
|
<parameter default="0.2" name="INAV_LAND_THR" type="FLOAT"> |
|
<short_desc>Land detector throttle threshold</short_desc> |
|
<long_desc>Value should be lower than minimal hovering thrust. Half of it is good choice.</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="0.2" name="INAV_DELAY_GPS" type="FLOAT"> |
|
<short_desc>GPS delay</short_desc> |
|
<long_desc>GPS delay compensation</long_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
<unit>s</unit> |
|
</parameter> |
|
<parameter default="0" name="CBRK_NO_VISION" type="INT32"> |
|
<short_desc>Disable vision input</short_desc> |
|
<long_desc>Set to the appropriate key (328754) to disable vision input.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="1" name="INAV_ENABLED" type="INT32"> |
|
<short_desc>INAV enabled</short_desc> |
|
<long_desc>If set to 1, use INAV for position estimation. |
|
Else the system uses the combined attitude / position |
|
filter framework.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
</group> |
|
<group name="Radio Calibration"> |
|
<parameter default="1000.0" name="RC1_MIN" type="FLOAT"> |
|
<short_desc>RC Channel 1 Minimum</short_desc> |
|
<long_desc>Minimum value for RC channel 1</long_desc> |
|
<min>800.0</min> |
|
<max>1500.0</max> |
|
</parameter> |
|
<parameter default="1500.0" name="RC1_TRIM" type="FLOAT"> |
|
<short_desc>RC Channel 1 Trim</short_desc> |
|
<long_desc>Mid point value (same as min for throttle)</long_desc> |
|
<min>800.0</min> |
|
<max>2200.0</max> |
|
</parameter> |
|
<parameter default="2000.0" name="RC1_MAX" type="FLOAT"> |
|
<short_desc>RC Channel 1 Maximum</short_desc> |
|
<long_desc>Maximum value for RC channel 1</long_desc> |
|
<min>1500.0</min> |
|
<max>2200.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="RC1_REV" type="FLOAT"> |
|
<short_desc>RC Channel 1 Reverse</short_desc> |
|
<long_desc>Set to -1 to reverse channel.</long_desc> |
|
<min>-1.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="10.0" name="RC1_DZ" type="FLOAT"> |
|
<short_desc>RC Channel 1 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1000.0" name="RC2_MIN" type="FLOAT"> |
|
<short_desc>RC Channel 2 Minimum</short_desc> |
|
<long_desc>Minimum value for RC channel 2</long_desc> |
|
<min>800.0</min> |
|
<max>1500.0</max> |
|
</parameter> |
|
<parameter default="1500.0" name="RC2_TRIM" type="FLOAT"> |
|
<short_desc>RC Channel 2 Trim</short_desc> |
|
<long_desc>Mid point value (same as min for throttle)</long_desc> |
|
<min>800.0</min> |
|
<max>2200.0</max> |
|
</parameter> |
|
<parameter default="2000.0" name="RC2_MAX" type="FLOAT"> |
|
<short_desc>RC Channel 2 Maximum</short_desc> |
|
<long_desc>Maximum value for RC channel 2</long_desc> |
|
<min>1500.0</min> |
|
<max>2200.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="RC2_REV" type="FLOAT"> |
|
<short_desc>RC Channel 2 Reverse</short_desc> |
|
<long_desc>Set to -1 to reverse channel.</long_desc> |
|
<min>-1.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="10.0" name="RC2_DZ" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1000" name="RC3_MIN" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1500" name="RC3_TRIM" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="2000" name="RC3_MAX" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="RC3_REV" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="10.0" name="RC3_DZ" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1000" name="RC4_MIN" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1500" name="RC4_TRIM" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="2000" name="RC4_MAX" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="RC4_REV" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="10.0" name="RC4_DZ" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1000" name="RC5_MIN" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1500" name="RC5_TRIM" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="2000" name="RC5_MAX" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="RC5_REV" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="10.0" name="RC5_DZ" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1000" name="RC6_MIN" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1500" name="RC6_TRIM" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="2000" name="RC6_MAX" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="RC6_REV" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="10.0" name="RC6_DZ" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1000" name="RC7_MIN" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1500" name="RC7_TRIM" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="2000" name="RC7_MAX" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="RC7_REV" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="10.0" name="RC7_DZ" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1000" name="RC8_MIN" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1500" name="RC8_TRIM" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="2000" name="RC8_MAX" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="RC8_REV" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="10.0" name="RC8_DZ" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1000" name="RC9_MIN" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1500" name="RC9_TRIM" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="2000" name="RC9_MAX" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="RC9_REV" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="RC9_DZ" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1000" name="RC10_MIN" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1500" name="RC10_TRIM" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="2000" name="RC10_MAX" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="RC10_REV" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="RC10_DZ" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1000" name="RC11_MIN" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1500" name="RC11_TRIM" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="2000" name="RC11_MAX" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="RC11_REV" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="RC11_DZ" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1000" name="RC12_MIN" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1500" name="RC12_TRIM" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="2000" name="RC12_MAX" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="RC12_REV" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="RC12_DZ" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1000" name="RC13_MIN" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1500" name="RC13_TRIM" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="2000" name="RC13_MAX" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="RC13_REV" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="RC13_DZ" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1000" name="RC14_MIN" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1500" name="RC14_TRIM" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="2000" name="RC14_MAX" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="RC14_REV" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="RC14_DZ" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1000" name="RC15_MIN" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1500" name="RC15_TRIM" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="2000" name="RC15_MAX" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="RC15_REV" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="RC15_DZ" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1000" name="RC16_MIN" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1500" name="RC16_TRIM" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="2000" name="RC16_MAX" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="RC16_REV" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="RC16_DZ" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1000" name="RC17_MIN" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1500" name="RC17_TRIM" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="2000" name="RC17_MAX" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="RC17_REV" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="RC17_DZ" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1000" name="RC18_MIN" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1500" name="RC18_TRIM" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="2000" name="RC18_MAX" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="RC18_REV" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="RC18_DZ" type="FLOAT"> |
|
<short_desc>RC Channel 2 dead zone</short_desc> |
|
<long_desc>The +- range of this value around the trim value will be considered as zero.</long_desc> |
|
<min>0.0</min> |
|
<max>100.0</max> |
|
</parameter> |
|
<parameter default="-1" name="RC_DSM_BIND" type="INT32"> |
|
<short_desc>DSM binding trigger</short_desc> |
|
<long_desc>-1 = Idle, 0 = Start DSM2 bind, 1 = Start DSMX bind</long_desc> |
|
</parameter> |
|
<parameter default="0" name="RC_CHAN_CNT" type="INT32"> |
|
<short_desc>RC channel count</short_desc> |
|
<long_desc>This parameter is used by Ground Station software to save the number |
|
of channels which were used during RC calibration. It is only meant |
|
for ground station use.</long_desc> |
|
<min>0</min> |
|
<max>18</max> |
|
</parameter> |
|
<parameter default="1" name="RC_TH_USER" type="INT32"> |
|
<short_desc>RC mode switch threshold automaic distribution</short_desc> |
|
<long_desc>This parameter is used by Ground Station software to specify whether |
|
the threshold values for flight mode switches were automatically calculated. |
|
0 indicates that the threshold values were set by the user. Any other value |
|
indicates that the threshold value where automatically set by the ground |
|
station software. It is only meant for ground station use.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="1" name="RC_MAP_ROLL" type="INT32"> |
|
<short_desc>Roll control channel mapping</short_desc> |
|
<long_desc>The channel index (starting from 1 for channel 1) indicates |
|
which channel should be used for reading roll inputs from. |
|
A value of zero indicates the switch is not assigned.</long_desc> |
|
<min>0</min> |
|
<max>18</max> |
|
</parameter> |
|
<parameter default="2" name="RC_MAP_PITCH" type="INT32"> |
|
<short_desc>Pitch control channel mapping</short_desc> |
|
<long_desc>The channel index (starting from 1 for channel 1) indicates |
|
which channel should be used for reading pitch inputs from. |
|
A value of zero indicates the switch is not assigned.</long_desc> |
|
<min>0</min> |
|
<max>18</max> |
|
</parameter> |
|
<parameter default="3" name="RC_MAP_THROTTLE" type="INT32"> |
|
<short_desc>Throttle control channel mapping</short_desc> |
|
<long_desc>The channel index (starting from 1 for channel 1) indicates |
|
which channel should be used for reading throttle inputs from. |
|
A value of zero indicates the switch is not assigned.</long_desc> |
|
<min>0</min> |
|
<max>18</max> |
|
</parameter> |
|
<parameter default="4" name="RC_MAP_YAW" type="INT32"> |
|
<short_desc>Yaw control channel mapping</short_desc> |
|
<long_desc>The channel index (starting from 1 for channel 1) indicates |
|
which channel should be used for reading yaw inputs from. |
|
A value of zero indicates the switch is not assigned.</long_desc> |
|
<min>0</min> |
|
<max>18</max> |
|
</parameter> |
|
<parameter default="0" name="RC_MAP_AUX1" type="INT32"> |
|
<short_desc>Auxiliary switch 1 channel mapping</short_desc> |
|
<long_desc>Default function: Camera pitch</long_desc> |
|
<min>0</min> |
|
<max>18</max> |
|
</parameter> |
|
<parameter default="0" name="RC_MAP_AUX2" type="INT32"> |
|
<short_desc>Auxiliary switch 2 channel mapping</short_desc> |
|
<long_desc>Default function: Camera roll</long_desc> |
|
<min>0</min> |
|
<max>18</max> |
|
</parameter> |
|
<parameter default="0" name="RC_MAP_AUX3" type="INT32"> |
|
<short_desc>Auxiliary switch 3 channel mapping</short_desc> |
|
<long_desc>Default function: Camera azimuth / yaw</long_desc> |
|
<min>0</min> |
|
<max>18</max> |
|
</parameter> |
|
<parameter default="0" name="RC_MAP_PARAM1" type="INT32"> |
|
<short_desc>Channel which changes a parameter</short_desc> |
|
<long_desc>Can be used for parameter tuning with the RC. This one is further referenced as the 1st parameter channel. |
|
Set to 0 to deactivate *</long_desc> |
|
<min>0</min> |
|
<max>18</max> |
|
</parameter> |
|
<parameter default="0" name="RC_MAP_PARAM2" type="INT32"> |
|
<short_desc>Channel which changes a parameter</short_desc> |
|
<long_desc>Can be used for parameter tuning with the RC. This one is further referenced as the 2nd parameter channel. |
|
Set to 0 to deactivate *</long_desc> |
|
<min>0</min> |
|
<max>18</max> |
|
</parameter> |
|
<parameter default="0" name="RC_MAP_PARAM3" type="INT32"> |
|
<short_desc>Channel which changes a parameter</short_desc> |
|
<long_desc>Can be used for parameter tuning with the RC. This one is further referenced as the 3th parameter channel. |
|
Set to 0 to deactivate *</long_desc> |
|
<min>0</min> |
|
<max>18</max> |
|
</parameter> |
|
<parameter default="0" name="RC_FAILS_THR" type="INT32"> |
|
<short_desc>Failsafe channel PWM threshold</short_desc> |
|
<min>800</min> |
|
<max>2200</max> |
|
</parameter> |
|
<parameter default="0" name="RC_RSSI_PWM_CHAN" type="INT32"> |
|
<short_desc>PWM input channel that provides RSSI</short_desc> |
|
<long_desc>0: do not read RSSI from input channel |
|
1-18: read RSSI from specified input channel |
|
Specify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters.</long_desc> |
|
<min>0</min> |
|
<max>18</max> |
|
</parameter> |
|
<parameter default="1000" name="RC_RSSI_PWM_MAX" type="INT32"> |
|
<short_desc>Max input value for RSSI reading</short_desc> |
|
<long_desc>Only used if RC_RSSI_PWM_CHAN > 0</long_desc> |
|
<min>0</min> |
|
<max>2000</max> |
|
</parameter> |
|
<parameter default="2000" name="RC_RSSI_PWM_MIN" type="INT32"> |
|
<short_desc>Min input value for RSSI reading</short_desc> |
|
<long_desc>Only used if RC_RSSI_PWM_CHAN > 0</long_desc> |
|
<min>0</min> |
|
<max>2000</max> |
|
</parameter> |
|
</group> |
|
<group name="Radio Signal Loss"> |
|
<parameter default="120.0" name="NAV_RCL_LT" type="FLOAT"> |
|
<short_desc>Loiter Time</short_desc> |
|
<long_desc>The amount of time in seconds the system should loiter at current position before termination |
|
Set to -1 to make the system skip loitering</long_desc> |
|
<min>-1.0</min> |
|
<unit>seconds</unit> |
|
</parameter> |
|
</group> |
|
<group name="Radio Switches"> |
|
<parameter default="0" name="RC_MAP_MODE_SW" type="INT32"> |
|
<short_desc>Mode switch channel mapping</short_desc> |
|
<long_desc>This is the main flight mode selector. |
|
The channel index (starting from 1 for channel 1) indicates |
|
which channel should be used for deciding about the main mode. |
|
A value of zero indicates the switch is not assigned.</long_desc> |
|
<min>0</min> |
|
<max>18</max> |
|
</parameter> |
|
<parameter default="0" name="RC_MAP_RETURN_SW" type="INT32"> |
|
<short_desc>Return switch channel mapping</short_desc> |
|
<min>0</min> |
|
<max>18</max> |
|
</parameter> |
|
<parameter default="0" name="RC_MAP_POSCTL_SW" type="INT32"> |
|
<short_desc>Posctl switch channel mapping</short_desc> |
|
<min>0</min> |
|
<max>18</max> |
|
</parameter> |
|
<parameter default="0" name="RC_MAP_LOITER_SW" type="INT32"> |
|
<short_desc>Loiter switch channel mapping</short_desc> |
|
<min>0</min> |
|
<max>18</max> |
|
</parameter> |
|
<parameter default="0" name="RC_MAP_ACRO_SW" type="INT32"> |
|
<short_desc>Acro switch channel mapping</short_desc> |
|
<min>0</min> |
|
<max>18</max> |
|
</parameter> |
|
<parameter default="0" name="RC_MAP_OFFB_SW" type="INT32"> |
|
<short_desc>Offboard switch channel mapping</short_desc> |
|
<min>0</min> |
|
<max>18</max> |
|
</parameter> |
|
<parameter default="0" name="RC_MAP_FLAPS" type="INT32"> |
|
<short_desc>Flaps channel mapping</short_desc> |
|
<min>0</min> |
|
<max>18</max> |
|
</parameter> |
|
<parameter default="0.25" name="RC_ASSIST_TH" type="FLOAT"> |
|
<short_desc>Threshold for selecting assist mode</short_desc> |
|
<long_desc>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</long_desc> |
|
<min>-1</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0.75" name="RC_AUTO_TH" type="FLOAT"> |
|
<short_desc>Threshold for selecting auto mode</short_desc> |
|
<long_desc>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</long_desc> |
|
<min>-1</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0.5" name="RC_POSCTL_TH" type="FLOAT"> |
|
<short_desc>Threshold for selecting posctl mode</short_desc> |
|
<long_desc>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</long_desc> |
|
<min>-1</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0.5" name="RC_RETURN_TH" type="FLOAT"> |
|
<short_desc>Threshold for selecting return to launch mode</short_desc> |
|
<long_desc>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</long_desc> |
|
<min>-1</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0.5" name="RC_LOITER_TH" type="FLOAT"> |
|
<short_desc>Threshold for selecting loiter mode</short_desc> |
|
<long_desc>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</long_desc> |
|
<min>-1</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0.5" name="RC_ACRO_TH" type="FLOAT"> |
|
<short_desc>Threshold for selecting acro mode</short_desc> |
|
<long_desc>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</long_desc> |
|
<min>-1</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0.5" name="RC_OFFB_TH" type="FLOAT"> |
|
<short_desc>Threshold for selecting offboard mode</short_desc> |
|
<long_desc>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</long_desc> |
|
<min>-1</min> |
|
<max>1</max> |
|
</parameter> |
|
</group> |
|
<group name="Return To Land"> |
|
<parameter default="60" name="RTL_RETURN_ALT" type="FLOAT"> |
|
<short_desc>RTL altitude</short_desc> |
|
<long_desc>Altitude to fly back in RTL in meters</long_desc> |
|
<min>0</min> |
|
<max>150</max> |
|
<unit>meters</unit> |
|
</parameter> |
|
<parameter default="30" name="RTL_DESCEND_ALT" type="FLOAT"> |
|
<short_desc>RTL loiter altitude</short_desc> |
|
<long_desc>Stay at this altitude above home position after RTL descending. |
|
Land (i.e. slowly descend) from this altitude if autolanding allowed.</long_desc> |
|
<min>2</min> |
|
<max>100</max> |
|
<unit>meters</unit> |
|
</parameter> |
|
<parameter default="-1.0" name="RTL_LAND_DELAY" type="FLOAT"> |
|
<short_desc>RTL delay</short_desc> |
|
<long_desc>Delay after descend before landing in RTL mode. |
|
If set to -1 the system will not land but loiter at NAV_LAND_ALT.</long_desc> |
|
<min>-1</min> |
|
<max>300</max> |
|
<unit>seconds</unit> |
|
</parameter> |
|
</group> |
|
<group name="SD Logging"> |
|
<parameter default="-1" name="SDLOG_RATE" type="INT32"> |
|
<short_desc>Logging rate</short_desc> |
|
<long_desc>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).</long_desc> |
|
<min>-1</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="-1" name="SDLOG_EXT" type="INT32"> |
|
<short_desc>Enable extended logging mode</short_desc> |
|
<long_desc>A value of -1 indicates the commandline 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).</long_desc> |
|
<min>-1</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0" name="SDLOG_GPSTIME" type="INT32"> |
|
<short_desc>Use timestamps only if GPS 3D fix is available</short_desc> |
|
<long_desc>A value of 1 constrains the log folder creation |
|
to only use the time stamp if a 3D GPS lock is |
|
present.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
</group> |
|
<group name="Sensor Calibration"> |
|
<parameter default="0" name="CAL_BOARD_ID" type="INT32"> |
|
<short_desc>ID of the board this parameter set was calibrated on</short_desc> |
|
</parameter> |
|
<parameter default="0" name="CAL_GYRO0_ID" type="INT32"> |
|
<short_desc>ID of the Gyro that the calibration is for</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_GYRO0_XOFF" type="FLOAT"> |
|
<short_desc>Gyro X-axis offset</short_desc> |
|
<min>-10.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_GYRO0_YOFF" type="FLOAT"> |
|
<short_desc>Gyro Y-axis offset</short_desc> |
|
<min>-10.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_GYRO0_ZOFF" type="FLOAT"> |
|
<short_desc>Gyro Z-axis offset</short_desc> |
|
<min>-5.0</min> |
|
<max>5.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_GYRO0_XSCALE" type="FLOAT"> |
|
<short_desc>Gyro X-axis scaling factor</short_desc> |
|
<min>-1.5</min> |
|
<max>1.5</max> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_GYRO0_YSCALE" type="FLOAT"> |
|
<short_desc>Gyro Y-axis scaling factor</short_desc> |
|
<min>-1.5</min> |
|
<max>1.5</max> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_GYRO0_ZSCALE" type="FLOAT"> |
|
<short_desc>Gyro Z-axis scaling factor</short_desc> |
|
<min>-1.5</min> |
|
<max>1.5</max> |
|
</parameter> |
|
<parameter default="0" name="CAL_MAG0_ID" type="INT32"> |
|
<short_desc>ID of Magnetometer the calibration is for</short_desc> |
|
</parameter> |
|
<parameter default="-1" name="CAL_MAG0_ROT" type="INT32"> |
|
<short_desc>Rotation of magnetometer 0 relative to airframe</short_desc> |
|
<long_desc>An internal magnetometer will force a value of -1, so a GCS |
|
should only attempt to configure the rotation if the value is |
|
greater than or equal to zero.</long_desc> |
|
<min>-1</min> |
|
<max>30</max> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_MAG0_XOFF" type="FLOAT"> |
|
<short_desc>Magnetometer X-axis offset</short_desc> |
|
<min>-500.0</min> |
|
<max>500.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_MAG0_YOFF" type="FLOAT"> |
|
<short_desc>Magnetometer Y-axis offset</short_desc> |
|
<min>-500.0</min> |
|
<max>500.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_MAG0_ZOFF" type="FLOAT"> |
|
<short_desc>Magnetometer Z-axis offset</short_desc> |
|
<min>-500.0</min> |
|
<max>500.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_MAG0_XSCALE" type="FLOAT"> |
|
<short_desc>Magnetometer X-axis scaling factor</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_MAG0_YSCALE" type="FLOAT"> |
|
<short_desc>Magnetometer Y-axis scaling factor</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_MAG0_ZSCALE" type="FLOAT"> |
|
<short_desc>Magnetometer Z-axis scaling factor</short_desc> |
|
</parameter> |
|
<parameter default="0" name="CAL_ACC0_ID" type="INT32"> |
|
<short_desc>ID of the Accelerometer that the calibration is for</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_ACC0_XOFF" type="FLOAT"> |
|
<short_desc>Accelerometer X-axis offset</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_ACC0_YOFF" type="FLOAT"> |
|
<short_desc>Accelerometer Y-axis offset</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_ACC0_ZOFF" type="FLOAT"> |
|
<short_desc>Accelerometer Z-axis offset</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_ACC0_XSCALE" type="FLOAT"> |
|
<short_desc>Accelerometer X-axis scaling factor</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_ACC0_YSCALE" type="FLOAT"> |
|
<short_desc>Accelerometer Y-axis scaling factor</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_ACC0_ZSCALE" type="FLOAT"> |
|
<short_desc>Accelerometer Z-axis scaling factor</short_desc> |
|
</parameter> |
|
<parameter default="0" name="CAL_GYRO1_ID" type="INT32"> |
|
<short_desc>ID of the Gyro that the calibration is for</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_GYRO1_XOFF" type="FLOAT"> |
|
<short_desc>Gyro X-axis offset</short_desc> |
|
<min>-10.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_GYRO1_YOFF" type="FLOAT"> |
|
<short_desc>Gyro Y-axis offset</short_desc> |
|
<min>-10.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_GYRO1_ZOFF" type="FLOAT"> |
|
<short_desc>Gyro Z-axis offset</short_desc> |
|
<min>-5.0</min> |
|
<max>5.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_GYRO1_XSCALE" type="FLOAT"> |
|
<short_desc>Gyro X-axis scaling factor</short_desc> |
|
<min>-1.5</min> |
|
<max>1.5</max> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_GYRO1_YSCALE" type="FLOAT"> |
|
<short_desc>Gyro Y-axis scaling factor</short_desc> |
|
<min>-1.5</min> |
|
<max>1.5</max> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_GYRO1_ZSCALE" type="FLOAT"> |
|
<short_desc>Gyro Z-axis scaling factor</short_desc> |
|
<min>-1.5</min> |
|
<max>1.5</max> |
|
</parameter> |
|
<parameter default="0" name="CAL_MAG1_ID" type="INT32"> |
|
<short_desc>ID of Magnetometer the calibration is for</short_desc> |
|
</parameter> |
|
<parameter default="-1" name="CAL_MAG1_ROT" type="INT32"> |
|
<short_desc>Rotation of magnetometer 1 relative to airframe</short_desc> |
|
<long_desc>An internal magnetometer will force a value of -1, so a GCS |
|
should only attempt to configure the rotation if the value is |
|
greater than or equal to zero.</long_desc> |
|
<min>-1</min> |
|
<max>30</max> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_MAG1_XOFF" type="FLOAT"> |
|
<short_desc>Magnetometer X-axis offset</short_desc> |
|
<min>-500.0</min> |
|
<max>500.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_MAG1_YOFF" type="FLOAT"> |
|
<short_desc>Magnetometer Y-axis offset</short_desc> |
|
<min>-500.0</min> |
|
<max>500.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_MAG1_ZOFF" type="FLOAT"> |
|
<short_desc>Magnetometer Z-axis offset</short_desc> |
|
<min>-500.0</min> |
|
<max>500.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_MAG1_XSCALE" type="FLOAT"> |
|
<short_desc>Magnetometer X-axis scaling factor</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_MAG1_YSCALE" type="FLOAT"> |
|
<short_desc>Magnetometer Y-axis scaling factor</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_MAG1_ZSCALE" type="FLOAT"> |
|
<short_desc>Magnetometer Z-axis scaling factor</short_desc> |
|
</parameter> |
|
<parameter default="0" name="CAL_ACC1_ID" type="INT32"> |
|
<short_desc>ID of the Accelerometer that the calibration is for</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_ACC1_XOFF" type="FLOAT"> |
|
<short_desc>Accelerometer X-axis offset</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_ACC1_YOFF" type="FLOAT"> |
|
<short_desc>Accelerometer Y-axis offset</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_ACC1_ZOFF" type="FLOAT"> |
|
<short_desc>Accelerometer Z-axis offset</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_ACC1_XSCALE" type="FLOAT"> |
|
<short_desc>Accelerometer X-axis scaling factor</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_ACC1_YSCALE" type="FLOAT"> |
|
<short_desc>Accelerometer Y-axis scaling factor</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_ACC1_ZSCALE" type="FLOAT"> |
|
<short_desc>Accelerometer Z-axis scaling factor</short_desc> |
|
</parameter> |
|
<parameter default="0" name="CAL_GYRO2_ID" type="INT32"> |
|
<short_desc>ID of the Gyro that the calibration is for</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_GYRO2_XOFF" type="FLOAT"> |
|
<short_desc>Gyro X-axis offset</short_desc> |
|
<min>-10.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_GYRO2_YOFF" type="FLOAT"> |
|
<short_desc>Gyro Y-axis offset</short_desc> |
|
<min>-10.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_GYRO2_ZOFF" type="FLOAT"> |
|
<short_desc>Gyro Z-axis offset</short_desc> |
|
<min>-5.0</min> |
|
<max>5.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_GYRO2_XSCALE" type="FLOAT"> |
|
<short_desc>Gyro X-axis scaling factor</short_desc> |
|
<min>-1.5</min> |
|
<max>1.5</max> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_GYRO2_YSCALE" type="FLOAT"> |
|
<short_desc>Gyro Y-axis scaling factor</short_desc> |
|
<min>-1.5</min> |
|
<max>1.5</max> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_GYRO2_ZSCALE" type="FLOAT"> |
|
<short_desc>Gyro Z-axis scaling factor</short_desc> |
|
<min>-1.5</min> |
|
<max>1.5</max> |
|
</parameter> |
|
<parameter default="0" name="CAL_MAG2_ID" type="INT32"> |
|
<short_desc>ID of Magnetometer the calibration is for</short_desc> |
|
</parameter> |
|
<parameter default="-1" name="CAL_MAG2_ROT" type="INT32"> |
|
<short_desc>Rotation of magnetometer 2 relative to airframe</short_desc> |
|
<long_desc>An internal magnetometer will force a value of -1, so a GCS |
|
should only attempt to configure the rotation if the value is |
|
greater than or equal to zero.</long_desc> |
|
<min>-1</min> |
|
<max>30</max> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_MAG2_XOFF" type="FLOAT"> |
|
<short_desc>Magnetometer X-axis offset</short_desc> |
|
<min>-500.0</min> |
|
<max>500.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_MAG2_YOFF" type="FLOAT"> |
|
<short_desc>Magnetometer Y-axis offset</short_desc> |
|
<min>-500.0</min> |
|
<max>500.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_MAG2_ZOFF" type="FLOAT"> |
|
<short_desc>Magnetometer Z-axis offset</short_desc> |
|
<min>-500.0</min> |
|
<max>500.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_MAG2_XSCALE" type="FLOAT"> |
|
<short_desc>Magnetometer X-axis scaling factor</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_MAG2_YSCALE" type="FLOAT"> |
|
<short_desc>Magnetometer Y-axis scaling factor</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_MAG2_ZSCALE" type="FLOAT"> |
|
<short_desc>Magnetometer Z-axis scaling factor</short_desc> |
|
</parameter> |
|
<parameter default="0" name="CAL_ACC2_ID" type="INT32"> |
|
<short_desc>ID of the Accelerometer that the calibration is for</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_ACC2_XOFF" type="FLOAT"> |
|
<short_desc>Accelerometer X-axis offset</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_ACC2_YOFF" type="FLOAT"> |
|
<short_desc>Accelerometer Y-axis offset</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="CAL_ACC2_ZOFF" type="FLOAT"> |
|
<short_desc>Accelerometer Z-axis offset</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_ACC2_XSCALE" type="FLOAT"> |
|
<short_desc>Accelerometer X-axis scaling factor</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_ACC2_YSCALE" type="FLOAT"> |
|
<short_desc>Accelerometer Y-axis scaling factor</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="CAL_ACC2_ZSCALE" type="FLOAT"> |
|
<short_desc>Accelerometer Z-axis scaling factor</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="SENS_DPRES_OFF" type="FLOAT"> |
|
<short_desc>Differential pressure sensor offset</short_desc> |
|
<long_desc>The offset (zero-reading) in Pascal</long_desc> |
|
</parameter> |
|
<parameter default="0" name="SENS_DPRES_ANSC" type="FLOAT"> |
|
<short_desc>Differential pressure sensor analog scaling</short_desc> |
|
<long_desc>Pick the appropriate scaling from the datasheet. |
|
this number defines the (linear) conversion from voltage |
|
to Pascal (pa). For the MPXV7002DP this is 1000. |
|
NOTE: If the sensor always registers zero, try switching |
|
the static and dynamic tubes.</long_desc> |
|
</parameter> |
|
<parameter default="1013.25" name="SENS_BARO_QNH" type="FLOAT"> |
|
<short_desc>QNH for barometer</short_desc> |
|
<min>500</min> |
|
<max>1500</max> |
|
<unit>hPa</unit> |
|
</parameter> |
|
<parameter default="0" name="SENS_BOARD_ROT" type="INT32"> |
|
<short_desc>Board rotation</short_desc> |
|
<long_desc>This parameter defines the rotation of the FMU board relative to the platform. |
|
Possible values are: |
|
0 = No rotation |
|
1 = Yaw 45° |
|
2 = Yaw 90° |
|
3 = Yaw 135° |
|
4 = Yaw 180° |
|
5 = Yaw 225° |
|
6 = Yaw 270° |
|
7 = Yaw 315° |
|
8 = Roll 180° |
|
9 = Roll 180°, Yaw 45° |
|
10 = Roll 180°, Yaw 90° |
|
11 = Roll 180°, Yaw 135° |
|
12 = Pitch 180° |
|
13 = Roll 180°, Yaw 225° |
|
14 = Roll 180°, Yaw 270° |
|
15 = Roll 180°, Yaw 315° |
|
16 = Roll 90° |
|
17 = Roll 90°, Yaw 45° |
|
18 = Roll 90°, Yaw 90° |
|
19 = Roll 90°, Yaw 135° |
|
20 = Roll 270° |
|
21 = Roll 270°, Yaw 45° |
|
22 = Roll 270°, Yaw 90° |
|
23 = Roll 270°, Yaw 135° |
|
24 = Pitch 90° |
|
25 = Pitch 270°</long_desc> |
|
</parameter> |
|
<parameter default="0" name="SENS_FLOW_ROT" type="INT32"> |
|
<short_desc>PX4Flow board rotation</short_desc> |
|
<long_desc>This parameter defines the rotation of the PX4FLOW board relative to the platform. |
|
Zero rotation is defined as Y on flow board pointing towards front of vehicle |
|
Possible values are: |
|
0 = No rotation |
|
1 = Yaw 45° |
|
2 = Yaw 90° |
|
3 = Yaw 135° |
|
4 = Yaw 180° |
|
5 = Yaw 225° |
|
6 = Yaw 270° |
|
7 = Yaw 315°</long_desc> |
|
</parameter> |
|
<parameter default="0.0" name="SENS_BOARD_Y_OFF" type="FLOAT"> |
|
<short_desc>Board rotation Y (Pitch) offset</short_desc> |
|
<long_desc>This parameter defines a rotational offset in degrees around the Y (Pitch) axis. It allows the user |
|
to fine tune the board offset in the event of misalignment.</long_desc> |
|
</parameter> |
|
<parameter default="0.0" name="SENS_BOARD_X_OFF" type="FLOAT"> |
|
<short_desc>Board rotation X (Roll) offset</short_desc> |
|
<long_desc>This parameter defines a rotational offset in degrees around the X (Roll) axis It allows the user |
|
to fine tune the board offset in the event of misalignment.</long_desc> |
|
</parameter> |
|
<parameter default="0.0" name="SENS_BOARD_Z_OFF" type="FLOAT"> |
|
<short_desc>Board rotation Z (YAW) offset</short_desc> |
|
<long_desc>This parameter defines a rotational offset in degrees around the Z (Yaw) axis. It allows the user |
|
to fine tune the board offset in the event of misalignment.</long_desc> |
|
</parameter> |
|
<parameter default="0" name="SENS_EXT_MAG_ROT" type="INT32"> |
|
<short_desc>External magnetometer rotation</short_desc> |
|
<long_desc>This parameter defines the rotation of the external magnetometer relative |
|
to the platform (not relative to the FMU). |
|
See SENS_BOARD_ROT for possible values.</long_desc> |
|
</parameter> |
|
<parameter default="0" name="SENS_EXT_MAG" type="INT32"> |
|
<short_desc>Set usage of external magnetometer</short_desc> |
|
<long_desc>* Set to 0 (default) to auto-detect (will try to get the external as primary) |
|
* Set to 1 to force the external magnetometer as primary |
|
* Set to 2 to force the internal magnetometer as primary</long_desc> |
|
<min>0</min> |
|
<max>2</max> |
|
</parameter> |
|
</group> |
|
<group name="Sensor Enable"> |
|
<parameter default="0" name="SENS_EN_LL40LS" type="INT32"> |
|
<short_desc>Enable Lidar-Lite (LL40LS) pwm driver</short_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
</group> |
|
<group name="Subscriber Example"> |
|
<parameter default="" name="SUB_INTERV" type="INT32"> |
|
<short_desc>Interval of one subscriber in the example in ms</short_desc> |
|
</parameter> |
|
<parameter default="" name="SUB_TESTF" type="FLOAT"> |
|
<short_desc>Float Demonstration Parameter in the Example</short_desc> |
|
</parameter> |
|
</group> |
|
<group name="System"> |
|
<parameter default="0" name="SYS_AUTOSTART" type="INT32"> |
|
<short_desc>Auto-start script index</short_desc> |
|
<long_desc>Defines the auto-start script used to bootstrap the system.</long_desc> |
|
</parameter> |
|
<parameter default="0" name="SYS_AUTOCONFIG" type="INT32"> |
|
<short_desc>Automatically configure default values</short_desc> |
|
<long_desc>Set to 1 to reset parameters on next system startup (setting defaults). |
|
Platform-specific values are used if available. |
|
RC* parameters are preserved.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="1" name="SYS_USE_IO" type="INT32"> |
|
<short_desc>Set usage of IO board</short_desc> |
|
<long_desc>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.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="2" name="SYS_RESTART_TYPE" type="INT32"> |
|
<short_desc>Set restart type</short_desc> |
|
<long_desc>Set by px4io to indicate type of restart</long_desc> |
|
<min>0</min> |
|
<max>2</max> |
|
</parameter> |
|
<parameter default="0" name="SYS_COMPANION" type="INT32"> |
|
<short_desc>Companion computer interface</short_desc> |
|
<long_desc>Configures the baud rate of the companion computer interface. |
|
Set to zero to disable, set to 921600 to enable. |
|
CURRENTLY ONLY SUPPORTS 921600 BAUD! Use extras.txt for |
|
other baud rates.</long_desc> |
|
<min>0</min> |
|
<max>921600</max> |
|
</parameter> |
|
<parameter default="1" name="SYS_PARAM_VER" type="INT32"> |
|
<short_desc>Parameter version</short_desc> |
|
<long_desc>This monotonically increasing number encodes the parameter compatibility set. |
|
whenever it increases parameters might not be backwards compatible and |
|
ground control stations should suggest a fresh configuration.</long_desc> |
|
<min>0</min> |
|
</parameter> |
|
</group> |
|
<group name="UAVCAN"> |
|
<parameter default="0" name="UAVCAN_ENABLE" type="INT32"> |
|
<short_desc>Enable UAVCAN</short_desc> |
|
<long_desc>Enables support for UAVCAN-interfaced actuators and sensors.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="1" name="UAVCAN_NODE_ID" type="INT32"> |
|
<short_desc>UAVCAN Node ID</short_desc> |
|
<long_desc>Read the specs at http://uavcan.org to learn more about Node ID.</long_desc> |
|
<min>1</min> |
|
<max>125</max> |
|
</parameter> |
|
<parameter default="1000000" name="UAVCAN_BITRATE" type="INT32"> |
|
<short_desc>UAVCAN CAN bus bitrate</short_desc> |
|
<min>20000</min> |
|
<max>1000000</max> |
|
</parameter> |
|
</group> |
|
<group name="VTOL Attitude Control"> |
|
<parameter default="0" name="VT_MOT_COUNT" type="INT32"> |
|
<short_desc>VTOL number of engines</short_desc> |
|
<min>1</min> |
|
</parameter> |
|
<parameter default="900" name="VT_IDLE_PWM_MC" type="INT32"> |
|
<short_desc>Idle speed of VTOL when in multicopter mode</short_desc> |
|
<min>900</min> |
|
</parameter> |
|
<parameter default="10.0" name="VT_MC_ARSPD_MIN" type="FLOAT"> |
|
<short_desc>Minimum airspeed in multicopter mode</short_desc> |
|
<long_desc>This is the minimum speed of the air flowing over the control surfaces.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="30.0" name="VT_MC_ARSPD_MAX" type="FLOAT"> |
|
<short_desc>Maximum airspeed in multicopter mode</short_desc> |
|
<long_desc>This is the maximum speed of the air flowing over the control surfaces.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="10.0" name="VT_MC_ARSPD_TRIM" type="FLOAT"> |
|
<short_desc>Trim airspeed when in multicopter mode</short_desc> |
|
<long_desc>This is the airflow over the control surfaces for which no airspeed scaling is applied in multicopter mode.</long_desc> |
|
<min>0.0</min> |
|
</parameter> |
|
<parameter default="0" name="VT_FW_PERM_STAB" type="INT32"> |
|
<short_desc>Permanent stabilization in fw mode</short_desc> |
|
<long_desc>If set to one this parameter will cause permanent attitude stabilization in fw mode. |
|
This parameter has been introduced for pure convenience sake.</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0.0" name="VT_FW_PITCH_TRIM" type="FLOAT"> |
|
<short_desc>Fixed wing pitch trim</short_desc> |
|
<long_desc>This parameter allows to adjust the neutral elevon position in fixed wing mode.</long_desc> |
|
<min>-1</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="120.0" name="VT_POWER_MAX" type="FLOAT"> |
|
<short_desc>Motor max power</short_desc> |
|
<long_desc>Indicates the maximum power the motor is able to produce. Used to calculate |
|
propeller efficiency map.</long_desc> |
|
<min>1</min> |
|
</parameter> |
|
<parameter default="0.0" name="VT_PROP_EFF" type="FLOAT"> |
|
<short_desc>Propeller efficiency parameter</short_desc> |
|
<long_desc>Influences propeller efficiency at different power settings. Should be tuned beforehand.</long_desc> |
|
<min>0.5</min> |
|
<max>0.9</max> |
|
</parameter> |
|
<parameter default="0.3" name="VT_ARSP_LP_GAIN" type="FLOAT"> |
|
<short_desc>Total airspeed estimate low-pass filter gain</short_desc> |
|
<long_desc>Gain for tuning the low-pass filter for the total airspeed estimate</long_desc> |
|
<min>0.0</min> |
|
<max>0.99</max> |
|
</parameter> |
|
</group> |
|
<group name="mTECS"> |
|
<parameter default="0" name="MT_ENABLED" type="INT32"> |
|
<short_desc>mTECS enabled</short_desc> |
|
<long_desc>Set to 1 to enable mTECS</long_desc> |
|
<min>0</min> |
|
<max>1</max> |
|
</parameter> |
|
<parameter default="0.7" name="MT_THR_FF" type="FLOAT"> |
|
<short_desc>Total Energy Rate Control Feedforward |
|
Maps the total energy rate setpoint to the throttle setpoint</short_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.1" name="MT_THR_P" type="FLOAT"> |
|
<short_desc>Total Energy Rate Control P |
|
Maps the total energy rate error to the throttle setpoint</short_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.25" name="MT_THR_I" type="FLOAT"> |
|
<short_desc>Total Energy Rate Control I |
|
Maps the integrated total energy rate to the throttle setpoint</short_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.7" name="MT_THR_OFF" type="FLOAT"> |
|
<short_desc>Total Energy Rate Control Offset (Cruise throttle sp)</short_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.4" name="MT_PIT_FF" type="FLOAT"> |
|
<short_desc>Energy Distribution Rate Control Feedforward |
|
Maps the energy distribution rate setpoint to the pitch setpoint</short_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.03" name="MT_PIT_P" type="FLOAT"> |
|
<short_desc>Energy Distribution Rate Control P |
|
Maps the energy distribution rate error to the pitch setpoint</short_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.03" name="MT_PIT_I" type="FLOAT"> |
|
<short_desc>Energy Distribution Rate Control I |
|
Maps the integrated energy distribution rate error to the pitch setpoint</short_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="MT_PIT_OFF" type="FLOAT"> |
|
<short_desc>Total Energy Distribution Offset (Cruise pitch sp)</short_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="MT_THR_MIN" type="FLOAT"> |
|
<short_desc>Minimal Throttle Setpoint</short_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="MT_THR_MAX" type="FLOAT"> |
|
<short_desc>Maximal Throttle Setpoint</short_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="-45.0" name="MT_PIT_MIN" type="FLOAT"> |
|
<short_desc>Minimal Pitch Setpoint in Degrees</short_desc> |
|
<min>-90.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="20.0" name="MT_PIT_MAX" type="FLOAT"> |
|
<short_desc>Maximal Pitch Setpoint in Degrees</short_desc> |
|
<min>-90.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="1.0" name="MT_ALT_LP" type="FLOAT"> |
|
<short_desc>Lowpass (cutoff freq.) for altitude</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="MT_FPA_LP" type="FLOAT"> |
|
<short_desc>Lowpass (cutoff freq.) for the flight path angle</short_desc> |
|
</parameter> |
|
<parameter default="0.3" name="MT_FPA_P" type="FLOAT"> |
|
<short_desc>P gain for the altitude control |
|
Maps the altitude error to the flight path angle setpoint</short_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="MT_FPA_D" type="FLOAT"> |
|
<short_desc>D gain for the altitude control |
|
Maps the change of altitude error to the flight path angle setpoint</short_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="MT_FPA_D_LP" type="FLOAT"> |
|
<short_desc>Lowpass for FPA error derivative calculation (see MT_FPA_D)</short_desc> |
|
</parameter> |
|
<parameter default="-20.0" name="MT_FPA_MIN" type="FLOAT"> |
|
<short_desc>Minimal flight path angle setpoint</short_desc> |
|
<min>-90.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="30.0" name="MT_FPA_MAX" type="FLOAT"> |
|
<short_desc>Maximal flight path angle setpoint</short_desc> |
|
<min>-90.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="0.5" name="MT_A_LP" type="FLOAT"> |
|
<short_desc>Lowpass (cutoff freq.) for airspeed</short_desc> |
|
</parameter> |
|
<parameter default="0.5" name="MT_AD_LP" type="FLOAT"> |
|
<short_desc>Airspeed derivative calculation lowpass</short_desc> |
|
</parameter> |
|
<parameter default="0.3" name="MT_ACC_P" type="FLOAT"> |
|
<short_desc>P gain for the airspeed control |
|
Maps the airspeed error to the acceleration setpoint</short_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="MT_ACC_D" type="FLOAT"> |
|
<short_desc>D gain for the airspeed control |
|
Maps the change of airspeed error to the acceleration setpoint</short_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="0.5" name="MT_ACC_D_LP" type="FLOAT"> |
|
<short_desc>Lowpass for ACC error derivative calculation (see MT_ACC_D)</short_desc> |
|
</parameter> |
|
<parameter default="-40.0" name="MT_ACC_MIN" type="FLOAT"> |
|
<short_desc>Minimal acceleration (air)</short_desc> |
|
<unit>m/s^2</unit> |
|
</parameter> |
|
<parameter default="40.0" name="MT_ACC_MAX" type="FLOAT"> |
|
<short_desc>Maximal acceleration (air)</short_desc> |
|
<unit>m/s^2</unit> |
|
</parameter> |
|
<parameter default="1.0" name="MT_TKF_THR_MIN" type="FLOAT"> |
|
<short_desc>Minimal throttle during takeoff</short_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="MT_TKF_THR_MAX" type="FLOAT"> |
|
<short_desc>Maximal throttle during takeoff</short_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="MT_TKF_PIT_MIN" type="FLOAT"> |
|
<short_desc>Minimal pitch during takeoff</short_desc> |
|
<min>-90.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="45.0" name="MT_TKF_PIT_MAX" type="FLOAT"> |
|
<short_desc>Maximal pitch during takeoff</short_desc> |
|
<min>-90.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="1.0" name="MT_USP_THR_MIN" type="FLOAT"> |
|
<short_desc>Minimal throttle in underspeed mode</short_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="1.0" name="MT_USP_THR_MAX" type="FLOAT"> |
|
<short_desc>Maximal throttle in underspeed mode</short_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="-45.0" name="MT_USP_PIT_MIN" type="FLOAT"> |
|
<short_desc>Minimal pitch in underspeed mode</short_desc> |
|
<min>-90.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="0.0" name="MT_USP_PIT_MAX" type="FLOAT"> |
|
<short_desc>Maximal pitch in underspeed mode</short_desc> |
|
<min>-90.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="0.0" name="MT_LND_THR_MIN" type="FLOAT"> |
|
<short_desc>Minimal throttle in landing mode (only last phase of landing)</short_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="0.0" name="MT_LND_THR_MAX" type="FLOAT"> |
|
<short_desc>Maximal throttle in landing mode (only last phase of landing)</short_desc> |
|
<min>0.0</min> |
|
<max>1.0</max> |
|
</parameter> |
|
<parameter default="-5.0" name="MT_LND_PIT_MIN" type="FLOAT"> |
|
<short_desc>Minimal pitch in landing mode</short_desc> |
|
<min>-90.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="15.0" name="MT_LND_PIT_MAX" type="FLOAT"> |
|
<short_desc>Maximal pitch in landing mode</short_desc> |
|
<min>-90.0</min> |
|
<max>90.0</max> |
|
<unit>deg</unit> |
|
</parameter> |
|
<parameter default="10.0" name="MT_THR_I_MAX" type="FLOAT"> |
|
<short_desc>Integrator Limit for Total Energy Rate Control</short_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
<parameter default="10.0" name="MT_PIT_I_MAX" type="FLOAT"> |
|
<short_desc>Integrator Limit for Energy Distribution Rate Control</short_desc> |
|
<min>0.0</min> |
|
<max>10.0</max> |
|
</parameter> |
|
</group> |
|
<group name="Miscellaneous"> |
|
<parameter default="0.1" name="EXFW_HDNG_P" type="FLOAT"> |
|
<short_desc>EXFW_HDNG_P</short_desc> |
|
</parameter> |
|
<parameter default="0.2" name="EXFW_ROLL_P" type="FLOAT"> |
|
<short_desc>EXFW_ROLL_P</short_desc> |
|
</parameter> |
|
<parameter default="0.2" name="EXFW_PITCH_P" type="FLOAT"> |
|
<short_desc>EXFW_PITCH_P</short_desc> |
|
</parameter> |
|
<parameter default="0.1" name="RV_YAW_P" type="FLOAT"> |
|
<short_desc>RV_YAW_P</short_desc> |
|
</parameter> |
|
<parameter default="0.4" name="FPE_LO_THRUST" type="FLOAT"> |
|
<short_desc>FPE_LO_THRUST</short_desc> |
|
</parameter> |
|
<parameter default="0.5" name="FPE_SONAR_LP_U" type="FLOAT"> |
|
<short_desc>FPE_SONAR_LP_U</short_desc> |
|
</parameter> |
|
<parameter default="0.2" name="FPE_SONAR_LP_L" type="FLOAT"> |
|
<short_desc>FPE_SONAR_LP_L</short_desc> |
|
</parameter> |
|
<parameter default="0" name="FPE_DEBUG" type="INT32"> |
|
<short_desc>FPE_DEBUG</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="SO3_COMP_KP" type="FLOAT"> |
|
<short_desc>SO3_COMP_KP</short_desc> |
|
</parameter> |
|
<parameter default="0.05" name="SO3_COMP_KI" type="FLOAT"> |
|
<short_desc>SO3_COMP_KI</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="SO3_ROLL_OFFS" type="FLOAT"> |
|
<short_desc>SO3_ROLL_OFFS</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="SO3_PITCH_OFFS" type="FLOAT"> |
|
<short_desc>SO3_PITCH_OFFS</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="SO3_YAW_OFFS" type="FLOAT"> |
|
<short_desc>SO3_YAW_OFFS</short_desc> |
|
</parameter> |
|
<parameter default="2.5" name="FW_FLARE_PMIN" type="FLOAT"> |
|
<short_desc>Flare, minimum pitch</short_desc> |
|
<long_desc>Minimum pitch during flare, a positive sign means nose up |
|
Applied once FW_LND_TLALT is reached</long_desc> |
|
</parameter> |
|
<parameter default="15.0" name="FW_FLARE_PMAX" type="FLOAT"> |
|
<short_desc>Flare, maximum pitch</short_desc> |
|
<long_desc>Maximum pitch during flare, a positive sign means nose up |
|
Applied once FW_LND_TLALT is reached</long_desc> |
|
</parameter> |
|
<parameter default="300.0" name="FWB_P_LP" type="FLOAT"> |
|
<short_desc>FWB_P_LP</short_desc> |
|
</parameter> |
|
<parameter default="300.0" name="FWB_Q_LP" type="FLOAT"> |
|
<short_desc>FWB_Q_LP</short_desc> |
|
</parameter> |
|
<parameter default="300.0" name="FWB_R_LP" type="FLOAT"> |
|
<short_desc>FWB_R_LP</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="FWB_R_HP" type="FLOAT"> |
|
<short_desc>FWB_R_HP</short_desc> |
|
</parameter> |
|
<parameter default="0.3" name="FWB_P2AIL" type="FLOAT"> |
|
<short_desc>FWB_P2AIL</short_desc> |
|
</parameter> |
|
<parameter default="0.1" name="FWB_Q2ELV" type="FLOAT"> |
|
<short_desc>FWB_Q2ELV</short_desc> |
|
</parameter> |
|
<parameter default="0.1" name="FWB_R2RDR" type="FLOAT"> |
|
<short_desc>FWB_R2RDR</short_desc> |
|
</parameter> |
|
<parameter default="0.5" name="FWB_PSI2PHI" type="FLOAT"> |
|
<short_desc>FWB_PSI2PHI</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="FWB_PHI2P" type="FLOAT"> |
|
<short_desc>FWB_PHI2P</short_desc> |
|
</parameter> |
|
<parameter default="0.3" name="FWB_PHI_LIM_MAX" type="FLOAT"> |
|
<short_desc>FWB_PHI_LIM_MAX</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="FWB_V2THE_P" type="FLOAT"> |
|
<short_desc>FWB_V2THE_P</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="FWB_V2THE_I" type="FLOAT"> |
|
<short_desc>FWB_V2THE_I</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="FWB_V2THE_D" type="FLOAT"> |
|
<short_desc>FWB_V2THE_D</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="FWB_V2THE_D_LP" type="FLOAT"> |
|
<short_desc>FWB_V2THE_D_LP</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="FWB_V2THE_I_MAX" type="FLOAT"> |
|
<short_desc>FWB_V2THE_I_MAX</short_desc> |
|
</parameter> |
|
<parameter default="-0.5" name="FWB_THE_MIN" type="FLOAT"> |
|
<short_desc>FWB_THE_MIN</short_desc> |
|
</parameter> |
|
<parameter default="0.5" name="FWB_THE_MAX" type="FLOAT"> |
|
<short_desc>FWB_THE_MAX</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="FWB_THE2Q_P" type="FLOAT"> |
|
<short_desc>FWB_THE2Q_P</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="FWB_THE2Q_I" type="FLOAT"> |
|
<short_desc>FWB_THE2Q_I</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="FWB_THE2Q_D" type="FLOAT"> |
|
<short_desc>FWB_THE2Q_D</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="FWB_THE2Q_D_LP" type="FLOAT"> |
|
<short_desc>FWB_THE2Q_D_LP</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="FWB_THE2Q_I_MAX" type="FLOAT"> |
|
<short_desc>FWB_THE2Q_I_MAX</short_desc> |
|
</parameter> |
|
<parameter default="0.01" name="FWB_H2THR_P" type="FLOAT"> |
|
<short_desc>FWB_H2THR_P</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="FWB_H2THR_I" type="FLOAT"> |
|
<short_desc>FWB_H2THR_I</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="FWB_H2THR_D" type="FLOAT"> |
|
<short_desc>FWB_H2THR_D</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="FWB_H2THR_D_LP" type="FLOAT"> |
|
<short_desc>FWB_H2THR_D_LP</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="FWB_H2THR_I_MAX" type="FLOAT"> |
|
<short_desc>FWB_H2THR_I_MAX</short_desc> |
|
</parameter> |
|
<parameter default="1.57" name="FWB_XT2YAW_MAX" type="FLOAT"> |
|
<short_desc>FWB_XT2YAW_MAX</short_desc> |
|
</parameter> |
|
<parameter default="0.005" name="FWB_XT2YAW" type="FLOAT"> |
|
<short_desc>FWB_XT2YAW</short_desc> |
|
</parameter> |
|
<parameter default="10.0" name="FWB_V_MIN" type="FLOAT"> |
|
<short_desc>FWB_V_MIN</short_desc> |
|
</parameter> |
|
<parameter default="12.0" name="FWB_V_CMD" type="FLOAT"> |
|
<short_desc>FWB_V_CMD</short_desc> |
|
</parameter> |
|
<parameter default="16.0" name="FWB_V_MAX" type="FLOAT"> |
|
<short_desc>FWB_V_MAX</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="FWB_CR_MAX" type="FLOAT"> |
|
<short_desc>FWB_CR_MAX</short_desc> |
|
</parameter> |
|
<parameter default="0.01" name="FWB_CR2THR_P" type="FLOAT"> |
|
<short_desc>FWB_CR2THR_P</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="FWB_CR2THR_I" type="FLOAT"> |
|
<short_desc>FWB_CR2THR_I</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="FWB_CR2THR_D" type="FLOAT"> |
|
<short_desc>FWB_CR2THR_D</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="FWB_CR2THR_D_LP" type="FLOAT"> |
|
<short_desc>FWB_CR2THR_D_LP</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="FWB_CR2THR_I_MAX" type="FLOAT"> |
|
<short_desc>FWB_CR2THR_I_MAX</short_desc> |
|
</parameter> |
|
<parameter default="0.8" name="FWB_TRIM_THR" type="FLOAT"> |
|
<short_desc>FWB_TRIM_THR</short_desc> |
|
</parameter> |
|
<parameter default="12.0" name="FWB_TRIM_V" type="FLOAT"> |
|
<short_desc>FWB_TRIM_V</short_desc> |
|
</parameter> |
|
<parameter default="10.0" name="SEG_TH2V_P" type="FLOAT"> |
|
<short_desc>SEG_TH2V_P</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="SEG_TH2V_I" type="FLOAT"> |
|
<short_desc>SEG_TH2V_I</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="SEG_TH2V_I_MAX" type="FLOAT"> |
|
<short_desc>SEG_TH2V_I_MAX</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="SEG_Q2V" type="FLOAT"> |
|
<short_desc>SEG_Q2V</short_desc> |
|
</parameter> |
|
<parameter default="0" name="RC_RL1_DSM_VCC" type="INT32"> |
|
<short_desc>RC_RL1_DSM_VCC</short_desc> |
|
</parameter> |
|
<parameter default="0" name="RC_MAP_FAILSAFE" type="INT32"> |
|
<short_desc>Failsafe channel mapping</short_desc> |
|
<long_desc>The RC mapping index indicates which channel is used for failsafe |
|
If 0, whichever channel is mapped to throttle is used |
|
otherwise the value indicates the specific rc channel to use</long_desc> |
|
<min>0</min> |
|
<max>18</max> |
|
</parameter> |
|
<parameter default="0.0" name="TRIM_ROLL" type="FLOAT"> |
|
<short_desc>TRIM_ROLL</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="TRIM_PITCH" type="FLOAT"> |
|
<short_desc>TRIM_PITCH</short_desc> |
|
</parameter> |
|
<parameter default="0.0" name="TRIM_YAW" type="FLOAT"> |
|
<short_desc>TRIM_YAW</short_desc> |
|
</parameter> |
|
<parameter default="-1.0" name="TEST_MIN" type="FLOAT"> |
|
<short_desc>TEST_MIN</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="TEST_MAX" type="FLOAT"> |
|
<short_desc>TEST_MAX</short_desc> |
|
</parameter> |
|
<parameter default="0.5" name="TEST_TRIM" type="FLOAT"> |
|
<short_desc>TEST_TRIM</short_desc> |
|
</parameter> |
|
<parameter default="10.0" name="TEST_HP" type="FLOAT"> |
|
<short_desc>TEST_HP</short_desc> |
|
</parameter> |
|
<parameter default="10.0" name="TEST_LP" type="FLOAT"> |
|
<short_desc>TEST_LP</short_desc> |
|
</parameter> |
|
<parameter default="0.2" name="TEST_P" type="FLOAT"> |
|
<short_desc>TEST_P</short_desc> |
|
</parameter> |
|
<parameter default="0.1" name="TEST_I" type="FLOAT"> |
|
<short_desc>TEST_I</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="TEST_I_MAX" type="FLOAT"> |
|
<short_desc>TEST_I_MAX</short_desc> |
|
</parameter> |
|
<parameter default="0.01" name="TEST_D" type="FLOAT"> |
|
<short_desc>TEST_D</short_desc> |
|
</parameter> |
|
<parameter default="10.0" name="TEST_D_LP" type="FLOAT"> |
|
<short_desc>TEST_D_LP</short_desc> |
|
</parameter> |
|
<parameter default="1.0" name="TEST_MEAN" type="FLOAT"> |
|
<short_desc>TEST_MEAN</short_desc> |
|
</parameter> |
|
<parameter default="2.0" name="TEST_DEV" type="FLOAT"> |
|
<short_desc>TEST_DEV</short_desc> |
|
</parameter> |
|
</group> |
|
</parameters>
|
|
|