Skip to content
PX4ParameterFactMetaData.xml 250 KiB
Newer Older
<?xml version='1.0' encoding='UTF-8'?>
<parameters>
  <parameter_version_major>1</parameter_version_major>
Lorenz Meier's avatar
Lorenz Meier committed
  <parameter_version_minor>4</parameter_version_minor>
Don Gagne's avatar
Don Gagne committed
  <group name="UAVCAN Motor Parameters" no_code_generation="true">
    <parameter default="75" name="ctl_bw" type="INT32">
      <short_desc>Speed controller bandwidth</short_desc>
      <long_desc>Speed controller bandwidth, in Hz. Higher values result in faster speed and current rise times, but may result in overshoot and higher current consumption. For fixed-wing aircraft, this value should be less than 50 Hz; for multirotors, values up to 100 Hz may provide improvements in responsiveness.</long_desc>
      <unit>Hertz</unit>
      <min>10</min>
      <max>250</max>
    </parameter>
    <parameter default="1" name="ctl_dir" type="INT32">
      <short_desc>Reverse direction</short_desc>
      <long_desc>Motor spin direction as detected during initial enumeration. Use 0 or 1 to reverse direction.</long_desc>
      <min>0</min>
      <max>1</max>
    </parameter>
    <parameter default="1" name="ctl_gain" type="FLOAT">
      <short_desc>Speed (RPM) controller gain</short_desc>
      <long_desc>Speed (RPM) controller gain. Determines controller
            aggressiveness; units are amp-seconds per radian. Systems with
            higher rotational inertia (large props) will need gain increased;
            systems with low rotational inertia (small props) may need gain
            decreased. Higher values result in faster response, but may result
            in oscillation and excessive overshoot. Lower values result in a
            slower, smoother response.</long_desc>
      <unit>amp-seconds per radian</unit>
      <decimal>3</decimal>
      <min>0.00</min>
      <max>1.00</max>
    </parameter>
    <parameter default="3.5" name="ctl_hz_idle" type="FLOAT">
      <short_desc>Idle speed (e Hz)</short_desc>
      <long_desc>Idle speed (e Hz)</long_desc>
      <unit>Hertz</unit>
      <decimal>3</decimal>
      <min>0.0</min>
      <max>100.0</max>
    </parameter>
    <parameter default="25" name="ctl_start_rate" type="INT32">
      <short_desc>Spin-up rate (e Hz/s)</short_desc>
      <long_desc>Spin-up rate (e Hz/s)</long_desc>
      <unit>Hz/s</unit>
      <min>5</min>
      <max>1000</max>
    </parameter>
    <parameter default="0" name="esc_index" type="INT32">
      <short_desc>Index of this ESC in throttle command messages.</short_desc>
      <long_desc>Index of this ESC in throttle command messages.</long_desc>
      <unit>Index</unit>
      <min>0</min>
      <max>15</max>
    </parameter>
    <parameter default="20034" name="id_ext_status" type="INT32">
      <short_desc>Extended status ID</short_desc>
      <long_desc>Extended status ID</long_desc>
      <min>1</min>
      <max>1000000</max>
    </parameter>
    <parameter default="50000" name="int_ext_status" type="INT32">
      <short_desc>Extended status interval (µs)</short_desc>
      <long_desc>Extended status interval (µs)</long_desc>
      <unit>µs</unit>
      <min>0</min>
      <max>1000000</max>
    </parameter>
    <parameter default="50000" name="int_status" type="INT32">
      <short_desc>ESC status interval (µs)</short_desc>
      <long_desc>ESC status interval (µs)</long_desc>
      <unit>µs</unit>
      <max>1000000</max>
    </parameter>
    <parameter default="12" name="mot_i_max" type="FLOAT">
      <short_desc>Motor current limit in amps</short_desc>
      <long_desc>Motor current limit in amps. This determines the maximum
            current controller setpoint, as well as the maximum allowable
            current setpoint slew rate. This value should generally be set to
            the continuous current rating listed in the motor’s specification
            sheet, or set equal to the motor’s specified continuous power
            divided by the motor voltage limit.</long_desc>
      <unit>Amps</unit>
      <decimal>3</decimal>
      <min>1</min>
      <max>80</max>
    </parameter>
    <parameter default="2300" name="mot_kv" type="INT32">
      <short_desc>Motor Kv in RPM per volt</short_desc>
      <long_desc>Motor Kv in RPM per volt. This can be taken from the motor’s
            specification sheet; accuracy will help control performance but
            some deviation from the specified value is acceptable.</long_desc>
      <unit>RPM/v</unit>
      <min>0</min>
Don Gagne's avatar
Don Gagne committed
      <max>4000</max>
    </parameter>
    <parameter default="0.0" name="mot_ls" type="FLOAT">
      <short_desc>READ ONLY: Motor inductance in henries.</short_desc>
      <long_desc>READ ONLY: Motor inductance in henries. This is measured on start-up.</long_desc>
      <unit>henries</unit>
      <decimal>3</decimal>
    </parameter>
    <parameter default="14" name="mot_num_poles" type="INT32">
      <short_desc>Number of motor poles.</short_desc>
      <long_desc>Number of motor poles. Used to convert mechanical speeds to
            electrical speeds. This number should be taken from the motor’s
            specification sheet.</long_desc>
      <unit>Poles</unit>
      <min>2</min>
      <max>40</max>
    </parameter>
    <parameter default="0.0" name="mot_rs" type="FLOAT">
      <short_desc>READ ONLY: Motor resistance in ohms</short_desc>
      <long_desc>READ ONLY: Motor resistance in ohms. This is measured on start-up. When
            tuning a new motor, check that this value is approximately equal
            to the value shown in the motor’s specification sheet.</long_desc>
      <unit>Ohms</unit>
      <decimal>3</decimal>
    </parameter>
Don Gagne's avatar
Don Gagne committed
    <parameter default="0.5" name="mot_v_accel" type="FLOAT">
      <short_desc>Acceleration limit (V)</short_desc>
      <long_desc>Acceleration limit (V)</long_desc>
      <unit>Volts</unit>
      <decimal>3</decimal>
      <min>0.01</min>
      <max>1.00</max>
    </parameter>
    <parameter default="14.8" name="mot_v_max" type="FLOAT">
      <short_desc>Motor voltage limit in volts</short_desc>
      <long_desc>Motor voltage limit in volts. The current controller’s
            commanded voltage will never exceed this value. Note that this may
            safely be above the nominal voltage of the motor; to determine the
            actual motor voltage limit, divide the motor’s rated power by the
            motor current limit.</long_desc>
      <unit>Volts</unit>
      <decimal>3</decimal>
      <min>0</min>
    </parameter>
  </group>
  <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="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>
      <decimal>2</decimal>
    </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>
      <decimal>2</decimal>
    </parameter>
    <parameter default="0.1" name="ATT_W_EXT_HDG" type="FLOAT">
      <short_desc>Complimentary filter external heading 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>
      <decimal>2</decimal>
    </parameter>
    <parameter default="0.0" name="ATT_MAG_DECL" type="FLOAT">
      <short_desc>Magnetic declination, in degrees</short_desc>
Don Gagne's avatar
Don Gagne committed
      <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>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>deg</unit>
      <decimal>2</decimal>
    </parameter>
    <parameter default="1" name="ATT_MAG_DECL_A" type="INT32">
      <short_desc>Enable automatic GPS based declination compensation</short_desc>
Lorenz Meier's avatar
Lorenz Meier committed
      <boolean />
    <parameter default="0" name="ATT_EXT_HDG_M" type="INT32">
      <short_desc>External heading usage mode (from Motion capture/Vision)
Set to 1 to use heading estimate from vision.
Set to 2 to use heading from motion capture</short_desc>
      <min>0</min>
      <max>2</max>
Lorenz Meier's avatar
Lorenz Meier committed
      <values>
        <value code="1">Vision</value>
        <value code="0">None</value>
        <value code="2">Motion Capture</value>
      </values>
Lorenz Meier's avatar
Lorenz Meier committed
    <parameter default="1" name="ATT_ACC_COMP" type="INT32">
      <short_desc>Enable acceleration compensation based on GPS
velocity</short_desc>
Lorenz Meier's avatar
Lorenz Meier committed
      <boolean />
    </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>
      <decimal>3</decimal>
Don Gagne's avatar
Don Gagne committed
    <parameter default="0.2" name="ATT_VIBE_THRESH" type="FLOAT">
      <short_desc>Threshold (of RMS) to warn about high vibration levels</short_desc>
      <min>0.01</min>
      <max>10</max>
      <decimal>2</decimal>
Don Gagne's avatar
Don Gagne committed
    </parameter>
  </group>
  <group name="Battery Calibration">
    <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>
      <decimal>2</decimal>
Lorenz Meier's avatar
Lorenz Meier committed
      <increment>0.01</increment>
    </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>
      <decimal>2</decimal>
Lorenz Meier's avatar
Lorenz Meier committed
      <increment>0.01</increment>
    </parameter>
    <parameter default="0.07" name="BAT_V_LOAD_DROP" type="FLOAT">
      <short_desc>Voltage drop per cell on 100% load</short_desc>
Don Gagne's avatar
Don Gagne committed
      <long_desc>This implicitely defines the internal resistance to maximum current ratio and assumes linearity.</long_desc>
      <min>0.0</min>
      <max>1.5</max>
      <decimal>2</decimal>
Lorenz Meier's avatar
Lorenz Meier committed
      <increment>0.01</increment>
    </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>
      <min>2</min>
Don Gagne's avatar
Don Gagne committed
      <max>10</max>
      <values>
Lorenz Meier's avatar
Lorenz Meier committed
        <value code="11">11S Battery</value>
        <value code="10">10S Battery</value>
Lorenz Meier's avatar
Lorenz Meier committed
        <value code="13">13S Battery</value>
        <value code="12">12S Battery</value>
        <value code="15">15S Battery</value>
        <value code="14">14S Battery</value>
        <value code="16">16S Battery</value>
        <value code="3">3S Battery</value>
        <value code="2">2S Battery</value>
        <value code="5">5S Battery</value>
        <value code="4">4S Battery</value>
        <value code="7">7S Battery</value>
        <value code="6">6S Battery</value>
        <value code="9">9S Battery</value>
        <value code="8">8S Battery</value>
      </values>
    </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>
Lorenz Meier's avatar
Lorenz Meier committed
      <min>-1.0</min>
      <max>100000</max>
      <decimal>0</decimal>
Lorenz Meier's avatar
Lorenz Meier committed
      <increment>50</increment>
Don Gagne's avatar
Don Gagne committed
    <parameter default="10000" name="BAT_V_SCALE_IO" type="INT32">
      <short_desc>Scaling factor for battery voltage sensor on PX4IO</short_desc>
      <min>1</min>
      <max>100000</max>
    </parameter>
    <parameter default="-1.0" name="BAT_V_SCALING" type="FLOAT">
Don Gagne's avatar
Don Gagne committed
      <short_desc>Scaling factor for battery voltage sensor on FMU v2</short_desc>
Don Gagne's avatar
Don Gagne committed
      <decimal>8</decimal>
Don Gagne's avatar
Don Gagne committed
    </parameter>
    <parameter default="-1.0" name="BAT_C_SCALING" type="FLOAT">
Don Gagne's avatar
Don Gagne committed
      <short_desc>Scaling factor for battery current sensor</short_desc>
Don Gagne's avatar
Don Gagne committed
      <decimal>8</decimal>
Don Gagne's avatar
Don Gagne committed
    </parameter>
Lorenz Meier's avatar
Lorenz Meier committed
    <parameter default="-1.0" name="BAT_C_OFFSET" type="FLOAT">
      <short_desc>Offset for battery current sensor</short_desc>
      <decimal>8</decimal>
    </parameter>
Don Gagne's avatar
Don Gagne committed
  </group>
  <group name="Camera trigger">
    <parameter default="40.0" name="TRIG_INTERVAL" type="FLOAT">
      <short_desc>Camera trigger interval</short_desc>
      <long_desc>This parameter sets the time between two consecutive trigger events</long_desc>
      <min>4.0</min>
      <max>10000.0</max>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>ms</unit>
Don Gagne's avatar
Don Gagne committed
    </parameter>
    <parameter default="0" name="TRIG_POLARITY" type="INT32">
      <short_desc>Camera trigger polarity</short_desc>
      <long_desc>This parameter sets the polarity of the trigger (0 = ACTIVE_LOW, 1 = ACTIVE_HIGH )</long_desc>
      <min>0</min>
      <max>1</max>
Lorenz Meier's avatar
Lorenz Meier committed
      <values>
        <value code="1">ACTIVE_HIGH</value>
        <value code="0">ACTIVE_LOW</value>
      </values>
Don Gagne's avatar
Don Gagne committed
    </parameter>
    <parameter default="0.5" name="TRIG_ACT_TIME" type="FLOAT">
      <short_desc>Camera trigger activation time</short_desc>
      <long_desc>This parameter sets the time the trigger needs to pulled high or low.</long_desc>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>ms</unit>
Don Gagne's avatar
Don Gagne committed
    </parameter>
    <parameter default="0" name="TRIG_MODE" type="INT32">
      <short_desc>Camera trigger mode</short_desc>
Lorenz Meier's avatar
Lorenz Meier committed
      <long_desc>0 disables the trigger, 1 sets it to enabled on command, 2 always on, 3 distance based, 4 distance based enabled on command</long_desc>
Don Gagne's avatar
Don Gagne committed
      <min>0</min>
Lorenz Meier's avatar
Lorenz Meier committed
      <max>4</max>
Lorenz Meier's avatar
Lorenz Meier committed
      <values>
        <value code="1">CMD</value>
        <value code="0">Disable</value>
        <value code="3">Distance</value>
        <value code="2">Always</value>
      </values>
Don Gagne's avatar
Don Gagne committed
    </parameter>
    <parameter default="12" name="TRIG_PINS" type="INT32">
      <short_desc>Camera trigger pin</short_desc>
      <long_desc>Selects which pin is used, ranges from 1 to 6 (AUX1-AUX6)</long_desc>
      <min>1</min>
      <max>123456</max>
    </parameter>
Lorenz Meier's avatar
Lorenz Meier committed
    <parameter default="25.0" name="TRIG_DISTANCE" type="FLOAT">
      <short_desc>Camera trigger distance</short_desc>
      <long_desc>Sets the distance at which to trigger the camera.</long_desc>
      <min>0</min>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>m</unit>
Lorenz Meier's avatar
Lorenz Meier committed
    </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>
Don Gagne's avatar
Don Gagne committed
      <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>
Lorenz Meier's avatar
Lorenz Meier committed
      <reboot_required>true</reboot_required>
    </parameter>
    <parameter default="0" name="CBRK_RATE_CTRL" type="INT32">
      <short_desc>Circuit breaker for rate controller output</short_desc>
Don Gagne's avatar
Don Gagne committed
      <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>
Lorenz Meier's avatar
Lorenz Meier committed
      <reboot_required>true</reboot_required>
    </parameter>
    <parameter default="0" name="CBRK_IO_SAFETY" type="INT32">
      <short_desc>Circuit breaker for IO safety</short_desc>
Don Gagne's avatar
Don Gagne committed
      <long_desc>Setting this parameter to 22027 will disable IO safety. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK</long_desc>
Lorenz Meier's avatar
Lorenz Meier committed
      <reboot_required>true</reboot_required>
    </parameter>
    <parameter default="0" name="CBRK_AIRSPD_CHK" type="INT32">
      <short_desc>Circuit breaker for airspeed sensor</short_desc>
Don Gagne's avatar
Don Gagne committed
      <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>
Lorenz Meier's avatar
Lorenz Meier committed
      <reboot_required>true</reboot_required>
    </parameter>
    <parameter default="121212" name="CBRK_FLIGHTTERM" type="INT32">
      <short_desc>Circuit breaker for flight termination</short_desc>
Don Gagne's avatar
Don Gagne committed
      <long_desc>Setting this parameter to 121212 will disable the flight termination action. --&gt; The IO driver will not do flight termination if requested by the FMU WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK</long_desc>
Lorenz Meier's avatar
Lorenz Meier committed
      <reboot_required>true</reboot_required>
    </parameter>
    <parameter default="284953" name="CBRK_ENGINEFAIL" type="INT32">
      <short_desc>Circuit breaker for engine failure detection</short_desc>
Lorenz Meier's avatar
Lorenz Meier committed
      <long_desc>Setting this parameter to 284953 will disable the engine failure detection. If the aircraft is in engine failure mode the engine failure flag will be set to healthy WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK</long_desc>
Lorenz Meier's avatar
Lorenz Meier committed
      <reboot_required>true</reboot_required>
    </parameter>
    <parameter default="240024" name="CBRK_GPSFAIL" type="INT32">
      <short_desc>Circuit breaker for GPS failure detection</short_desc>
Don Gagne's avatar
Don Gagne committed
      <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>
Lorenz Meier's avatar
Lorenz Meier committed
      <reboot_required>true</reboot_required>
    <parameter default="0" name="CBRK_BUZZER" type="INT32">
      <short_desc>Circuit breaker for disabling buzzer</short_desc>
      <long_desc>Setting this parameter to 782097 will disable the buzzer audio notification. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK</long_desc>
      <min>0</min>
      <max>782097</max>
Lorenz Meier's avatar
Lorenz Meier committed
      <reboot_required>true</reboot_required>
    <parameter default="0" name="CBRK_USB_CHK" type="INT32">
      <short_desc>Circuit breaker for USB link check</short_desc>
      <long_desc>Setting this parameter to 197848 will disable the USB connected checks in the commander. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK</long_desc>
      <min>0</min>
      <max>197848</max>
Lorenz Meier's avatar
Lorenz Meier committed
      <reboot_required>true</reboot_required>
    </parameter>
  </group>
  <group name="Commander">
    <parameter default="0" name="COM_DL_LOSS_EN" type="INT32">
Lorenz Meier's avatar
Lorenz Meier committed
      <short_desc>Datalink loss failsafe</short_desc>
      <long_desc>Set to 1 to enable actions triggered when the datalink is lost.</long_desc>
Lorenz Meier's avatar
Lorenz Meier committed
      <boolean />
    </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>
Lorenz Meier's avatar
Lorenz Meier committed
      <max>300</max>
      <unit>s</unit>
Lorenz Meier's avatar
Lorenz Meier committed
      <decimal>1</decimal>
      <increment>0.5</increment>
    </parameter>
    <parameter default="0" name="COM_DL_REG_T" type="INT32">
      <short_desc>Datalink regain time threshold</short_desc>
Don Gagne's avatar
Don Gagne committed
      <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>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>s</unit>
Lorenz Meier's avatar
Lorenz Meier committed
      <decimal>1</decimal>
      <increment>0.5</increment>
    </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>
      <decimal>1</decimal>
Lorenz Meier's avatar
Lorenz Meier committed
      <increment>0.05</increment>
    </parameter>
    <parameter default="5.0" name="COM_EF_C2T" type="FLOAT">
      <short_desc>Engine Failure Current/Throttle Threshold</short_desc>
Don Gagne's avatar
Don Gagne committed
      <long_desc>Engine failure triggers only below this current value</long_desc>
Lorenz Meier's avatar
Lorenz Meier committed
      <max>50.0</max>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>A</unit>
      <decimal>2</decimal>
Lorenz Meier's avatar
Lorenz Meier committed
      <increment>1</increment>
    </parameter>
    <parameter default="10.0" name="COM_EF_TIME" type="FLOAT">
      <short_desc>Engine Failure Time Threshold</short_desc>
Don Gagne's avatar
Don Gagne committed
      <long_desc>Engine failure triggers only if the throttle threshold and the current to throttle threshold are violated for this time</long_desc>
Don Gagne's avatar
Don Gagne committed
      <max>60.0</max>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>s</unit>
      <decimal>1</decimal>
Lorenz Meier's avatar
Lorenz Meier committed
      <increment>1</increment>
    </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>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>s</unit>
      <decimal>1</decimal>
Lorenz Meier's avatar
Lorenz Meier committed
      <increment>0.1</increment>
Don Gagne's avatar
Don Gagne committed
    <parameter default="5.0" name="COM_HOME_H_T" type="FLOAT">
      <short_desc>Home set horizontal threshold</short_desc>
      <long_desc>The home position will be set if the estimated positioning accuracy is below the threshold.</long_desc>
      <min>2</min>
      <max>15</max>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>m</unit>
      <decimal>2</decimal>
Lorenz Meier's avatar
Lorenz Meier committed
      <increment>0.5</increment>
Don Gagne's avatar
Don Gagne committed
    </parameter>
    <parameter default="10.0" name="COM_HOME_V_T" type="FLOAT">
      <short_desc>Home set vertical threshold</short_desc>
      <long_desc>The home position will be set if the estimated positioning accuracy is below the threshold.</long_desc>
      <min>5</min>
      <max>25</max>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>m</unit>
      <decimal>2</decimal>
Lorenz Meier's avatar
Lorenz Meier committed
      <increment>0.5</increment>
Don Gagne's avatar
Don Gagne committed
    </parameter>
    <parameter default="1" name="COM_AUTOS_PAR" type="INT32">
      <short_desc>Autosaving of params</short_desc>
Don Gagne's avatar
Don Gagne committed
      <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>
Lorenz Meier's avatar
Lorenz Meier committed
      <boolean />
    </parameter>
    <parameter default="0" name="COM_RC_IN_MODE" type="INT32">
      <short_desc>RC control input mode</short_desc>
Lorenz Meier's avatar
Lorenz Meier committed
      <long_desc>The default value of 0 requires a valid RC transmitter setup. Setting this to 1 allows joystick control and 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>
      <values>
Lorenz Meier's avatar
Lorenz Meier committed
        <value code="1">Joystick/No RC Checks</value>
        <value code="0">RC Transmitter</value>
        <value code="2">Virtual RC by Joystick</value>
      </values>
    <parameter default="0" name="COM_DISARM_LAND" type="INT32">
      <short_desc>Time-out for auto disarm after landing</short_desc>
      <long_desc>A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be automatically disarmed in case a landing situation has been detected during this period. A value of zero means that automatic disarming is disabled.</long_desc>
      <min>0</min>
Lorenz Meier's avatar
Lorenz Meier committed
      <max>20</max>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>s</unit>
Lorenz Meier's avatar
Lorenz Meier committed
      <decimal>0</decimal>
      <increment>1</increment>
  </group>
  <group name="Data Link Loss">
    <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>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>s</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>
Don Gagne's avatar
Don Gagne committed
      <min>-900000000</min>
      <max>900000000</max>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>deg * 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>
Don Gagne's avatar
Don Gagne committed
      <min>-1800000000</min>
      <max>1800000000</max>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>deg * 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>
Don Gagne's avatar
Don Gagne committed
      <min>-50</min>
      <max>30000</max>
      <unit>m</unit>
    </parameter>
    <parameter default="120.0" name="NAV_DLL_AH_T" type="FLOAT">
Don Gagne's avatar
Don Gagne committed
      <short_desc>Airfield 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>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>s</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>
Don Gagne's avatar
Don Gagne committed
      <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>
Lorenz Meier's avatar
Lorenz Meier committed
      <boolean />
Don Gagne's avatar
Don Gagne committed
    <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>-900000000</min>
      <max>900000000</max>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>deg * 1e7</unit>
Don Gagne's avatar
Don Gagne committed
    </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>-1800000000</min>
      <max>1800000000</max>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>deg * 1e7</unit>
Don Gagne's avatar
Don Gagne committed
    </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>-50</min>
      <unit>m</unit>
    </parameter>
  <group name="EKF2">
    <parameter default="0" name="EKF2_MAG_DELAY" type="FLOAT">
      <short_desc>Magnetometer measurement delay relative to IMU measurements</short_desc>
      <min>0</min>
      <max>300</max>
      <unit>ms</unit>
    </parameter>
    <parameter default="0" name="EKF2_BARO_DELAY" type="FLOAT">
      <short_desc>Barometer measurement delay relative to IMU measurements</short_desc>
      <min>0</min>
      <max>300</max>
      <unit>ms</unit>
    </parameter>
    <parameter default="200" name="EKF2_GPS_DELAY" type="FLOAT">
      <short_desc>GPS measurement delay relative to IMU measurements</short_desc>
      <min>0</min>
      <max>300</max>
      <unit>ms</unit>
    </parameter>
    <parameter default="200" name="EKF2_ASP_DELAY" type="FLOAT">
      <short_desc>Airspeed measurement delay relative to IMU measurements</short_desc>
      <min>0</min>
      <max>300</max>
      <unit>ms</unit>
    </parameter>
    <parameter default="21" name="EKF2_GPS_CHECK" type="INT32">
Lorenz Meier's avatar
Lorenz Meier committed
      <short_desc>Integer bitmask controlling GPS checks</short_desc>
      <long_desc>Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Minimum required sat count set by EKF2_REQ_NSATS 1 : Minimum required GDoP set by EKF2_REQ_GDOP 2 : Maximum allowed horizontal position error set by EKF2_REQ_EPH 3 : Maximum allowed vertical position error set by EKF2_REQ_EPV 4 : Maximum allowed speed error set by EKF2_REQ_SACC 5 : Maximum allowed horizontal position rate set by EKF2_REQ_HDRIFT. This check can only be used if the vehciel is stationary during alignment. 6 : Maximum allowed vertical position rate set by EKF2_REQ_VDRIFT. This check can only be used if the vehciel is stationary during alignment. 7 : Maximum allowed horizontal speed set by EKF2_REQ_HDRIFT. This check can only be used if the vehciel is stationary during alignment. 8 : Maximum allowed vertical velocity discrepancy set by EKF2_REQ_VDRIFT</long_desc>
      <min>0</min>
      <max>511</max>
    </parameter>
    <parameter default="5.0" name="EKF2_REQ_EPH" type="FLOAT">
      <short_desc>Required EPH to use GPS</short_desc>
      <min>2</min>
      <max>100</max>
      <unit>m</unit>
    </parameter>
    <parameter default="8.0" name="EKF2_REQ_EPV" type="FLOAT">
      <short_desc>Required EPV to use GPS</short_desc>
      <min>2</min>
      <max>100</max>
      <unit>m</unit>
    </parameter>
    <parameter default="1.0" name="EKF2_REQ_SACC" type="FLOAT">
      <short_desc>Required speed accuracy to use GPS</short_desc>
      <min>0.5</min>
      <max>5.0</max>
      <unit>m/s</unit>
    </parameter>
    <parameter default="6" name="EKF2_REQ_NSATS" type="INT32">
      <short_desc>Required satellite count to use GPS</short_desc>
      <min>4</min>
      <max>12</max>
    </parameter>
    <parameter default="2.5" name="EKF2_REQ_GDOP" type="FLOAT">
      <short_desc>Required GDoP to use GPS</short_desc>
      <min>1.5</min>
      <max>5.0</max>
    </parameter>
    <parameter default="0.3" name="EKF2_REQ_HDRIFT" type="FLOAT">
      <short_desc>Maximum horizontal drift speed to use GPS</short_desc>
      <min>0.1</min>
      <max>1.0</max>
      <unit>m/s</unit>
    </parameter>
    <parameter default="0.5" name="EKF2_REQ_VDRIFT" type="FLOAT">
      <short_desc>Maximum vertical drift speed to use GPS</short_desc>
      <min>0.1</min>
      <max>1.5</max>
      <unit>m/s</unit>
    </parameter>
Lorenz Meier's avatar
Lorenz Meier committed
    <parameter default="6.0e-2" name="EKF2_GYR_NOISE" type="FLOAT">
      <short_desc>Rate gyro noise for covariance prediction</short_desc>
      <min>0.0001</min>
Lorenz Meier's avatar
Lorenz Meier committed
      <max>0.1</max>
      <unit>rad/s</unit>
    </parameter>
    <parameter default="0.25" name="EKF2_ACC_NOISE" type="FLOAT">
      <short_desc>Accelerometer noise for covariance prediction</short_desc>
      <min>0.01</min>
      <max>1.0</max>
      <unit>m/s/s</unit>
    </parameter>
Lorenz Meier's avatar
Lorenz Meier committed
    <parameter default="2.5e-6" name="EKF2_GYR_B_NOISE" type="FLOAT">
      <short_desc>Process noise for delta angle bias prediction</short_desc>
      <min>0.0</min>
      <max>0.0001</max>
      <unit>rad/s</unit>
    </parameter>
Lorenz Meier's avatar
Lorenz Meier committed
    <parameter default="3.0e-5" name="EKF2_ACC_B_NOISE" type="FLOAT">
      <short_desc>Process noise for delta velocity z bias prediction</short_desc>
      <min>0.0</min>
      <max>0.01</max>
      <unit>m/s/s</unit>
    </parameter>
Lorenz Meier's avatar
Lorenz Meier committed
    <parameter default="3.0e-4" name="EKF2_GYR_S_NOISE" type="FLOAT">
      <short_desc>Process noise for delta angle scale factor prediction</short_desc>
      <min>0.0</min>
      <max>0.01</max>
    </parameter>
Lorenz Meier's avatar
Lorenz Meier committed
    <parameter default="5.0e-4" name="EKF2_MAG_B_NOISE" type="FLOAT">
      <short_desc>Process noise for body magnetic field prediction</short_desc>
      <min>0.0</min>
      <max>0.1</max>
      <unit>Gauss/s</unit>
    </parameter>
    <parameter default="2.5e-3" name="EKF2_MAG_E_NOISE" type="FLOAT">
      <short_desc>Process noise for earth magnetic field prediction</short_desc>
      <min>0.0</min>
      <max>0.1</max>
      <unit>Gauss/s</unit>
    </parameter>
    <parameter default="1.0e-1" name="EKF2_WIND_NOISE" type="FLOAT">
      <short_desc>Process noise for wind velocity prediction</short_desc>
      <min>0.0</min>
      <max>1.0</max>
      <unit>m/s/s</unit>
    </parameter>
    <parameter default="0.5" name="EKF2_GPS_V_NOISE" type="FLOAT">
      <short_desc>Measurement noise for gps horizontal velocity</short_desc>
      <min>0.01</min>
      <max>5.0</max>
      <unit>m/s</unit>
    </parameter>
Lorenz Meier's avatar
Lorenz Meier committed
    <parameter default="0.5" name="EKF2_GPS_P_NOISE" type="FLOAT">
      <short_desc>Measurement noise for gps position</short_desc>
      <min>0.01</min>
      <max>10.0</max>
      <unit>m</unit>
    </parameter>
    <parameter default="10.0" name="EKF2_NOAID_NOISE" type="FLOAT">
      <short_desc>Measurement noise for non-aiding position hold</short_desc>
      <min>0.5</min>
      <max>50.0</max>
      <unit>m</unit>
    </parameter>
    <parameter default="3.0" name="EKF2_BARO_NOISE" type="FLOAT">
      <short_desc>Measurement noise for barometric altitude</short_desc>
      <min>0.01</min>
      <max>15.0</max>
      <unit>m</unit>
    </parameter>
Lorenz Meier's avatar
Lorenz Meier committed
    <parameter default="0.3" name="EKF2_HEAD_NOISE" type="FLOAT">
      <short_desc>Measurement noise for magnetic heading fusion</short_desc>
      <min>0.01</min>
      <max>1.0</max>
      <unit>rad</unit>
    </parameter>
    <parameter default="5.0e-2" name="EKF2_MAG_NOISE" type="FLOAT">
      <short_desc>Measurement noise for magnetometer 3-axis fusion</short_desc>
      <min>0.001</min>
      <max>1.0</max>
      <unit>Gauss</unit>
    </parameter>
Lorenz Meier's avatar
Lorenz Meier committed
    <parameter default="1.4" name="EKF2_EAS_NOISE" type="FLOAT">
      <short_desc>Measurement noise for airspeed fusion</short_desc>
      <min>0.5</min>
      <max>5.0</max>
      <unit>m/s</unit>
    </parameter>
    <parameter default="0" name="EKF2_MAG_DECL" type="FLOAT">
      <short_desc>Magnetic declination</short_desc>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>deg</unit>
    </parameter>
Lorenz Meier's avatar
Lorenz Meier committed
    <parameter default="2.6" name="EKF2_HDG_GATE" type="FLOAT">
      <short_desc>Gate size for magnetic heading fusion</short_desc>
      <min>1.0</min>
      <unit>SD</unit>
    </parameter>
    <parameter default="3.0" name="EKF2_MAG_GATE" type="FLOAT">
      <short_desc>Gate size for magnetometer XYZ component fusion</short_desc>
      <min>1.0</min>
      <unit>SD</unit>
    </parameter>
    <parameter default="7" name="EKF2_DECL_TYPE" type="INT32">
Lorenz Meier's avatar
Lorenz Meier committed
      <short_desc>Integer bitmask controlling handling of magnetic declination</short_desc>
      <long_desc>Set bits in the following positions to enable functions. 0 : Set to true to use the declination from the geo_lookup library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value. 1 : Set to true to save the EKF2_MAG_DECL parameter to the value returned by the EKF when the vehicle disarms. 2 : Set to true to always use the declination as an observaton when 3-axis magnetometer fusion is being used.</long_desc>
      <min>0</min>
      <max>7</max>
    </parameter>
    <parameter default="0" name="EKF2_MAG_TYPE" type="INT32">
Lorenz Meier's avatar
Lorenz Meier committed
      <short_desc>Type of magnetometer fusion</short_desc>
      <long_desc>Integer controlling the type of magnetometer fusion used - magnetic heading or 3-axis magnetometer. If set to automatic: heading fusion on-ground and 3-axis fusion in-flight</long_desc>
      <values>
        <value code="1">Magnetic heading</value>
        <value code="0">Automatic</value>
        <value code="3">2-D projection</value>
        <value code="2">3-axis fusion</value>
        <value code="4">None</value>
      </values>
    </parameter>
Lorenz Meier's avatar
Lorenz Meier committed
    <parameter default="5.0" name="EKF2_BARO_GATE" type="FLOAT">
      <short_desc>Gate size for barometric height fusion</short_desc>
      <min>1.0</min>
      <unit>SD</unit>
    </parameter>
Lorenz Meier's avatar
Lorenz Meier committed
    <parameter default="5.0" name="EKF2_GPS_P_GATE" type="FLOAT">
      <short_desc>Gate size for GPS horizontal position fusion</short_desc>
      <min>1.0</min>
      <unit>SD</unit>
    </parameter>
Lorenz Meier's avatar
Lorenz Meier committed
    <parameter default="5.0" name="EKF2_GPS_V_GATE" type="FLOAT">
      <short_desc>Gate size for GPS velocity fusion</short_desc>
      <min>1.0</min>
      <unit>SD</unit>
    </parameter>
Lorenz Meier's avatar
Lorenz Meier committed
    <parameter default="0" name="EKF2_REC_RPL" type="INT32">
Lorenz Meier's avatar
Lorenz Meier committed
      <short_desc>Replay mode</short_desc>
      <long_desc>A value of 1 indicates that the ekf2 module will publish replay messages for logging.</long_desc>
      <boolean />
    </parameter>
    <parameter default="1" name="EKF2_AID_MASK" type="INT32">
      <short_desc>Integer bitmask controlling which external aiding sources will be used</short_desc>
      <long_desc>Set bits in the following positions to enable: 0 : Set to true to use GPS data if available 1 : Set to true to use optical flow data if available</long_desc>
Lorenz Meier's avatar
Lorenz Meier committed
      <min>0</min>
Lorenz Meier's avatar
Lorenz Meier committed
      <max>3</max>
    </parameter>
    <parameter default="0" name="EKF2_HGT_MODE" type="INT32">
      <short_desc>Determines the primary source of height data used by the EKF</short_desc>
      <long_desc>The range sensor option should only be used when for operation over a flat surface as the local NED origin will move up and down with ground level.</long_desc>
      <values>
        <value code="1">Reserved (GPS)</value>
        <value code="0">Barometric pressure</value>
        <value code="2">Range sensor</value>
      </values>
    </parameter>
    <parameter default="0.1" name="EKF2_RNG_NOISE" type="FLOAT">
      <short_desc>Measurement noise for range finder fusion</short_desc>
      <min>0.01</min>
      <unit>m</unit>
    </parameter>
    <parameter default="5.0" name="EKF2_RNG_GATE" type="FLOAT">
      <short_desc>Gate size for range finder fusion</short_desc>
      <min>1.0</min>
      <unit>SD</unit>
    </parameter>
    <parameter default="0.1" name="EKF2_MIN_RNG" type="FLOAT">
      <short_desc>Minimum valid range for the range finder</short_desc>
      <min>0.01</min>
      <unit>m</unit>
    </parameter>
    <parameter default="0.15" name="EKF2_OF_N_MIN" type="FLOAT">
      <short_desc>Measurement noise for the optical flow sensor when it's reported quality metric is at the maximum</short_desc>
      <min>0.05</min>
      <unit>rad/s</unit>
    </parameter>
    <parameter default="0.5" name="EKF2_OF_N_MAX" type="FLOAT">
      <short_desc>Measurement noise for the optical flow sensor</short_desc>
      <long_desc>(when it's reported quality metric is at the minimum set by EKF2_OF_QMIN). The following condition must be met: EKF2_OF_N_MAXN &gt;= EKF2_OF_N_MIN</long_desc>
      <min>0.05</min>
      <unit>rad/s</unit>
    </parameter>
    <parameter default="1" name="EKF2_OF_QMIN" type="INT32">
      <short_desc>Optical Flow data will only be used if the sensor reports a quality metric &gt;= EKF2_OF_QMIN</short_desc>
      <min>0</min>
      <max>255</max>
    </parameter>
    <parameter default="3.0" name="EKF2_OF_GATE" type="FLOAT">
      <short_desc>Gate size for optical flow fusion</short_desc>
      <min>1.0</min>
      <unit>SD</unit>
    </parameter>
    <parameter default="2.5" name="EKF2_OF_RMAX" type="FLOAT">
      <short_desc>Optical Flow data will not fused if the magnitude of the flow rate &gt; EKF2_OF_RMAX</short_desc>
      <min>1.0</min>
      <unit>rad/s</unit>
    </parameter>
    <parameter default="5.0" name="EKF2_TERR_NOISE" type="FLOAT">
      <short_desc>Terrain altitude process noise - accounts for instability in vehicle height estimate</short_desc>
      <min>0.5</min>
      <unit>m/s</unit>
    </parameter>
    <parameter default="0.5" name="EKF2_TERR_GRAD" type="FLOAT">
      <short_desc>Magnitude of terrain gradient</short_desc>
      <min>0.0</min>
      <unit>m/m</unit>
Lorenz Meier's avatar
Lorenz Meier committed
    </parameter>
  <group name="FW Attitude Control">
    <parameter default="0.4" name="FW_R_TC" type="FLOAT">
      <short_desc>Attitude Roll Time Constant</short_desc>
      <long_desc>This defines the latency between a roll 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>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>s</unit>
    <parameter default="0.4" name="FW_P_TC" type="FLOAT">
      <short_desc>Attitude Pitch Time Constant</short_desc>
      <long_desc>This defines the latency between a pitch 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.2</min>
      <max>1.0</max>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>s</unit>
    </parameter>
Don Gagne's avatar
Don Gagne committed
    <parameter default="0.08" name="FW_PR_P" type="FLOAT">
      <short_desc>Pitch rate proportional gain</short_desc>
Don Gagne's avatar
Don Gagne committed
      <long_desc>This defines how much the elevator input will be commanded depending on the current body angular rate error.</long_desc>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>%/rad/s</unit>
Don Gagne's avatar
Don Gagne committed
    <parameter default="0.02" name="FW_PR_I" type="FLOAT">
      <short_desc>Pitch rate integrator gain</short_desc>
Don Gagne's avatar
Don Gagne committed
      <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.005</min>
      <max>0.5</max>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>%/rad</unit>
Don Gagne's avatar
Don Gagne committed
    <parameter default="60.0" name="FW_P_RMAX_POS" type="FLOAT">
      <short_desc>Maximum positive / up pitch rate</short_desc>
Don Gagne's avatar
Don Gagne committed
      <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>
Don Gagne's avatar
Don Gagne committed
    <parameter default="60.0" name="FW_P_RMAX_NEG" type="FLOAT">
      <short_desc>Maximum negative / down pitch rate</short_desc>
Don Gagne's avatar
Don Gagne committed
      <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>
Don Gagne's avatar
Don Gagne committed
    <parameter default="0.4" name="FW_PR_IMAX" type="FLOAT">
      <short_desc>Pitch rate integrator limit</short_desc>
Don Gagne's avatar
Don Gagne committed
      <long_desc>The portion of the integrator part in the control surface deflection is limited to this value</long_desc>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>%</unit>
    </parameter>
    <parameter default="0.05" name="FW_RR_P" type="FLOAT">
      <short_desc>Roll rate proportional Gain</short_desc>
Don Gagne's avatar
Don Gagne committed
      <long_desc>This defines how much the aileron input will be commanded depending on the current body angular rate error.</long_desc>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>%/rad/s</unit>
Don Gagne's avatar
Don Gagne committed
    <parameter default="0.01" name="FW_RR_I" type="FLOAT">
      <short_desc>Roll rate integrator Gain</short_desc>
Don Gagne's avatar
Don Gagne committed
      <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.005</min>
      <max>0.2</max>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>%/rad</unit>
    </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>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>%</unit>
Don Gagne's avatar
Don Gagne committed
    <parameter default="70.0" name="FW_R_RMAX" type="FLOAT">
      <short_desc>Maximum Roll Rate</short_desc>
Don Gagne's avatar
Don Gagne committed
      <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>
Don Gagne's avatar
Don Gagne committed
      <long_desc>This defines how much the rudder input will be commanded depending on the current body angular rate error.</long_desc>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>%/rad/s</unit>
    </parameter>
    <parameter default="0.0" name="FW_YR_I" type="FLOAT">
      <short_desc>Yaw rate integrator gain</short_desc>
Don Gagne's avatar
Don Gagne committed
      <long_desc>This gain defines how much control response will result out of a steady state error. It trims any constant error.</long_desc>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>%/rad</unit>
    </parameter>
    <parameter default="0.2" name="FW_YR_IMAX" type="FLOAT">
      <short_desc>Yaw rate integrator limit</short_desc>
Don Gagne's avatar
Don Gagne committed
      <long_desc>The portion of the integrator part in the control surface deflection is limited to this value</long_desc>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>%</unit>
    </parameter>
    <parameter default="0.0" name="FW_Y_RMAX" type="FLOAT">
      <short_desc>Maximum Yaw Rate</short_desc>
Don Gagne's avatar
Don Gagne committed
      <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.5" name="FW_WR_P" type="FLOAT">
      <short_desc>Wheel steering rate proportional gain</short_desc>
      <long_desc>This defines how much the wheel steering input will be commanded depending on the current body angular rate error.</long_desc>
      <min>0.005</min>
      <max>1.0</max>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>%/rad/s</unit>
    </parameter>
    <parameter default="0.1" name="FW_WR_I" type="FLOAT">
      <short_desc>Wheel steering 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>
Lorenz Meier's avatar
Lorenz Meier committed
      <unit>%/rad</unit>
    </parameter>