<?xml version='1.0' encoding='UTF-8'?>
<parameters>
  <version>3</version>
  <parameter_version_major>1</parameter_version_major>
  <parameter_version_minor>15</parameter_version_minor>
  <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>
      <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>
    <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 Q estimator">
    <parameter default="1" name="ATT_ACC_COMP" type="INT32">
      <short_desc>Acceleration compensation based on GPS
velocity</short_desc>
      <boolean />
      <scope>modules/attitude_estimator_q</scope>
    </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>
      <scope>modules/attitude_estimator_q</scope>
    </parameter>
    <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>
      <scope>modules/attitude_estimator_q</scope>
      <values>
        <value code="0">None</value>
        <value code="1">Vision</value>
        <value code="2">Motion Capture</value>
      </values>
    </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>deg</unit>
      <decimal>2</decimal>
      <scope>modules/attitude_estimator_q</scope>
    </parameter>
    <parameter default="1" name="ATT_MAG_DECL_A" type="INT32">
      <short_desc>Automatic GPS based declination compensation</short_desc>
      <boolean />
      <scope>modules/attitude_estimator_q</scope>
    </parameter>
    <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>
      <scope>modules/attitude_estimator_q</scope>
    </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>
      <scope>modules/attitude_estimator_q</scope>
    </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>
      <scope>modules/attitude_estimator_q</scope>
    </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>
      <scope>modules/attitude_estimator_q</scope>
    </parameter>
  </group>
  <group name="Battery Calibration">
    <parameter default="-1.0" name="BAT_A_PER_V" type="FLOAT">
      <short_desc>Battery current per volt (A/V)</short_desc>
      <long_desc>The voltage seen by the 3.3V ADC multiplied by this factor will determine the battery current. A value of -1 means to use the board default.</long_desc>
      <decimal>8</decimal>
      <scope>modules/sensors</scope>
    </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>
      <min>-1.0</min>
      <max>100000</max>
      <unit>mAh</unit>
      <decimal>0</decimal>
      <increment>50</increment>
      <reboot_required>true</reboot_required>
      <scope>lib/battery</scope>
    </parameter>
    <parameter default="-1.0" name="BAT_CNT_V_CURR" type="FLOAT">
      <short_desc>Scaling from ADC counts to volt on the ADC input (battery current)</short_desc>
      <long_desc>This is not the battery current, but the intermediate ADC voltage. A value of -1 signifies that the board defaults are used, which is highly recommended.</long_desc>
      <decimal>8</decimal>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="-1.0" name="BAT_CNT_V_VOLT" type="FLOAT">
      <short_desc>Scaling from ADC counts to volt on the ADC input (battery voltage)</short_desc>
      <long_desc>This is not the battery voltage, but the intermediate ADC voltage. A value of -1 signifies that the board defaults are used, which is highly recommended.</long_desc>
      <decimal>8</decimal>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.07" name="BAT_CRIT_THR" type="FLOAT">
      <short_desc>Critical threshold</short_desc>
      <long_desc>Sets the threshold when the battery will be reported as critically low. This has to be lower than the low threshold. This threshold commonly will trigger RTL.</long_desc>
      <min>0.05</min>
      <max>0.1</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <reboot_required>true</reboot_required>
      <scope>lib/battery</scope>
    </parameter>
    <parameter default="0.05" name="BAT_EMERGEN_THR" type="FLOAT">
      <short_desc>Emergency threshold</short_desc>
      <long_desc>Sets the threshold when the battery will be reported as dangerously low. This has to be lower than the critical threshold. This threshold commonly will trigger landing.</long_desc>
      <min>0.03</min>
      <max>0.07</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <reboot_required>true</reboot_required>
      <scope>lib/battery</scope>
    </parameter>
    <parameter default="0.15" name="BAT_LOW_THR" type="FLOAT">
      <short_desc>Low threshold</short_desc>
      <long_desc>Sets the threshold when the battery will be reported as low. This has to be higher than the critical threshold.</long_desc>
      <min>0.12</min>
      <max>0.4</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <reboot_required>true</reboot_required>
      <scope>lib/battery</scope>
    </parameter>
    <parameter default="0" 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>
      <reboot_required>true</reboot_required>
      <scope>lib/battery</scope>
      <values>
        <value code="0">Unconfigured</value>
        <value code="2">2S Battery</value>
        <value code="3">3S Battery</value>
        <value code="4">4S Battery</value>
        <value code="5">5S Battery</value>
        <value code="6">6S Battery</value>
        <value code="7">7S Battery</value>
        <value code="8">8S Battery</value>
        <value code="9">9S Battery</value>
        <value code="10">10S Battery</value>
        <value code="11">11S Battery</value>
        <value code="12">12S Battery</value>
        <value code="13">13S Battery</value>
        <value code="14">14S Battery</value>
        <value code="15">15S Battery</value>
        <value code="16">16S Battery</value>
      </values>
    </parameter>
    <parameter default="-1.0" name="BAT_R_INTERNAL" type="FLOAT">
      <short_desc>Explicitly defines the per cell internal resistance</short_desc>
      <long_desc>If non-negative, then this will be used in place of BAT_V_LOAD_DROP for all calculations.</long_desc>
      <min>-1.0</min>
      <max>0.2</max>
      <unit>Ohms</unit>
      <reboot_required>true</reboot_required>
      <scope>lib/battery</scope>
    </parameter>
    <parameter default="0" name="BAT_SOURCE" type="INT32">
      <short_desc>Battery monitoring source</short_desc>
      <long_desc>This parameter controls the source of battery data. The value 'Power Module' means that measurements are expected to come from a power module. If the value is set to 'External' then the system expects to receive mavlink battery status messages.</long_desc>
      <min>0</min>
      <max>1</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Power Module</value>
        <value code="1">External</value>
      </values>
    </parameter>
    <parameter default="4.05" name="BAT_V_CHARGED" type="FLOAT">
      <short_desc>Full cell voltage (5C load)</short_desc>
      <long_desc>Defines the voltage where a single cell of the battery is considered full under a mild load. This will never be the nominal voltage of 4.2V</long_desc>
      <unit>V</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <reboot_required>true</reboot_required>
      <scope>lib/battery</scope>
    </parameter>
    <parameter default="-1.0" name="BAT_V_DIV" type="FLOAT">
      <short_desc>Battery voltage divider (V divider)</short_desc>
      <long_desc>This is the divider from battery voltage to 3.3V ADC voltage. If using e.g. Mauch power modules the value from the datasheet can be applied straight here. A value of -1 means to use the board default.</long_desc>
      <decimal>8</decimal>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="3.5" name="BAT_V_EMPTY" type="FLOAT">
      <short_desc>Empty cell voltage (5C load)</short_desc>
      <long_desc>Defines the voltage where a single cell of the battery is considered empty. The voltage should be chosen before the steep dropoff to 2.8V. A typical lithium battery can only be discharged down to 10% before it drops off to a voltage level damaging the cells.</long_desc>
      <unit>V</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <reboot_required>true</reboot_required>
      <scope>lib/battery</scope>
    </parameter>
    <parameter default="0.3" name="BAT_V_LOAD_DROP" type="FLOAT">
      <short_desc>Voltage drop per cell on full throttle</short_desc>
      <long_desc>This implicitely defines the internal resistance to maximum current ratio and assumes linearity. A good value to use is the difference between the 5C and 20-25C load. Not used if BAT_R_INTERNAL is set.</long_desc>
      <min>0.07</min>
      <max>0.5</max>
      <unit>V</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <reboot_required>true</reboot_required>
      <scope>lib/battery</scope>
    </parameter>
    <parameter default="0.0" name="BAT_V_OFFS_CURR" type="FLOAT">
      <short_desc>Offset in volt as seen by the ADC input of the current sensor</short_desc>
      <long_desc>This offset will be subtracted before calculating the battery current based on the voltage.</long_desc>
      <decimal>8</decimal>
      <scope>modules/sensors</scope>
    </parameter>
  </group>
  <group name="Camera Control">
    <parameter default="0" name="CAM_FBACK_MODE" type="INT32">
      <short_desc>Camera feedback mode</short_desc>
      <long_desc>Sets the camera feedback mode.</long_desc>
      <min>0</min>
      <max>1</max>
      <scope>modules/camera_feedback</scope>
      <values>
        <value code="0">Disabled</value>
        <value code="1">Feedback on trigger</value>
      </values>
    </parameter>
  </group>
  <group name="Camera trigger">
    <parameter default="40.0" 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>
      <min>0.1</min>
      <max>3000</max>
      <unit>ms</unit>
      <decimal>1</decimal>
      <scope>drivers/camera_trigger</scope>
    </parameter>
    <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>
      <unit>m</unit>
      <decimal>1</decimal>
      <increment>1</increment>
      <scope>drivers/camera_trigger</scope>
    </parameter>
    <parameter default="4" name="TRIG_INTERFACE" type="INT32">
      <short_desc>Camera trigger Interface</short_desc>
      <long_desc>Selects the trigger interface</long_desc>
      <reboot_required>true</reboot_required>
      <scope>drivers/camera_trigger</scope>
      <values>
        <value code="1">GPIO</value>
        <value code="2">Seagull MAP2 (over PWM)</value>
        <value code="3">MAVLink (forward via MAV_CMD_IMAGE_START_CAPTURE)</value>
        <value code="4">Generic PWM (IR trigger, servo)</value>
      </values>
    </parameter>
    <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>
      <unit>ms</unit>
      <decimal>1</decimal>
      <scope>drivers/camera_trigger</scope>
    </parameter>
    <parameter default="0" name="TRIG_MODE" type="INT32">
      <short_desc>Camera trigger mode</short_desc>
      <min>0</min>
      <max>4</max>
      <reboot_required>true</reboot_required>
      <scope>drivers/camera_trigger</scope>
      <values>
        <value code="0">Disable</value>
        <value code="1">Time based, on command</value>
        <value code="2">Time based, always on</value>
        <value code="3">Distance based, always on</value>
        <value code="4">Distance based, on command (Survey mode)</value>
      </values>
    </parameter>
    <parameter default="56" 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 on px4fmu-v2 and the rail pins on px4fmu-v4). The PWM interface takes two pins per camera, while relay triggers on every pin individually. Example: Value 56 would trigger on pins 5 and 6.</long_desc>
      <min>1</min>
      <max>123456</max>
      <decimal>0</decimal>
      <reboot_required>true</reboot_required>
      <scope>drivers/camera_trigger</scope>
    </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>
      <scope>drivers/camera_trigger</scope>
      <values>
        <value code="0">Active low</value>
        <value code="1">Active high</value>
      </values>
    </parameter>
  </group>
  <group name="Circuit Breaker">
    <parameter category="Developer" 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>
      <reboot_required>true</reboot_required>
      <scope>modules/systemlib</scope>
    </parameter>
    <parameter category="Developer" 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>
      <reboot_required>true</reboot_required>
      <scope>modules/systemlib</scope>
    </parameter>
    <parameter category="Developer" 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 engine failure flag will be set to healthy WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK</long_desc>
      <min>0</min>
      <max>284953</max>
      <reboot_required>true</reboot_required>
      <scope>modules/systemlib</scope>
    </parameter>
    <parameter category="Developer" 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. --&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>
      <min>0</min>
      <max>121212</max>
      <reboot_required>true</reboot_required>
      <scope>modules/systemlib</scope>
    </parameter>
    <parameter category="Developer" default="0" 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>
      <reboot_required>true</reboot_required>
      <scope>modules/systemlib</scope>
    </parameter>
    <parameter category="Developer" default="0" name="CBRK_IO_SAFETY" type="INT32">
      <short_desc>Circuit breaker for IO safety</short_desc>
      <long_desc>Setting this parameter to 22027 will disable IO safety. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK</long_desc>
      <min>0</min>
      <max>22027</max>
      <reboot_required>true</reboot_required>
      <scope>modules/systemlib</scope>
    </parameter>
    <parameter category="Developer" 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>
      <reboot_required>true</reboot_required>
      <scope>modules/systemlib</scope>
    </parameter>
    <parameter category="Developer" 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>
      <reboot_required>true</reboot_required>
      <scope>modules/systemlib</scope>
    </parameter>
    <parameter category="Developer" 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>
      <reboot_required>true</reboot_required>
      <scope>modules/systemlib</scope>
    </parameter>
    <parameter category="Developer" default="0" name="CBRK_VELPOSERR" type="INT32">
      <short_desc>Circuit breaker for position error check</short_desc>
      <long_desc>Setting this parameter to 201607 will disable the position and velocity accuracy checks in the commander. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK</long_desc>
      <min>0</min>
      <max>201607</max>
      <reboot_required>true</reboot_required>
      <scope>modules/systemlib</scope>
    </parameter>
  </group>
  <group name="Commander">
    <parameter default="256010" name="COM_ARM_AUTH" type="INT32">
      <short_desc>Arm authorization parameters, this uint32_t will be splitted between starting from the LSB:
- 8bits to authorizer system id
- 16bits to authentication method parameter, this will be used to store a timeout for the first 2 methods but can be used to another parameter for other new authentication methods.
- 7bits to authentication method
- one arm = 0
- two step arm = 1
* the MSB bit is not used to avoid problems in the conversion between int and uint</short_desc>
      <long_desc>Default value: (10 &lt;&lt; 0 | 1000 &lt;&lt; 8 | 0 &lt;&lt; 24) = 256010 - authorizer system id = 10 - authentication method parameter = 10000msec of timeout - authentication method = during arm</long_desc>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="2.4e-3" name="COM_ARM_EKF_AB" type="FLOAT">
      <short_desc>Maximum value of EKF accelerometer delta velocity bias estimate that will allow arming.
Note: ekf2 will limit the delta velocity bias estimate magnitude to be less than EKF2_ABL_LIM * FILTER_UPDATE_PERIOD_MS * 0.001 so this parameter must be less than that to be useful</short_desc>
      <min>0.001</min>
      <max>0.01</max>
      <unit>m/s</unit>
      <decimal>4</decimal>
      <increment>0.0001</increment>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="8.7e-4" name="COM_ARM_EKF_GB" type="FLOAT">
      <short_desc>Maximum value of EKF gyro delta angle bias estimate that will allow arming</short_desc>
      <min>0.0001</min>
      <max>0.0017</max>
      <unit>rad</unit>
      <decimal>5</decimal>
      <increment>0.0001</increment>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="1.0" name="COM_ARM_EKF_HGT" type="FLOAT">
      <short_desc>Maximum EKF height innovation test ratio that will allow arming</short_desc>
      <min>0.1</min>
      <max>1.0</max>
      <unit>m</unit>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="0.5" name="COM_ARM_EKF_POS" type="FLOAT">
      <short_desc>Maximum EKF position innovation test ratio that will allow arming</short_desc>
      <min>0.1</min>
      <max>1.0</max>
      <unit>m</unit>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="0.5" name="COM_ARM_EKF_VEL" type="FLOAT">
      <short_desc>Maximum EKF velocity innovation test ratio that will allow arming</short_desc>
      <min>0.1</min>
      <max>1.0</max>
      <unit>m/s</unit>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="0.5" name="COM_ARM_EKF_YAW" type="FLOAT">
      <short_desc>Maximum EKF yaw innovation test ratio that will allow arming</short_desc>
      <min>0.1</min>
      <max>1.0</max>
      <unit>rad</unit>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="0.7" name="COM_ARM_IMU_ACC" type="FLOAT">
      <short_desc>Maximum accelerometer inconsistency between IMU units that will allow arming</short_desc>
      <min>0.1</min>
      <max>1.0</max>
      <unit>m/s/s</unit>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="0.25" name="COM_ARM_IMU_GYR" type="FLOAT">
      <short_desc>Maximum rate gyro inconsistency between IMU units that will allow arming</short_desc>
      <min>0.02</min>
      <max>0.3</max>
      <unit>rad/s</unit>
      <decimal>3</decimal>
      <increment>0.01</increment>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="0.15" name="COM_ARM_MAG" type="FLOAT">
      <short_desc>Maximum magnetic field inconsistency between units that will allow arming</short_desc>
      <min>0.05</min>
      <max>0.5</max>
      <unit>Gauss</unit>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="0" name="COM_ARM_MIS_REQ" type="INT32">
      <short_desc>Require valid mission to arm</short_desc>
      <long_desc>The default allows to arm the vehicle without a valid mission.</long_desc>
      <boolean />
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="0" name="COM_ARM_SWISBTN" type="INT32">
      <short_desc>Arm switch is only a button</short_desc>
      <long_desc>The default uses the arm switch as real switch. If parameter set button gets handled like stick arming.</long_desc>
      <min>0</min>
      <max>1</max>
      <scope>modules/commander</scope>
      <values>
        <value code="0">Arm switch is a switch that stays on when armed</value>
        <value code="1">Arm switch is a button that only triggers arming and disarming</value>
      </values>
    </parameter>
    <parameter default="1" name="COM_ARM_WO_GPS" type="INT32">
      <short_desc>Allow arming without GPS</short_desc>
      <long_desc>The default allows to arm the vehicle without GPS signal.</long_desc>
      <boolean />
      <scope>modules/commander</scope>
    </parameter>
    <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. The vehicle will also auto-disarm right after arming if it has not even flown, however the time will be longer by a factor of 5. A value of zero means that automatic disarming is disabled.</long_desc>
      <min>0</min>
      <max>20</max>
      <unit>s</unit>
      <decimal>0</decimal>
      <increment>1</increment>
      <scope>modules/commander</scope>
    </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>5</min>
      <max>300</max>
      <unit>s</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/commander</scope>
    </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>3</max>
      <unit>s</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/commander</scope>
    </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 value</long_desc>
      <min>0.0</min>
      <max>50.0</max>
      <unit>A/%</unit>
      <decimal>2</decimal>
      <increment>1</increment>
      <scope>modules/commander</scope>
    </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>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/commander</scope>
    </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>60.0</max>
      <unit>s</unit>
      <decimal>1</decimal>
      <increment>1</increment>
      <scope>modules/commander</scope>
    </parameter>
    <parameter category="System" default="0" name="COM_FLIGHT_UUID" type="INT32" volatile="true">
      <short_desc>Next flight UUID</short_desc>
      <long_desc>This number is incremented automatically after every flight on disarming in order to remember the next flight UUID. The first flight is 0.</long_desc>
      <min>0</min>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="-1" name="COM_FLTMODE1" type="INT32">
      <short_desc>First flightmode slot (1000-1160)</short_desc>
      <long_desc>If the main switch channel is in this range the selected flight mode will be applied.</long_desc>
      <scope>modules/commander</scope>
      <values>
        <value code="-1">Unassigned</value>
        <value code="0">Manual</value>
        <value code="1">Altitude</value>
        <value code="2">Position</value>
        <value code="3">Mission</value>
        <value code="4">Hold</value>
        <value code="5">Return</value>
        <value code="6">Acro</value>
        <value code="7">Offboard</value>
        <value code="8">Stabilized</value>
        <value code="9">Rattitude</value>
        <value code="10">Takeoff</value>
        <value code="11">Land</value>
        <value code="12">Follow Me</value>
      </values>
    </parameter>
    <parameter default="-1" name="COM_FLTMODE2" type="INT32">
      <short_desc>Second flightmode slot (1160-1320)</short_desc>
      <long_desc>If the main switch channel is in this range the selected flight mode will be applied.</long_desc>
      <scope>modules/commander</scope>
      <values>
        <value code="-1">Unassigned</value>
        <value code="0">Manual</value>
        <value code="1">Altitude</value>
        <value code="2">Position</value>
        <value code="3">Mission</value>
        <value code="4">Hold</value>
        <value code="5">Return</value>
        <value code="6">Acro</value>
        <value code="7">Offboard</value>
        <value code="8">Stabilized</value>
        <value code="9">Rattitude</value>
        <value code="10">Takeoff</value>
        <value code="11">Land</value>
        <value code="12">Follow Me</value>
      </values>
    </parameter>
    <parameter default="-1" name="COM_FLTMODE3" type="INT32">
      <short_desc>Third flightmode slot (1320-1480)</short_desc>
      <long_desc>If the main switch channel is in this range the selected flight mode will be applied.</long_desc>
      <scope>modules/commander</scope>
      <values>
        <value code="-1">Unassigned</value>
        <value code="0">Manual</value>
        <value code="1">Altitude</value>
        <value code="2">Position</value>
        <value code="3">Mission</value>
        <value code="4">Hold</value>
        <value code="5">Return</value>
        <value code="6">Acro</value>
        <value code="7">Offboard</value>
        <value code="8">Stabilized</value>
        <value code="9">Rattitude</value>
        <value code="10">Takeoff</value>
        <value code="11">Land</value>
        <value code="12">Follow Me</value>
      </values>
    </parameter>
    <parameter default="-1" name="COM_FLTMODE4" type="INT32">
      <short_desc>Fourth flightmode slot (1480-1640)</short_desc>
      <long_desc>If the main switch channel is in this range the selected flight mode will be applied.</long_desc>
      <scope>modules/commander</scope>
      <values>
        <value code="-1">Unassigned</value>
        <value code="0">Manual</value>
        <value code="1">Altitude</value>
        <value code="2">Position</value>
        <value code="3">Mission</value>
        <value code="4">Hold</value>
        <value code="5">Return</value>
        <value code="6">Acro</value>
        <value code="7">Offboard</value>
        <value code="8">Stabilized</value>
        <value code="9">Rattitude</value>
        <value code="10">Takeoff</value>
        <value code="11">Land</value>
        <value code="12">Follow Me</value>
      </values>
    </parameter>
    <parameter default="-1" name="COM_FLTMODE5" type="INT32">
      <short_desc>Fifth flightmode slot (1640-1800)</short_desc>
      <long_desc>If the main switch channel is in this range the selected flight mode will be applied.</long_desc>
      <scope>modules/commander</scope>
      <values>
        <value code="-1">Unassigned</value>
        <value code="0">Manual</value>
        <value code="1">Altitude</value>
        <value code="2">Position</value>
        <value code="3">Mission</value>
        <value code="4">Hold</value>
        <value code="5">Return</value>
        <value code="6">Acro</value>
        <value code="7">Offboard</value>
        <value code="8">Stabilized</value>
        <value code="9">Rattitude</value>
        <value code="10">Takeoff</value>
        <value code="11">Land</value>
        <value code="12">Follow Me</value>
      </values>
    </parameter>
    <parameter default="-1" name="COM_FLTMODE6" type="INT32">
      <short_desc>Sixth flightmode slot (1800-2000)</short_desc>
      <long_desc>If the main switch channel is in this range the selected flight mode will be applied.</long_desc>
      <scope>modules/commander</scope>
      <values>
        <value code="-1">Unassigned</value>
        <value code="0">Manual</value>
        <value code="1">Altitude</value>
        <value code="2">Position</value>
        <value code="3">Mission</value>
        <value code="4">Hold</value>
        <value code="5">Return</value>
        <value code="6">Acro</value>
        <value code="7">Offboard</value>
        <value code="8">Stabilized</value>
        <value code="9">Rattitude</value>
        <value code="10">Takeoff</value>
        <value code="11">Land</value>
        <value code="12">Follow Me</value>
      </values>
    </parameter>
    <parameter default="120" name="COM_HLDL_LOSS_T" type="INT32">
      <short_desc>High Latency Datalink loss time threshold</short_desc>
      <long_desc>After this amount of seconds without datalink the data link lost mode triggers</long_desc>
      <min>60</min>
      <max>3600</max>
      <unit>s</unit>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="0" name="COM_HLDL_REG_T" type="INT32">
      <short_desc>High Latency 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>60</max>
      <unit>s</unit>
      <scope>modules/commander</scope>
    </parameter>
    <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>
      <unit>m</unit>
      <decimal>2</decimal>
      <increment>0.5</increment>
      <scope>modules/commander</scope>
    </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>
      <unit>m</unit>
      <decimal>2</decimal>
      <increment>0.5</increment>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="0" name="COM_LOW_BAT_ACT" type="INT32">
      <short_desc>Battery failsafe mode</short_desc>
      <long_desc>Action the system takes on low battery. Defaults to off</long_desc>
      <decimal>0</decimal>
      <increment>1</increment>
      <scope>modules/commander</scope>
      <values>
        <value code="0">Warning</value>
        <value code="1">Return to land</value>
        <value code="2">Land at current position</value>
        <value code="3">Return to land at critically low level, land at current position if reaching dangerously low levels</value>
      </values>
    </parameter>
    <parameter default="0.0" name="COM_OF_LOSS_T" type="FLOAT">
      <short_desc>Time-out to wait when offboard connection is lost before triggering offboard lost action.
See COM_OBL_ACT and COM_OBL_RC_ACT to configure action</short_desc>
      <min>0</min>
      <max>60</max>
      <unit>second</unit>
      <increment>1</increment>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="1" name="COM_POS_FS_DELAY" type="INT32">
      <short_desc>Loss of position failsafe activation delay</short_desc>
      <long_desc>This sets number of seconds that the position checks need to be failed before the failsafe will activate. The default value has been optimised for rotary wing applications. For fixed wing applications, a larger value between 5 and 10 should be used.</long_desc>
      <min>1</min>
      <max>100</max>
      <unit>sec</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="5" name="COM_POS_FS_EPH" type="FLOAT">
      <short_desc>Horizontal position error threshold</short_desc>
      <long_desc>This is the horizontal position error (EPV) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing.</long_desc>
      <unit>m</unit>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="10" name="COM_POS_FS_EPV" type="FLOAT">
      <short_desc>Vertical position error threshold</short_desc>
      <long_desc>This is the vertical position error (EPV) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing.</long_desc>
      <unit>m</unit>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="10" name="COM_POS_FS_GAIN" type="INT32">
      <short_desc>Loss of position probation gain factor</short_desc>
      <long_desc>This sets the rate that the loss of position probation time grows when position checks are failing. The default value has been optimised for rotary wing applications. For fixed wing applications a value of 0 should be used.</long_desc>
      <reboot_required>true</reboot_required>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="30" name="COM_POS_FS_PROB" type="INT32">
      <short_desc>Loss of position probation delay at takeoff</short_desc>
      <long_desc>The probation delay is the number of seconds that the EKF innovation checks need to pass for the position to be declared good after it has been declared bad. The probation delay will be reset to this parameter value when takeoff is detected. After takeoff, if position checks are passing, the probation delay will reduce by one second for every lapsed second of valid position down to a minimum of 1 second. If position checks are failing, the probation delay will increase by COM_POS_FS_GAIN seconds for every lapsed second up to a maximum of 100 seconds. The default value has been optimised for rotary wing applications. For fixed wing applications, a value of 1 should be used.</long_desc>
      <min>1</min>
      <max>100</max>
      <unit>sec</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="1000" name="COM_RC_ARM_HYST" type="INT32">
      <short_desc>RC input arm/disarm command duration</short_desc>
      <long_desc>The default value of 1000 requires the stick to be held in the arm or disarm position for 1 second.</long_desc>
      <min>100</min>
      <max>1500</max>
      <scope>modules/commander</scope>
    </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 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>
      <min>0</min>
      <max>2</max>
      <scope>modules/commander</scope>
      <values>
        <value code="0">RC Transmitter</value>
        <value code="1">Joystick/No RC Checks</value>
        <value code="2">Virtual RC by Joystick</value>
      </values>
    </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>s</unit>
      <decimal>1</decimal>
      <increment>0.1</increment>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="0" name="COM_RC_OVERRIDE" type="INT32">
      <short_desc>Enable RC stick override of auto modes</short_desc>
      <boolean />
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="12.0" name="COM_RC_STICK_OV" type="FLOAT">
      <short_desc>RC stick override threshold</short_desc>
      <long_desc>If an RC stick is moved more than by this amount the system will interpret this as override request by the pilot.</long_desc>
      <min>5</min>
      <max>40</max>
      <unit>%</unit>
      <decimal>0</decimal>
      <increment>0.05</increment>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="1" name="COM_VEL_FS_EVH" type="FLOAT">
      <short_desc>Horizontal velocity error threshold</short_desc>
      <long_desc>This is the horizontal velocity error (EVH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing.</long_desc>
      <unit>m</unit>
      <scope>modules/commander</scope>
    </parameter>
  </group>
  <group name="Data Link Loss">
    <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>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <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>
      <unit>deg * 1e7</unit>
      <scope>modules/navigator</scope>
    </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>
      <unit>deg * 1e7</unit>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="120.0" name="NAV_DLL_AH_T" type="FLOAT">
      <short_desc>Airfield home 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>
      <max>3600.0</max>
      <unit>s</unit>
      <decimal>0</decimal>
      <increment>1</increment>
      <scope>modules/navigator</scope>
    </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>
      <boolean />
      <scope>modules/navigator</scope>
    </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>-50</min>
      <max>30000</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/navigator</scope>
    </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>-900000000</min>
      <max>900000000</max>
      <unit>deg * 1e7</unit>
      <scope>modules/navigator</scope>
    </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>-1800000000</min>
      <max>1800000000</max>
      <unit>deg * 1e7</unit>
      <scope>modules/navigator</scope>
    </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>
      <max>3600.0</max>
      <unit>s</unit>
      <decimal>0</decimal>
      <increment>1</increment>
      <scope>modules/navigator</scope>
    </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>
      <scope>modules/navigator</scope>
    </parameter>
  </group>
  <group name="EKF2">
    <parameter default="0.2" name="EKF2_ABIAS_INIT" type="FLOAT">
      <short_desc>1-sigma IMU accelerometer switch-on bias</short_desc>
      <min>0.0</min>
      <max>0.5</max>
      <unit>m/s/s</unit>
      <decimal>2</decimal>
      <reboot_required>true</reboot_required>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="25.0" name="EKF2_ABL_ACCLIM" type="FLOAT">
      <short_desc>Maximum IMU accel magnitude that allows IMU bias learning.
If the magnitude of the IMU accelerometer vector exceeds this value, the EKF delta velocity state estimation will be inhibited.
This reduces the adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale factor errors on the delta velocity bias estimates</short_desc>
      <min>20.0</min>
      <max>200.0</max>
      <unit>m/s/s</unit>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="3.0" name="EKF2_ABL_GYRLIM" type="FLOAT">
      <short_desc>Maximum IMU gyro angular rate magnitude that allows IMU bias learning.
If the magnitude of the IMU angular rate vector exceeds this value, the EKF delta velocity state estimation will be inhibited.
This reduces the adverse effect of rapid rotation rates and associated errors on the delta velocity bias estimates</short_desc>
      <min>2.0</min>
      <max>20.0</max>
      <unit>rad/s</unit>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.4" name="EKF2_ABL_LIM" type="FLOAT">
      <short_desc>Accelerometer bias learning limit. The ekf delta velocity bias states will be limited to within a range equivalent to +- of this value</short_desc>
      <min>0.0</min>
      <max>0.8</max>
      <unit>m/s/s</unit>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.5" name="EKF2_ABL_TAU" type="FLOAT">
      <short_desc>Time constant used by acceleration and angular rate magnitude checks used to inhibit delta velocity bias learning.
The vector magnitude of angular rate and acceleration used to check if learning should be inhibited has a peak hold filter applied to it with an exponential decay.
This parameter controls the time constant of the decay</short_desc>
      <min>0.1</min>
      <max>1.0</max>
      <unit>s</unit>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="3.0e-3" name="EKF2_ACC_B_NOISE" type="FLOAT">
      <short_desc>Process noise for IMU accelerometer bias prediction</short_desc>
      <min>0.0</min>
      <max>0.01</max>
      <unit>m/s**3</unit>
      <decimal>6</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="3.5e-1" 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>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="1" name="EKF2_AID_MASK" type="INT32">
      <short_desc>Integer bitmask controlling data fusion and aiding methods</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 2 : Set to true to inhibit IMU bias estimation 3 : Set to true to enable vision position fusion 4 : Set to true to enable vision yaw fusion 5 : Set to true to enable multi-rotor drag specific force fusion 6 : set to true if the EV observations are in a non NED reference frame and need to be rotated before being used</long_desc>
      <min>0</min>
      <max>127</max>
      <reboot_required>true</reboot_required>
      <scope>modules/ekf2</scope>
      <bitmask>
        <bit index="0">use GPS</bit>
        <bit index="1">use optical flow</bit>
        <bit index="2">inhibit IMU bias estimation</bit>
        <bit index="3">vision position fusion</bit>
        <bit index="4">vision yaw fusion</bit>
        <bit index="5">multi-rotor drag fusion</bit>
        <bit index="6">rotate external vision</bit>
      </bitmask>
    </parameter>
    <parameter default="0.1" name="EKF2_ANGERR_INIT" type="FLOAT">
      <short_desc>1-sigma tilt angle uncertainty after gravity vector alignment</short_desc>
      <min>0.0</min>
      <max>0.5</max>
      <unit>rad</unit>
      <decimal>3</decimal>
      <reboot_required>true</reboot_required>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.0" name="EKF2_ARSP_THR" type="FLOAT">
      <short_desc>Airspeed fusion threshold. A value of zero will deactivate airspeed fusion. Any other positive
value will determine the minimum airspeed which will still be fused. Set to about 90% of the vehicles stall speed.
Both airspeed fusion and sideslip fusion must be active for the EKF to continue navigating after loss of GPS.
Use EKF2_FUSE_BETA to activate sideslip fusion</short_desc>
      <min>0.0</min>
      <unit>m/s</unit>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="20.0" name="EKF2_ASPD_MAX" type="FLOAT">
      <short_desc>Upper limit on airspeed along individual axes used to correct baro for position error effects</short_desc>
      <min>5.0</min>
      <max>50.0</max>
      <unit>m/s</unit>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="100" 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>
      <decimal>1</decimal>
      <reboot_required>true</reboot_required>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="5" name="EKF2_AVEL_DELAY" type="FLOAT">
      <short_desc>Auxillary Velocity Estimate (e.g from a landing target) delay relative to IMU measurements</short_desc>
      <min>0</min>
      <max>300</max>
      <unit>ms</unit>
      <decimal>1</decimal>
      <reboot_required>true</reboot_required>
      <scope>modules/ekf2</scope>
    </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>
      <decimal>1</decimal>
      <reboot_required>true</reboot_required>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="5.0" name="EKF2_BARO_GATE" type="FLOAT">
      <short_desc>Gate size for barometric and GPS height fusion</short_desc>
      <long_desc>Sets the number of standard deviations used by the innovation consistency test.</long_desc>
      <min>1.0</min>
      <unit>SD</unit>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="2.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>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="25.0" name="EKF2_BCOEF_X" type="FLOAT">
      <short_desc>X-axis ballistic coefficient used by the multi-rotor specific drag force model.
This should be adjusted to minimise variance of the X-axis drag specific force innovation sequence</short_desc>
      <min>1.0</min>
      <max>100.0</max>
      <unit>kg/m**2</unit>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="25.0" name="EKF2_BCOEF_Y" type="FLOAT">
      <short_desc>Y-axis ballistic coefficient used by the multi-rotor specific drag force model.
This should be adjusted to minimise variance of the Y-axis drag specific force innovation sequence</short_desc>
      <min>1.0</min>
      <max>100.0</max>
      <unit>kg/m**2</unit>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="5.0" name="EKF2_BETA_GATE" type="FLOAT">
      <short_desc>Gate size for synthetic sideslip fusion</short_desc>
      <long_desc>Sets the number of standard deviations used by the innovation consistency test.</long_desc>
      <min>1.0</min>
      <unit>SD</unit>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.3" name="EKF2_BETA_NOISE" type="FLOAT">
      <short_desc>Noise for synthetic sideslip fusion</short_desc>
      <min>0.1</min>
      <max>1.0</max>
      <unit>m/s</unit>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="7" name="EKF2_DECL_TYPE" type="INT32">
      <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 observation when 3-axis magnetometer fusion is being used.</long_desc>
      <min>0</min>
      <max>7</max>
      <reboot_required>true</reboot_required>
      <scope>modules/ekf2</scope>
      <bitmask>
        <bit index="0">use geo_lookup declination</bit>
        <bit index="1">save EKF2_MAG_DECL on disarm</bit>
        <bit index="2">use declination as an observation</bit>
      </bitmask>
    </parameter>
    <parameter default="2.5" name="EKF2_DRAG_NOISE" type="FLOAT">
      <short_desc>Specific drag force observation noise variance used by the multi-rotor specific drag force model.
Increasing it makes the multi-rotor wind estimates adjust more slowly</short_desc>
      <min>0.5</min>
      <max>10.0</max>
      <unit>(m/sec**2)**2</unit>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <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>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.05" name="EKF2_EVA_NOISE" type="FLOAT">
      <short_desc>Measurement noise for vision angle observations used when the vision system does not supply error estimates</short_desc>
      <min>0.01</min>
      <unit>rad</unit>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.05" name="EKF2_EVP_NOISE" type="FLOAT">
      <short_desc>Measurement noise for vision position observations used when the vision system does not supply error estimates</short_desc>
      <min>0.01</min>
      <unit>m</unit>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="175" name="EKF2_EV_DELAY" type="FLOAT">
      <short_desc>Vision Position Estimator delay relative to IMU measurements</short_desc>
      <min>0</min>
      <max>300</max>
      <unit>ms</unit>
      <decimal>1</decimal>
      <reboot_required>true</reboot_required>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="5.0" name="EKF2_EV_GATE" type="FLOAT">
      <short_desc>Gate size for vision estimate fusion</short_desc>
      <long_desc>Sets the number of standard deviations used by the innovation consistency test.</long_desc>
      <min>1.0</min>
      <unit>SD</unit>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.0" name="EKF2_EV_POS_X" type="FLOAT">
      <short_desc>X position of VI sensor focal point in body frame</short_desc>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.0" name="EKF2_EV_POS_Y" type="FLOAT">
      <short_desc>Y position of VI sensor focal point in body frame</short_desc>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.0" name="EKF2_EV_POS_Z" type="FLOAT">
      <short_desc>Z position of VI sensor focal point in body frame</short_desc>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0" name="EKF2_FUSE_BETA" type="INT32">
      <short_desc>Boolean determining if synthetic sideslip measurements should fused</short_desc>
      <long_desc>A value of 1 indicates that fusion is active Both  sideslip fusion and airspeed fusion must be active for the EKF to continue navigating after loss of GPS. Use EKF2_ARSP_THR to activate airspeed fusion.</long_desc>
      <boolean />
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.1" name="EKF2_GBIAS_INIT" type="FLOAT">
      <short_desc>1-sigma IMU gyro switch-on bias</short_desc>
      <min>0.0</min>
      <max>0.2</max>
      <unit>rad/sec</unit>
      <decimal>2</decimal>
      <reboot_required>true</reboot_required>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="21" name="EKF2_GPS_CHECK" type="INT32">
      <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 vehicle is stationary during alignment. 6 : Maximum allowed vertical position rate set by EKF2_REQ_VDRIFT. This check can only be used if the vehicle is stationary during alignment. 7 : Maximum allowed horizontal speed set by EKF2_REQ_HDRIFT. This check can only be used if the vehicle is stationary during alignment. 8 : Maximum allowed vertical velocity discrepancy set by EKF2_REQ_VDRIFT</long_desc>
      <min>0</min>
      <max>511</max>
      <scope>modules/ekf2</scope>
      <bitmask>
        <bit index="0">Min sat count (EKF2_REQ_NSATS)</bit>
        <bit index="1">Min GDoP (EKF2_REQ_GDOP)</bit>
        <bit index="2">Max horizontal position error (EKF2_REQ_EPH)</bit>
        <bit index="3">Max vertical position error (EKF2_REQ_EPV)</bit>
        <bit index="4">Max speed error (EKF2_REQ_SACC)</bit>
        <bit index="5">Max horizontal position rate (EKF2_REQ_HDRIFT)</bit>
        <bit index="6">Max vertical position rate (EKF2_REQ_VDRIFT)</bit>
        <bit index="7">Max horizontal speed (EKF2_REQ_HDRIFT)</bit>
        <bit index="8">Max vertical velocity discrepancy (EKF2_REQ_VDRIFT)</bit>
      </bitmask>
    </parameter>
    <parameter default="110" 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>
      <decimal>1</decimal>
      <reboot_required>true</reboot_required>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.0" name="EKF2_GPS_POS_X" type="FLOAT">
      <short_desc>X position of GPS antenna in body frame</short_desc>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.0" name="EKF2_GPS_POS_Y" type="FLOAT">
      <short_desc>Y position of GPS antenna in body frame</short_desc>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.0" name="EKF2_GPS_POS_Z" type="FLOAT">
      <short_desc>Z position of GPS antenna in body frame</short_desc>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="5.0" name="EKF2_GPS_P_GATE" type="FLOAT">
      <short_desc>Gate size for GPS horizontal position fusion</short_desc>
      <long_desc>Sets the number of standard deviations used by the innovation consistency test.</long_desc>
      <min>1.0</min>
      <unit>SD</unit>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <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>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="5.0" name="EKF2_GPS_V_GATE" type="FLOAT">
      <short_desc>Gate size for GPS velocity fusion</short_desc>
      <long_desc>Sets the number of standard deviations used by the innovation consistency test.</long_desc>
      <min>1.0</min>
      <unit>SD</unit>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </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>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="1.0e-3" name="EKF2_GYR_B_NOISE" type="FLOAT">
      <short_desc>Process noise for IMU rate gyro bias prediction</short_desc>
      <min>0.0</min>
      <max>0.01</max>
      <unit>rad/s**2</unit>
      <decimal>6</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="1.5e-2" name="EKF2_GYR_NOISE" type="FLOAT">
      <short_desc>Rate gyro noise for covariance prediction</short_desc>
      <min>0.0001</min>
      <max>0.1</max>
      <unit>rad/s</unit>
      <decimal>4</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="2.6" name="EKF2_HDG_GATE" type="FLOAT">
      <short_desc>Gate size for magnetic heading fusion</short_desc>
      <long_desc>Sets the number of standard deviations used by the innovation consistency test.</long_desc>
      <min>1.0</min>
      <unit>SD</unit>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <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>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </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>
      <reboot_required>true</reboot_required>
      <scope>modules/ekf2</scope>
      <values>
        <value code="0">Barometric pressure</value>
        <value code="1">GPS</value>
        <value code="2">Range sensor</value>
        <value code="3">Vision</value>
      </values>
    </parameter>
    <parameter default="0.0" name="EKF2_IMU_POS_X" type="FLOAT">
      <short_desc>X position of IMU in body frame</short_desc>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.0" name="EKF2_IMU_POS_Y" type="FLOAT">
      <short_desc>Y position of IMU in body frame</short_desc>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.0" name="EKF2_IMU_POS_Z" type="FLOAT">
      <short_desc>Z position of IMU in body frame</short_desc>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter category="System" default="0" name="EKF2_MAGBIAS_ID" type="INT32">
      <short_desc>ID of Magnetometer the learned bias is for</short_desc>
      <reboot_required>true</reboot_required>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter category="System" default="0.0" name="EKF2_MAGBIAS_X" type="FLOAT" volatile="true">
      <short_desc>Learned value of magnetometer X axis bias.
This is the amount of X-axis magnetometer bias learned by the EKF and saved from the last flight. It must be set to zero if the ground based magnetometer calibration is repeated</short_desc>
      <min>-0.5</min>
      <max>0.5</max>
      <unit>mGauss</unit>
      <decimal>3</decimal>
      <reboot_required>true</reboot_required>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter category="System" default="0.0" name="EKF2_MAGBIAS_Y" type="FLOAT" volatile="true">
      <short_desc>Learned value of magnetometer Y axis bias.
This is the amount of Y-axis magnetometer bias learned by the EKF and saved from the last flight. It must be set to zero if the ground based magnetometer calibration is repeated</short_desc>
      <min>-0.5</min>
      <max>0.5</max>
      <unit>mGauss</unit>
      <decimal>3</decimal>
      <reboot_required>true</reboot_required>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter category="System" default="0.0" name="EKF2_MAGBIAS_Z" type="FLOAT" volatile="true">
      <short_desc>Learned value of magnetometer Z axis bias.
This is the amount of Z-axis magnetometer bias learned by the EKF and saved from the last flight. It must be set to zero if the ground based magnetometer calibration is repeated</short_desc>
      <min>-0.5</min>
      <max>0.5</max>
      <unit>mGauss</unit>
      <decimal>3</decimal>
      <reboot_required>true</reboot_required>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.2" name="EKF2_MAGB_K" type="FLOAT">
      <short_desc>Maximum fraction of learned mag bias saved at each disarm.
Smaller values make the saved mag bias learn slower from flight to flight. Larger values make it learn faster. Must be &gt; 0.0 and &lt;= 1.0</short_desc>
      <min>0.0</min>
      <max>1.0</max>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="2.5E-7" name="EKF2_MAGB_VREF" type="FLOAT">
      <short_desc>State variance assumed for magnetometer bias storage.
This is a reference variance used to calculate the fraction of learned magnetometer bias that will be used to update the stored value. Smaller values will make the stored bias data adjust more slowly from flight to flight. Larger values will make it adjust faster</short_desc>
      <unit>mGauss**2</unit>
      <decimal>8</decimal>
      <reboot_required>true</reboot_required>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.5" name="EKF2_MAG_ACCLIM" type="FLOAT">
      <short_desc>Horizontal acceleration threshold used by automatic selection of magnetometer fusion method.
This parameter is used when the magnetometer fusion method is set automatically (EKF2_MAG_TYPE = 0). If the filtered horizontal acceleration is greater than this parameter value, then the EKF will use 3-axis magnetomer fusion</short_desc>
      <min>0.0</min>
      <max>5.0</max>
      <unit>m/s**2</unit>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="1.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>
      <decimal>6</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0" name="EKF2_MAG_DECL" type="FLOAT">
      <short_desc>Magnetic declination</short_desc>
      <unit>deg</unit>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <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>
      <decimal>1</decimal>
      <reboot_required>true</reboot_required>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="1.0e-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>
      <decimal>6</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="3.0" name="EKF2_MAG_GATE" type="FLOAT">
      <short_desc>Gate size for magnetometer XYZ component fusion</short_desc>
      <long_desc>Sets the number of standard deviations used by the innovation consistency test.</long_desc>
      <min>1.0</min>
      <unit>SD</unit>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </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>
      <decimal>3</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0" name="EKF2_MAG_TYPE" type="INT32">
      <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 with fallback to heading fusion if there is insufficient motion to make yaw or mag biases observable.</long_desc>
      <reboot_required>true</reboot_required>
      <scope>modules/ekf2</scope>
      <values>
        <value code="0">Automatic</value>
        <value code="1">Magnetic heading</value>
        <value code="2">3-axis fusion</value>
        <value code="3">None</value>
      </values>
    </parameter>
    <parameter default="0.25" name="EKF2_MAG_YAWLIM" type="FLOAT">
      <short_desc>Yaw rate threshold used by automatic selection of magnetometer fusion method.
This parameter is used when the magnetometer fusion method is set automatically (EKF2_MAG_TYPE = 0). If the filtered yaw rate is greater than this parameter value, then the EKF will use 3-axis magnetomer fusion</short_desc>
      <min>0.0</min>
      <max>0.5</max>
      <unit>rad/s</unit>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="20" name="EKF2_MIN_OBS_DT" type="INT32">
      <short_desc>Minimum time of arrival delta between non-IMU observations before data is downsampled.
Baro and Magnetometer data will be averaged before downsampling, other data will be point sampled resulting in loss of information</short_desc>
      <min>10</min>
      <max>50</max>
      <unit>ms</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/ekf2</scope>
    </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>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </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>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="5000000" name="EKF2_NOAID_TOUT" type="INT32">
      <short_desc>Maximum lapsed time from last fusion of measurements that constrain velocity drift before the EKF will report the horizontal nav solution as invalid</short_desc>
      <min>500000</min>
      <max>10000000</max>
      <unit>uSec</unit>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="5" name="EKF2_OF_DELAY" type="FLOAT">
      <short_desc>Optical flow measurement delay relative to IMU measurements
Assumes measurement is timestamped at trailing edge of integration period</short_desc>
      <min>0</min>
      <max>300</max>
      <unit>ms</unit>
      <decimal>1</decimal>
      <reboot_required>true</reboot_required>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="3.0" name="EKF2_OF_GATE" type="FLOAT">
      <short_desc>Gate size for optical flow fusion</short_desc>
      <long_desc>Sets the number of standard deviations used by the innovation consistency test.</long_desc>
      <min>1.0</min>
      <unit>SD</unit>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </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>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </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>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.0" name="EKF2_OF_POS_X" type="FLOAT">
      <short_desc>X position of optical flow focal point in body frame</short_desc>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.0" name="EKF2_OF_POS_Y" type="FLOAT">
      <short_desc>Y position of optical flow focal point in body frame</short_desc>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.0" name="EKF2_OF_POS_Z" type="FLOAT">
      <short_desc>Z position of optical flow focal point in body frame</short_desc>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/ekf2</scope>
    </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>
      <scope>modules/ekf2</scope>
    </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.
Control loops will be instructed to limit ground speed such that the flow rate produced by movement over ground is less than 50% of EKF2_OF_RMAX</short_desc>
      <min>1.0</min>
      <unit>rad/s</unit>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.0" name="EKF2_PCOEF_XN" type="FLOAT">
      <short_desc>Static pressure position error coefficient for the negative X axis.
This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis.
If the baro height estimate rises during backwards flight, then this will be a negative number</short_desc>
      <min>-0.5</min>
      <max>0.5</max>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.0" name="EKF2_PCOEF_XP" type="FLOAT">
      <short_desc>Static pressure position error coefficient for the positive X axis
This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis.
If the baro height estimate rises during forward flight, then this will be a negative number</short_desc>
      <min>-0.5</min>
      <max>0.5</max>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.0" name="EKF2_PCOEF_Y" type="FLOAT">
      <short_desc>Pressure position error coefficient for the Y axis.
This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the Y body axis.
If the baro height estimate rises during sideways flight, then this will be a negative number</short_desc>
      <min>-0.5</min>
      <max>0.5</max>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.0" name="EKF2_PCOEF_Z" type="FLOAT">
      <short_desc>Static pressure position error coefficient for the Z axis.
This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the Z body axis</short_desc>
      <min>-0.5</min>
      <max>0.5</max>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </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>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </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>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </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>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </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>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </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>
      <scope>modules/ekf2</scope>
    </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>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </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>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0" name="EKF2_RNG_AID" type="INT32">
      <short_desc>Range sensor aid</short_desc>
      <long_desc>If this parameter is enabled then the estimator will make use of the range finder measurements to estimate it's height even if range sensor is not the primary height source. It will only do so if conditions for range measurement fusion are met.</long_desc>
      <scope>modules/ekf2</scope>
      <values>
        <value code="0">Range aid disabled</value>
        <value code="1">Range aid enabled</value>
      </values>
    </parameter>
    <parameter default="5.0" name="EKF2_RNG_A_HMAX" type="FLOAT">
      <short_desc>Maximum absolute altitude (height above ground level) allowed for range aid mode</short_desc>
      <long_desc>If the vehicle absolute altitude exceeds this value then the estimator will not fuse range measurements to estimate it's height. This only applies when range aid mode is activated (EKF2_RNG_AID = enabled).</long_desc>
      <min>1.0</min>
      <max>10.0</max>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="1.0" name="EKF2_RNG_A_IGATE" type="FLOAT">
      <short_desc>Gate size used for innovation consistency checks for range aid fusion</short_desc>
      <long_desc>A lower value means HAGL needs to be more stable in order to use range finder for height estimation in range aid mode</long_desc>
      <min>0.1</min>
      <max>5.0</max>
      <unit>SD</unit>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="1.0" name="EKF2_RNG_A_VMAX" type="FLOAT">
      <short_desc>Maximum horizontal velocity allowed for range aid mode</short_desc>
      <long_desc>If the vehicle horizontal speed exceeds this value then the estimator will not fuse range measurements to estimate it's height. This only applies when range aid mode is activated (EKF2_RNG_AID = enabled).</long_desc>
      <min>0.1</min>
      <max>2</max>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="5" name="EKF2_RNG_DELAY" type="FLOAT">
      <short_desc>Range finder measurement delay relative to IMU measurements</short_desc>
      <min>0</min>
      <max>300</max>
      <unit>ms</unit>
      <decimal>1</decimal>
      <reboot_required>true</reboot_required>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="5.0" name="EKF2_RNG_GATE" type="FLOAT">
      <short_desc>Gate size for range finder fusion</short_desc>
      <long_desc>Sets the number of standard deviations used by the innovation consistency test.</long_desc>
      <min>1.0</min>
      <unit>SD</unit>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </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>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.0" name="EKF2_RNG_PITCH" type="FLOAT">
      <short_desc>Range sensor pitch offset</short_desc>
      <min>-0.75</min>
      <max>0.75</max>
      <unit>rad</unit>
      <decimal>3</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.0" name="EKF2_RNG_POS_X" type="FLOAT">
      <short_desc>X position of range finder origin in body frame</short_desc>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.0" name="EKF2_RNG_POS_Y" type="FLOAT">
      <short_desc>Y position of range finder origin in body frame</short_desc>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.0" name="EKF2_RNG_POS_Z" type="FLOAT">
      <short_desc>Z position of range finder origin in body frame</short_desc>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.05" name="EKF2_RNG_SFE" type="FLOAT">
      <short_desc>Range finder range dependant noise scaler</short_desc>
      <long_desc>Specifies the increase in range finder noise with range.</long_desc>
      <min>0.0</min>
      <max>0.2</max>
      <unit>m/m</unit>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="3.0" name="EKF2_TAS_GATE" type="FLOAT">
      <short_desc>Gate size for TAS fusion</short_desc>
      <long_desc>Sets the number of standard deviations used by the innovation consistency test.</long_desc>
      <min>1.0</min>
      <unit>SD</unit>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.25" name="EKF2_TAU_POS" type="FLOAT">
      <short_desc>Time constant of the position output prediction and smoothing filter. Controls how tightly the output track the EKF states</short_desc>
      <min>0.1</min>
      <max>1.0</max>
      <unit>s</unit>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
    <parameter default="0.25" name="EKF2_TAU_VEL" type="FLOAT">
      <short_desc>Time constant of the velocity output prediction and smoothing filter</short_desc>
      <max>1.0</max>
      <unit>s</unit>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </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>
      <decimal>2</decimal>
      <scope>modules/ekf2</scope>
    </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>
      <decimal>1</decimal>
      <scope>modules/ekf2</scope>
    </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>
      <decimal>3</decimal>
      <scope>modules/ekf2</scope>
    </parameter>
  </group>
  <group name="FW Attitude Control">
    <parameter default="90" name="FW_ACRO_X_MAX" type="FLOAT">
      <short_desc>Acro body x max rate</short_desc>
      <long_desc>This is the rate the controller is trying to achieve if the user applies full roll stick input in acro mode.</long_desc>
      <min>45</min>
      <max>720</max>
      <unit>degrees</unit>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="90" name="FW_ACRO_Y_MAX" type="FLOAT">
      <short_desc>Acro body y max rate</short_desc>
      <long_desc>This is the body y rate the controller is trying to achieve if the user applies full pitch stick input in acro mode.</long_desc>
      <min>45</min>
      <max>720</max>
      <unit>degrees</unit>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="45" name="FW_ACRO_Z_MAX" type="FLOAT">
      <short_desc>Acro body z max rate</short_desc>
      <long_desc>This is the body z rate the controller is trying to achieve if the user applies full yaw stick input in acro mode.</long_desc>
      <min>10</min>
      <max>180</max>
      <unit>degrees</unit>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="0" name="FW_ARSP_MODE" type="INT32">
      <short_desc>Airspeed mode</short_desc>
      <long_desc>For small wings or VTOL without airspeed sensor this parameter can be used to enable flying without an airspeed reading</long_desc>
      <scope>modules/fw_att_control</scope>
      <values>
        <value code="0">Normal (use airspeed if available)</value>
        <value code="1">Airspeed disabled</value>
      </values>
    </parameter>
    <parameter default="0" name="FW_BAT_SCALE_EN" type="INT32">
      <short_desc>Whether to scale throttle by battery power level</short_desc>
      <long_desc>This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The fixed wing should constantly behave as if it was fully charged with reduced max thrust at lower battery percentages. i.e. if cruise speed is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery.</long_desc>
      <boolean />
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="0.0" name="FW_DTRIM_P_FLPS" type="FLOAT">
      <short_desc>Pitch trim increment for flaps configuration</short_desc>
      <long_desc>This increment is added to the pitch trim whenever flaps are fully deployed.</long_desc>
      <min>-0.25</min>
      <max>0.25</max>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="0.0" name="FW_DTRIM_P_VMAX" type="FLOAT">
      <short_desc>Pitch trim increment at maximum airspeed</short_desc>
      <long_desc>This increment is added to TRIM_PITCH when airspeed is FW_AIRSP_MAX.</long_desc>
      <min>-0.25</min>
      <max>0.25</max>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="0.0" name="FW_DTRIM_P_VMIN" type="FLOAT">
      <short_desc>Pitch trim increment at minimum airspeed</short_desc>
      <long_desc>This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MIN.</long_desc>
      <min>-0.25</min>
      <max>0.25</max>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="0.0" name="FW_DTRIM_R_FLPS" type="FLOAT">
      <short_desc>Roll trim increment for flaps configuration</short_desc>
      <long_desc>This increment is added to TRIM_ROLL whenever flaps are fully deployed.</long_desc>
      <min>-0.25</min>
      <max>0.25</max>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="0.0" name="FW_DTRIM_R_VMAX" type="FLOAT">
      <short_desc>Roll trim increment at maximum airspeed</short_desc>
      <long_desc>This increment is added to TRIM_ROLL when airspeed is FW_AIRSP_MAX.</long_desc>
      <min>-0.25</min>
      <max>0.25</max>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="0.0" name="FW_DTRIM_R_VMIN" type="FLOAT">
      <short_desc>Roll trim increment at minimum airspeed</short_desc>
      <long_desc>This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MIN.</long_desc>
      <min>-0.25</min>
      <max>0.25</max>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="0.0" name="FW_DTRIM_Y_VMAX" type="FLOAT">
      <short_desc>Yaw trim increment at maximum airspeed</short_desc>
      <long_desc>This increment is added to TRIM_YAW when airspeed is FW_AIRSP_MAX.</long_desc>
      <min>-0.25</min>
      <max>0.25</max>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="0.0" name="FW_DTRIM_Y_VMIN" type="FLOAT">
      <short_desc>Yaw trim increment at minimum airspeed</short_desc>
      <long_desc>This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN.</long_desc>
      <min>-0.25</min>
      <max>0.25</max>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="0.0" name="FW_FLAPERON_SCL" type="FLOAT">
      <short_desc>Scale factor for flaperons</short_desc>
      <min>0.0</min>
      <max>1.0</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="1.0" name="FW_FLAPS_SCL" type="FLOAT">
      <short_desc>Scale factor for flaps</short_desc>
      <min>0.0</min>
      <max>1.0</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_att_control</scope>
    </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>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="1.0" name="FW_MAN_P_SC" type="FLOAT">
      <short_desc>Manual pitch scale</short_desc>
      <long_desc>Scale factor applied to the desired pitch actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces.</long_desc>
      <min>0.0</min>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_att_control</scope>
    </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>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="1.0" name="FW_MAN_R_SC" type="FLOAT">
      <short_desc>Manual roll scale</short_desc>
      <long_desc>Scale factor applied to the desired roll actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces.</long_desc>
      <min>0.0</min>
      <max>1.0</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="1.0" name="FW_MAN_Y_SC" type="FLOAT">
      <short_desc>Manual yaw scale</short_desc>
      <long_desc>Scale factor applied to the desired yaw actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces.</long_desc>
      <min>0.0</min>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="0.5" 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>
      <unit>%/rad/s</unit>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="0.02" 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.005</min>
      <max>0.5</max>
      <unit>%/rad</unit>
      <decimal>3</decimal>
      <increment>0.005</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="0.4" 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>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="0.08" 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>
      <unit>%/rad/s</unit>
      <decimal>3</decimal>
      <increment>0.005</increment>
      <scope>modules/fw_att_control</scope>
    </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>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="60.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>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="60.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>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <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>
      <unit>s</unit>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="0.8" name="FW_RATT_TH" type="FLOAT">
      <short_desc>Threshold for Rattitude mode</short_desc>
      <long_desc>Manual input needed in order to override attitude control rate setpoints and instead pass manual stick inputs as rate setpoints</long_desc>
      <min>0.0</min>
      <max>1.0</max>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="0.0" name="FW_RLL_TO_YAW_FF" type="FLOAT">
      <short_desc>Roll control to yaw control feedforward gain</short_desc>
      <long_desc>This gain can be used to counteract the "adverse yaw" effect for fixed wings. When the plane enters a roll it will tend to yaw the nose out of the turn. This gain enables the use of a yaw actuator (rudder, airbrakes, ...) to counteract this effect.</long_desc>
      <min>0.0</min>
      <decimal>1</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="0.5" 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>
      <unit>%/rad/s</unit>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="0.01" 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.005</min>
      <max>0.2</max>
      <unit>%/rad</unit>
      <decimal>3</decimal>
      <increment>0.005</increment>
      <scope>modules/fw_att_control</scope>
    </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>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/fw_att_control</scope>
    </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>
      <unit>%/rad/s</unit>
      <decimal>3</decimal>
      <increment>0.005</increment>
      <scope>modules/fw_att_control</scope>
    </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>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="70.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>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <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>
      <min>0.4</min>
      <max>1.0</max>
      <unit>s</unit>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="0.2" name="FW_WR_FF" type="FLOAT">
      <short_desc>Wheel steering 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>
      <unit>%/rad/s</unit>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/fw_att_control</scope>
    </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.005</min>
      <max>0.5</max>
      <unit>%/rad</unit>
      <decimal>3</decimal>
      <increment>0.005</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="1.0" name="FW_WR_IMAX" type="FLOAT">
      <short_desc>Wheel steering 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>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/fw_att_control</scope>
    </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>
      <unit>%/rad/s</unit>
      <decimal>3</decimal>
      <increment>0.005</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="0" name="FW_W_EN" type="INT32">
      <short_desc>Enable wheel steering controller</short_desc>
      <boolean />
      <scope>modules/fw_att_control</scope>
    </parameter>
    <parameter default="0.0" name="FW_W_RMAX" type="FLOAT">
      <short_desc>Maximum wheel steering rate</short_desc>
      <long_desc>This limits the maximum wheel steering 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>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_att_control</scope>
    </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>
      <unit>%/rad/s</unit>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/fw_att_control</scope>
    </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>
      <unit>%/rad</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_att_control</scope>
    </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>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/fw_att_control</scope>
    </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>
      <unit>%/rad/s</unit>
      <decimal>3</decimal>
      <increment>0.005</increment>
      <scope>modules/fw_att_control</scope>
    </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>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_att_control</scope>
    </parameter>
  </group>
  <group name="FW L1 Control">
    <parameter default="10.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 0 to disable climbout mode (not recommended).</long_desc>
      <min>0.0</min>
      <max>150.0</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </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>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
    <parameter default="20.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 18-25 meters works for most aircraft. Shorten slowly during tuning until response is sharp without oscillation.</long_desc>
      <min>12.0</min>
      <max>50.0</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
    <parameter default="1.3" name="FW_LND_AIRSPD_SC" type="FLOAT">
      <short_desc>Min. airspeed scaling factor for landing</short_desc>
      <long_desc>Multiplying this factor with the minimum airspeed of the plane gives the target airspeed the landing approach. FW_AIRSPD_MIN * FW_LND_AIRSPD_SC</long_desc>
      <min>1.0</min>
      <max>1.5</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
    <parameter default="5.0" name="FW_LND_ANG" type="FLOAT">
      <short_desc>Landing slope angle</short_desc>
      <min>1.0</min>
      <max>15.0</max>
      <unit>deg</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
    <parameter default="8.0" name="FW_LND_FLALT" type="FLOAT">
      <short_desc>Landing flare altitude (relative to landing altitude)</short_desc>
      <min>0.0</min>
      <max>25.0</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
    <parameter default="15.0" name="FW_LND_FL_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>
      <min>0</min>
      <max>45.0</max>
      <unit>deg</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
    <parameter default="2.5" name="FW_LND_FL_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>
      <min>0</min>
      <max>15.0</max>
      <unit>deg</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
    <parameter default="15.0" name="FW_LND_HHDIST" type="FLOAT">
      <short_desc>Landing heading hold horizontal distance.
Set to 0 to disable heading hold</short_desc>
      <min>0</min>
      <max>30.0</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
    <parameter default="10.0" name="FW_LND_HVIRT" type="FLOAT">
      <short_desc>FW_LND_HVIRT</short_desc>
      <min>1.0</min>
      <max>15.0</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </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.0 lets the system default to applying throttle limiting at 2/3 of the flare altitude.</long_desc>
      <min>-1.0</min>
      <max>30.0</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
    <parameter default="0" name="FW_LND_USETER" type="INT32">
      <short_desc>Use terrain estimate during landing</short_desc>
      <boolean />
      <scope>modules/fw_pos_control_l1</scope>
    </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>deg</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </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>deg</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
    <parameter default="50.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>35.0</min>
      <max>65.0</max>
      <unit>deg</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
    <parameter default="0.0" name="FW_THR_ALT_SCL" type="FLOAT">
      <short_desc>Scale throttle by pressure change</short_desc>
      <long_desc>Automatically adjust throttle to account for decreased air density at higher altitudes. Start with a scale factor of 1.0 and adjust for different propulsion systems. When flying without airspeed sensor this will help to keep a constant performance over large altitude ranges. The default value of 0 will disable scaling.</long_desc>
      <min>0.0</min>
      <max>10.0</max>
      <decimal>1</decimal>
      <increment>0.1</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
    <parameter default="0.6" 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>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
    <parameter default="0.15" name="FW_THR_IDLE" type="FLOAT">
      <short_desc>Idle throttle</short_desc>
      <long_desc>This is the minimum throttle while on the ground For aircraft with internal combustion engine this parameter should be set above desired idle rpm.</long_desc>
      <min>0.0</min>
      <max>0.4</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </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 aircraft will flare.</long_desc>
      <min>0.0</min>
      <max>1.0</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </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>
      <min>0.0</min>
      <max>1.0</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </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>
      <min>0.0</min>
      <max>1.0</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </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>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
  </group>
  <group name="FW Launch detection">
    <parameter default="0" name="LAUN_ALL_ON" type="INT32">
      <short_desc>Launch detection</short_desc>
      <boolean />
      <scope>modules/fw_pos_control_l1/launchdetection</scope>
    </parameter>
    <parameter default="30.0" name="LAUN_CAT_A" type="FLOAT">
      <short_desc>Catapult accelerometer threshold</short_desc>
      <long_desc>LAUN_CAT_A for LAUN_CAT_T serves as threshold to trigger launch detection.</long_desc>
      <min>0</min>
      <unit>m/s/s</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1/launchdetection</scope>
    </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 FW_THR_IDLE, set to 0 to deactivate</long_desc>
      <min>0.0</min>
      <max>10.0</max>
      <unit>s</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1/launchdetection</scope>
    </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.0</min>
      <max>45.0</max>
      <unit>deg</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1/launchdetection</scope>
    </parameter>
    <parameter default="0.05" name="LAUN_CAT_T" type="FLOAT">
      <short_desc>Catapult time threshold</short_desc>
      <long_desc>LAUN_CAT_A for LAUN_CAT_T serves as threshold to trigger launch detection.</long_desc>
      <min>0.0</min>
      <max>5.0</max>
      <unit>s</unit>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/fw_pos_control_l1/launchdetection</scope>
    </parameter>
  </group>
  <group name="FW TECS">
    <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>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </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>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
    <parameter default="15.0" name="FW_AIRSPD_TRIM" type="FLOAT">
      <short_desc>Cruise Airspeed</short_desc>
      <long_desc>The fixed wing controller tries to fly at this airspeed.</long_desc>
      <min>0.0</min>
      <max>40</max>
      <unit>m/s</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </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>
      <min>1.0</min>
      <max>15.0</max>
      <unit>m/s</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </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>
      <min>1.0</min>
      <max>10.0</max>
      <unit>rad/s</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
    <parameter default="0.8" name="FW_T_HRATE_FF" type="FLOAT">
      <short_desc>Height rate feed forward</short_desc>
      <min>0.0</min>
      <max>1.0</max>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
    <parameter default="0.05" name="FW_T_HRATE_P" type="FLOAT">
      <short_desc>Height rate proportional factor</short_desc>
      <min>0.0</min>
      <max>1.0</max>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </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>
      <min>0.0</min>
      <max>2.0</max>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </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>
      <min>0.0</min>
      <max>2.0</max>
      <decimal>1</decimal>
      <increment>0.1</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
    <parameter default="15.0" name="FW_T_RLL2THR" type="FLOAT">
      <short_desc>Roll -&gt; 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>
      <min>0.0</min>
      <max>20.0</max>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </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>
      <min>2.0</min>
      <max>15.0</max>
      <unit>m/s</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
    <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>
      <min>1.0</min>
      <max>5.0</max>
      <unit>m/s</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
    <parameter default="1.0" name="FW_T_SPDWEIGHT" type="FLOAT">
      <short_desc>Speed &lt;--&gt; 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>
      <min>0.0</min>
      <max>2.0</max>
      <decimal>1</decimal>
      <increment>1.0</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </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 airspeed sensor, whilst reducing it weights the solution more towards use of the accelerometer data.</long_desc>
      <min>1.0</min>
      <max>10.0</max>
      <unit>rad/s</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
    <parameter default="0.02" name="FW_T_SRATE_P" type="FLOAT">
      <short_desc>Speed rate P factor</short_desc>
      <min>0.0</min>
      <max>2.0</max>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </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>
      <min>1.0</min>
      <max>10.0</max>
      <unit>s</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </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>
      <min>0.0</min>
      <max>2.0</max>
      <decimal>1</decimal>
      <increment>0.1</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </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>
      <min>1.0</min>
      <max>10.0</max>
      <unit>s</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </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 m/s/s) either up or down that the controller will use to correct speed or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g) allows for reasonably aggressive pitch changes if required to recover from under-speed conditions.</long_desc>
      <min>1.0</min>
      <max>10.0</max>
      <unit>m/s/s</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1</scope>
    </parameter>
    <parameter default="10.0" name="GND_SPEED_MAX" type="FLOAT">
      <short_desc>Maximum ground speed</short_desc>
      <min>0.0</min>
      <max>40</max>
      <unit>m/s</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/gnd_pos_control</scope>
    </parameter>
    <parameter default="3.0" name="GND_SPEED_TRIM" type="FLOAT">
      <short_desc>Trim ground speed</short_desc>
      <min>0.0</min>
      <max>40</max>
      <unit>m/s</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/gnd_pos_control</scope>
    </parameter>
  </group>
  <group name="Follow target">
    <parameter default="8.0" name="NAV_FT_DST" type="FLOAT">
      <short_desc>Distance to follow target from</short_desc>
      <long_desc>The distance in meters to follow the target at</long_desc>
      <min>1.0</min>
      <unit>meters</unit>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="1" name="NAV_FT_FS" type="INT32">
      <short_desc>Side to follow target from</short_desc>
      <long_desc>The side to follow the target from (front right = 0, behind = 1, front = 2, front left = 3)</long_desc>
      <min>0</min>
      <max>3</max>
      <unit>n/a</unit>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="0.5" name="NAV_FT_RS" type="FLOAT">
      <short_desc>Dynamic filtering algorithm responsiveness to target movement
lower numbers increase the responsiveness to changing long lat
but also ignore less noise</short_desc>
      <min>0.0</min>
      <max>1.0</max>
      <unit>n/a</unit>
      <decimal>2</decimal>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="8.0" name="NAV_MIN_FT_HT" type="FLOAT">
      <short_desc>Minimum follow target altitude</short_desc>
      <long_desc>The minimum height in meters relative to home for following a target</long_desc>
      <min>8.0</min>
      <unit>meters</unit>
      <scope>modules/navigator</scope>
    </parameter>
  </group>
  <group name="GND Attitude Control">
    <parameter default="0" name="GND_BAT_SCALE_EN" type="INT32">
      <short_desc>Whether to scale throttle by battery power level</short_desc>
      <long_desc>This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The fixed wing should constantly behave as if it was fully charged with reduced max thrust at lower battery percentages. i.e. if cruise speed is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery.</long_desc>
      <boolean />
      <scope>modules/gnd_att_control</scope>
    </parameter>
    <parameter default="1.0" name="GND_GSPD_SP_TRIM" type="FLOAT">
      <short_desc>Groundspeed speed trim</short_desc>
      <long_desc>This allows to scale the turning radius depending on the speed.</long_desc>
      <min>0.0</min>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.1</increment>
      <scope>modules/gnd_att_control</scope>
    </parameter>
    <parameter default="1.0" name="GND_MAN_Y_SC" type="FLOAT">
      <short_desc>Manual yaw scale</short_desc>
      <long_desc>Scale factor applied to the desired yaw actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces.</long_desc>
      <min>0.0</min>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/gnd_att_control</scope>
    </parameter>
    <parameter default="0.0" name="GND_SPEED_D" type="FLOAT">
      <short_desc>Speed proportional gain</short_desc>
      <long_desc>This is the derivative gain for the speed closed loop controller</long_desc>
      <min>0.00</min>
      <max>50.0</max>
      <unit>%m/s</unit>
      <decimal>3</decimal>
      <increment>0.005</increment>
      <scope>modules/gnd_pos_control</scope>
    </parameter>
    <parameter default="0.1" name="GND_SPEED_I" type="FLOAT">
      <short_desc>Speed Integral gain</short_desc>
      <long_desc>This is the integral gain for the speed closed loop controller</long_desc>
      <min>0.00</min>
      <max>50.0</max>
      <unit>%m/s</unit>
      <decimal>3</decimal>
      <increment>0.005</increment>
      <scope>modules/gnd_pos_control</scope>
    </parameter>
    <parameter default="1.0" name="GND_SPEED_IMAX" type="FLOAT">
      <short_desc>Speed integral maximum value</short_desc>
      <long_desc>This is the maxim value the integral can reach to prevent wind-up.</long_desc>
      <min>0.005</min>
      <max>50.0</max>
      <unit>%m/s</unit>
      <decimal>3</decimal>
      <increment>0.005</increment>
      <scope>modules/gnd_pos_control</scope>
    </parameter>
    <parameter default="2.0" name="GND_SPEED_P" type="FLOAT">
      <short_desc>Speed proportional gain</short_desc>
      <long_desc>This is the proportional gain for the speed closed loop controller</long_desc>
      <min>0.005</min>
      <max>50.0</max>
      <unit>%m/s</unit>
      <decimal>3</decimal>
      <increment>0.005</increment>
      <scope>modules/gnd_pos_control</scope>
    </parameter>
    <parameter default="1.0" name="GND_SPEED_THR_SC" type="FLOAT">
      <short_desc>Speed to throttle scaler</short_desc>
      <long_desc>This is a gain to map the speed control output to the throttle linearly.</long_desc>
      <min>0.005</min>
      <max>50.0</max>
      <unit>%m/s</unit>
      <decimal>3</decimal>
      <increment>0.005</increment>
      <scope>modules/gnd_pos_control</scope>
    </parameter>
    <parameter default="1" name="GND_SP_CTRL_MODE" type="INT32">
      <short_desc>Control mode for speed</short_desc>
      <long_desc>This allows the user to choose between closed loop gps speed or open loop cruise throttle speed</long_desc>
      <min>0</min>
      <max>1</max>
      <scope>modules/gnd_pos_control</scope>
      <values>
        <value code="0">open loop control</value>
        <value code="1">close the loop with gps speed</value>
      </values>
    </parameter>
    <parameter default="0.00" name="GND_WR_D" type="FLOAT">
      <short_desc>Wheel steering rate integrator gain</short_desc>
      <min>0.00</min>
      <max>30</max>
      <unit>%/rad</unit>
      <decimal>3</decimal>
      <increment>0.005</increment>
      <scope>modules/gnd_att_control</scope>
    </parameter>
    <parameter default="0.0" name="GND_WR_FF" type="FLOAT">
      <short_desc>Wheel steering 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>
      <unit>%/rad/s</unit>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/gnd_att_control</scope>
    </parameter>
    <parameter default="0.00" name="GND_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.00</min>
      <max>0.5</max>
      <unit>%/rad</unit>
      <decimal>3</decimal>
      <increment>0.005</increment>
      <scope>modules/gnd_att_control</scope>
    </parameter>
    <parameter default="0.0" name="GND_WR_IMAX" type="FLOAT">
      <short_desc>Wheel steering 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>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/gnd_att_control</scope>
    </parameter>
    <parameter default="1.0" name="GND_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>
      <unit>%/rad/s</unit>
      <decimal>3</decimal>
      <increment>0.005</increment>
      <scope>modules/gnd_att_control</scope>
    </parameter>
    <parameter default="0.4" name="GND_WR_TC" type="FLOAT">
      <short_desc>Attitude Wheel Time Constant</short_desc>
      <long_desc>This defines the latency between a steering 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>s</unit>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/gnd_att_control</scope>
    </parameter>
    <parameter default="90.0" name="GND_W_RMAX" type="FLOAT">
      <short_desc>Maximum wheel steering rate</short_desc>
      <long_desc>This limits the maximum wheel steering 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>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/gnd_att_control</scope>
    </parameter>
  </group>
  <group name="GND POS Control">
    <parameter default="0.75" name="GND_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>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/gnd_pos_control</scope>
    </parameter>
    <parameter default="5.0" name="GND_L1_DIST" type="FLOAT">
      <short_desc>L1 distance</short_desc>
      <long_desc>This is the waypoint radius</long_desc>
      <min>0.0</min>
      <max>100.0</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <increment>0.1</increment>
      <scope>modules/gnd_pos_control</scope>
    </parameter>
    <parameter default="10.0" name="GND_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 rover it's following. Using values around 2-5 for a traxxas stampede. Shorten slowly during tuning until response is sharp without oscillation.</long_desc>
      <min>0.0</min>
      <max>50.0</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/gnd_pos_control</scope>
    </parameter>
    <parameter default="0.1" name="GND_THR_CRUISE" type="FLOAT">
      <short_desc>Cruise throttle</short_desc>
      <long_desc>This is the throttle setting required to achieve the desired cruise speed. 10% is ok for a traxxas stampede vxl with ESC set to training mode</long_desc>
      <min>0.0</min>
      <max>1.0</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/gnd_pos_control</scope>
    </parameter>
    <parameter default="0.0" name="GND_THR_IDLE" type="FLOAT">
      <short_desc>Idle throttle</short_desc>
      <long_desc>This is the minimum throttle while on the ground, it should be 0 for a rover</long_desc>
      <min>0.0</min>
      <max>0.4</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/gnd_pos_control</scope>
    </parameter>
    <parameter default="0.3" name="GND_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 a Traxxas stampede vxl with the ESC set to training, 30 % is enough</long_desc>
      <min>0.0</min>
      <max>1.0</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/gnd_pos_control</scope>
    </parameter>
    <parameter default="0.0" name="GND_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. Set to 0 for rover</long_desc>
      <min>0.0</min>
      <max>1.0</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/gnd_pos_control</scope>
    </parameter>
  </group>
  <group name="GPS">
    <parameter default="0" name="GPS_DUMP_COMM" type="INT32">
      <short_desc>Dump GPS communication to a file</short_desc>
      <long_desc>If this is set to 1, all GPS communication data will be published via uORB, and written to the log file as gps_dump message.</long_desc>
      <min>0</min>
      <max>1</max>
      <scope>drivers/gps</scope>
      <values>
        <value code="0">Disable</value>
        <value code="1">Enable</value>
      </values>
    </parameter>
    <parameter default="7" name="GPS_UBX_DYNMODEL" type="INT32">
      <short_desc>u-blox GPS dynamic platform model</short_desc>
      <long_desc>u-blox receivers support different dynamic platform models to adjust the navigation engine to the expected application environment.</long_desc>
      <min>0</min>
      <max>9</max>
      <reboot_required>true</reboot_required>
      <scope>drivers/gps</scope>
      <values>
        <value code="2">stationary</value>
        <value code="4">automotive</value>
        <value code="6">airborne with &lt;1g acceleration</value>
        <value code="7">airborne with &lt;2g acceleration</value>
        <value code="8">airborne with &lt;4g acceleration</value>
      </values>
    </parameter>
  </group>
  <group name="GPS Failure Navigation">
    <parameter default="0.0" name="NAV_GPSF_LT" type="FLOAT">
      <short_desc>Loiter time</short_desc>
      <long_desc>The time in seconds the system should do open loop loiter and wait for GPS recovery before it goes into flight termination. Set to 0 to disable.</long_desc>
      <min>0.0</min>
      <max>3600.0</max>
      <unit>s</unit>
      <decimal>0</decimal>
      <increment>1</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="0.0" name="NAV_GPSF_P" type="FLOAT">
      <short_desc>Fixed pitch angle</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>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="15.0" name="NAV_GPSF_R" type="FLOAT">
      <short_desc>Fixed bank angle</short_desc>
      <long_desc>Roll in degrees during the loiter</long_desc>
      <min>0.0</min>
      <max>30.0</max>
      <unit>deg</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="0.0" name="NAV_GPSF_TR" type="FLOAT">
      <short_desc>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>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/navigator</scope>
    </parameter>
  </group>
  <group name="Geofence">
    <parameter default="1" name="GF_ACTION" type="INT32">
      <short_desc>Geofence violation action</short_desc>
      <long_desc>Note: Setting this value to 4 enables flight termination, which will kill the vehicle on violation of the fence. Due to the inherent danger of this, this function is disabled using a software circuit breaker, which needs to be reset to 0 to really shut down the system.</long_desc>
      <min>0</min>
      <max>4</max>
      <scope>modules/navigator</scope>
      <values>
        <value code="0">None</value>
        <value code="1">Warning</value>
        <value code="2">Loiter</value>
        <value code="3">Return to Land</value>
        <value code="4">Flight terminate</value>
      </values>
    </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>
      <scope>modules/navigator</scope>
      <values>
        <value code="0">WGS84</value>
        <value code="1">AMSL</value>
      </values>
    </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>
      <increment>1</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="0" name="GF_MAX_HOR_DIST" type="FLOAT">
      <short_desc>Max horizontal distance in meters</short_desc>
      <long_desc>Maximum horizontal distance in meters the vehicle can be from home before triggering a geofence action. Disabled if 0.</long_desc>
      <min>0</min>
      <max>10000</max>
      <unit>m</unit>
      <increment>1</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="0" name="GF_MAX_VER_DIST" type="FLOAT">
      <short_desc>Max vertical distance in meters</short_desc>
      <long_desc>Maximum vertical distance in meters the vehicle can be from home before triggering a geofence action. Disabled if 0.</long_desc>
      <min>0</min>
      <max>10000</max>
      <unit>m</unit>
      <increment>1</increment>
      <scope>modules/navigator</scope>
    </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>
      <scope>modules/navigator</scope>
      <values>
        <value code="0">GPOS</value>
        <value code="1">GPS</value>
      </values>
    </parameter>
  </group>
  <group name="Iridium SBD">
    <parameter default="0" name="ISBD_READ_INT" type="INT32">
      <short_desc>Satellite radio read interval. Only required to be nonzero if data is not sent using a ring call</short_desc>
      <min>0</min>
      <max>5000</max>
      <unit>s</unit>
      <scope>drivers/telemetry/iridiumsbd</scope>
    </parameter>
    <parameter default="60" name="ISBD_SBD_TIMEOUT" type="INT32">
      <short_desc>Iridium SBD session timeout</short_desc>
      <min>0</min>
      <max>300</max>
      <unit>s</unit>
      <scope>drivers/telemetry/iridiumsbd</scope>
    </parameter>
    <parameter default="0" name="ISBD_STACK_TIME" type="INT32">
      <short_desc>Time [ms] the Iridium driver will wait for additional mavlink messages to combine them into one SBD message
Value 0 turns the functionality off</short_desc>
      <min>0</min>
      <max>500</max>
      <unit>ms</unit>
      <scope>drivers/telemetry/iridiumsbd</scope>
    </parameter>
  </group>
  <group name="Land Detector">
    <parameter default="8.00" name="LNDFW_AIRSPD_MAX" type="FLOAT">
      <short_desc>Airspeed max</short_desc>
      <long_desc>Maximum airspeed allowed in the landed state (m/s)</long_desc>
      <min>4</min>
      <max>20</max>
      <unit>m/s</unit>
      <decimal>1</decimal>
      <scope>modules/land_detector</scope>
    </parameter>
    <parameter default="8.0" name="LNDFW_VELI_MAX" type="FLOAT">
      <short_desc>Fixedwing max short-term velocity</short_desc>
      <long_desc>Maximum velocity integral in flight direction allowed in the landed state (m/s)</long_desc>
      <min>2</min>
      <max>10</max>
      <unit>m/s</unit>
      <decimal>1</decimal>
      <scope>modules/land_detector</scope>
    </parameter>
    <parameter default="5.0" name="LNDFW_VEL_XY_MAX" type="FLOAT">
      <short_desc>Fixedwing max horizontal velocity</short_desc>
      <long_desc>Maximum horizontal velocity allowed in the landed state (m/s)</long_desc>
      <min>0.5</min>
      <max>10</max>
      <unit>m/s</unit>
      <decimal>1</decimal>
      <scope>modules/land_detector</scope>
    </parameter>
    <parameter default="10.0" name="LNDFW_VEL_Z_MAX" type="FLOAT">
      <short_desc>Fixedwing max climb rate</short_desc>
      <long_desc>Maximum vertical velocity allowed in the landed state (m/s up and down)</long_desc>
      <min>5</min>
      <max>20</max>
      <unit>m/s</unit>
      <decimal>1</decimal>
      <scope>modules/land_detector</scope>
    </parameter>
    <parameter default="-1.0" name="LNDMC_ALT_MAX" type="FLOAT">
      <short_desc>Maximum altitude for multicopters</short_desc>
      <long_desc>The system will obey this limit as a hard altitude limit. This setting will be consolidated with the GF_MAX_VER_DIST parameter. A negative value indicates no altitude limitation.</long_desc>
      <min>-1</min>
      <max>10000</max>
      <unit>m</unit>
      <decimal>2</decimal>
      <scope>modules/land_detector</scope>
    </parameter>
    <parameter default="2.0" name="LNDMC_FFALL_THR" type="FLOAT">
      <short_desc>Multicopter specific force threshold</short_desc>
      <long_desc>Multicopter threshold on the specific force measured by accelerometers in m/s^2 for free-fall detection</long_desc>
      <min>0.1</min>
      <max>10</max>
      <unit>m/s^2</unit>
      <decimal>2</decimal>
      <scope>modules/land_detector</scope>
    </parameter>
    <parameter default="0.3" name="LNDMC_FFALL_TTRI" type="FLOAT">
      <short_desc>Multicopter free-fall trigger time</short_desc>
      <long_desc>Seconds (decimal) that freefall conditions have to met before triggering a freefall. Minimal value is limited by LAND_DETECTOR_UPDATE_RATE=50Hz in landDetector.h</long_desc>
      <min>0.02</min>
      <max>5</max>
      <unit>s</unit>
      <decimal>2</decimal>
      <scope>modules/land_detector</scope>
    </parameter>
    <parameter default="20.0" name="LNDMC_ROT_MAX" type="FLOAT">
      <short_desc>Multicopter max rotation</short_desc>
      <long_desc>Maximum allowed angular velocity around each axis allowed in the landed state.</long_desc>
      <unit>deg/s</unit>
      <decimal>1</decimal>
      <scope>modules/land_detector</scope>
    </parameter>
    <parameter default="0.1" name="LNDMC_THR_RANGE" type="FLOAT">
      <short_desc>Multicopter sub-hover throttle scaling</short_desc>
      <long_desc>The range between throttle_min and throttle_hover is scaled by this parameter to define how close to minimum throttle the current throttle value needs to be in order to get accepted as landed.</long_desc>
      <min>0.05</min>
      <max>0.5</max>
      <decimal>2</decimal>
      <scope>modules/land_detector</scope>
    </parameter>
    <parameter default="1.5" name="LNDMC_XY_VEL_MAX" type="FLOAT">
      <short_desc>Multicopter max horizontal velocity</short_desc>
      <long_desc>Maximum horizontal velocity allowed in the landed state (m/s)</long_desc>
      <unit>m/s</unit>
      <decimal>1</decimal>
      <scope>modules/land_detector</scope>
    </parameter>
    <parameter default="0.50" name="LNDMC_Z_VEL_MAX" type="FLOAT">
      <short_desc>Multicopter max climb rate</short_desc>
      <long_desc>Maximum vertical velocity allowed in the landed state (m/s up and down)</long_desc>
      <unit>m/s</unit>
      <decimal>1</decimal>
      <scope>modules/land_detector</scope>
    </parameter>
    <parameter category="System" default="0" name="LND_FLIGHT_T_HI" type="INT32" volatile="true">
      <short_desc>Total flight time in microseconds</short_desc>
      <long_desc>Total flight time of this autopilot. Higher 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI &lt;&lt; 32) | LND_FLIGHT_T_LO.</long_desc>
      <min>0</min>
      <scope>modules/land_detector</scope>
    </parameter>
    <parameter category="System" default="0" name="LND_FLIGHT_T_LO" type="INT32" volatile="true">
      <short_desc>Total flight time in microseconds</short_desc>
      <long_desc>Total flight time of this autopilot. Lower 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI &lt;&lt; 32) | LND_FLIGHT_T_LO.</long_desc>
      <min>0</min>
      <scope>modules/land_detector</scope>
    </parameter>
  </group>
  <group name="Landing target Estimator">
    <parameter default="10.0" name="LTEST_ACC_UNC" type="FLOAT">
      <short_desc>Acceleration uncertainty</short_desc>
      <long_desc>Variance of acceleration measurement used for landing target position prediction. Higher values results in tighter following of the measurements and more lenient outlier rejection</long_desc>
      <min>0.01</min>
      <unit>(m/s^2)^2</unit>
      <decimal>2</decimal>
      <scope>modules/landing_target_estimator</scope>
    </parameter>
    <parameter default="0.005" name="LTEST_MEAS_UNC" type="FLOAT">
      <short_desc>Landing target measurement uncertainty</short_desc>
      <long_desc>Variance of the landing target measurement from the driver. Higher values results in less agressive following of the measurement and a smoother output as well as fewer rejected measurements.</long_desc>
      <unit>tan(rad)^2</unit>
      <decimal>4</decimal>
      <scope>modules/landing_target_estimator</scope>
    </parameter>
    <parameter default="0" name="LTEST_MODE" type="INT32">
      <short_desc>Landing target mode</short_desc>
      <long_desc>Configure the mode of the landing target. Depending on the mode, the landing target observations are used differently to aid position estimation. Mode Moving:     The landing target may be moving around while in the field of view of the vehicle. Landing target measurements are not used to aid positioning. Mode Stationary: The landing target is stationary. Measured velocity w.r.t. the landing target is used to aid velocity estimation.</long_desc>
      <min>0</min>
      <max>1</max>
      <scope>modules/landing_target_estimator</scope>
      <values>
        <value code="0">Moving</value>
        <value code="1">Stationary</value>
      </values>
    </parameter>
    <parameter default="0.1" name="LTEST_POS_UNC_IN" type="FLOAT">
      <short_desc>Initial landing target position uncertainty</short_desc>
      <long_desc>Initial variance of the relative landing target position in x and y direction</long_desc>
      <min>0.001</min>
      <unit>m^2</unit>
      <decimal>3</decimal>
      <scope>modules/landing_target_estimator</scope>
    </parameter>
    <parameter default="1.0" name="LTEST_SCALE_X" type="FLOAT">
      <short_desc>Scale factor for sensor measurements in sensor x axis</short_desc>
      <long_desc>Landing target x measurements are scaled by this factor before being used</long_desc>
      <min>0.01</min>
      <decimal>3</decimal>
      <scope>modules/landing_target_estimator</scope>
    </parameter>
    <parameter default="1.0" name="LTEST_SCALE_Y" type="FLOAT">
      <short_desc>Scale factor for sensor measurements in sensor y axis</short_desc>
      <long_desc>Landing target y measurements are scaled by this factor before being used</long_desc>
      <min>0.01</min>
      <decimal>3</decimal>
      <scope>modules/landing_target_estimator</scope>
    </parameter>
    <parameter default="0.1" name="LTEST_VEL_UNC_IN" type="FLOAT">
      <short_desc>Initial landing target velocity uncertainty</short_desc>
      <long_desc>Initial variance of the relative landing target velocity in x and y direction</long_desc>
      <min>0.001</min>
      <unit>(m/s)^2</unit>
      <decimal>3</decimal>
      <scope>modules/landing_target_estimator</scope>
    </parameter>
  </group>
  <group name="Local Position Estimator">
    <parameter default="0.012" name="LPE_ACC_XY" type="FLOAT">
      <short_desc>Accelerometer xy noise density</short_desc>
      <long_desc>Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) Larger than data sheet to account for tilt error.</long_desc>
      <min>0.00001</min>
      <max>2</max>
      <unit>m/s^2/sqrt(Hz)</unit>
      <decimal>4</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="0.02" name="LPE_ACC_Z" type="FLOAT">
      <short_desc>Accelerometer z noise density</short_desc>
      <long_desc>Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz)</long_desc>
      <min>0.00001</min>
      <max>2</max>
      <unit>m/s^2/sqrt(Hz)</unit>
      <decimal>4</decimal>
      <scope>modules/local_position_estimator</scope>
    </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>100</max>
      <unit>m</unit>
      <decimal>2</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="3.0" name="LPE_EPH_MAX" type="FLOAT">
      <short_desc>Max EPH allowed for GPS initialization</short_desc>
      <min>1.0</min>
      <max>5.0</max>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="5.0" name="LPE_EPV_MAX" type="FLOAT">
      <short_desc>Max EPV allowed for GPS initialization</short_desc>
      <min>1.0</min>
      <max>5.0</max>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="0" name="LPE_FAKE_ORIGIN" type="INT32">
      <short_desc>Enable publishing of a fake global position (e.g for AUTO missions using Optical Flow)
by initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable</short_desc>
      <min>0</min>
      <max>1</max>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="0.001" name="LPE_FGYRO_HP" type="FLOAT">
      <short_desc>Flow gyro high pass filter cut off frequency</short_desc>
      <min>0</min>
      <max>2</max>
      <unit>Hz</unit>
      <decimal>3</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="0.0" name="LPE_FLW_OFF_Z" type="FLOAT">
      <short_desc>Optical flow z offset from center</short_desc>
      <min>-1</min>
      <max>1</max>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="150" name="LPE_FLW_QMIN" type="INT32">
      <short_desc>Optical flow minimum quality threshold</short_desc>
      <min>0</min>
      <max>255</max>
      <decimal>0</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="7.0" name="LPE_FLW_R" type="FLOAT">
      <short_desc>Optical flow rotation (roll/pitch) noise gain</short_desc>
      <min>0.1</min>
      <max>10.0</max>
      <unit>m/s / (rad)</unit>
      <decimal>3</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="7.0" name="LPE_FLW_RR" type="FLOAT">
      <short_desc>Optical flow angular velocity noise gain</short_desc>
      <min>0.0</min>
      <max>10.0</max>
      <unit>m/s / (rad/s)</unit>
      <decimal>3</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="1.3" name="LPE_FLW_SCALE" type="FLOAT">
      <short_desc>Optical flow scale</short_desc>
      <min>0.1</min>
      <max>10.0</max>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="145" name="LPE_FUSION" type="INT32">
      <short_desc>Integer bitmask controlling data fusion</short_desc>
      <long_desc>Set bits in the following positions to enable: 0 : Set to true to fuse GPS data if available, also requires GPS for altitude init 1 : Set to true to fuse optical flow data if available 2 : Set to true to fuse vision position 3 : Set to true to enable landing target 4 : Set to true to fuse land detector 5 : Set to true to publish AGL as local position down component 6 : Set to true to enable flow gyro compensation 7 : Set to true to enable baro fusion default (145 - GPS, baro, land detector)</long_desc>
      <min>0</min>
      <max>255</max>
      <scope>modules/local_position_estimator</scope>
      <bitmask>
        <bit index="0"> fuse GPS, requires GPS for alt. init</bit>
        <bit index="1"> fuse optical flow</bit>
        <bit index="2"> fuse vision position</bit>
        <bit index="3"> fuse landing target</bit>
        <bit index="4"> fuse land detector</bit>
        <bit index="5"> pub agl as lpos down</bit>
        <bit index="6"> flow gyro compensation</bit>
        <bit index="7"> fuse baro</bit>
      </bitmask>
    </parameter>
    <parameter default="0.29" name="LPE_GPS_DELAY" type="FLOAT">
      <short_desc>GPS delay compensaton</short_desc>
      <min>0</min>
      <max>0.4</max>
      <unit>sec</unit>
      <decimal>2</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="0.25" name="LPE_GPS_VXY" type="FLOAT">
      <short_desc>GPS xy velocity standard deviation.
EPV used if greater than this value</short_desc>
      <min>0.01</min>
      <max>2</max>
      <unit>m/s</unit>
      <decimal>3</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="0.25" 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>
      <decimal>3</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="1.0" name="LPE_GPS_XY" type="FLOAT">
      <short_desc>Minimum GPS xy standard deviation, uses reported EPH if greater</short_desc>
      <min>0.01</min>
      <max>5</max>
      <unit>m</unit>
      <decimal>2</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="3.0" name="LPE_GPS_Z" type="FLOAT">
      <short_desc>Minimum GPS z standard deviation, uses reported EPV if greater</short_desc>
      <min>0.01</min>
      <max>200</max>
      <unit>m</unit>
      <decimal>2</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="0.05" name="LPE_LAND_VXY" type="FLOAT">
      <short_desc>Land detector xy velocity standard deviation</short_desc>
      <min>0.01</min>
      <max>10.0</max>
      <unit>m/s</unit>
      <decimal>3</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="0.03" name="LPE_LAND_Z" type="FLOAT">
      <short_desc>Land detector z standard deviation</short_desc>
      <min>0.001</min>
      <max>10.0</max>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="47.397742" name="LPE_LAT" type="FLOAT">
      <short_desc>Local origin latitude for nav w/o GPS</short_desc>
      <min>-90</min>
      <max>90</max>
      <unit>deg</unit>
      <decimal>8</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="0.00" name="LPE_LDR_OFF_Z" type="FLOAT">
      <short_desc>Lidar z offset from center of vehicle +down</short_desc>
      <min>-1</min>
      <max>1</max>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="0.03" name="LPE_LDR_Z" type="FLOAT">
      <short_desc>Lidar z standard deviation</short_desc>
      <min>0.01</min>
      <max>1</max>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="8.545594" name="LPE_LON" type="FLOAT">
      <short_desc>Local origin longitude for nav w/o GPS</short_desc>
      <min>-180</min>
      <max>180</max>
      <unit>deg</unit>
      <decimal>8</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="0.0001" name="LPE_LT_COV" type="FLOAT">
      <short_desc>Minimum landing target standard covariance, uses reported covariance if greater</short_desc>
      <min>0.0</min>
      <max>10</max>
      <unit>m^2</unit>
      <decimal>2</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="1e-3" name="LPE_PN_B" type="FLOAT">
      <short_desc>Accel bias propagation noise density</short_desc>
      <min>0</min>
      <max>1</max>
      <unit>(m/s^2)/s/sqrt(Hz)</unit>
      <decimal>8</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="0.1" name="LPE_PN_P" type="FLOAT">
      <short_desc>Position propagation noise density</short_desc>
      <long_desc>Increase to trust measurements more. Decrease to trust model more.</long_desc>
      <min>0</min>
      <max>1</max>
      <unit>m/s/sqrt(Hz)</unit>
      <decimal>8</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="0.001" name="LPE_PN_T" type="FLOAT">
      <short_desc>Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001)</short_desc>
      <min>0</min>
      <max>1</max>
      <unit>(m/s)/(sqrt(hz))</unit>
      <decimal>3</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="0.1" name="LPE_PN_V" type="FLOAT">
      <short_desc>Velocity propagation noise density</short_desc>
      <long_desc>Increase to trust measurements more. Decrease to trust model more.</long_desc>
      <min>0</min>
      <max>1</max>
      <unit>(m/s)/s/sqrt(Hz)</unit>
      <decimal>8</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="0.00" name="LPE_SNR_OFF_Z" type="FLOAT">
      <short_desc>Sonar z offset from center of vehicle +down</short_desc>
      <min>-1</min>
      <max>1</max>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="0.05" name="LPE_SNR_Z" type="FLOAT">
      <short_desc>Sonar z standard deviation</short_desc>
      <min>0.01</min>
      <max>1</max>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="1.0" name="LPE_T_MAX_GRADE" type="FLOAT">
      <short_desc>Terrain maximum percent grade, hilly/outdoor (100 = 45 deg), flat/Indoor (0 = 0 deg)
Used to calculate increased terrain random walk nosie due to movement</short_desc>
      <min>0</min>
      <max>100</max>
      <unit>%</unit>
      <decimal>3</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="0.001" name="LPE_VIC_P" type="FLOAT">
      <short_desc>Vicon position standard deviation</short_desc>
      <min>0.0001</min>
      <max>1</max>
      <unit>m</unit>
      <decimal>4</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="0.1" name="LPE_VIS_DELAY" type="FLOAT">
      <short_desc>Vision delay compensaton</short_desc>
      <long_desc>Set to zero to enable automatic compensation from measurement timestamps</long_desc>
      <min>0</min>
      <max>0.1</max>
      <unit>sec</unit>
      <decimal>2</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="0.1" name="LPE_VIS_XY" type="FLOAT">
      <short_desc>Vision xy standard deviation</short_desc>
      <min>0.01</min>
      <max>1</max>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="0.5" name="LPE_VIS_Z" type="FLOAT">
      <short_desc>Vision z standard deviation</short_desc>
      <min>0.01</min>
      <max>100</max>
      <unit>m</unit>
      <decimal>3</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="0.3" name="LPE_VXY_PUB" type="FLOAT">
      <short_desc>Required velocity xy standard deviation to publish position</short_desc>
      <min>0.01</min>
      <max>1.0</max>
      <unit>m/s</unit>
      <decimal>3</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="5.0" name="LPE_X_LP" type="FLOAT">
      <short_desc>Cut frequency for state publication</short_desc>
      <min>5</min>
      <max>1000</max>
      <unit>Hz</unit>
      <decimal>0</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
    <parameter default="1.0" name="LPE_Z_PUB" type="FLOAT">
      <short_desc>Required z standard deviation to publish altitude/ terrain</short_desc>
      <min>0.3</min>
      <max>5.0</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <scope>modules/local_position_estimator</scope>
    </parameter>
  </group>
  <group name="MAVLink">
    <parameter default="0" name="MAV_BROADCAST" type="INT32">
      <short_desc>Broadcast heartbeats on local network</short_desc>
      <long_desc>This allows a ground control station to automatically find the drone on the local network.</long_desc>
      <scope>modules/mavlink</scope>
      <values>
        <value code="0">Never broadcast</value>
        <value code="1">Always broadcast</value>
      </values>
    </parameter>
    <parameter default="1" name="MAV_COMP_ID" type="INT32">
      <short_desc>MAVLink component ID</short_desc>
      <min>1</min>
      <max>250</max>
      <reboot_required>true</reboot_required>
      <scope>modules/mavlink</scope>
    </parameter>
    <parameter default="1" name="MAV_FWDEXTSP" type="INT32">
      <short_desc>Forward external setpoint messages</short_desc>
      <long_desc>If set to 1 incoming external setpoint messages will be directly forwarded to the controllers if in offboard control mode</long_desc>
      <boolean />
      <scope>modules/mavlink</scope>
    </parameter>
    <parameter default="0" name="MAV_PROTO_VER" type="INT32">
      <short_desc>MAVLink protocol version</short_desc>
      <scope>modules/mavlink</scope>
      <values>
        <value code="0">Default to 1, switch to 2 if GCS sends version 2</value>
        <value code="1">Always use version 1</value>
        <value code="2">Always use version 2</value>
      </values>
    </parameter>
    <parameter default="0" name="MAV_RADIO_ID" type="INT32">
      <short_desc>MAVLink Radio ID</short_desc>
      <long_desc>When non-zero the MAVLink app will attempt to configure the radio to this ID and re-set the parameter to 0. If the value is negative it will reset the complete radio config to factory defaults.</long_desc>
      <min>-1</min>
      <max>240</max>
      <scope>modules/mavlink</scope>
    </parameter>
    <parameter default="1" name="MAV_SYS_ID" type="INT32">
      <short_desc>MAVLink system ID</short_desc>
      <min>1</min>
      <max>250</max>
      <reboot_required>true</reboot_required>
      <scope>modules/mavlink</scope>
    </parameter>
    <parameter default="2" name="MAV_TYPE" type="INT32">
      <short_desc>MAVLink airframe type</short_desc>
      <min>1</min>
      <max>27</max>
      <scope>modules/mavlink</scope>
      <values>
        <value code="0">Generic micro air vehicle</value>
        <value code="1">Fixed wing aircraft</value>
        <value code="2">Quadrotor</value>
        <value code="3">Coaxial helicopter</value>
        <value code="4">Normal helicopter with tail rotor</value>
        <value code="5">Ground installation</value>
        <value code="6">Operator control unit / ground control station</value>
        <value code="7">Airship, controlled</value>
        <value code="8">Free balloon, uncontrolled</value>
        <value code="9">Rocket</value>
        <value code="10">Ground rover</value>
        <value code="11">Surface vessel, boat, ship</value>
        <value code="12">Submarine</value>
        <value code="13">Hexarotor</value>
        <value code="14">Octorotor</value>
        <value code="15">Tricopter</value>
        <value code="16">Flapping wing</value>
        <value code="17">Kite</value>
        <value code="18">Onboard companion controller</value>
        <value code="19">Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter.</value>
        <value code="20">Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter.</value>
        <value code="21">Tiltrotor VTOL</value>
        <value code="22">VTOL reserved 2</value>
        <value code="23">VTOL reserved 3</value>
        <value code="24">VTOL reserved 4</value>
        <value code="25">VTOL reserved 5</value>
        <value code="26">Onboard gimbal</value>
        <value code="27">Onboard ADSB peripheral</value>
      </values>
    </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 incoming HIL GPS messages are parsed.</long_desc>
      <boolean />
      <scope>modules/mavlink</scope>
    </parameter>
  </group>
  <group name="MKBLCTRL Testmode">
    <parameter default="0" name="MKBLCTRL_TEST" type="INT32">
      <short_desc>Test mode (Identify) of MKBLCTRL Driver</short_desc>
      <boolean />
      <scope>drivers/mkblctrl</scope>
    </parameter>
  </group>
  <group name="MPU9x50 Configuration">
    <parameter default="4" name="MPU_ACC_LPF_ENM" type="INT32">
      <short_desc>Low pass filter frequency for Accelerometer</short_desc>
      <scope>platforms/qurt/fc_addon/mpu_spi</scope>
      <values>
        <value code="0">MPU9X50_ACC_LPF_460HZ</value>
        <value code="1">MPU9X50_ACC_LPF_184HZ</value>
        <value code="2">MPU9X50_ACC_LPF_92HZ</value>
        <value code="3">MPU9X50_ACC_LPF_41HZ</value>
        <value code="4">MPU9X50_ACC_LPF_20HZ</value>
        <value code="5">MPU9X50_ACC_LPF_10HZ</value>
        <value code="6">MPU9X50_ACC_LPF_5HZ</value>
        <value code="7">MPU9X50_ACC_LPF_460HZ_NOLPF</value>
      </values>
    </parameter>
    <parameter default="4" name="MPU_GYRO_LPF_ENM" type="INT32">
      <short_desc>Low pass filter frequency for Gyro</short_desc>
      <scope>platforms/qurt/fc_addon/mpu_spi</scope>
      <values>
        <value code="0">MPU9X50_GYRO_LPF_250HZ</value>
        <value code="1">MPU9X50_GYRO_LPF_184HZ</value>
        <value code="2">MPU9X50_GYRO_LPF_92HZ</value>
        <value code="3">MPU9X50_GYRO_LPF_41HZ</value>
        <value code="4">MPU9X50_GYRO_LPF_20HZ</value>
        <value code="5">MPU9X50_GYRO_LPF_10HZ</value>
        <value code="6">MPU9X50_GYRO_LPF_5HZ</value>
        <value code="7">MPU9X50_GYRO_LPF_3600HZ_NOLPF</value>
      </values>
    </parameter>
    <parameter default="2" name="MPU_SAMPLE_R_ENM" type="INT32">
      <short_desc>Sample rate in Hz</short_desc>
      <scope>platforms/qurt/fc_addon/mpu_spi</scope>
      <values>
        <value code="0">MPU9x50_SAMPLE_RATE_100HZ</value>
        <value code="1">MPU9x50_SAMPLE_RATE_200HZ</value>
        <value code="2">MPU9x50_SAMPLE_RATE_500HZ</value>
        <value code="3">MPU9x50_SAMPLE_RATE_1000HZ</value>
      </values>
    </parameter>
  </group>
  <group name="Mission">
    <parameter default="0" name="COM_OBL_ACT" type="INT32">
      <short_desc>Set offboard loss failsafe mode</short_desc>
      <long_desc>The offboard loss failsafe will only be entered after a timeout, set by COM_OF_LOSS_T in seconds.</long_desc>
      <scope>modules/commander</scope>
      <values>
        <value code="0">Land at current position</value>
        <value code="1">Loiter</value>
        <value code="2">Return to Land</value>
      </values>
    </parameter>
    <parameter default="0" name="COM_OBL_RC_ACT" type="INT32">
      <short_desc>Set offboard loss failsafe mode when RC is available</short_desc>
      <long_desc>The offboard loss failsafe will only be entered after a timeout, set by COM_OF_LOSS_T in seconds.</long_desc>
      <scope>modules/commander</scope>
      <values>
        <value code="0">Position control</value>
        <value code="1">Altitude control</value>
        <value code="2">Manual</value>
        <value code="3">Return to Land</value>
        <value code="4">Land at current position</value>
        <value code="5">Loiter</value>
      </values>
    </parameter>
    <parameter default="0" name="COM_POSCTL_NAVL" type="INT32">
      <short_desc>Position control navigation loss response</short_desc>
      <long_desc>This sets the flight mode that will be used if navigation accuracy is no longer adequte for position control. Navigation accuracy checks can be disabled using the CBRK_VELPOSERR parameter, but doing so will remove protection for all flight modes.</long_desc>
      <scope>modules/commander</scope>
      <values>
        <value code="0">Assume use of remote control after fallback. Switch to ALTCTL if a height estimate is available, else switch to MANUAL.</value>
        <value code="1">Assume no use of remote control after fallback. Switch to DESCEND if a height estimate is available, else switch to TERMINATION.</value>
      </values>
    </parameter>
    <parameter default="0" name="COM_TAKEOFF_ACT" type="INT32">
      <short_desc>Action after TAKEOFF has been accepted</short_desc>
      <long_desc>The mode transition after TAKEOFF has completed successfully.</long_desc>
      <scope>modules/commander</scope>
      <values>
        <value code="0">Hold</value>
        <value code="1">Mission (if valid)</value>
      </values>
    </parameter>
    <parameter default="1" 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>
      <scope>modules/navigator</scope>
      <values>
        <value code="0">Zero Order Hold</value>
        <value code="1">First Order Hold</value>
      </values>
    </parameter>
    <parameter default="900" 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 home position.</long_desc>
      <min>0</min>
      <max>10000</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <increment>100</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="900" name="MIS_DIST_WPS" type="FLOAT">
      <short_desc>Maximal horizontal distance between waypoint</short_desc>
      <long_desc>Failsafe check to prevent running missions which are way too big. Set a value of zero or less to disable. The mission will not be started if any distance between two subsequent waypoints is greater than MIS_DIST_WPS.</long_desc>
      <min>0</min>
      <max>10000</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <increment>100</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="-1.0" name="MIS_LTRMIN_ALT" type="FLOAT">
      <short_desc>Minimum Loiter altitude</short_desc>
      <long_desc>This is the minimum altitude the system will always obey. The intent is to stay out of ground effect. set to -1, if there shouldn't be a minimum loiter altitude</long_desc>
      <min>-1</min>
      <max>80</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="0" name="MIS_MNT_YAW_CTL" type="INT32">
      <short_desc>Enable yaw control of the mount. (Only affects multicopters and ROI mission items)</short_desc>
      <long_desc>If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading mode as specified by MIS_YAWMODE. If disabled, the vehicle will yaw towards the ROI.</long_desc>
      <min>0</min>
      <max>1</max>
      <scope>modules/navigator</scope>
      <values>
        <value code="0">Disable</value>
        <value code="1">Enable</value>
      </values>
    </parameter>
    <parameter default="2.5" name="MIS_TAKEOFF_ALT" type="FLOAT">
      <short_desc>Take-off altitude</short_desc>
      <long_desc>This is the minimum altitude the system will take off to.</long_desc>
      <min>0</min>
      <max>80</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="1" name="MIS_YAWMODE" type="INT32">
      <short_desc>Multirotor only. Yaw setpoint mode</short_desc>
      <long_desc>The values are defined in the enum mission_altitude_mode</long_desc>
      <min>0</min>
      <max>3</max>
      <scope>modules/navigator</scope>
      <values>
        <value code="0">Heading as set by waypoint</value>
        <value code="1">Heading towards waypoint</value>
        <value code="2">Heading towards home</value>
        <value code="3">Heading away from home</value>
      </values>
    </parameter>
    <parameter default="12.0" name="MIS_YAW_ERR" type="FLOAT">
      <short_desc>Max yaw error in degrees needed for waypoint heading acceptance</short_desc>
      <min>0</min>
      <max>90</max>
      <unit>deg</unit>
      <decimal>1</decimal>
      <increment>1</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="-1.0" name="MIS_YAW_TMT" type="FLOAT">
      <short_desc>Time in seconds we wait on reaching target heading at a waypoint if it is forced</short_desc>
      <long_desc>If set &gt; 0 it will ignore the target heading for normal waypoint acceptance. If the waypoint forces the heading the timeout will matter. For example on VTOL forwards transition. Mainly useful for VTOLs that have less yaw authority and might not reach target yaw in wind. Disabled by default.</long_desc>
      <min>-1</min>
      <max>20</max>
      <unit>s</unit>
      <decimal>1</decimal>
      <increment>1</increment>
      <scope>modules/navigator</scope>
    </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. For fixed wing the L1 turning distance is used for horizontal acceptance.</long_desc>
      <min>0.05</min>
      <max>200.0</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="0" name="NAV_DLL_ACT" type="INT32">
      <short_desc>Set data link loss failsafe mode</short_desc>
      <long_desc>The data link loss failsafe will only be entered after a timeout, set by COM_DL_LOSS_T in seconds. Once the timeout occurs the selected action will be executed. Setting this parameter to 4 will enable CASA Outback Challenge rules, which are only recommended to participants of that competition.</long_desc>
      <scope>modules/navigator</scope>
      <values>
        <value code="0">Disabled</value>
        <value code="1">Loiter</value>
        <value code="2">Return to Land</value>
        <value code="3">Land at current position</value>
        <value code="4">Data Link Auto Recovery (CASA Outback Challenge rules)</value>
        <value code="5">Terminate</value>
        <value code="6">Lockdown</value>
      </values>
    </parameter>
    <parameter default="1" name="NAV_FORCE_VT" type="INT32">
      <short_desc>Force VTOL mode takeoff and land</short_desc>
      <boolean />
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="10.0" name="NAV_FW_ALT_RAD" type="FLOAT">
      <short_desc>FW Altitude Acceptance Radius</short_desc>
      <long_desc>Acceptance radius for fixedwing altitude.</long_desc>
      <min>0.05</min>
      <max>200.0</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <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>25</min>
      <max>1000</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="0.8" name="NAV_MC_ALT_RAD" type="FLOAT">
      <short_desc>MC Altitude Acceptance Radius</short_desc>
      <long_desc>Acceptance radius for multicopter altitude.</long_desc>
      <min>0.05</min>
      <max>200.0</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="2" name="NAV_RCL_ACT" type="INT32">
      <short_desc>Set RC loss failsafe mode</short_desc>
      <long_desc>The RC loss failsafe will only be entered after a timeout, set by COM_RC_LOSS_T in seconds. If RC input checks have been disabled by setting the COM_RC_IN_MODE param it will not be triggered. Setting this parameter to 4 will enable CASA Outback Challenge rules, which are only recommended to participants of that competition.</long_desc>
      <scope>modules/navigator</scope>
      <values>
        <value code="0">Disabled</value>
        <value code="1">Loiter</value>
        <value code="2">Return to Land</value>
        <value code="3">Land at current position</value>
        <value code="4">RC Auto Recovery (CASA Outback Challenge rules)</value>
        <value code="5">Terminate</value>
        <value code="6">Lockdown</value>
      </values>
    </parameter>
    <parameter default="120.0" name="NAV_RCL_LT" type="FLOAT">
      <short_desc>RC Loss Loiter Time (CASA Outback Challenge rules)</short_desc>
      <long_desc>The amount of time in seconds the system should loiter at current position before termination. Only applies if NAV_RCL_ACT is set to 2 (CASA Outback Challenge rules). Set to -1 to make the system skip loitering.</long_desc>
      <min>-1.0</min>
      <unit>s</unit>
      <decimal>1</decimal>
      <increment>0.1</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="1" name="NAV_TRAFF_AVOID" type="INT32">
      <short_desc>Set traffic avoidance mode</short_desc>
      <long_desc>Enabling this will allow the system to respond to transponder data from e.g. ADSB transponders</long_desc>
      <scope>modules/navigator</scope>
      <values>
        <value code="0">Disabled</value>
        <value code="1">Warn only</value>
        <value code="2">Return to Land</value>
        <value code="3">Land immediately</value>
      </values>
    </parameter>
    <parameter default="0" name="VT_WV_LND_EN" type="INT32">
      <short_desc>Weather-vane mode landings for missions</short_desc>
      <boolean />
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="0" name="VT_WV_LTR_EN" type="INT32">
      <short_desc>Weather-vane mode for loiter</short_desc>
      <boolean />
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="0" name="VT_WV_TKO_EN" type="INT32">
      <short_desc>Enable weather-vane mode takeoff for missions</short_desc>
      <boolean />
      <scope>modules/vtol_att_control</scope>
    </parameter>
  </group>
  <group name="Mount">
    <parameter default="0" name="MNT_DO_STAB" type="INT32">
      <short_desc>Stabilize the mount (set to true for servo gimbal, false for passthrough).
Does not affect MAVLINK_ROI input</short_desc>
      <boolean />
      <scope>drivers/vmount</scope>
    </parameter>
    <parameter default="0" name="MNT_MAN_PITCH" type="INT32">
      <short_desc>Auxiliary channel to control pitch (in AUX input or manual mode)</short_desc>
      <min>0</min>
      <max>5</max>
      <scope>drivers/vmount</scope>
      <values>
        <value code="0">Disable</value>
        <value code="1">AUX1</value>
        <value code="2">AUX2</value>
        <value code="3">AUX3</value>
        <value code="4">AUX4</value>
        <value code="5">AUX5</value>
      </values>
    </parameter>
    <parameter default="0" name="MNT_MAN_ROLL" type="INT32">
      <short_desc>Auxiliary channel to control roll (in AUX input or manual mode)</short_desc>
      <min>0</min>
      <max>5</max>
      <scope>drivers/vmount</scope>
      <values>
        <value code="0">Disable</value>
        <value code="1">AUX1</value>
        <value code="2">AUX2</value>
        <value code="3">AUX3</value>
        <value code="4">AUX4</value>
        <value code="5">AUX5</value>
      </values>
    </parameter>
    <parameter default="0" name="MNT_MAN_YAW" type="INT32">
      <short_desc>Auxiliary channel to control yaw (in AUX input or manual mode)</short_desc>
      <min>0</min>
      <max>5</max>
      <scope>drivers/vmount</scope>
      <values>
        <value code="0">Disable</value>
        <value code="1">AUX1</value>
        <value code="2">AUX2</value>
        <value code="3">AUX3</value>
        <value code="4">AUX4</value>
        <value code="5">AUX5</value>
      </values>
    </parameter>
    <parameter default="154" name="MNT_MAV_COMPID" type="INT32">
      <short_desc>Mavlink Component ID of the mount</short_desc>
      <long_desc>If MNT_MODE_OUT is MAVLINK, mount configure/control commands will be sent with this component ID.</long_desc>
      <scope>drivers/vmount</scope>
    </parameter>
    <parameter default="1" name="MNT_MAV_SYSID" type="INT32">
      <short_desc>Mavlink System ID of the mount</short_desc>
      <long_desc>If MNT_MODE_OUT is MAVLINK, mount configure/control commands will be sent with this target ID.</long_desc>
      <scope>drivers/vmount</scope>
    </parameter>
    <parameter default="-1" name="MNT_MODE_IN" type="INT32">
      <short_desc>Mount input mode</short_desc>
      <long_desc>RC uses the AUX input channels (see MNT_MAN_* parameters), MAVLINK_ROI uses the MAV_CMD_DO_SET_ROI Mavlink message, and MAVLINK_DO_MOUNT the MAV_CMD_DO_MOUNT_CONFIGURE and MAV_CMD_DO_MOUNT_CONTROL messages to control a mount.</long_desc>
      <min>-1</min>
      <max>3</max>
      <reboot_required>true</reboot_required>
      <scope>drivers/vmount</scope>
      <values>
        <value code="-1">DISABLED</value>
        <value code="0">AUTO</value>
        <value code="1">RC</value>
        <value code="2">MAVLINK_ROI</value>
        <value code="3">MAVLINK_DO_MOUNT</value>
      </values>
    </parameter>
    <parameter default="0" name="MNT_MODE_OUT" type="INT32">
      <short_desc>Mount output mode</short_desc>
      <long_desc>AUX uses the mixer output Control Group #2. MAVLINK uses the MAV_CMD_DO_MOUNT_CONFIGURE and MAV_CMD_DO_MOUNT_CONTROL MavLink messages to control a mount (set MNT_MAV_SYSID &amp; MNT_MAV_COMPID)</long_desc>
      <min>0</min>
      <max>1</max>
      <scope>drivers/vmount</scope>
      <values>
        <value code="0">AUX</value>
        <value code="1">MAVLINK</value>
      </values>
    </parameter>
    <parameter default="0.0" name="MNT_OB_LOCK_MODE" type="FLOAT">
      <short_desc>Mixer value for selecting a locking mode
if required for the gimbal (only in AUX output mode)</short_desc>
      <min>-1.0</min>
      <max>1.0</max>
      <decimal>3</decimal>
      <scope>drivers/vmount</scope>
    </parameter>
    <parameter default="-1.0" name="MNT_OB_NORM_MODE" type="FLOAT">
      <short_desc>Mixer value for selecting normal mode
if required by the gimbal (only in AUX output mode)</short_desc>
      <min>-1.0</min>
      <max>1.0</max>
      <decimal>3</decimal>
      <scope>drivers/vmount</scope>
    </parameter>
    <parameter default="0.0" name="MNT_OFF_PITCH" type="FLOAT">
      <short_desc>Offset for pitch channel output in degrees</short_desc>
      <min>-360.0</min>
      <max>360.0</max>
      <decimal>1</decimal>
      <scope>drivers/vmount</scope>
    </parameter>
    <parameter default="0.0" name="MNT_OFF_ROLL" type="FLOAT">
      <short_desc>Offset for roll channel output in degrees</short_desc>
      <min>-360.0</min>
      <max>360.0</max>
      <decimal>1</decimal>
      <scope>drivers/vmount</scope>
    </parameter>
    <parameter default="0.0" name="MNT_OFF_YAW" type="FLOAT">
      <short_desc>Offset for yaw channel output in degrees</short_desc>
      <min>-360.0</min>
      <max>360.0</max>
      <decimal>1</decimal>
      <scope>drivers/vmount</scope>
    </parameter>
    <parameter default="360.0" name="MNT_RANGE_PITCH" type="FLOAT">
      <short_desc>Range of pitch channel output in degrees (only in AUX output mode)</short_desc>
      <min>1.0</min>
      <max>720.0</max>
      <decimal>1</decimal>
      <scope>drivers/vmount</scope>
    </parameter>
    <parameter default="360.0" name="MNT_RANGE_ROLL" type="FLOAT">
      <short_desc>Range of roll channel output in degrees (only in AUX output mode)</short_desc>
      <min>1.0</min>
      <max>720.0</max>
      <decimal>1</decimal>
      <scope>drivers/vmount</scope>
    </parameter>
    <parameter default="360.0" name="MNT_RANGE_YAW" type="FLOAT">
      <short_desc>Range of yaw channel output in degrees (only in AUX output mode)</short_desc>
      <min>1.0</min>
      <max>720.0</max>
      <decimal>1</decimal>
      <scope>drivers/vmount</scope>
    </parameter>
  </group>
  <group name="Multicopter Attitude Control">
    <parameter default="0.69" name="MC_ACRO_EXPO" type="FLOAT">
      <short_desc>Acro mode Expo factor for Roll and Pitch</short_desc>
      <long_desc>Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve</long_desc>
      <min>0</min>
      <max>1</max>
      <decimal>2</decimal>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="0.69" name="MC_ACRO_EXPO_Y" type="FLOAT">
      <short_desc>Acro mode Expo factor for Yaw</short_desc>
      <long_desc>Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve</long_desc>
      <min>0</min>
      <max>1</max>
      <decimal>2</decimal>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="720.0" name="MC_ACRO_P_MAX" type="FLOAT">
      <short_desc>Max acro pitch rate
default: 2 turns per second</short_desc>
      <min>0.0</min>
      <max>1800.0</max>
      <unit>deg/s</unit>
      <decimal>1</decimal>
      <increment>5</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="720.0" name="MC_ACRO_R_MAX" type="FLOAT">
      <short_desc>Max acro roll rate
default: 2 turns per second</short_desc>
      <min>0.0</min>
      <max>1800.0</max>
      <unit>deg/s</unit>
      <decimal>1</decimal>
      <increment>5</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="0.7" name="MC_ACRO_SUPEXPO" type="FLOAT">
      <short_desc>Acro mode SuperExpo factor for Roll and Pitch</short_desc>
      <long_desc>SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO. 0 Pure Expo function 0.7 resonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect</long_desc>
      <min>0</min>
      <max>0.95</max>
      <decimal>2</decimal>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="0.7" name="MC_ACRO_SUPEXPOY" type="FLOAT">
      <short_desc>Acro mode SuperExpo factor for Yaw</short_desc>
      <long_desc>SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y. 0 Pure Expo function 0.7 resonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect</long_desc>
      <min>0</min>
      <max>0.95</max>
      <decimal>2</decimal>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="540.0" name="MC_ACRO_Y_MAX" type="FLOAT">
      <short_desc>Max acro yaw rate
default 1.5 turns per second</short_desc>
      <min>0.0</min>
      <max>1800.0</max>
      <unit>deg/s</unit>
      <decimal>1</decimal>
      <increment>5</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="0" name="MC_AIRMODE" type="INT32">
      <short_desc>Multicopter air-mode</short_desc>
      <long_desc>The air-mode enables the mixer to increase the total thrust of the multirotor in order to keep attitude and rate control even at low and high throttle. This function should be disabled during tuning as it will help the controller to diverge if the closed-loop is unstable.</long_desc>
      <boolean />
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="0" name="MC_BAT_SCALE_EN" type="INT32">
      <short_desc>Battery power level scaler</short_desc>
      <long_desc>This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The copter should constantly behave as if it was fully charged with reduced max acceleration at lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery.</long_desc>
      <boolean />
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="30." name="MC_DTERM_CUTOFF" type="FLOAT">
      <short_desc>Cutoff frequency for the low pass filter on the D-term in the rate controller</short_desc>
      <long_desc>The D-term uses the derivative of the rate and thus is the most susceptible to noise. Therefore, using a D-term filter allows to decrease the driver-level filtering, which leads to reduced control latency and permits to increase the P gains. A value of 0 disables the filter.</long_desc>
      <min>0</min>
      <max>1000</max>
      <unit>Hz</unit>
      <decimal>0</decimal>
      <increment>10</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="0.003" 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>
      <decimal>4</decimal>
      <increment>0.0005</increment>
      <scope>modules/mc_att_control</scope>
    </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>
      <decimal>4</decimal>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="0.05" 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>
      <decimal>3</decimal>
      <increment>0.01</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="220.0" name="MC_PITCHRATE_MAX" type="FLOAT">
      <short_desc>Max pitch rate</short_desc>
      <long_desc>Limit for pitch rate in manual and auto modes (except acro). Has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. This is not only limited by the vehicle's properties, but also by the maximum measurement rate of the gyro.</long_desc>
      <min>0.0</min>
      <max>1800.0</max>
      <unit>deg/s</unit>
      <decimal>1</decimal>
      <increment>5</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="0.15" 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>
      <max>0.6</max>
      <decimal>3</decimal>
      <increment>0.01</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="6.5" 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>
      <max>12</max>
      <unit>1/s</unit>
      <decimal>2</decimal>
      <increment>0.1</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="0.30" name="MC_PR_INT_LIM" type="FLOAT">
      <short_desc>Pitch rate integrator limit</short_desc>
      <long_desc>Pitch rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large pitch moment trim changes.</long_desc>
      <min>0.0</min>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="0.8" name="MC_RATT_TH" type="FLOAT">
      <short_desc>Threshold for Rattitude mode</short_desc>
      <long_desc>Manual input needed in order to override attitude control rate setpoints and instead pass manual stick inputs as rate setpoints</long_desc>
      <min>0.0</min>
      <max>1.0</max>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="0.003" 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>
      <max>0.01</max>
      <decimal>4</decimal>
      <increment>0.0005</increment>
      <scope>modules/mc_att_control</scope>
    </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>
      <decimal>4</decimal>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="0.05" 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>
      <decimal>3</decimal>
      <increment>0.01</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="220.0" name="MC_ROLLRATE_MAX" type="FLOAT">
      <short_desc>Max roll rate</short_desc>
      <long_desc>Limit for roll rate in manual and auto modes (except acro). Has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. This is not only limited by the vehicle's properties, but also by the maximum measurement rate of the gyro.</long_desc>
      <min>0.0</min>
      <max>1800.0</max>
      <unit>deg/s</unit>
      <decimal>1</decimal>
      <increment>5</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="0.15" 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>
      <max>0.5</max>
      <decimal>3</decimal>
      <increment>0.01</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="6.5" 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>
      <max>12</max>
      <unit>1/s</unit>
      <decimal>2</decimal>
      <increment>0.1</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="0.30" name="MC_RR_INT_LIM" type="FLOAT">
      <short_desc>Roll rate integrator limit</short_desc>
      <long_desc>Roll rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large roll moment trim changes.</long_desc>
      <min>0.0</min>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="1.0" name="MC_TPA_BREAK_D" type="FLOAT">
      <short_desc>TPA D Breakpoint</short_desc>
      <long_desc>Throttle PID Attenuation (TPA) Magnitude of throttle setpoint at which to begin attenuating roll/pitch D gain</long_desc>
      <min>0.0</min>
      <max>1.0</max>
      <decimal>2</decimal>
      <increment>0.1</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="1.0" name="MC_TPA_BREAK_I" type="FLOAT">
      <short_desc>TPA I Breakpoint</short_desc>
      <long_desc>Throttle PID Attenuation (TPA) Magnitude of throttle setpoint at which to begin attenuating roll/pitch I gain</long_desc>
      <min>0.0</min>
      <max>1.0</max>
      <decimal>2</decimal>
      <increment>0.1</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="1.0" name="MC_TPA_BREAK_P" type="FLOAT">
      <short_desc>TPA P Breakpoint</short_desc>
      <long_desc>Throttle PID Attenuation (TPA) Magnitude of throttle setpoint at which to begin attenuating roll/pitch P gain</long_desc>
      <min>0.0</min>
      <max>1.0</max>
      <decimal>2</decimal>
      <increment>0.1</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="0.0" name="MC_TPA_RATE_D" type="FLOAT">
      <short_desc>TPA Rate D</short_desc>
      <long_desc>Throttle PID Attenuation (TPA) Rate at which to attenuate roll/pitch D gain Attenuation factor is 1.0 when throttle magnitude is below the setpoint Above the setpoint, the attenuation factor is (1 - rate * (throttle - breakpoint) / (1.0 - breakpoint))</long_desc>
      <min>0.0</min>
      <max>1.0</max>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="0.0" name="MC_TPA_RATE_I" type="FLOAT">
      <short_desc>TPA Rate I</short_desc>
      <long_desc>Throttle PID Attenuation (TPA) Rate at which to attenuate roll/pitch I gain Attenuation factor is 1.0 when throttle magnitude is below the setpoint Above the setpoint, the attenuation factor is (1 - rate * (throttle - breakpoint) / (1.0 - breakpoint))</long_desc>
      <min>0.0</min>
      <max>1.0</max>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="0.0" name="MC_TPA_RATE_P" type="FLOAT">
      <short_desc>TPA Rate P</short_desc>
      <long_desc>Throttle PID Attenuation (TPA) Rate at which to attenuate roll/pitch P gain Attenuation factor is 1.0 when throttle magnitude is below the setpoint Above the setpoint, the attenuation factor is (1 - rate * (throttle - breakpoint) / (1.0 - breakpoint))</long_desc>
      <min>0.0</min>
      <max>1.0</max>
      <decimal>2</decimal>
      <increment>0.05</increment>
      <scope>modules/mc_att_control</scope>
    </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>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/mc_att_control</scope>
    </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>
      <decimal>4</decimal>
      <increment>0.01</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="0.1" 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>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="200.0" name="MC_YAWRATE_MAX" type="FLOAT">
      <short_desc>Max yaw rate</short_desc>
      <min>0.0</min>
      <max>1800.0</max>
      <unit>deg/s</unit>
      <decimal>1</decimal>
      <increment>5</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="0.2" 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>
      <max>0.6</max>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="45.0" name="MC_YAWRAUTO_MAX" type="FLOAT">
      <short_desc>Max yaw rate in auto mode</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>
      <decimal>1</decimal>
      <increment>5</increment>
      <scope>modules/mc_att_control</scope>
    </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>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="2.8" 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>
      <max>5</max>
      <unit>1/s</unit>
      <decimal>2</decimal>
      <increment>0.1</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
    <parameter default="0.30" name="MC_YR_INT_LIM" type="FLOAT">
      <short_desc>Yaw rate integrator limit</short_desc>
      <long_desc>Yaw rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large yaw moment trim changes.</long_desc>
      <min>0.0</min>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/mc_att_control</scope>
    </parameter>
  </group>
  <group name="Multicopter Position Control">
    <parameter default="10.0" name="MPC_ACC_DOWN_MAX" type="FLOAT">
      <short_desc>Maximum vertical acceleration in velocity controlled modes down</short_desc>
      <min>2.0</min>
      <max>15.0</max>
      <unit>m/s/s</unit>
      <decimal>2</decimal>
      <increment>1</increment>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="5.0" name="MPC_ACC_HOR" type="FLOAT">
      <short_desc>Acceleration for auto and for manual</short_desc>
      <min>2.0</min>
      <max>15.0</max>
      <unit>m/s/s</unit>
      <decimal>2</decimal>
      <increment>1</increment>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="0.5" name="MPC_ACC_HOR_FLOW" type="FLOAT">
      <short_desc>Horizontal acceleration in manual modes when optical flow ground speed limit is removed.
If full stick is being applied and the EKF starts using GPS whilst using optical flow,
the vehicle will accelerate at this rate until the normal position control speed is achieved</short_desc>
      <min>0.2</min>
      <max>2.0</max>
      <unit>m/s/s</unit>
      <decimal>1</decimal>
      <increment>0.1</increment>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="10.0" name="MPC_ACC_HOR_MAX" type="FLOAT">
      <short_desc>Maximum horizontal acceleration for auto mode and maximum deceleration for manual mode</short_desc>
      <min>2.0</min>
      <max>15.0</max>
      <unit>m/s/s</unit>
      <decimal>2</decimal>
      <increment>1</increment>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="10.0" name="MPC_ACC_UP_MAX" type="FLOAT">
      <short_desc>Maximum vertical acceleration in velocity controlled modes upward</short_desc>
      <min>2.0</min>
      <max>15.0</max>
      <unit>m/s/s</unit>
      <decimal>2</decimal>
      <increment>1</increment>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="0" name="MPC_ALT_MODE" type="INT32">
      <short_desc>Altitude control mode, note mode 1 only tested with LPE</short_desc>
      <min>0</min>
      <max>1</max>
      <scope>modules/mc_pos_control</scope>
      <values>
        <value code="0">Altitude following</value>
        <value code="1">Terrain following</value>
      </values>
    </parameter>
    <parameter default="3.0" name="MPC_CRUISE_90" type="FLOAT">
      <short_desc>Cruise speed when angle prev-current/current-next setpoint
is 90 degrees. It should be lower than MPC_XY_CRUISE</short_desc>
      <long_desc>Applies only in AUTO modes (includes also RTL / hold / etc.)</long_desc>
      <min>1.0</min>
      <max>20.0</max>
      <unit>m/s</unit>
      <decimal>2</decimal>
      <increment>1</increment>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="5.0" name="MPC_DEC_HOR_SLOW" type="FLOAT">
      <short_desc>Slow horizontal manual deceleration for manual mode</short_desc>
      <min>0.5</min>
      <max>10.0</max>
      <unit>m/s/s</unit>
      <decimal>2</decimal>
      <increment>1</increment>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="0" name="MPC_FLT_TSK" type="INT32">
      <short_desc>Flag to test flight tasks instead of legacy functionality
Temporary Parameter during the transition to flight tasks</short_desc>
      <min>0</min>
      <max>1</max>
      <scope>modules/mc_pos_control</scope>
      <values>
        <value code="0">Legacy Functionality</value>
        <value code="1">Test flight tasks</value>
      </values>
    </parameter>
    <parameter default="0.1" name="MPC_HOLD_DZ" type="FLOAT">
      <short_desc>Deadzone of sticks where position hold is enabled</short_desc>
      <min>0.0</min>
      <max>1.0</max>
      <decimal>2</decimal>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="0.8" name="MPC_HOLD_MAX_XY" type="FLOAT">
      <short_desc>Maximum horizontal velocity for which position hold is enabled (use 0 to disable check)</short_desc>
      <min>0.0</min>
      <max>3.0</max>
      <unit>m/s</unit>
      <decimal>2</decimal>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="0.6" name="MPC_HOLD_MAX_Z" type="FLOAT">
      <short_desc>Maximum vertical velocity for which position hold is enabled (use 0 to disable check)</short_desc>
      <min>0.0</min>
      <max>3.0</max>
      <unit>m/s</unit>
      <decimal>2</decimal>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="0.0" name="MPC_JERK_MAX" type="FLOAT">
      <short_desc>Maximum jerk in manual controlled mode for BRAKING to zero.
If this value is below MPC_JERK_MIN, the acceleration limit in xy and z
is MPC_ACC_HOR_MAX and MPC_ACC_UP_MAX respectively instantaneously when the
user demands brake (=zero stick input).
Otherwise the acceleration limit increases from current acceleration limit
towards MPC_ACC_HOR_MAX/MPC_ACC_UP_MAX with jerk limit</short_desc>
      <min>0.0</min>
      <max>15.0</max>
      <unit>m/s/s/s</unit>
      <decimal>2</decimal>
      <increment>1</increment>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="1.0" name="MPC_JERK_MIN" type="FLOAT">
      <short_desc>Minimum jerk in manual controlled mode for BRAKING to zero</short_desc>
      <min>0.5</min>
      <max>10.0</max>
      <unit>m/s/s/s</unit>
      <decimal>2</decimal>
      <increment>1</increment>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="10.0" name="MPC_LAND_ALT1" type="FLOAT">
      <short_desc>Altitude for 1. step of slow landing (descend)</short_desc>
      <long_desc>Below this altitude descending velocity gets limited to a value between "MPC_Z_VEL_MAX" and "MPC_LAND_SPEED" to enable a smooth descent experience Value needs to be higher than "MPC_LAND_ALT2"</long_desc>
      <min>0</min>
      <max>122</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="5.0" name="MPC_LAND_ALT2" type="FLOAT">
      <short_desc>Altitude for 2. step of slow landing (landing)</short_desc>
      <long_desc>Below this altitude descending velocity gets limited to "MPC_LAND_SPEED" Value needs to be lower than "MPC_LAND_ALT1"</long_desc>
      <min>0</min>
      <max>122</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="0.7" name="MPC_LAND_SPEED" type="FLOAT">
      <short_desc>Landing descend rate</short_desc>
      <min>0.6</min>
      <unit>m/s</unit>
      <decimal>1</decimal>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="1.0" name="MPC_MANTHR_MAX" type="FLOAT">
      <short_desc>Maximum manual thrust</short_desc>
      <long_desc>Limit max allowed thrust for Manual mode.</long_desc>
      <min>0.0</min>
      <max>1.0</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="0.08" name="MPC_MANTHR_MIN" type="FLOAT">
      <short_desc>Minimum manual thrust</short_desc>
      <long_desc>Minimum vertical thrust. It's recommended to set it &gt; 0 to avoid free fall with zero thrust. With MC_AIRMODE set to 1, this can safely be set to 0.</long_desc>
      <min>0.0</min>
      <max>1.0</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="35.0" name="MPC_MAN_TILT_MAX" type="FLOAT">
      <short_desc>Maximal tilt angle in manual or altitude mode</short_desc>
      <min>0.0</min>
      <max>90.0</max>
      <unit>deg</unit>
      <decimal>1</decimal>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="200.0" name="MPC_MAN_Y_MAX" type="FLOAT">
      <short_desc>Max manual yaw rate</short_desc>
      <min>0.0</min>
      <max>400</max>
      <unit>deg/s</unit>
      <decimal>1</decimal>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="0.5" name="MPC_THR_HOVER" type="FLOAT">
      <short_desc>Hover thrust</short_desc>
      <long_desc>Vertical thrust required to hover. This value is mapped to center stick for manual throttle control. With this value set to the thrust required to hover, transition from manual to ALTCTL mode while hovering will occur with the throttle stick near center, which is then interpreted as (near) zero demand for vertical speed.</long_desc>
      <min>0.2</min>
      <max>0.8</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="1.0" name="MPC_THR_MAX" type="FLOAT">
      <short_desc>Maximum thrust in auto thrust control</short_desc>
      <long_desc>Limit max allowed thrust</long_desc>
      <min>0.0</min>
      <max>1.0</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="0.12" name="MPC_THR_MIN" type="FLOAT">
      <short_desc>Minimum thrust in auto thrust control</short_desc>
      <long_desc>It's recommended to set it &gt; 0 to avoid free fall with zero thrust.</long_desc>
      <min>0.05</min>
      <max>1.0</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/mc_pos_control</scope>
    </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>
      <decimal>1</decimal>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="12.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>
      <decimal>1</decimal>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="0.4" name="MPC_TKO_RAMP_T" type="FLOAT">
      <short_desc>Position control smooth takeoff ramp time constant</short_desc>
      <long_desc>Increasing this value will make automatic and manual takeoff slower. If it's too slow the drone might scratch the ground and tip over.</long_desc>
      <min>0.1</min>
      <max>1</max>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="1.5" name="MPC_TKO_SPEED" type="FLOAT">
      <short_desc>Takeoff climb rate</short_desc>
      <min>1</min>
      <max>5</max>
      <unit>m/s</unit>
      <decimal>2</decimal>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="5.0" name="MPC_VELD_LP" type="FLOAT">
      <short_desc>Low pass filter cut freq. for numerical velocity derivative</short_desc>
      <min>0.0</min>
      <max>10</max>
      <unit>Hz</unit>
      <decimal>2</decimal>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="10.0" name="MPC_VEL_MANUAL" type="FLOAT">
      <short_desc>Maximum horizontal velocity setpoint for manual controlled mode
If velocity setpoint larger than MPC_XY_VEL_MAX is set, then
the setpoint will be capped to MPC_XY_VEL_MAX</short_desc>
      <min>3.0</min>
      <max>20.0</max>
      <unit>m/s</unit>
      <decimal>2</decimal>
      <increment>1</increment>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="5.0" name="MPC_XY_CRUISE" type="FLOAT">
      <short_desc>Maximum horizontal velocity in mission</short_desc>
      <long_desc>Normal horizontal velocity in AUTO modes (includes also RTL / hold / etc.) and endpoint for position stabilized mode (POSCTRL).</long_desc>
      <min>3.0</min>
      <max>20.0</max>
      <unit>m/s</unit>
      <decimal>2</decimal>
      <increment>1</increment>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="0.0" name="MPC_XY_MAN_EXPO" type="FLOAT">
      <short_desc>Manual control stick exponential curve sensitivity attenuation with small velocity setpoints</short_desc>
      <long_desc>The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve</long_desc>
      <min>0</min>
      <max>1</max>
      <decimal>2</decimal>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="0.95" name="MPC_XY_P" type="FLOAT">
      <short_desc>Proportional gain for horizontal position error</short_desc>
      <min>0.0</min>
      <max>2.0</max>
      <decimal>2</decimal>
      <scope>modules/mc_pos_control</scope>
    </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.005</min>
      <max>0.1</max>
      <decimal>3</decimal>
      <scope>modules/mc_pos_control</scope>
    </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>
      <max>0.1</max>
      <decimal>3</decimal>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="12.0" name="MPC_XY_VEL_MAX" type="FLOAT">
      <short_desc>Maximum horizontal velocity</short_desc>
      <long_desc>Maximum horizontal velocity in AUTO mode. If higher speeds are commanded in a mission they will be capped to this velocity.</long_desc>
      <min>0.0</min>
      <max>20.0</max>
      <unit>m/s</unit>
      <decimal>2</decimal>
      <increment>1</increment>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="0.09" name="MPC_XY_VEL_P" type="FLOAT">
      <short_desc>Proportional gain for horizontal velocity error</short_desc>
      <min>0.06</min>
      <max>0.15</max>
      <decimal>2</decimal>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="0.0" name="MPC_Z_MAN_EXPO" type="FLOAT">
      <short_desc>Manual control stick vertical exponential curve</short_desc>
      <long_desc>The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve</long_desc>
      <min>0</min>
      <max>1</max>
      <decimal>2</decimal>
      <scope>modules/mc_pos_control</scope>
    </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>
      <max>1.5</max>
      <decimal>2</decimal>
      <scope>modules/mc_pos_control</scope>
    </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>
      <max>0.1</max>
      <decimal>3</decimal>
      <scope>modules/mc_pos_control</scope>
    </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.01</min>
      <max>0.1</max>
      <decimal>3</decimal>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="1.0" name="MPC_Z_VEL_MAX_DN" type="FLOAT">
      <short_desc>Maximum vertical descent velocity</short_desc>
      <long_desc>Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL, POSCTRL).</long_desc>
      <min>0.5</min>
      <max>4.0</max>
      <unit>m/s</unit>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="3.0" name="MPC_Z_VEL_MAX_UP" type="FLOAT">
      <short_desc>Maximum vertical ascent velocity</short_desc>
      <long_desc>Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL, POSCTRL).</long_desc>
      <min>0.5</min>
      <max>8.0</max>
      <unit>m/s</unit>
      <decimal>1</decimal>
      <scope>modules/mc_pos_control</scope>
    </parameter>
    <parameter default="0.2" name="MPC_Z_VEL_P" type="FLOAT">
      <short_desc>Proportional gain for vertical velocity error</short_desc>
      <min>0.1</min>
      <max>0.4</max>
      <decimal>2</decimal>
      <scope>modules/mc_pos_control</scope>
    </parameter>
  </group>
  <group name="PWM Outputs">
    <parameter default="0.0" name="MOT_SLEW_MAX" type="FLOAT">
      <short_desc>Minimum motor rise time (slew rate limit)</short_desc>
      <long_desc>Minimum time allowed for the motor input signal to pass through a range of 1000 PWM units. A value x means that the motor signal can only go from 1000 to 2000 PWM in maximum x seconds. Zero means that slew rate limiting is disabled.</long_desc>
      <min>0.0</min>
      <unit>s/(1000*PWM)</unit>
      <scope>drivers/px4fmu</scope>
    </parameter>
    <parameter default="-1" name="PWM_AUX_DIS1" type="INT32">
      <short_desc>Set the disarmed PWM for the AUX 1 output</short_desc>
      <long_desc>This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARMED will be used</long_desc>
      <min>-1</min>
      <max>2200</max>
      <unit>us</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="-1" name="PWM_AUX_DIS2" type="INT32">
      <short_desc>Set the disarmed PWM for the AUX 2 output</short_desc>
      <long_desc>This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARMED will be used</long_desc>
      <min>-1</min>
      <max>2200</max>
      <unit>us</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="-1" name="PWM_AUX_DIS3" type="INT32">
      <short_desc>Set the disarmed PWM for the AUX 3 output</short_desc>
      <long_desc>This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARMED will be used</long_desc>
      <min>-1</min>
      <max>2200</max>
      <unit>us</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="-1" name="PWM_AUX_DIS4" type="INT32">
      <short_desc>Set the disarmed PWM for the AUX 4 output</short_desc>
      <long_desc>This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARMED will be used</long_desc>
      <min>-1</min>
      <max>2200</max>
      <unit>us</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="-1" name="PWM_AUX_DIS5" type="INT32">
      <short_desc>Set the disarmed PWM for the AUX 5 output</short_desc>
      <long_desc>This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARMED will be used</long_desc>
      <min>-1</min>
      <max>2200</max>
      <unit>us</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="-1" name="PWM_AUX_DIS6" type="INT32">
      <short_desc>Set the disarmed PWM for the AUX 6 output</short_desc>
      <long_desc>This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARMED will be used</long_desc>
      <min>-1</min>
      <max>2200</max>
      <unit>us</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1500" name="PWM_AUX_DISARMED" type="INT32">
      <short_desc>Set the disarmed PWM for auxiliary outputs</short_desc>
      <long_desc>This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed.</long_desc>
      <min>0</min>
      <max>2200</max>
      <unit>us</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="2000" name="PWM_AUX_MAX" type="INT32">
      <short_desc>Set the maximum PWM for the auxiliary outputs</short_desc>
      <long_desc>Set to 2000 for default or 2100 to increase servo travel</long_desc>
      <min>1600</min>
      <max>2200</max>
      <unit>us</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1000" name="PWM_AUX_MIN" type="INT32">
      <short_desc>Set the minimum PWM for the auxiliary outputs</short_desc>
      <long_desc>Set to 1000 for default or 900 to increase servo travel</long_desc>
      <min>800</min>
      <max>1400</max>
      <unit>us</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="PWM_AUX_REV1" type="INT32">
      <short_desc>Invert direction of aux output channel 1</short_desc>
      <long_desc>Enable to invert the channel.</long_desc>
      <boolean />
      <scope>drivers/px4fmu</scope>
    </parameter>
    <parameter default="0" name="PWM_AUX_REV2" type="INT32">
      <short_desc>Invert direction of aux output channel 2</short_desc>
      <long_desc>Enable to invert the channel.</long_desc>
      <boolean />
      <scope>drivers/px4fmu</scope>
    </parameter>
    <parameter default="0" name="PWM_AUX_REV3" type="INT32">
      <short_desc>Invert direction of aux output channel 3</short_desc>
      <long_desc>Enable to invert the channel.</long_desc>
      <boolean />
      <scope>drivers/px4fmu</scope>
    </parameter>
    <parameter default="0" name="PWM_AUX_REV4" type="INT32">
      <short_desc>Invert direction of aux output channel 4</short_desc>
      <long_desc>Enable to invert the channel.</long_desc>
      <boolean />
      <scope>drivers/px4fmu</scope>
    </parameter>
    <parameter default="0" name="PWM_AUX_REV5" type="INT32">
      <short_desc>Invert direction of aux output channel 5</short_desc>
      <long_desc>Enable to invert the channel.</long_desc>
      <boolean />
      <scope>drivers/px4fmu</scope>
    </parameter>
    <parameter default="0" name="PWM_AUX_REV6" type="INT32">
      <short_desc>Invert direction of aux output channel 6</short_desc>
      <long_desc>Enable to invert the channel.</long_desc>
      <boolean />
      <scope>drivers/px4fmu</scope>
    </parameter>
    <parameter default="0" name="PWM_AUX_TRIM1" type="FLOAT">
      <short_desc>Trim value for FMU PWM output channel 1</short_desc>
      <long_desc>Set to normalized offset</long_desc>
      <min>-0.2</min>
      <max>0.2</max>
      <decimal>2</decimal>
      <scope>drivers/px4fmu</scope>
    </parameter>
    <parameter default="0" name="PWM_AUX_TRIM2" type="FLOAT">
      <short_desc>Trim value for FMU PWM output channel 2</short_desc>
      <long_desc>Set to normalized offset</long_desc>
      <min>-0.2</min>
      <max>0.2</max>
      <decimal>2</decimal>
      <scope>drivers/px4fmu</scope>
    </parameter>
    <parameter default="0" name="PWM_AUX_TRIM3" type="FLOAT">
      <short_desc>Trim value for FMU PWM output channel 3</short_desc>
      <long_desc>Set to normalized offset</long_desc>
      <min>-0.2</min>
      <max>0.2</max>
      <decimal>2</decimal>
      <scope>drivers/px4fmu</scope>
    </parameter>
    <parameter default="0" name="PWM_AUX_TRIM4" type="FLOAT">
      <short_desc>Trim value for FMU PWM output channel 4</short_desc>
      <long_desc>Set to normalized offset</long_desc>
      <min>-0.2</min>
      <max>0.2</max>
      <decimal>2</decimal>
      <scope>drivers/px4fmu</scope>
    </parameter>
    <parameter default="0" name="PWM_AUX_TRIM5" type="FLOAT">
      <short_desc>Trim value for FMU PWM output channel 5</short_desc>
      <long_desc>Set to normalized offset</long_desc>
      <min>-0.2</min>
      <max>0.2</max>
      <decimal>2</decimal>
      <scope>drivers/px4fmu</scope>
    </parameter>
    <parameter default="0" name="PWM_AUX_TRIM6" type="FLOAT">
      <short_desc>Trim value for FMU PWM output channel 6</short_desc>
      <long_desc>Set to normalized offset</long_desc>
      <min>-0.2</min>
      <max>0.2</max>
      <decimal>2</decimal>
      <scope>drivers/px4fmu</scope>
    </parameter>
    <parameter default="900" name="PWM_DISARMED" type="INT32">
      <short_desc>Set the disarmed PWM for the main outputs</short_desc>
      <long_desc>This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed.</long_desc>
      <min>0</min>
      <max>2200</max>
      <unit>us</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="-1" name="PWM_MAIN_DIS1" type="INT32">
      <short_desc>Set the disarmed PWM for the main 1 output</short_desc>
      <long_desc>This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used</long_desc>
      <min>-1</min>
      <max>2200</max>
      <unit>us</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="-1" name="PWM_MAIN_DIS2" type="INT32">
      <short_desc>Set the disarmed PWM for the main 2 output</short_desc>
      <long_desc>This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used</long_desc>
      <min>-1</min>
      <max>2200</max>
      <unit>us</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="-1" name="PWM_MAIN_DIS3" type="INT32">
      <short_desc>Set the disarmed PWM for the main 3 output</short_desc>
      <long_desc>This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used</long_desc>
      <min>-1</min>
      <max>2200</max>
      <unit>us</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="-1" name="PWM_MAIN_DIS4" type="INT32">
      <short_desc>Set the disarmed PWM for the main 4 output</short_desc>
      <long_desc>This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used</long_desc>
      <min>-1</min>
      <max>2200</max>
      <unit>us</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="-1" name="PWM_MAIN_DIS5" type="INT32">
      <short_desc>Set the disarmed PWM for the main 5 output</short_desc>
      <long_desc>This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used</long_desc>
      <min>-1</min>
      <max>2200</max>
      <unit>us</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="-1" name="PWM_MAIN_DIS6" type="INT32">
      <short_desc>Set the disarmed PWM for the main 6 output</short_desc>
      <long_desc>This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used</long_desc>
      <min>-1</min>
      <max>2200</max>
      <unit>us</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="-1" name="PWM_MAIN_DIS7" type="INT32">
      <short_desc>Set the disarmed PWM for the main 7 output</short_desc>
      <long_desc>This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used</long_desc>
      <min>-1</min>
      <max>2200</max>
      <unit>us</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="-1" name="PWM_MAIN_DIS8" type="INT32">
      <short_desc>Set the disarmed PWM for the main 8 output</short_desc>
      <long_desc>This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used</long_desc>
      <min>-1</min>
      <max>2200</max>
      <unit>us</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="PWM_MAIN_REV1" type="INT32">
      <short_desc>Invert direction of main output channel 1</short_desc>
      <long_desc>Enable to invert the channel.</long_desc>
      <boolean />
      <scope>drivers/px4io</scope>
    </parameter>
    <parameter default="0" name="PWM_MAIN_REV2" type="INT32">
      <short_desc>Invert direction of main output channel 2</short_desc>
      <long_desc>Enable to invert the channel.</long_desc>
      <boolean />
      <scope>drivers/px4io</scope>
    </parameter>
    <parameter default="0" name="PWM_MAIN_REV3" type="INT32">
      <short_desc>Invert direction of main output channel 3</short_desc>
      <long_desc>Enable to invert the channel.</long_desc>
      <boolean />
      <scope>drivers/px4io</scope>
    </parameter>
    <parameter default="0" name="PWM_MAIN_REV4" type="INT32">
      <short_desc>Invert direction of main output channel 4</short_desc>
      <long_desc>Enable to invert the channel.</long_desc>
      <boolean />
      <scope>drivers/px4io</scope>
    </parameter>
    <parameter default="0" name="PWM_MAIN_REV5" type="INT32">
      <short_desc>Invert direction of main output channel 5</short_desc>
      <long_desc>Enable to invert the channel.</long_desc>
      <boolean />
      <scope>drivers/px4io</scope>
    </parameter>
    <parameter default="0" name="PWM_MAIN_REV6" type="INT32">
      <short_desc>Invert direction of main output channel 6</short_desc>
      <long_desc>Enable to invert the channel.</long_desc>
      <boolean />
      <scope>drivers/px4io</scope>
    </parameter>
    <parameter default="0" name="PWM_MAIN_REV7" type="INT32">
      <short_desc>Invert direction of main output channel 7</short_desc>
      <long_desc>Enable to invert the channel.</long_desc>
      <boolean />
      <scope>drivers/px4io</scope>
    </parameter>
    <parameter default="0" name="PWM_MAIN_REV8" type="INT32">
      <short_desc>Invert direction of main output channel 8</short_desc>
      <long_desc>Enable to invert the channel.</long_desc>
      <boolean />
      <scope>drivers/px4io</scope>
    </parameter>
    <parameter default="0" name="PWM_MAIN_TRIM1" type="FLOAT">
      <short_desc>Trim value for main output channel 1</short_desc>
      <long_desc>Set to normalized offset</long_desc>
      <min>-0.2</min>
      <max>0.2</max>
      <decimal>2</decimal>
      <scope>drivers/px4io</scope>
    </parameter>
    <parameter default="0" name="PWM_MAIN_TRIM2" type="FLOAT">
      <short_desc>Trim value for main output channel 2</short_desc>
      <long_desc>Set to normalized offset</long_desc>
      <min>-0.2</min>
      <max>0.2</max>
      <decimal>2</decimal>
      <scope>drivers/px4io</scope>
    </parameter>
    <parameter default="0" name="PWM_MAIN_TRIM3" type="FLOAT">
      <short_desc>Trim value for main output channel 3</short_desc>
      <long_desc>Set to normalized offset</long_desc>
      <min>-0.2</min>
      <max>0.2</max>
      <decimal>2</decimal>
      <scope>drivers/px4io</scope>
    </parameter>
    <parameter default="0" name="PWM_MAIN_TRIM4" type="FLOAT">
      <short_desc>Trim value for main output channel 4</short_desc>
      <long_desc>Set to normalized offset</long_desc>
      <min>-0.2</min>
      <max>0.2</max>
      <decimal>2</decimal>
      <scope>drivers/px4io</scope>
    </parameter>
    <parameter default="0" name="PWM_MAIN_TRIM5" type="FLOAT">
      <short_desc>Trim value for main output channel 5</short_desc>
      <long_desc>Set to normalized offset</long_desc>
      <min>-0.2</min>
      <max>0.2</max>
      <decimal>2</decimal>
      <scope>drivers/px4io</scope>
    </parameter>
    <parameter default="0" name="PWM_MAIN_TRIM6" type="FLOAT">
      <short_desc>Trim value for main output channel 6</short_desc>
      <long_desc>Set to normalized offset</long_desc>
      <min>-0.2</min>
      <max>0.2</max>
      <decimal>2</decimal>
      <scope>drivers/px4io</scope>
    </parameter>
    <parameter default="0" name="PWM_MAIN_TRIM7" type="FLOAT">
      <short_desc>Trim value for main output channel 7</short_desc>
      <long_desc>Set to normalized offset</long_desc>
      <min>-0.2</min>
      <max>0.2</max>
      <decimal>2</decimal>
      <scope>drivers/px4io</scope>
    </parameter>
    <parameter default="0" name="PWM_MAIN_TRIM8" type="FLOAT">
      <short_desc>Trim value for main output channel 8</short_desc>
      <long_desc>Set to normalized offset</long_desc>
      <min>-0.2</min>
      <max>0.2</max>
      <decimal>2</decimal>
      <scope>drivers/px4io</scope>
    </parameter>
    <parameter default="2000" name="PWM_MAX" type="INT32">
      <short_desc>Set the maximum PWM for the main outputs</short_desc>
      <long_desc>Set to 2000 for industry default or 2100 to increase servo travel.</long_desc>
      <min>1600</min>
      <max>2200</max>
      <unit>us</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1000" name="PWM_MIN" type="INT32">
      <short_desc>Set the minimum PWM for the main outputs</short_desc>
      <long_desc>Set to 1000 for industry default or 900 to increase servo travel.</long_desc>
      <min>800</min>
      <max>1400</max>
      <unit>us</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="400" name="PWM_RATE" type="INT32">
      <short_desc>Set the PWM output frequency for the main outputs</short_desc>
      <long_desc>Set to 400 for industry default or 1000 for high frequency ESCs. Set to 0 for Oneshot125.</long_desc>
      <min>-1</min>
      <max>2000</max>
      <unit>Hz</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="PWM_SBUS_MODE" type="INT32">
      <short_desc>S.BUS out</short_desc>
      <long_desc>Set to 1 to enable S.BUS version 1 output instead of RSSI.</long_desc>
      <boolean />
      <scope>drivers/px4io</scope>
    </parameter>
    <parameter default="0.0" name="THR_MDL_FAC" type="FLOAT">
      <short_desc>Thrust to PWM model parameter</short_desc>
      <long_desc>Parameter used to model the relationship between static thrust and motor input PWM. Model is: thrust = (1-factor)*PWM + factor * PWM^2</long_desc>
      <min>0.0</min>
      <max>1.0</max>
      <scope>drivers/px4fmu</scope>
    </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>
      <scope>examples/bottle_drop</scope>
    </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>
      <scope>examples/bottle_drop</scope>
    </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>kg</unit>
      <scope>examples/bottle_drop</scope>
    </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>
      <scope>examples/bottle_drop</scope>
    </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>m</unit>
      <scope>examples/bottle_drop</scope>
    </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>m</unit>
      <scope>examples/bottle_drop</scope>
    </parameter>
  </group>
  <group name="Position Estimator INAV">
    <parameter category="Developer" 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>328754</max>
      <reboot_required>true</reboot_required>
      <scope>modules/position_estimator_inav</scope>
    </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>
      <scope>modules/position_estimator_inav</scope>
    </parameter>
    <parameter default="0" name="INAV_DISAB_MOCAP" type="FLOAT">
      <short_desc>Mo-cap</short_desc>
      <long_desc>Set to 0 if using fake GPS</long_desc>
      <scope>modules/position_estimator_inav</scope>
      <values>
        <value code="0">Mo-cap enabled</value>
        <value code="1">Mo-cap disabled</value>
      </values>
    </parameter>
    <parameter default="0.0" name="INAV_FLOW_DIST_X" type="FLOAT">
      <short_desc>Flow module offset (center of rotation) in X direction</short_desc>
      <long_desc>Yaw X flow compensation</long_desc>
      <min>-1.0</min>
      <max>1.0</max>
      <unit>m</unit>
      <scope>modules/position_estimator_inav</scope>
    </parameter>
    <parameter default="0.0" name="INAV_FLOW_DIST_Y" type="FLOAT">
      <short_desc>Flow module offset (center of rotation) in Y direction</short_desc>
      <long_desc>Yaw Y flow compensation</long_desc>
      <min>-1.0</min>
      <max>1.0</max>
      <unit>m</unit>
      <scope>modules/position_estimator_inav</scope>
    </parameter>
    <parameter default="1.35" name="INAV_FLOW_K" type="FLOAT">
      <short_desc>Optical flow scale factor</short_desc>
      <long_desc>Factor to scale optical flow</long_desc>
      <min>0.0</min>
      <max>10.0</max>
      <scope>modules/position_estimator_inav</scope>
    </parameter>
    <parameter default="0.3" 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>
      <scope>modules/position_estimator_inav</scope>
    </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>
      <scope>modules/position_estimator_inav</scope>
    </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>
      <scope>modules/position_estimator_inav</scope>
    </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>
      <scope>modules/position_estimator_inav</scope>
    </parameter>
    <parameter default="0.2" name="INAV_LIDAR_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>
      <scope>modules/position_estimator_inav</scope>
    </parameter>
    <parameter default="0" name="INAV_LIDAR_EST" type="FLOAT">
      <short_desc>LIDAR for altitude estimation</short_desc>
      <boolean />
      <scope>modules/position_estimator_inav</scope>
    </parameter>
    <parameter default="0.0" name="INAV_LIDAR_OFF" type="FLOAT">
      <short_desc>LIDAR calibration offset</short_desc>
      <long_desc>LIDAR calibration offset. Value will be added to the measured distance</long_desc>
      <min>-20</min>
      <max>20</max>
      <unit>m</unit>
      <scope>modules/position_estimator_inav</scope>
    </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>
      <scope>modules/position_estimator_inav</scope>
    </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>
      <scope>modules/position_estimator_inav</scope>
    </parameter>
    <parameter default="10.0" name="INAV_W_MOC_P" type="FLOAT">
      <short_desc>Weight for mocap system</short_desc>
      <long_desc>Weight (cutoff frequency) for mocap position measurements.</long_desc>
      <min>0.0</min>
      <max>10.0</max>
      <scope>modules/position_estimator_inav</scope>
    </parameter>
    <parameter default="0.8" 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>
      <scope>modules/position_estimator_inav</scope>
    </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>
      <scope>modules/position_estimator_inav</scope>
    </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>
      <scope>modules/position_estimator_inav</scope>
    </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>
      <scope>modules/position_estimator_inav</scope>
    </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>
      <scope>modules/position_estimator_inav</scope>
    </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>
      <scope>modules/position_estimator_inav</scope>
    </parameter>
    <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>
      <scope>modules/position_estimator_inav</scope>
    </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>
      <scope>modules/position_estimator_inav</scope>
    </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>
      <scope>modules/position_estimator_inav</scope>
    </parameter>
    <parameter default="3.0" name="INAV_W_Z_LIDAR" type="FLOAT">
      <short_desc>Z axis weight for lidar</short_desc>
      <long_desc>Weight (cutoff frequency) for lidar measurements.</long_desc>
      <min>0.0</min>
      <max>10.0</max>
      <scope>modules/position_estimator_inav</scope>
    </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>
      <scope>modules/position_estimator_inav</scope>
    </parameter>
  </group>
  <group name="Precision Land">
    <parameter default="5.0" name="PLD_BTOUT" type="FLOAT">
      <short_desc>Landing Target Timeout</short_desc>
      <long_desc>Time after which the landing target is considered lost without any new measurements.</long_desc>
      <min>0.0</min>
      <max>50</max>
      <unit>s</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="0.1" name="PLD_FAPPR_ALT" type="FLOAT">
      <short_desc>Final approach altitude</short_desc>
      <long_desc>Allow final approach (without horizontal positioning) if losing landing target closer than this to the ground.</long_desc>
      <min>0.0</min>
      <max>10</max>
      <unit>m</unit>
      <decimal>2</decimal>
      <increment>0.1</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="0.2" name="PLD_HACC_RAD" type="FLOAT">
      <short_desc>Horizontal acceptance radius</short_desc>
      <long_desc>Start descending if closer above landing target than this.</long_desc>
      <min>0.0</min>
      <max>10</max>
      <unit>m</unit>
      <decimal>2</decimal>
      <increment>0.1</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="3" name="PLD_MAX_SRCH" type="INT32">
      <short_desc>Maximum number of search attempts</short_desc>
      <long_desc>Maximum number of times to seach for the landing target if it is lost during the precision landing.</long_desc>
      <min>0</min>
      <max>100</max>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="10.0" name="PLD_SRCH_ALT" type="FLOAT">
      <short_desc>Search altitude</short_desc>
      <long_desc>Altitude above home to which to climb when searching for the landing target.</long_desc>
      <min>0.0</min>
      <max>100</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <increment>0.1</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="10.0" name="PLD_SRCH_TOUT" type="FLOAT">
      <short_desc>Search timeout</short_desc>
      <long_desc>Time allowed to search for the landing target before falling back to normal landing.</long_desc>
      <min>0.0</min>
      <max>100</max>
      <unit>s</unit>
      <decimal>1</decimal>
      <increment>0.1</increment>
      <scope>modules/navigator</scope>
    </parameter>
  </group>
  <group name="RC Receiver Configuration">
    <parameter default="1" name="RC_RECEIVER_TYPE" type="INT32">
      <short_desc>RC receiver type</short_desc>
      <long_desc>Acceptable values: - RC_RECEIVER_SPEKTRUM = 1, - RC_RECEIVER_LEMONRX = 2,</long_desc>
      <scope>platforms/qurt/fc_addon/rc_receiver</scope>
    </parameter>
  </group>
  <group name="Radio Calibration">
    <parameter default="0.0" name="RC10_DZ" type="FLOAT">
      <short_desc>RC channel 10 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>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="2000" name="RC10_MAX" type="FLOAT">
      <short_desc>RC channel 10 maximum</short_desc>
      <long_desc>Maximum value for this channel.</long_desc>
      <min>1500.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1000" name="RC10_MIN" type="FLOAT">
      <short_desc>RC channel 10 minimum</short_desc>
      <long_desc>Minimum value for this channel.</long_desc>
      <min>800.0</min>
      <max>1500.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="RC10_REV" type="FLOAT">
      <short_desc>RC channel 10 reverse</short_desc>
      <long_desc>Set to -1 to reverse channel.</long_desc>
      <min>-1.0</min>
      <max>1.0</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1.0">Reverse</value>
        <value code="1.0">Normal</value>
      </values>
    </parameter>
    <parameter default="1500" name="RC10_TRIM" type="FLOAT">
      <short_desc>RC channel 10 trim</short_desc>
      <long_desc>Mid point value (has to be set to the same as min for throttle channel).</long_desc>
      <min>800.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="RC11_DZ" type="FLOAT">
      <short_desc>RC channel 11 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>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="2000" name="RC11_MAX" type="FLOAT">
      <short_desc>RC channel 11 maximum</short_desc>
      <long_desc>Maximum value for this channel.</long_desc>
      <min>1500.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1000" name="RC11_MIN" type="FLOAT">
      <short_desc>RC channel 11 minimum</short_desc>
      <long_desc>Minimum value for this channel.</long_desc>
      <min>800.0</min>
      <max>1500.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="RC11_REV" type="FLOAT">
      <short_desc>RC channel 11 reverse</short_desc>
      <long_desc>Set to -1 to reverse channel.</long_desc>
      <min>-1.0</min>
      <max>1.0</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1.0">Reverse</value>
        <value code="1.0">Normal</value>
      </values>
    </parameter>
    <parameter default="1500" name="RC11_TRIM" type="FLOAT">
      <short_desc>RC channel 11 trim</short_desc>
      <long_desc>Mid point value (has to be set to the same as min for throttle channel).</long_desc>
      <min>800.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="RC12_DZ" type="FLOAT">
      <short_desc>RC channel 12 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>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="2000" name="RC12_MAX" type="FLOAT">
      <short_desc>RC channel 12 maximum</short_desc>
      <long_desc>Maximum value for this channel.</long_desc>
      <min>1500.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1000" name="RC12_MIN" type="FLOAT">
      <short_desc>RC channel 12 minimum</short_desc>
      <long_desc>Minimum value for this channel.</long_desc>
      <min>800.0</min>
      <max>1500.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="RC12_REV" type="FLOAT">
      <short_desc>RC channel 12 reverse</short_desc>
      <long_desc>Set to -1 to reverse channel.</long_desc>
      <min>-1.0</min>
      <max>1.0</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1.0">Reverse</value>
        <value code="1.0">Normal</value>
      </values>
    </parameter>
    <parameter default="1500" name="RC12_TRIM" type="FLOAT">
      <short_desc>RC channel 12 trim</short_desc>
      <long_desc>Mid point value (has to be set to the same as min for throttle channel).</long_desc>
      <min>800.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="RC13_DZ" type="FLOAT">
      <short_desc>RC channel 13 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>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="2000" name="RC13_MAX" type="FLOAT">
      <short_desc>RC channel 13 maximum</short_desc>
      <long_desc>Maximum value for this channel.</long_desc>
      <min>1500.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1000" name="RC13_MIN" type="FLOAT">
      <short_desc>RC channel 13 minimum</short_desc>
      <long_desc>Minimum value for this channel.</long_desc>
      <min>800.0</min>
      <max>1500.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="RC13_REV" type="FLOAT">
      <short_desc>RC channel 13 reverse</short_desc>
      <long_desc>Set to -1 to reverse channel.</long_desc>
      <min>-1.0</min>
      <max>1.0</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1.0">Reverse</value>
        <value code="1.0">Normal</value>
      </values>
    </parameter>
    <parameter default="1500" name="RC13_TRIM" type="FLOAT">
      <short_desc>RC channel 13 trim</short_desc>
      <long_desc>Mid point value (has to be set to the same as min for throttle channel).</long_desc>
      <min>800.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="RC14_DZ" type="FLOAT">
      <short_desc>RC channel 14 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>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="2000" name="RC14_MAX" type="FLOAT">
      <short_desc>RC channel 14 maximum</short_desc>
      <long_desc>Maximum value for this channel.</long_desc>
      <min>1500.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1000" name="RC14_MIN" type="FLOAT">
      <short_desc>RC channel 14 minimum</short_desc>
      <long_desc>Minimum value for this channel.</long_desc>
      <min>800.0</min>
      <max>1500.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="RC14_REV" type="FLOAT">
      <short_desc>RC channel 14 reverse</short_desc>
      <long_desc>Set to -1 to reverse channel.</long_desc>
      <min>-1.0</min>
      <max>1.0</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1.0">Reverse</value>
        <value code="1.0">Normal</value>
      </values>
    </parameter>
    <parameter default="1500" name="RC14_TRIM" type="FLOAT">
      <short_desc>RC channel 14 trim</short_desc>
      <long_desc>Mid point value (has to be set to the same as min for throttle channel).</long_desc>
      <min>800.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="RC15_DZ" type="FLOAT">
      <short_desc>RC channel 15 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>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="2000" name="RC15_MAX" type="FLOAT">
      <short_desc>RC channel 15 maximum</short_desc>
      <long_desc>Maximum value for this channel.</long_desc>
      <min>1500.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1000" name="RC15_MIN" type="FLOAT">
      <short_desc>RC channel 15 minimum</short_desc>
      <long_desc>Minimum value for this channel.</long_desc>
      <min>800.0</min>
      <max>1500.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="RC15_REV" type="FLOAT">
      <short_desc>RC channel 15 reverse</short_desc>
      <long_desc>Set to -1 to reverse channel.</long_desc>
      <min>-1.0</min>
      <max>1.0</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1.0">Reverse</value>
        <value code="1.0">Normal</value>
      </values>
    </parameter>
    <parameter default="1500" name="RC15_TRIM" type="FLOAT">
      <short_desc>RC channel 15 trim</short_desc>
      <long_desc>Mid point value (has to be set to the same as min for throttle channel).</long_desc>
      <min>800.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="RC16_DZ" type="FLOAT">
      <short_desc>RC channel 16 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>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="2000" name="RC16_MAX" type="FLOAT">
      <short_desc>RC channel 16 maximum</short_desc>
      <long_desc>Maximum value for this channel.</long_desc>
      <min>1500.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1000" name="RC16_MIN" type="FLOAT">
      <short_desc>RC channel 16 minimum</short_desc>
      <long_desc>Minimum value for this channel.</long_desc>
      <min>800.0</min>
      <max>1500.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="RC16_REV" type="FLOAT">
      <short_desc>RC channel 16 reverse</short_desc>
      <long_desc>Set to -1 to reverse channel.</long_desc>
      <min>-1.0</min>
      <max>1.0</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1.0">Reverse</value>
        <value code="1.0">Normal</value>
      </values>
    </parameter>
    <parameter default="1500" name="RC16_TRIM" type="FLOAT">
      <short_desc>RC channel 16 trim</short_desc>
      <long_desc>Mid point value (has to be set to the same as min for throttle channel).</long_desc>
      <min>800.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="RC17_DZ" type="FLOAT">
      <short_desc>RC channel 17 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>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="2000" name="RC17_MAX" type="FLOAT">
      <short_desc>RC channel 17 maximum</short_desc>
      <long_desc>Maximum value for this channel.</long_desc>
      <min>1500.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1000" name="RC17_MIN" type="FLOAT">
      <short_desc>RC channel 17 minimum</short_desc>
      <long_desc>Minimum value for this channel.</long_desc>
      <min>800.0</min>
      <max>1500.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="RC17_REV" type="FLOAT">
      <short_desc>RC channel 17 reverse</short_desc>
      <long_desc>Set to -1 to reverse channel.</long_desc>
      <min>-1.0</min>
      <max>1.0</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1.0">Reverse</value>
        <value code="1.0">Normal</value>
      </values>
    </parameter>
    <parameter default="1500" name="RC17_TRIM" type="FLOAT">
      <short_desc>RC channel 17 trim</short_desc>
      <long_desc>Mid point value (has to be set to the same as min for throttle channel).</long_desc>
      <min>800.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="RC18_DZ" type="FLOAT">
      <short_desc>RC channel 18 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>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="2000" name="RC18_MAX" type="FLOAT">
      <short_desc>RC channel 18 maximum</short_desc>
      <long_desc>Maximum value for this channel.</long_desc>
      <min>1500.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1000" name="RC18_MIN" type="FLOAT">
      <short_desc>RC channel 18 minimum</short_desc>
      <long_desc>Minimum value for this channel.</long_desc>
      <min>800.0</min>
      <max>1500.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="RC18_REV" type="FLOAT">
      <short_desc>RC channel 18 reverse</short_desc>
      <long_desc>Set to -1 to reverse channel.</long_desc>
      <min>-1.0</min>
      <max>1.0</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1.0">Reverse</value>
        <value code="1.0">Normal</value>
      </values>
    </parameter>
    <parameter default="1500" name="RC18_TRIM" type="FLOAT">
      <short_desc>RC channel 18 trim</short_desc>
      <long_desc>Mid point value (has to be set to the same as min for throttle channel).</long_desc>
      <min>800.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </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>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </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>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <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>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </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>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1.0">Reverse</value>
        <value code="1.0">Normal</value>
      </values>
    </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>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </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>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="2000.0" name="RC2_MAX" type="FLOAT">
      <short_desc>RC channel 2 maximum</short_desc>
      <long_desc>Maximum value for this channel.</long_desc>
      <min>1500.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1000.0" name="RC2_MIN" type="FLOAT">
      <short_desc>RC channel 2 minimum</short_desc>
      <long_desc>Minimum value for this channel.</long_desc>
      <min>800.0</min>
      <max>1500.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </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>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1.0">Reverse</value>
        <value code="1.0">Normal</value>
      </values>
    </parameter>
    <parameter default="1500.0" name="RC2_TRIM" type="FLOAT">
      <short_desc>RC channel 2 trim</short_desc>
      <long_desc>Mid point value (has to be set to the same as min for throttle channel).</long_desc>
      <min>800.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="10.0" name="RC3_DZ" type="FLOAT">
      <short_desc>RC channel 3 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>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="2000" name="RC3_MAX" type="FLOAT">
      <short_desc>RC channel 3 maximum</short_desc>
      <long_desc>Maximum value for this channel.</long_desc>
      <min>1500.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1000" name="RC3_MIN" type="FLOAT">
      <short_desc>RC channel 3 minimum</short_desc>
      <long_desc>Minimum value for this channel.</long_desc>
      <min>800.0</min>
      <max>1500.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="RC3_REV" type="FLOAT">
      <short_desc>RC channel 3 reverse</short_desc>
      <long_desc>Set to -1 to reverse channel.</long_desc>
      <min>-1.0</min>
      <max>1.0</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1.0">Reverse</value>
        <value code="1.0">Normal</value>
      </values>
    </parameter>
    <parameter default="1500" name="RC3_TRIM" type="FLOAT">
      <short_desc>RC channel 3 trim</short_desc>
      <long_desc>Mid point value (has to be set to the same as min for throttle channel).</long_desc>
      <min>800.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="10.0" name="RC4_DZ" type="FLOAT">
      <short_desc>RC channel 4 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>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="2000" name="RC4_MAX" type="FLOAT">
      <short_desc>RC channel 4 maximum</short_desc>
      <long_desc>Maximum value for this channel.</long_desc>
      <min>1500.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1000" name="RC4_MIN" type="FLOAT">
      <short_desc>RC channel 4 minimum</short_desc>
      <long_desc>Minimum value for this channel.</long_desc>
      <min>800.0</min>
      <max>1500.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="RC4_REV" type="FLOAT">
      <short_desc>RC channel 4 reverse</short_desc>
      <long_desc>Set to -1 to reverse channel.</long_desc>
      <min>-1.0</min>
      <max>1.0</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1.0">Reverse</value>
        <value code="1.0">Normal</value>
      </values>
    </parameter>
    <parameter default="1500" name="RC4_TRIM" type="FLOAT">
      <short_desc>RC channel 4 trim</short_desc>
      <long_desc>Mid point value (has to be set to the same as min for throttle channel).</long_desc>
      <min>800.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="10.0" name="RC5_DZ" type="FLOAT">
      <short_desc>RC channel 5 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>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="2000" name="RC5_MAX" type="FLOAT">
      <short_desc>RC channel 5 maximum</short_desc>
      <long_desc>Maximum value for this channel.</long_desc>
      <min>1500.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1000" name="RC5_MIN" type="FLOAT">
      <short_desc>RC channel 5 minimum</short_desc>
      <long_desc>Minimum value for this channel.</long_desc>
      <min>800.0</min>
      <max>1500.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="RC5_REV" type="FLOAT">
      <short_desc>RC channel 5 reverse</short_desc>
      <long_desc>Set to -1 to reverse channel.</long_desc>
      <min>-1.0</min>
      <max>1.0</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1.0">Reverse</value>
        <value code="1.0">Normal</value>
      </values>
    </parameter>
    <parameter default="1500" name="RC5_TRIM" type="FLOAT">
      <short_desc>RC channel 5 trim</short_desc>
      <long_desc>Mid point value (has to be set to the same as min for throttle channel).</long_desc>
      <min>800.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="10.0" name="RC6_DZ" type="FLOAT">
      <short_desc>RC channel 6 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>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="2000" name="RC6_MAX" type="FLOAT">
      <short_desc>RC channel 6 maximum</short_desc>
      <long_desc>Maximum value for this channel.</long_desc>
      <min>1500.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1000" name="RC6_MIN" type="FLOAT">
      <short_desc>RC channel 6 minimum</short_desc>
      <long_desc>Minimum value for this channel.</long_desc>
      <min>800.0</min>
      <max>1500.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="RC6_REV" type="FLOAT">
      <short_desc>RC channel 6 reverse</short_desc>
      <long_desc>Set to -1 to reverse channel.</long_desc>
      <min>-1.0</min>
      <max>1.0</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1.0">Reverse</value>
        <value code="1.0">Normal</value>
      </values>
    </parameter>
    <parameter default="1500" name="RC6_TRIM" type="FLOAT">
      <short_desc>RC channel 6 trim</short_desc>
      <long_desc>Mid point value (has to be set to the same as min for throttle channel).</long_desc>
      <min>800.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="10.0" name="RC7_DZ" type="FLOAT">
      <short_desc>RC channel 7 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>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="2000" name="RC7_MAX" type="FLOAT">
      <short_desc>RC channel 7 maximum</short_desc>
      <long_desc>Maximum value for this channel.</long_desc>
      <min>1500.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1000" name="RC7_MIN" type="FLOAT">
      <short_desc>RC channel 7 minimum</short_desc>
      <long_desc>Minimum value for this channel.</long_desc>
      <min>800.0</min>
      <max>1500.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="RC7_REV" type="FLOAT">
      <short_desc>RC channel 7 reverse</short_desc>
      <long_desc>Set to -1 to reverse channel.</long_desc>
      <min>-1.0</min>
      <max>1.0</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1.0">Reverse</value>
        <value code="1.0">Normal</value>
      </values>
    </parameter>
    <parameter default="1500" name="RC7_TRIM" type="FLOAT">
      <short_desc>RC channel 7 trim</short_desc>
      <long_desc>Mid point value (has to be set to the same as min for throttle channel).</long_desc>
      <min>800.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="10.0" name="RC8_DZ" type="FLOAT">
      <short_desc>RC channel 8 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>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="2000" name="RC8_MAX" type="FLOAT">
      <short_desc>RC channel 8 maximum</short_desc>
      <long_desc>Maximum value for this channel.</long_desc>
      <min>1500.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1000" name="RC8_MIN" type="FLOAT">
      <short_desc>RC channel 8 minimum</short_desc>
      <long_desc>Minimum value for this channel.</long_desc>
      <min>800.0</min>
      <max>1500.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="RC8_REV" type="FLOAT">
      <short_desc>RC channel 8 reverse</short_desc>
      <long_desc>Set to -1 to reverse channel.</long_desc>
      <min>-1.0</min>
      <max>1.0</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1.0">Reverse</value>
        <value code="1.0">Normal</value>
      </values>
    </parameter>
    <parameter default="1500" name="RC8_TRIM" type="FLOAT">
      <short_desc>RC channel 8 trim</short_desc>
      <long_desc>Mid point value (has to be set to the same as min for throttle channel).</long_desc>
      <min>800.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="RC9_DZ" type="FLOAT">
      <short_desc>RC channel 9 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>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="2000" name="RC9_MAX" type="FLOAT">
      <short_desc>RC channel 9 maximum</short_desc>
      <long_desc>Maximum value for this channel.</long_desc>
      <min>1500.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1000" name="RC9_MIN" type="FLOAT">
      <short_desc>RC channel 9 minimum</short_desc>
      <long_desc>Minimum value for this channel.</long_desc>
      <min>800.0</min>
      <max>1500.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="RC9_REV" type="FLOAT">
      <short_desc>RC channel 9 reverse</short_desc>
      <long_desc>Set to -1 to reverse channel.</long_desc>
      <min>-1.0</min>
      <max>1.0</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1.0">Reverse</value>
        <value code="1.0">Normal</value>
      </values>
    </parameter>
    <parameter default="1500" name="RC9_TRIM" type="FLOAT">
      <short_desc>RC channel 9 trim</short_desc>
      <long_desc>Mid point value (has to be set to the same as min for throttle channel).</long_desc>
      <min>800.0</min>
      <max>2200.0</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </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>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="RC_FAILS_THR" type="INT32">
      <short_desc>Failsafe channel PWM threshold</short_desc>
      <long_desc>Set to a value slightly above the PWM value assumed by throttle in a failsafe event, but ensure it is below the PWM value assumed by throttle during normal operation.</long_desc>
      <min>0</min>
      <max>2200</max>
      <unit>us</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="10.0" name="RC_FLT_CUTOFF" type="FLOAT">
      <short_desc>Cutoff frequency for the low pass filter on roll, pitch, yaw and throttle</short_desc>
      <long_desc>Does not get set unless below RC_FLT_SMP_RATE/2 because of filter instability characteristics. Set to 0 to disable the filter.</long_desc>
      <min>0</min>
      <unit>Hz</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="50.0" name="RC_FLT_SMP_RATE" type="FLOAT">
      <short_desc>Sample rate of the remote control values for the low pass filter on roll, pitch, yaw and throttle</short_desc>
      <long_desc>Has an influence on the cutoff frequency precision.</long_desc>
      <min>1.0</min>
      <unit>Hz</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="RC_MAP_AUX1" type="INT32">
      <short_desc>AUX1 Passthrough RC channel</short_desc>
      <long_desc>Default function: Camera pitch</long_desc>
      <min>0</min>
      <max>18</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" name="RC_MAP_AUX2" type="INT32">
      <short_desc>AUX2 Passthrough RC channel</short_desc>
      <long_desc>Default function: Camera roll</long_desc>
      <min>0</min>
      <max>18</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" name="RC_MAP_AUX3" type="INT32">
      <short_desc>AUX3 Passthrough RC channel</short_desc>
      <long_desc>Default function: Camera azimuth / yaw</long_desc>
      <min>0</min>
      <max>18</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" name="RC_MAP_AUX4" type="INT32">
      <short_desc>AUX4 Passthrough RC channel</short_desc>
      <min>0</min>
      <max>18</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" name="RC_MAP_AUX5" type="INT32">
      <short_desc>AUX5 Passthrough RC channel</short_desc>
      <min>0</min>
      <max>18</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </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>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" name="RC_MAP_PARAM1" type="INT32">
      <short_desc>PARAM1 tuning channel</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>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" name="RC_MAP_PARAM2" type="INT32">
      <short_desc>PARAM2 tuning channel</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>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" name="RC_MAP_PARAM3" type="INT32">
      <short_desc>PARAM3 tuning channel</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>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" 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>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" 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>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" 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>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" 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>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </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>
      <scope>drivers/px4io</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </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 &gt; 0</long_desc>
      <min>0</min>
      <max>2000</max>
      <scope>drivers/px4io</scope>
    </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 &gt; 0</long_desc>
      <min>0</min>
      <max>2000</max>
      <scope>drivers/px4io</scope>
    </parameter>
    <parameter default="0.0" name="TRIM_PITCH" type="FLOAT">
      <short_desc>Pitch trim</short_desc>
      <long_desc>The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS.</long_desc>
      <min>-0.25</min>
      <max>0.25</max>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="0.0" name="TRIM_ROLL" type="FLOAT">
      <short_desc>Roll trim</short_desc>
      <long_desc>The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS.</long_desc>
      <min>-0.25</min>
      <max>0.25</max>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/commander</scope>
    </parameter>
    <parameter default="0.0" name="TRIM_YAW" type="FLOAT">
      <short_desc>Yaw trim</short_desc>
      <long_desc>The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS.</long_desc>
      <min>-0.25</min>
      <max>0.25</max>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/commander</scope>
    </parameter>
  </group>
  <group name="Radio Switches">
    <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&gt;th negative : true when channel&lt;th</long_desc>
      <min>-1</min>
      <max>1</max>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.25" name="RC_ARMSWITCH_TH" type="FLOAT">
      <short_desc>Threshold for the arm switch</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&gt;th negative : true when channel&lt;th</long_desc>
      <min>-1</min>
      <max>1</max>
      <scope>modules/sensors</scope>
    </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&gt;th negative : true when channel&lt;th</long_desc>
      <min>-1</min>
      <max>1</max>
      <scope>modules/sensors</scope>
    </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&gt;th negative : true when channel&lt;th</long_desc>
      <min>-1</min>
      <max>1</max>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.25" name="RC_GEAR_TH" type="FLOAT">
      <short_desc>Threshold for the landing gear switch</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&gt;th negative : true when channel&lt;th</long_desc>
      <min>-1</min>
      <max>1</max>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.25" name="RC_KILLSWITCH_TH" type="FLOAT">
      <short_desc>Threshold for the kill switch</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&gt;th negative : true when channel&lt;th</long_desc>
      <min>-1</min>
      <max>1</max>
      <scope>modules/sensors</scope>
    </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&gt;th negative : true when channel&lt;th</long_desc>
      <min>-1</min>
      <max>1</max>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.5" name="RC_MAN_TH" type="FLOAT">
      <short_desc>Threshold for the manual switch</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&gt;th negative : true when channel&lt;th</long_desc>
      <min>-1</min>
      <max>1</max>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="RC_MAP_ACRO_SW" type="INT32">
      <short_desc>Acro switch channel</short_desc>
      <min>0</min>
      <max>18</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" name="RC_MAP_ARM_SW" type="INT32">
      <short_desc>Arm switch channel</short_desc>
      <min>0</min>
      <max>18</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" name="RC_MAP_FLAPS" type="INT32">
      <short_desc>Flaps channel</short_desc>
      <min>0</min>
      <max>18</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" name="RC_MAP_FLTMODE" type="INT32">
      <short_desc>Single channel flight mode selection</short_desc>
      <long_desc>If this parameter is non-zero, flight modes are only selected by this channel and are assigned to six slots.</long_desc>
      <min>0</min>
      <max>18</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" name="RC_MAP_GEAR_SW" type="INT32">
      <short_desc>Landing gear switch channel</short_desc>
      <min>0</min>
      <max>18</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" name="RC_MAP_KILL_SW" type="INT32">
      <short_desc>Kill switch channel</short_desc>
      <min>0</min>
      <max>18</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" name="RC_MAP_LOITER_SW" type="INT32">
      <short_desc>Loiter switch channel</short_desc>
      <min>0</min>
      <max>18</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" name="RC_MAP_MAN_SW" type="INT32">
      <short_desc>Manual switch channel mapping</short_desc>
      <min>0</min>
      <max>18</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <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>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" name="RC_MAP_OFFB_SW" type="INT32">
      <short_desc>Offboard switch channel</short_desc>
      <min>0</min>
      <max>18</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" name="RC_MAP_POSCTL_SW" type="INT32">
      <short_desc>Position Control switch channel</short_desc>
      <min>0</min>
      <max>18</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" name="RC_MAP_RATT_SW" type="INT32">
      <short_desc>Rattitude switch channel</short_desc>
      <min>0</min>
      <max>18</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" name="RC_MAP_RETURN_SW" type="INT32">
      <short_desc>Return switch channel</short_desc>
      <min>0</min>
      <max>18</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" name="RC_MAP_STAB_SW" type="INT32">
      <short_desc>Stabilize switch channel mapping</short_desc>
      <min>0</min>
      <max>18</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </parameter>
    <parameter default="0" name="RC_MAP_TRANS_SW" type="INT32">
      <short_desc>VTOL transition switch channel mapping</short_desc>
      <min>0</min>
      <max>18</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Unassigned</value>
        <value code="1">Channel 1</value>
        <value code="2">Channel 2</value>
        <value code="3">Channel 3</value>
        <value code="4">Channel 4</value>
        <value code="5">Channel 5</value>
        <value code="6">Channel 6</value>
        <value code="7">Channel 7</value>
        <value code="8">Channel 8</value>
        <value code="9">Channel 9</value>
        <value code="10">Channel 10</value>
        <value code="11">Channel 11</value>
        <value code="12">Channel 12</value>
        <value code="13">Channel 13</value>
        <value code="14">Channel 14</value>
        <value code="15">Channel 15</value>
        <value code="16">Channel 16</value>
        <value code="17">Channel 17</value>
        <value code="18">Channel 18</value>
      </values>
    </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&gt;th negative : true when channel&lt;th</long_desc>
      <min>-1</min>
      <max>1</max>
      <scope>modules/sensors</scope>
    </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&gt;th negative : true when channel&lt;th</long_desc>
      <min>-1</min>
      <max>1</max>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.5" name="RC_RATT_TH" type="FLOAT">
      <short_desc>Threshold for selecting rattitude 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&gt;th negative : true when channel&lt;th</long_desc>
      <min>-1</min>
      <max>1</max>
      <scope>modules/sensors</scope>
    </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&gt;th negative : true when channel&lt;th</long_desc>
      <min>-1</min>
      <max>1</max>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.5" name="RC_STAB_TH" type="FLOAT">
      <short_desc>Threshold for the stabilize switch</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&gt;th negative : true when channel&lt;th</long_desc>
      <min>-1</min>
      <max>1</max>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.25" name="RC_TRANS_TH" type="FLOAT">
      <short_desc>Threshold for the VTOL transition switch</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&gt;th negative : true when channel&lt;th</long_desc>
      <min>-1</min>
      <max>1</max>
      <scope>modules/sensors</scope>
    </parameter>
  </group>
  <group name="Return To Land">
    <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>m</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/navigator</scope>
    </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 RTL_DESCEND_ALT.</long_desc>
      <min>-1</min>
      <max>300</max>
      <unit>s</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <parameter default="0" name="RTL_LAND_TYPE" type="INT32">
      <short_desc>RTL land location</short_desc>
      <long_desc>Land at the home location or planned mission landing</long_desc>
      <scope>modules/navigator</scope>
      <values>
        <value code="0">Home Position</value>
        <value code="1">Planned Landing (Mission)</value>
      </values>
    </parameter>
    <parameter default="5.0" name="RTL_MIN_DIST" type="FLOAT">
      <short_desc>Minimum distance to trigger rising to a safe altitude</short_desc>
      <long_desc>If the system is horizontally closer than this distance to home it will land straight on home instead of raising to the return altitude first.</long_desc>
      <min>0.5</min>
      <max>20</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/navigator</scope>
    </parameter>
    <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>m</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/navigator</scope>
    </parameter>
  </group>
  <group name="Runway Takeoff">
    <parameter default="1.3" name="RWTO_AIRSPD_SCL" type="FLOAT">
      <short_desc>Min. airspeed scaling factor for takeoff.
Pitch up will be commanded when the following airspeed is reached:
FW_AIRSPD_MIN * RWTO_AIRSPD_SCL</short_desc>
      <min>0.0</min>
      <max>2.0</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_pos_control_l1/runway_takeoff</scope>
    </parameter>
    <parameter default="0" name="RWTO_HDG" type="INT32">
      <short_desc>Specifies which heading should be held during runnway takeoff</short_desc>
      <long_desc>0: airframe heading, 1: heading towards takeoff waypoint</long_desc>
      <min>0</min>
      <max>1</max>
      <scope>modules/fw_pos_control_l1/runway_takeoff</scope>
      <values>
        <value code="0">Airframe</value>
        <value code="1">Waypoint</value>
      </values>
    </parameter>
    <parameter default="20.0" name="RWTO_MAX_PITCH" type="FLOAT">
      <short_desc>Max pitch during takeoff.
Fixed-wing settings are used if set to 0. Note that there is also a minimum
pitch of 10 degrees during takeoff, so this must be larger if set</short_desc>
      <min>0.0</min>
      <max>60.0</max>
      <unit>deg</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1/runway_takeoff</scope>
    </parameter>
    <parameter default="25.0" name="RWTO_MAX_ROLL" type="FLOAT">
      <short_desc>Max roll during climbout.
Roll is limited during climbout to ensure enough lift and prevents aggressive
navigation before we're on a safe height</short_desc>
      <min>0.0</min>
      <max>60.0</max>
      <unit>deg</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1/runway_takeoff</scope>
    </parameter>
    <parameter default="1.0" name="RWTO_MAX_THR" type="FLOAT">
      <short_desc>Max throttle during runway takeoff.
(Can be used to test taxi on runway)</short_desc>
      <min>0.0</min>
      <max>1.0</max>
      <unit>norm</unit>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/fw_pos_control_l1/runway_takeoff</scope>
    </parameter>
    <parameter default="5.0" name="RWTO_NAV_ALT" type="FLOAT">
      <short_desc>Altitude AGL at which we have enough ground clearance to allow some roll.
Until RWTO_NAV_ALT is reached the plane is held level and only
rudder is used to keep the heading (see RWTO_HDG). This should be below
FW_CLMBOUT_DIFF if FW_CLMBOUT_DIFF &gt; 0</short_desc>
      <min>0.0</min>
      <max>100.0</max>
      <unit>m</unit>
      <decimal>1</decimal>
      <increment>1</increment>
      <scope>modules/fw_pos_control_l1/runway_takeoff</scope>
    </parameter>
    <parameter default="0.0" name="RWTO_PSP" type="FLOAT">
      <short_desc>Pitch setpoint during taxi / before takeoff airspeed is reached.
A taildragger with stearable wheel might need to pitch up
a little to keep it's wheel on the ground before airspeed
to takeoff is reached</short_desc>
      <min>0.0</min>
      <max>20.0</max>
      <unit>deg</unit>
      <decimal>1</decimal>
      <increment>0.5</increment>
      <scope>modules/fw_pos_control_l1/runway_takeoff</scope>
    </parameter>
    <parameter default="0" name="RWTO_TKOFF" type="INT32">
      <short_desc>Runway takeoff with landing gear</short_desc>
      <boolean />
      <scope>modules/fw_pos_control_l1/runway_takeoff</scope>
    </parameter>
  </group>
  <group name="SD Logging">
    <parameter default="0" name="SDLOG_DIRS_MAX" type="INT32">
      <short_desc>Maximum number of log directories to keep</short_desc>
      <long_desc>If there are more log directories than this value, the system will delete the oldest directories during startup. In addition, the system will delete old logs if there is not enough free space left. The minimum amount is 300 MB. If this is set to 0, old directories will only be removed if the free space falls below the minimum.</long_desc>
      <min>0</min>
      <max>1000</max>
      <reboot_required>true</reboot_required>
      <scope>modules/logger</scope>
    </parameter>
    <parameter default="-1" name="SDLOG_EXT" type="INT32">
      <short_desc>Extended logging mode</short_desc>
      <long_desc>A value of -1 indicates the command line argument should be obeyed. A value of 0 disables extended logging mode, a value of 1 enables it. This parameter is only read out before logging starts (which commonly is before arming).</long_desc>
      <min>-1</min>
      <max>1</max>
      <scope>modules/sdlog2</scope>
      <values>
        <value code="-1">Command Line</value>
        <value code="0">Disable</value>
        <value code="1">Enable</value>
      </values>
    </parameter>
    <parameter default="1" name="SDLOG_GPSTIME" type="INT32">
      <short_desc>Use timestamps only if GPS 3D fix is available</short_desc>
      <long_desc>Constrain the log folder creation to only use the time stamp if a 3D GPS lock is present.</long_desc>
      <boolean />
      <scope>modules/sdlog2</scope>
    </parameter>
    <parameter default="0" name="SDLOG_MODE" type="INT32">
      <short_desc>Logging Mode</short_desc>
      <long_desc>Determines when to start and stop logging. By default, logging is started when arming the system, and stopped when disarming. This parameter is only for the new logger (SYS_LOGGER=1).</long_desc>
      <min>0</min>
      <max>2</max>
      <reboot_required>true</reboot_required>
      <scope>modules/logger</scope>
      <values>
        <value code="0">when armed until disarm (default)</value>
        <value code="1">from boot until disarm</value>
        <value code="2">from boot until shutdown</value>
      </values>
    </parameter>
    <parameter default="2" name="SDLOG_PRIO_BOOST" type="INT32">
      <short_desc>Give logging app higher thread priority to avoid data loss.
This is used for gathering replay logs for the ekf2 module</short_desc>
      <long_desc>A value of 0 indicates that the default priority is used. Increasing the parameter in steps of one increases the priority.</long_desc>
      <min>0</min>
      <max>3</max>
      <scope>modules/sdlog2</scope>
      <values>
        <value code="0">Low priority</value>
        <value code="1">Default priority</value>
        <value code="2">Medium priority</value>
        <value code="3">Max priority</value>
      </values>
    </parameter>
    <parameter default="3" name="SDLOG_PROFILE" type="INT32">
      <short_desc>Logging Topic Profile</short_desc>
      <long_desc>This is an integer bitmask controlling the set and rates of logged topics. The default allows for general log analysis and estimator replay, while keeping the log file size reasonably small. Enabling multiple sets leads to higher bandwidth requirements and larger log files. Set bits in the following positions to enable: 0 : Set to true to use the default set (used for general log analysis) 1 : Set to true to enable full rate estimator (EKF2) replay topics 2 : Set to true to enable topics for thermal calibration (high rate raw IMU and Baro sensor data) 3 : Set to true to enable topics for system identification (high rate actuator control and IMU data) 4 : Set to true to enable full rates for analysis of fast maneuvers (RC, attitude, rates and actuators) 5 : Set to true to enable debugging topics (debug_*.msg topics, for custom code) 6 : Set to true to enable topics for sensor comparison (low rate raw IMU, Baro and Magnetomer data)</long_desc>
      <min>0</min>
      <max>127</max>
      <reboot_required>true</reboot_required>
      <scope>modules/logger</scope>
      <bitmask>
        <bit index="0">default set (log analysis)</bit>
        <bit index="1">estimator replay (EKF2)</bit>
        <bit index="2">thermal calibration</bit>
        <bit index="3">system identification</bit>
        <bit index="4">high rate</bit>
        <bit index="5">debug</bit>
        <bit index="6">sensor comparison</bit>
      </bitmask>
    </parameter>
    <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>250</max>
      <unit>Hz</unit>
      <scope>modules/sdlog2</scope>
    </parameter>
    <parameter default="0" name="SDLOG_UTC_OFFSET" type="INT32">
      <short_desc>UTC offset (unit: min)</short_desc>
      <long_desc>the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets</long_desc>
      <min>-1000</min>
      <max>1000</max>
      <unit>min</unit>
      <scope>modules/logger</scope>
    </parameter>
    <parameter default="1" name="SDLOG_UUID" type="INT32">
      <short_desc>Log UUID</short_desc>
      <long_desc>If set to 1, add an ID to the log, which uniquely identifies the vehicle</long_desc>
      <boolean />
      <scope>modules/logger</scope>
    </parameter>
  </group>
  <group name="SITL">
    <parameter default="60" name="SIM_BAT_DRAIN" type="FLOAT">
      <short_desc>Simulator Battery drain interval</short_desc>
      <min>1</min>
      <max>86400</max>
      <unit>s</unit>
      <increment>1</increment>
      <scope>modules/simulator</scope>
    </parameter>
    <parameter default="14560" name="SITL_UDP_PRT" type="INT32">
      <short_desc>Simulator UDP port</short_desc>
      <scope>modules/simulator</scope>
    </parameter>
  </group>
  <group name="Sensor Calibration">
    <parameter category="Developer" default="1" name="CAL_ACC0_EN" type="INT32">
      <short_desc>Accelerometer 0 enabled</short_desc>
      <boolean />
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="0" name="CAL_ACC0_ID" type="INT32">
      <short_desc>ID of the Accelerometer that the calibration is for</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="0.0" name="CAL_ACC0_XOFF" type="FLOAT">
      <short_desc>Accelerometer X-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="1.0" name="CAL_ACC0_XSCALE" type="FLOAT">
      <short_desc>Accelerometer X-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="0.0" name="CAL_ACC0_YOFF" type="FLOAT">
      <short_desc>Accelerometer Y-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="1.0" name="CAL_ACC0_YSCALE" type="FLOAT">
      <short_desc>Accelerometer Y-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="0.0" name="CAL_ACC0_ZOFF" type="FLOAT">
      <short_desc>Accelerometer Z-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="1.0" name="CAL_ACC0_ZSCALE" type="FLOAT">
      <short_desc>Accelerometer Z-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="Developer" default="1" name="CAL_ACC1_EN" type="INT32">
      <short_desc>Accelerometer 1 enabled</short_desc>
      <boolean />
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="0" name="CAL_ACC1_ID" type="INT32">
      <short_desc>ID of the Accelerometer that the calibration is for</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="0.0" name="CAL_ACC1_XOFF" type="FLOAT">
      <short_desc>Accelerometer X-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="1.0" name="CAL_ACC1_XSCALE" type="FLOAT">
      <short_desc>Accelerometer X-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="0.0" name="CAL_ACC1_YOFF" type="FLOAT">
      <short_desc>Accelerometer Y-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="1.0" name="CAL_ACC1_YSCALE" type="FLOAT">
      <short_desc>Accelerometer Y-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="0.0" name="CAL_ACC1_ZOFF" type="FLOAT">
      <short_desc>Accelerometer Z-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="1.0" name="CAL_ACC1_ZSCALE" type="FLOAT">
      <short_desc>Accelerometer Z-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="Developer" default="1" name="CAL_ACC2_EN" type="INT32">
      <short_desc>Accelerometer 2 enabled</short_desc>
      <boolean />
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="0" name="CAL_ACC2_ID" type="INT32">
      <short_desc>ID of the Accelerometer that the calibration is for</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="0.0" name="CAL_ACC2_XOFF" type="FLOAT">
      <short_desc>Accelerometer X-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="1.0" name="CAL_ACC2_XSCALE" type="FLOAT">
      <short_desc>Accelerometer X-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="0.0" name="CAL_ACC2_YOFF" type="FLOAT">
      <short_desc>Accelerometer Y-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="1.0" name="CAL_ACC2_YSCALE" type="FLOAT">
      <short_desc>Accelerometer Y-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="0.0" name="CAL_ACC2_ZOFF" type="FLOAT">
      <short_desc>Accelerometer Z-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="1.0" name="CAL_ACC2_ZSCALE" type="FLOAT">
      <short_desc>Accelerometer Z-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter category="System" default="0" name="CAL_ACC_PRIME" type="INT32">
      <short_desc>Primary accel ID</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="CAL_AIR_CMODEL" type="INT32">
      <short_desc>Airspeed sensor compensation model for the SDP3x</short_desc>
      <long_desc>Model with Pitot CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor. Model without Pitot (1.5 mm tubes) CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor. Tube Pressure Drop CAL_AIR_TUBED_MM: Diameter in mm of the pitot and tubes, must have the same diameter. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor and the static + dynamic port length of the pitot.</long_desc>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">Model with Pitot</value>
        <value code="1">Model without Pitot (1.5 mm tubes)</value>
        <value code="2">Tube Pressure Drop</value>
      </values>
    </parameter>
    <parameter default="1.5" name="CAL_AIR_TUBED_MM" type="FLOAT">
      <short_desc>Airspeed sensor tube diameter. Only used for the Tube Pressure Drop Compensation</short_desc>
      <min>0.1</min>
      <max>100</max>
      <unit>millimeter</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.2" name="CAL_AIR_TUBELEN" type="FLOAT">
      <short_desc>Airspeed sensor tube length</short_desc>
      <long_desc>See the CAL_AIR_CMODEL explanation on how this parameter should be set.</long_desc>
      <min>0.01</min>
      <max>2.00</max>
      <unit>meter</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="CAL_BARO_PRIME" type="INT32">
      <short_desc>Primary baro ID</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1" name="CAL_GYRO0_EN" type="INT32">
      <short_desc>Gyro 0 enabled</short_desc>
      <boolean />
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="CAL_GYRO0_ID" type="INT32">
      <short_desc>ID of the Gyro that the calibration is for</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="CAL_GYRO0_XOFF" type="FLOAT">
      <short_desc>Gyro X-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="CAL_GYRO0_XSCALE" type="FLOAT">
      <short_desc>Gyro X-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="CAL_GYRO0_YOFF" type="FLOAT">
      <short_desc>Gyro Y-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="CAL_GYRO0_YSCALE" type="FLOAT">
      <short_desc>Gyro Y-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="CAL_GYRO0_ZOFF" type="FLOAT">
      <short_desc>Gyro Z-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="CAL_GYRO0_ZSCALE" type="FLOAT">
      <short_desc>Gyro Z-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1" name="CAL_GYRO1_EN" type="INT32">
      <short_desc>Gyro 1 enabled</short_desc>
      <boolean />
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="CAL_GYRO1_ID" type="INT32">
      <short_desc>ID of the Gyro that the calibration is for</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="CAL_GYRO1_XOFF" type="FLOAT">
      <short_desc>Gyro X-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="CAL_GYRO1_XSCALE" type="FLOAT">
      <short_desc>Gyro X-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="CAL_GYRO1_YOFF" type="FLOAT">
      <short_desc>Gyro Y-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="CAL_GYRO1_YSCALE" type="FLOAT">
      <short_desc>Gyro Y-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="CAL_GYRO1_ZOFF" type="FLOAT">
      <short_desc>Gyro Z-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="CAL_GYRO1_ZSCALE" type="FLOAT">
      <short_desc>Gyro Z-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1" name="CAL_GYRO2_EN" type="INT32">
      <short_desc>Gyro 2 enabled</short_desc>
      <boolean />
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="CAL_GYRO2_ID" type="INT32">
      <short_desc>ID of the Gyro that the calibration is for</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="CAL_GYRO2_XOFF" type="FLOAT">
      <short_desc>Gyro X-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="CAL_GYRO2_XSCALE" type="FLOAT">
      <short_desc>Gyro X-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="CAL_GYRO2_YOFF" type="FLOAT">
      <short_desc>Gyro Y-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="CAL_GYRO2_YSCALE" type="FLOAT">
      <short_desc>Gyro Y-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="CAL_GYRO2_ZOFF" type="FLOAT">
      <short_desc>Gyro Z-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="CAL_GYRO2_ZSCALE" type="FLOAT">
      <short_desc>Gyro Z-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="CAL_GYRO_PRIME" type="INT32">
      <short_desc>Primary gyro ID</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1" name="CAL_MAG0_EN" type="INT32">
      <short_desc>Mag 0 enabled</short_desc>
      <boolean />
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="CAL_MAG0_ID" type="INT32">
      <short_desc>ID of Magnetometer the calibration is for</short_desc>
      <scope>modules/sensors</scope>
    </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>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1">Internal mag</value>
        <value code="0">No rotation</value>
        <value code="1">Yaw 45°</value>
        <value code="2">Yaw 90°</value>
        <value code="3">Yaw 135°</value>
        <value code="4">Yaw 180°</value>
        <value code="5">Yaw 225°</value>
        <value code="6">Yaw 270°</value>
        <value code="7">Yaw 315°</value>
        <value code="8">Roll 180°</value>
        <value code="9">Roll 180°, Yaw 45°</value>
        <value code="10">Roll 180°, Yaw 90°</value>
        <value code="11">Roll 180°, Yaw 135°</value>
        <value code="12">Pitch 180°</value>
        <value code="13">Roll 180°, Yaw 225°</value>
        <value code="14">Roll 180°, Yaw 270°</value>
        <value code="15">Roll 180°, Yaw 315°</value>
        <value code="16">Roll 90°</value>
        <value code="17">Roll 90°, Yaw 45°</value>
        <value code="18">Roll 90°, Yaw 90°</value>
        <value code="19">Roll 90°, Yaw 135°</value>
        <value code="20">Roll 270°</value>
        <value code="21">Roll 270°, Yaw 45°</value>
        <value code="22">Roll 270°, Yaw 90°</value>
        <value code="23">Roll 270°, Yaw 135°</value>
        <value code="24">Pitch 90°</value>
        <value code="25">Pitch 270°</value>
      </values>
    </parameter>
    <parameter default="0.0" name="CAL_MAG0_XOFF" type="FLOAT">
      <short_desc>Magnetometer X-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="CAL_MAG0_XSCALE" type="FLOAT">
      <short_desc>Magnetometer X-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="CAL_MAG0_YOFF" type="FLOAT">
      <short_desc>Magnetometer Y-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="CAL_MAG0_YSCALE" type="FLOAT">
      <short_desc>Magnetometer Y-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="CAL_MAG0_ZOFF" type="FLOAT">
      <short_desc>Magnetometer Z-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="CAL_MAG0_ZSCALE" type="FLOAT">
      <short_desc>Magnetometer Z-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1" name="CAL_MAG1_EN" type="INT32">
      <short_desc>Mag 1 enabled</short_desc>
      <boolean />
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="CAL_MAG1_ID" type="INT32">
      <short_desc>ID of Magnetometer the calibration is for</short_desc>
      <scope>modules/sensors</scope>
    </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>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1">Internal mag</value>
        <value code="0">No rotation</value>
        <value code="1">Yaw 45°</value>
        <value code="2">Yaw 90°</value>
        <value code="3">Yaw 135°</value>
        <value code="4">Yaw 180°</value>
        <value code="5">Yaw 225°</value>
        <value code="6">Yaw 270°</value>
        <value code="7">Yaw 315°</value>
        <value code="8">Roll 180°</value>
        <value code="9">Roll 180°, Yaw 45°</value>
        <value code="10">Roll 180°, Yaw 90°</value>
        <value code="11">Roll 180°, Yaw 135°</value>
        <value code="12">Pitch 180°</value>
        <value code="13">Roll 180°, Yaw 225°</value>
        <value code="14">Roll 180°, Yaw 270°</value>
        <value code="15">Roll 180°, Yaw 315°</value>
        <value code="16">Roll 90°</value>
        <value code="17">Roll 90°, Yaw 45°</value>
        <value code="18">Roll 90°, Yaw 90°</value>
        <value code="19">Roll 90°, Yaw 135°</value>
        <value code="20">Roll 270°</value>
        <value code="21">Roll 270°, Yaw 45°</value>
        <value code="22">Roll 270°, Yaw 90°</value>
        <value code="23">Roll 270°, Yaw 135°</value>
        <value code="24">Pitch 90°</value>
        <value code="25">Pitch 270°</value>
      </values>
    </parameter>
    <parameter default="0.0" name="CAL_MAG1_XOFF" type="FLOAT">
      <short_desc>Magnetometer X-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="CAL_MAG1_XSCALE" type="FLOAT">
      <short_desc>Magnetometer X-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="CAL_MAG1_YOFF" type="FLOAT">
      <short_desc>Magnetometer Y-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="CAL_MAG1_YSCALE" type="FLOAT">
      <short_desc>Magnetometer Y-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="CAL_MAG1_ZOFF" type="FLOAT">
      <short_desc>Magnetometer Z-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="CAL_MAG1_ZSCALE" type="FLOAT">
      <short_desc>Magnetometer Z-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1" name="CAL_MAG2_EN" type="INT32">
      <short_desc>Mag 2 enabled</short_desc>
      <boolean />
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="CAL_MAG2_ID" type="INT32">
      <short_desc>ID of Magnetometer the calibration is for</short_desc>
      <scope>modules/sensors</scope>
    </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>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1">Internal mag</value>
        <value code="0">No rotation</value>
        <value code="1">Yaw 45°</value>
        <value code="2">Yaw 90°</value>
        <value code="3">Yaw 135°</value>
        <value code="4">Yaw 180°</value>
        <value code="5">Yaw 225°</value>
        <value code="6">Yaw 270°</value>
        <value code="7">Yaw 315°</value>
        <value code="8">Roll 180°</value>
        <value code="9">Roll 180°, Yaw 45°</value>
        <value code="10">Roll 180°, Yaw 90°</value>
        <value code="11">Roll 180°, Yaw 135°</value>
        <value code="12">Pitch 180°</value>
        <value code="13">Roll 180°, Yaw 225°</value>
        <value code="14">Roll 180°, Yaw 270°</value>
        <value code="15">Roll 180°, Yaw 315°</value>
        <value code="16">Roll 90°</value>
        <value code="17">Roll 90°, Yaw 45°</value>
        <value code="18">Roll 90°, Yaw 90°</value>
        <value code="19">Roll 90°, Yaw 135°</value>
        <value code="20">Roll 270°</value>
        <value code="21">Roll 270°, Yaw 45°</value>
        <value code="22">Roll 270°, Yaw 90°</value>
        <value code="23">Roll 270°, Yaw 135°</value>
        <value code="24">Pitch 90°</value>
        <value code="25">Pitch 270°</value>
      </values>
    </parameter>
    <parameter default="0.0" name="CAL_MAG2_XOFF" type="FLOAT">
      <short_desc>Magnetometer X-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="CAL_MAG2_XSCALE" type="FLOAT">
      <short_desc>Magnetometer X-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="CAL_MAG2_YOFF" type="FLOAT">
      <short_desc>Magnetometer Y-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="CAL_MAG2_YSCALE" type="FLOAT">
      <short_desc>Magnetometer Y-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="CAL_MAG2_ZOFF" type="FLOAT">
      <short_desc>Magnetometer Z-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="CAL_MAG2_ZSCALE" type="FLOAT">
      <short_desc>Magnetometer Z-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1" name="CAL_MAG3_EN" type="INT32">
      <short_desc>Mag 3 enabled</short_desc>
      <boolean />
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="CAL_MAG3_ID" type="INT32">
      <short_desc>ID of Magnetometer the calibration is for</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="-1" name="CAL_MAG3_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>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1">Internal mag</value>
        <value code="0">No rotation</value>
        <value code="1">Yaw 45°</value>
        <value code="2">Yaw 90°</value>
        <value code="3">Yaw 135°</value>
        <value code="4">Yaw 180°</value>
        <value code="5">Yaw 225°</value>
        <value code="6">Yaw 270°</value>
        <value code="7">Yaw 315°</value>
        <value code="8">Roll 180°</value>
        <value code="9">Roll 180°, Yaw 45°</value>
        <value code="10">Roll 180°, Yaw 90°</value>
        <value code="11">Roll 180°, Yaw 135°</value>
        <value code="12">Pitch 180°</value>
        <value code="13">Roll 180°, Yaw 225°</value>
        <value code="14">Roll 180°, Yaw 270°</value>
        <value code="15">Roll 180°, Yaw 315°</value>
        <value code="16">Roll 90°</value>
        <value code="17">Roll 90°, Yaw 45°</value>
        <value code="18">Roll 90°, Yaw 90°</value>
        <value code="19">Roll 90°, Yaw 135°</value>
        <value code="20">Roll 270°</value>
        <value code="21">Roll 270°, Yaw 45°</value>
        <value code="22">Roll 270°, Yaw 90°</value>
        <value code="23">Roll 270°, Yaw 135°</value>
        <value code="24">Pitch 90°</value>
        <value code="25">Pitch 270°</value>
      </values>
    </parameter>
    <parameter default="0.0" name="CAL_MAG3_XOFF" type="FLOAT">
      <short_desc>Magnetometer X-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="CAL_MAG3_XSCALE" type="FLOAT">
      <short_desc>Magnetometer X-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="CAL_MAG3_YOFF" type="FLOAT">
      <short_desc>Magnetometer Y-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="CAL_MAG3_YSCALE" type="FLOAT">
      <short_desc>Magnetometer Y-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="CAL_MAG3_ZOFF" type="FLOAT">
      <short_desc>Magnetometer Z-axis offset</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="CAL_MAG3_ZSCALE" type="FLOAT">
      <short_desc>Magnetometer Z-axis scaling factor</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="CAL_MAG_PRIME" type="INT32">
      <short_desc>Primary mag ID</short_desc>
      <scope>modules/sensors</scope>
    </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>
      <scope>modules/sensors</scope>
    </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>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.7" name="SENS_FLOW_MINRNG" type="FLOAT">
      <short_desc>Optical Flow minimum focus distance</short_desc>
      <long_desc>This parameter defines the minimum distance from ground required for the optical flow sensor to operate reliably. The sensor may be usable below this height, but accuracy will progressively reduce to loss of focus. *</long_desc>
      <scope>modules/sensors</scope>
    </parameter>
  </group>
  <group name="Sensors">
    <parameter default="63" name="CAL_MAG_SIDES" type="INT32">
      <short_desc>Bitfield selecting mag sides for calibration</short_desc>
      <long_desc>DETECT_ORIENTATION_TAIL_DOWN = 1 DETECT_ORIENTATION_NOSE_DOWN = 2 DETECT_ORIENTATION_LEFT = 4 DETECT_ORIENTATION_RIGHT = 8 DETECT_ORIENTATION_UPSIDE_DOWN = 16 DETECT_ORIENTATION_RIGHTSIDE_UP = 32</long_desc>
      <min>34</min>
      <max>63</max>
      <scope>modules/sensors</scope>
      <values>
        <value code="34">Two side calibration</value>
        <value code="38">Three side calibration</value>
        <value code="63">Six side calibration</value>
      </values>
    </parameter>
    <parameter default="30.0" name="IMU_ACCEL_CUTOFF" type="FLOAT">
      <short_desc>Driver level cutoff frequency for accel</short_desc>
      <long_desc>The cutoff frequency for the 2nd order butterworth filter on the accel driver. This features is currently supported by the mpu6000 and mpu9250. This only affects the signal sent to the controllers, not the estimators. 0 disables the filter.</long_desc>
      <min>0</min>
      <max>1000</max>
      <unit>Hz</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="80.0" name="IMU_GYRO_CUTOFF" type="FLOAT">
      <short_desc>Driver level cutoff frequency for gyro</short_desc>
      <long_desc>The cutoff frequency for the 2nd order butterworth filter on the gyro driver. This features is currently supported by the mpu6000 and mpu9250. This only affects the signal sent to the controllers, not the estimators. 0 disables the filter.</long_desc>
      <min>0</min>
      <max>1000</max>
      <unit>Hz</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
    </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>
      <scope>modules/sensors</scope>
    </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.</long_desc>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">No rotation</value>
        <value code="1">Yaw 45°</value>
        <value code="2">Yaw 90°</value>
        <value code="3">Yaw 135°</value>
        <value code="4">Yaw 180°</value>
        <value code="5">Yaw 225°</value>
        <value code="6">Yaw 270°</value>
        <value code="7">Yaw 315°</value>
        <value code="8">Roll 180°</value>
        <value code="9">Roll 180°, Yaw 45°</value>
        <value code="10">Roll 180°, Yaw 90°</value>
        <value code="11">Roll 180°, Yaw 135°</value>
        <value code="12">Pitch 180°</value>
        <value code="13">Roll 180°, Yaw 225°</value>
        <value code="14">Roll 180°, Yaw 270°</value>
        <value code="15">Roll 180°, Yaw 315°</value>
        <value code="16">Roll 90°</value>
        <value code="17">Roll 90°, Yaw 45°</value>
        <value code="18">Roll 90°, Yaw 90°</value>
        <value code="19">Roll 90°, Yaw 135°</value>
        <value code="20">Roll 270°</value>
        <value code="21">Roll 270°, Yaw 45°</value>
        <value code="22">Roll 270°, Yaw 90°</value>
        <value code="23">Roll 270°, Yaw 135°</value>
        <value code="24">Pitch 90°</value>
        <value code="25">Pitch 270°</value>
        <value code="26">Roll 270°, Yaw 270°</value>
        <value code="27">Roll 180°, Pitch 270°</value>
        <value code="28">Pitch 90°, Yaw 180</value>
        <value code="29">Pitch 90°, Roll 90°</value>
        <value code="30">Yaw 293°, Pitch 68°, Roll 90° (Solo)</value>
        <value code="31">Pitch 90°, Roll 270°</value>
        <value code="32">Pitch 9°, Yaw 180°</value>
        <value code="33">Pitch 45°</value>
        <value code="34">Pitch 315°</value>
      </values>
    </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>
      <unit>deg</unit>
      <scope>modules/sensors</scope>
    </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>
      <unit>deg</unit>
      <scope>modules/sensors</scope>
    </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>
      <unit>deg</unit>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="SENS_EN_LEDDAR1" type="INT32">
      <short_desc>LeddarOne rangefinder</short_desc>
      <boolean />
      <reboot_required>true</reboot_required>
      <scope>drivers/distance_sensor/leddar_one</scope>
    </parameter>
    <parameter default="0" name="SENS_EN_LL40LS" type="INT32">
      <short_desc>Lidar-Lite (LL40LS)</short_desc>
      <min>0</min>
      <max>2</max>
      <reboot_required>true</reboot_required>
      <scope>drivers/distance_sensor/ll40ls</scope>
      <values>
        <value code="0">Disabled</value>
        <value code="1">PWM</value>
        <value code="2">I2C</value>
      </values>
    </parameter>
    <parameter default="0" name="SENS_EN_MB12XX" type="INT32">
      <short_desc>Maxbotix Sonar (mb12xx)</short_desc>
      <boolean />
      <reboot_required>true</reboot_required>
      <scope>drivers/distance_sensor/mb12xx</scope>
    </parameter>
    <parameter default="0" name="SENS_EN_SF0X" type="INT32">
      <short_desc>Lightware laser rangefinder (serial)</short_desc>
      <min>0</min>
      <max>4</max>
      <reboot_required>true</reboot_required>
      <scope>drivers/distance_sensor/sf0x</scope>
      <values>
        <value code="0">Disabled</value>
        <value code="1">SF02</value>
        <value code="2">SF10/a</value>
        <value code="3">SF10/b</value>
        <value code="4">SF10/c</value>
        <value code="5">SF11/c</value>
      </values>
    </parameter>
    <parameter default="0" name="SENS_EN_SF1XX" type="INT32">
      <short_desc>Lightware SF1xx/SF20/LW20 laser rangefinder (i2c)</short_desc>
      <min>0</min>
      <max>5</max>
      <reboot_required>true</reboot_required>
      <scope>drivers/distance_sensor/sf1xx</scope>
      <values>
        <value code="0">Disabled</value>
        <value code="1">SF10/a</value>
        <value code="2">SF10/b</value>
        <value code="3">SF10/c</value>
        <value code="4">SF11/c</value>
        <value code="5">SF/LW20</value>
      </values>
    </parameter>
    <parameter default="0" name="SENS_EN_TFMINI" type="INT32">
      <short_desc>Benewake TFmini laser rangefinder</short_desc>
      <boolean />
      <reboot_required>true</reboot_required>
      <scope>drivers/distance_sensor/tfmini</scope>
    </parameter>
    <parameter default="-1" name="SENS_EN_THERMAL" type="INT32">
      <short_desc>Thermal control of sensor temperature</short_desc>
      <scope>modules/sensors</scope>
      <values>
        <value code="-1">Thermal control unavailable</value>
        <value code="0">Thermal control off</value>
      </values>
    </parameter>
    <parameter default="0" name="SENS_EN_TRANGER" type="INT32">
      <short_desc>TeraRanger Rangefinder (i2c)</short_desc>
      <min>0</min>
      <max>3</max>
      <reboot_required>true</reboot_required>
      <scope>drivers/distance_sensor/teraranger</scope>
      <values>
        <value code="0">Disabled</value>
        <value code="1">Autodetect</value>
        <value code="2">TROne</value>
        <value code="3">TREvo60m</value>
        <value code="4">TREvo600Hz</value>
      </values>
    </parameter>
    <parameter default="6" name="SENS_FLOW_ROT" type="INT32">
      <short_desc>PX4Flow board rotation</short_desc>
      <long_desc>This parameter defines the yaw rotation of the PX4FLOW board relative to the vehicle body frame. Zero rotation is defined as X on flow board pointing towards front of vehicle. The recommneded installation default for the PX4FLOW board is with the Y axis forward (270 deg yaw).</long_desc>
      <reboot_required>true</reboot_required>
      <scope>modules/sensors</scope>
      <values>
        <value code="0">No rotation</value>
        <value code="1">Yaw 45°</value>
        <value code="2">Yaw 90°</value>
        <value code="3">Yaw 135°</value>
        <value code="4">Yaw 180°</value>
        <value code="5">Yaw 225°</value>
        <value code="6">Yaw 270°</value>
        <value code="7">Yaw 315°</value>
      </values>
    </parameter>
  </group>
  <group name="Snapdragon UART ESC">
    <parameter default="250000" name="UART_ESC_BAUD" type="INT32">
      <short_desc>ESC UART baud rate</short_desc>
      <long_desc>Default rate is 250Kbps, whic is used in off-the-shelf QRP ESC products.</long_desc>
      <scope>platforms/qurt/fc_addon/uart_esc</scope>
    </parameter>
    <parameter default="2" name="UART_ESC_MODEL" type="INT32">
      <short_desc>ESC model</short_desc>
      <long_desc>See esc_model_t enum definition in uart_esc_dev.h for all supported ESC model enum values.</long_desc>
      <scope>platforms/qurt/fc_addon/uart_esc</scope>
      <values>
        <value code="0">ESC_200QX</value>
        <value code="1">ESC_350QX</value>
        <value code="2">ESC_210QC</value>
      </values>
    </parameter>
    <parameter default="4" name="UART_ESC_MOTOR1" type="INT32">
      <short_desc>Motor 1 Mapping</short_desc>
      <scope>platforms/qurt/fc_addon/uart_esc</scope>
    </parameter>
    <parameter default="2" name="UART_ESC_MOTOR2" type="INT32">
      <short_desc>Motor 2 Mapping</short_desc>
      <scope>platforms/qurt/fc_addon/uart_esc</scope>
    </parameter>
    <parameter default="1" name="UART_ESC_MOTOR3" type="INT32">
      <short_desc>Motor 3 Mapping</short_desc>
      <scope>platforms/qurt/fc_addon/uart_esc</scope>
    </parameter>
    <parameter default="3" name="UART_ESC_MOTOR4" type="INT32">
      <short_desc>Motor 4 Mapping</short_desc>
      <scope>platforms/qurt/fc_addon/uart_esc</scope>
    </parameter>
  </group>
  <group name="Subscriber Example">
    <parameter default="100" name="SUB_INTERV" type="INT32">
      <short_desc>Interval of one subscriber in the example in ms</short_desc>
      <unit>ms</unit>
      <scope>examples/subscriber</scope>
    </parameter>
    <parameter default="3.14" name="SUB_TESTF" type="FLOAT">
      <short_desc>Float Demonstration Parameter in the Example</short_desc>
      <scope>examples/subscriber</scope>
    </parameter>
  </group>
  <group name="Syslink">
    <parameter default="231" name="SLNK_RADIO_ADDR1" type="INT32">
      <short_desc>Operating address of the NRF51 (most significant byte)</short_desc>
      <scope>modules/syslink</scope>
    </parameter>
    <parameter default="3890735079" name="SLNK_RADIO_ADDR2" type="INT32">
      <short_desc>Operating address of the NRF51 (least significant 4 bytes)</short_desc>
      <scope>modules/syslink</scope>
    </parameter>
    <parameter default="80" name="SLNK_RADIO_CHAN" type="INT32">
      <short_desc>Operating channel of the NRF51</short_desc>
      <min>0</min>
      <max>125</max>
      <scope>modules/syslink</scope>
    </parameter>
    <parameter default="2" name="SLNK_RADIO_RATE" type="INT32">
      <short_desc>Operating datarate of the NRF51</short_desc>
      <min>0</min>
      <max>2</max>
      <scope>modules/syslink</scope>
    </parameter>
  </group>
  <group name="System">
    <parameter default="15" name="LED_RGB_MAXBRT" type="INT32">
      <short_desc>RGB Led brightness limit</short_desc>
      <long_desc>Set to 0 to disable, 1 for minimum brightness up to 15 (max)</long_desc>
      <min>0</min>
      <max>15</max>
      <scope>drivers/rgbled</scope>
    </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>
      <scope>modules/systemlib</scope>
      <values>
        <value code="0">Keep parameters</value>
        <value code="1">Reset parameters</value>
      </values>
    </parameter>
    <parameter default="0" name="SYS_AUTOSTART" type="INT32">
      <short_desc>Auto-start script index</short_desc>
      <long_desc>CHANGING THIS VALUE REQUIRES A RESTART. Defines the auto-start script used to bootstrap the system.</long_desc>
      <min>0</min>
      <max>99999</max>
      <reboot_required>true</reboot_required>
      <scope>modules/systemlib</scope>
    </parameter>
    <parameter default="0" name="SYS_CAL_ACCEL" type="INT32">
      <short_desc>Enable auto start of accelerometer thermal calibration at the next power up</short_desc>
      <long_desc>0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the the temperature calibration starts. default (0, no calibration)</long_desc>
      <min>0</min>
      <max>1</max>
      <scope>modules/systemlib</scope>
    </parameter>
    <parameter default="0" name="SYS_CAL_BARO" type="INT32">
      <short_desc>Enable auto start of barometer thermal calibration at the next power up</short_desc>
      <long_desc>0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the the temperature calibration starts. default (0, no calibration)</long_desc>
      <min>0</min>
      <max>1</max>
      <scope>modules/systemlib</scope>
    </parameter>
    <parameter default="0" name="SYS_CAL_GYRO" type="INT32">
      <short_desc>Enable auto start of rate gyro thermal calibration at the next power up</short_desc>
      <long_desc>0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the the temperature calibration starts. default (0, no calibration)</long_desc>
      <min>0</min>
      <max>1</max>
      <scope>modules/systemlib</scope>
    </parameter>
    <parameter default="24" name="SYS_CAL_TDEL" type="INT32">
      <short_desc>Required temperature rise during thermal calibration</short_desc>
      <long_desc>A temperature increase greater than this value is required during calibration. Calibration will complete for each sensor when the temperature increase above the starting temeprature exceeds the value set by SYS_CAL_TDEL. If the temperature rise is insufficient, the calibration will continue indefinitely and the board will need to be repowered to exit.</long_desc>
      <min>10</min>
      <unit>deg C</unit>
      <scope>modules/systemlib</scope>
    </parameter>
    <parameter default="10" name="SYS_CAL_TMAX" type="INT32">
      <short_desc>Maximum starting temperature for thermal calibration</short_desc>
      <long_desc>Temperature calibration will not start if the temperature of any sensor is higher than the value set by SYS_CAL_TMAX.</long_desc>
      <unit>deg C</unit>
      <scope>modules/systemlib</scope>
    </parameter>
    <parameter default="5" name="SYS_CAL_TMIN" type="INT32">
      <short_desc>Minimum starting temperature for thermal calibration</short_desc>
      <long_desc>Temperature calibration for each sensor will ignore data if the temperature is lower than the value set by SYS_CAL_TMIN.</long_desc>
      <unit>deg C</unit>
      <scope>modules/systemlib</scope>
    </parameter>
    <parameter default="157600" name="SYS_COMPANION" type="INT32">
      <short_desc>TELEM2 as companion computer link</short_desc>
      <long_desc>CHANGING THIS VALUE REQUIRES A RESTART. Configures the baud rate of the TELEM2 connector as companion computer interface.</long_desc>
      <min>0</min>
      <max>1921600</max>
      <reboot_required>true</reboot_required>
      <scope>modules/systemlib</scope>
      <values>
        <value code="0">Disabled</value>
        <value code="10">FrSky Telemetry</value>
        <value code="20">Crazyflie (Syslink)</value>
        <value code="57600">Companion Link (57600 baud, 8N1)</value>
        <value code="157600">OSD (57600 baud, 8N1)</value>
        <value code="257600">Command Receiver (57600 baud, 8N1)</value>
        <value code="319200">Normal Telemetry (19200 baud, 8N1)</value>
        <value code="338400">Normal Telemetry (38400 baud, 8N1)</value>
        <value code="357600">Normal Telemetry (57600 baud, 8N1)</value>
        <value code="419200">Iridium Telemetry (19200 baud, 8N1)</value>
        <value code="519200">Minimal Telemetry (19200 baud, 8N1)</value>
        <value code="538400">Minimal Telemetry (38400 baud, 8N1)</value>
        <value code="557600">Minimal Telemetry (57600 baud, 8N1)</value>
        <value code="921600">Companion Link (921600 baud, 8N1)</value>
        <value code="1921600">ESP8266 (921600 baud, 8N1)</value>
        <value code="3115200">Normal Telemetry (115200 baud, 8N1)</value>
        <value code="5115200">Minimal Telemetry (115200 baud, 8N1)</value>
      </values>
    </parameter>
    <parameter default="0" name="SYS_FMU_TASK" type="INT32">
      <short_desc>Run the FMU as a task to reduce latency</short_desc>
      <long_desc>If true, the FMU will run in a separate task instead of on the work queue. Set this if low latency is required, for example for racing. This is a trade-off between RAM usage and latency: running as a task, it requires a separate stack and directly polls on the control topics, whereas running on the work queue, it runs at a fixed update rate.</long_desc>
      <boolean />
      <reboot_required>true</reboot_required>
      <scope>drivers/px4fmu</scope>
    </parameter>
    <parameter default="0" name="SYS_HITL" type="INT32">
      <short_desc>Enable HITL mode on next boot</short_desc>
      <long_desc>While enabled the system will boot in HITL mode and not enable all sensors and checks. When disabled the same vehicle can be normally flown outdoors.</long_desc>
      <boolean />
      <reboot_required>true</reboot_required>
      <scope>modules/systemlib</scope>
    </parameter>
    <parameter default="1" name="SYS_LOGGER" type="INT32">
      <short_desc>SD logger</short_desc>
      <min>0</min>
      <max>1</max>
      <reboot_required>true</reboot_required>
      <scope>modules/systemlib</scope>
      <values>
        <value code="0">sdlog2 (legacy)</value>
        <value code="1">logger (default)</value>
      </values>
    </parameter>
    <parameter default="2" name="SYS_MC_EST_GROUP" type="INT32">
      <short_desc>Set multicopter estimator group</short_desc>
      <long_desc>Set the group of estimators used for multicopters and VTOLs</long_desc>
      <min>1</min>
      <max>2</max>
      <reboot_required>true</reboot_required>
      <scope>modules/systemlib</scope>
      <values>
        <value code="1">local_position_estimator, attitude_estimator_q</value>
        <value code="2">ekf2</value>
      </values>
    </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>
      <scope>modules/systemlib</scope>
    </parameter>
    <parameter category="System" default="2" name="SYS_RESTART_TYPE" type="INT32" volatile="true">
      <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>
      <scope>modules/systemlib</scope>
      <values>
        <value code="0">Data survives resets</value>
        <value code="1">Data survives in-flight resets only</value>
        <value code="2">Data does not survive reset</value>
      </values>
    </parameter>
    <parameter default="1" name="SYS_STCK_EN" type="INT32">
      <short_desc>Enable stack checking</short_desc>
      <boolean />
      <scope>modules/systemlib</scope>
    </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>
      <boolean />
      <reboot_required>true</reboot_required>
      <scope>drivers/px4io</scope>
    </parameter>
  </group>
  <group name="Testing">
    <parameter default="2" name="TEST_1" type="INT32">
      <short_desc>TEST_1</short_desc>
      <scope>systemcmds/tests</scope>
    </parameter>
    <parameter default="4" name="TEST_2" type="INT32">
      <short_desc>TEST_2</short_desc>
      <scope>systemcmds/tests</scope>
    </parameter>
    <parameter default="5.0" name="TEST_3" type="FLOAT">
      <short_desc>TEST_3</short_desc>
      <scope>systemcmds/tests</scope>
    </parameter>
    <parameter default="0.01" name="TEST_D" type="FLOAT">
      <short_desc>TEST_D</short_desc>
      <scope>lib/controllib/controllib_test</scope>
    </parameter>
    <parameter default="2.0" name="TEST_DEV" type="FLOAT">
      <short_desc>TEST_DEV</short_desc>
      <scope>lib/controllib/controllib_test</scope>
    </parameter>
    <parameter default="10.0" name="TEST_D_LP" type="FLOAT">
      <short_desc>TEST_D_LP</short_desc>
      <scope>lib/controllib/controllib_test</scope>
    </parameter>
    <parameter default="10.0" name="TEST_HP" type="FLOAT">
      <short_desc>TEST_HP</short_desc>
      <scope>lib/controllib/controllib_test</scope>
    </parameter>
    <parameter default="0.1" name="TEST_I" type="FLOAT">
      <short_desc>TEST_I</short_desc>
      <scope>lib/controllib/controllib_test</scope>
    </parameter>
    <parameter default="1.0" name="TEST_I_MAX" type="FLOAT">
      <short_desc>TEST_I_MAX</short_desc>
      <scope>lib/controllib/controllib_test</scope>
    </parameter>
    <parameter default="10.0" name="TEST_LP" type="FLOAT">
      <short_desc>TEST_LP</short_desc>
      <scope>lib/controllib/controllib_test</scope>
    </parameter>
    <parameter default="1.0" name="TEST_MAX" type="FLOAT">
      <short_desc>TEST_MAX</short_desc>
      <scope>lib/controllib/controllib_test</scope>
    </parameter>
    <parameter default="1.0" name="TEST_MEAN" type="FLOAT">
      <short_desc>TEST_MEAN</short_desc>
      <scope>lib/controllib/controllib_test</scope>
    </parameter>
    <parameter default="-1.0" name="TEST_MIN" type="FLOAT">
      <short_desc>TEST_MIN</short_desc>
      <scope>lib/controllib/controllib_test</scope>
    </parameter>
    <parameter default="0.2" name="TEST_P" type="FLOAT">
      <short_desc>TEST_P</short_desc>
      <scope>lib/controllib/controllib_test</scope>
    </parameter>
    <parameter default="12345678" name="TEST_PARAMS" type="INT32">
      <short_desc>TEST_PARAMS</short_desc>
      <scope>systemcmds/tests</scope>
    </parameter>
    <parameter default="16" name="TEST_RC2_X" type="INT32">
      <short_desc>TEST_RC2_X</short_desc>
      <scope>systemcmds/tests</scope>
    </parameter>
    <parameter default="8" name="TEST_RC_X" type="INT32">
      <short_desc>TEST_RC_X</short_desc>
      <scope>systemcmds/tests</scope>
    </parameter>
    <parameter default="0.5" name="TEST_TRIM" type="FLOAT">
      <short_desc>TEST_TRIM</short_desc>
      <scope>lib/controllib/controllib_test</scope>
    </parameter>
  </group>
  <group name="Thermal Compensation">
    <parameter default="0" name="TC_A0_ID" type="INT32">
      <short_desc>ID of Accelerometer that the calibration is for</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="TC_A0_SCL_0" type="FLOAT">
      <short_desc>Accelerometer scale factor - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="TC_A0_SCL_1" type="FLOAT">
      <short_desc>Accelerometer scale factor - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="TC_A0_SCL_2" type="FLOAT">
      <short_desc>Accelerometer scale factor - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="100.0" name="TC_A0_TMAX" type="FLOAT">
      <short_desc>Accelerometer calibration maximum temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A0_TMIN" type="FLOAT">
      <short_desc>Accelerometer calibration minimum temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="25.0" name="TC_A0_TREF" type="FLOAT">
      <short_desc>Accelerometer calibration reference temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A0_X0_0" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^0 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A0_X0_1" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^0 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A0_X0_2" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^0 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A0_X1_0" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^1 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A0_X1_1" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^1 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A0_X1_2" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^1 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A0_X2_0" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^2 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A0_X2_1" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^2 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A0_X2_2" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^2 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A0_X3_0" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^3 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A0_X3_1" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^3 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A0_X3_2" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^3 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="TC_A1_ID" type="INT32">
      <short_desc>ID of Accelerometer that the calibration is for</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="TC_A1_SCL_0" type="FLOAT">
      <short_desc>Accelerometer scale factor - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="TC_A1_SCL_1" type="FLOAT">
      <short_desc>Accelerometer scale factor - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="TC_A1_SCL_2" type="FLOAT">
      <short_desc>Accelerometer scale factor - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="100.0" name="TC_A1_TMAX" type="FLOAT">
      <short_desc>Accelerometer calibration maximum temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A1_TMIN" type="FLOAT">
      <short_desc>Accelerometer calibration minimum temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="25.0" name="TC_A1_TREF" type="FLOAT">
      <short_desc>Accelerometer calibration reference temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A1_X0_0" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^0 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A1_X0_1" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^0 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A1_X0_2" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^0 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A1_X1_0" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^1 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A1_X1_1" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^1 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A1_X1_2" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^1 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A1_X2_0" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^2 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A1_X2_1" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^2 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A1_X2_2" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^2 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A1_X3_0" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^3 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A1_X3_1" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^3 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A1_X3_2" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^3 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="TC_A2_ID" type="INT32">
      <short_desc>ID of Accelerometer that the calibration is for</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="TC_A2_SCL_0" type="FLOAT">
      <short_desc>Accelerometer scale factor - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="TC_A2_SCL_1" type="FLOAT">
      <short_desc>Accelerometer scale factor - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="TC_A2_SCL_2" type="FLOAT">
      <short_desc>Accelerometer scale factor - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="100.0" name="TC_A2_TMAX" type="FLOAT">
      <short_desc>Accelerometer calibration maximum temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A2_TMIN" type="FLOAT">
      <short_desc>Accelerometer calibration minimum temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="25.0" name="TC_A2_TREF" type="FLOAT">
      <short_desc>Accelerometer calibration reference temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A2_X0_0" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^0 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A2_X0_1" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^0 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A2_X0_2" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^0 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A2_X1_0" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^1 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A2_X1_1" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^1 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A2_X1_2" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^1 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A2_X2_0" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^2 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A2_X2_1" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^2 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A2_X2_2" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^2 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A2_X3_0" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^3 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A2_X3_1" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^3 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_A2_X3_2" type="FLOAT">
      <short_desc>Accelerometer offset temperature ^3 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="TC_A_ENABLE" type="INT32">
      <short_desc>Thermal compensation for accelerometer sensors</short_desc>
      <min>0</min>
      <max>1</max>
      <boolean />
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="TC_B0_ID" type="INT32">
      <short_desc>ID of Barometer that the calibration is for</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="TC_B0_SCL" type="FLOAT">
      <short_desc>Barometer scale factor - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="75.0" name="TC_B0_TMAX" type="FLOAT">
      <short_desc>Barometer calibration maximum temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="5.0" name="TC_B0_TMIN" type="FLOAT">
      <short_desc>Barometer calibration minimum temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="40.0" name="TC_B0_TREF" type="FLOAT">
      <short_desc>Barometer calibration reference temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_B0_X0" type="FLOAT">
      <short_desc>Barometer offset temperature ^0 polynomial coefficient</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_B0_X1" type="FLOAT">
      <short_desc>Barometer offset temperature ^1 polynomial coefficients</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_B0_X2" type="FLOAT">
      <short_desc>Barometer offset temperature ^2 polynomial coefficient</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_B0_X3" type="FLOAT">
      <short_desc>Barometer offset temperature ^3 polynomial coefficient</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_B0_X4" type="FLOAT">
      <short_desc>Barometer offset temperature ^4 polynomial coefficient</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_B0_X5" type="FLOAT">
      <short_desc>Barometer offset temperature ^5 polynomial coefficient</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="TC_B1_ID" type="INT32">
      <short_desc>ID of Barometer that the calibration is for</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="TC_B1_SCL" type="FLOAT">
      <short_desc>Barometer scale factor - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="75.0" name="TC_B1_TMAX" type="FLOAT">
      <short_desc>Barometer calibration maximum temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="5.0" name="TC_B1_TMIN" type="FLOAT">
      <short_desc>Barometer calibration minimum temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="40.0" name="TC_B1_TREF" type="FLOAT">
      <short_desc>Barometer calibration reference temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_B1_X0" type="FLOAT">
      <short_desc>Barometer offset temperature ^0 polynomial coefficient</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_B1_X1" type="FLOAT">
      <short_desc>Barometer offset temperature ^1 polynomial coefficients</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_B1_X2" type="FLOAT">
      <short_desc>Barometer offset temperature ^2 polynomial coefficient</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_B1_X3" type="FLOAT">
      <short_desc>Barometer offset temperature ^3 polynomial coefficient</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_B1_X4" type="FLOAT">
      <short_desc>Barometer offset temperature ^4 polynomial coefficient</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_B1_X5" type="FLOAT">
      <short_desc>Barometer offset temperature ^5 polynomial coefficient</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="TC_B2_ID" type="INT32">
      <short_desc>ID of Barometer that the calibration is for</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="TC_B2_SCL" type="FLOAT">
      <short_desc>Barometer scale factor - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="75.0" name="TC_B2_TMAX" type="FLOAT">
      <short_desc>Barometer calibration maximum temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="5.0" name="TC_B2_TMIN" type="FLOAT">
      <short_desc>Barometer calibration minimum temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="40.0" name="TC_B2_TREF" type="FLOAT">
      <short_desc>Barometer calibration reference temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_B2_X0" type="FLOAT">
      <short_desc>Barometer offset temperature ^0 polynomial coefficient</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_B2_X1" type="FLOAT">
      <short_desc>Barometer offset temperature ^1 polynomial coefficients</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_B2_X2" type="FLOAT">
      <short_desc>Barometer offset temperature ^2 polynomial coefficient</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_B2_X3" type="FLOAT">
      <short_desc>Barometer offset temperature ^3 polynomial coefficient</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_B2_X4" type="FLOAT">
      <short_desc>Barometer offset temperature ^4 polynomial coefficient</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_B2_X5" type="FLOAT">
      <short_desc>Barometer offset temperature ^5 polynomial coefficient</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="TC_B_ENABLE" type="INT32">
      <short_desc>Thermal compensation for barometric pressure sensors</short_desc>
      <min>0</min>
      <max>1</max>
      <boolean />
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="TC_G0_ID" type="INT32">
      <short_desc>ID of Gyro that the calibration is for</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="TC_G0_SCL_0" type="FLOAT">
      <short_desc>Gyro scale factor - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="TC_G0_SCL_1" type="FLOAT">
      <short_desc>Gyro scale factor - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="TC_G0_SCL_2" type="FLOAT">
      <short_desc>Gyro scale factor - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="100.0" name="TC_G0_TMAX" type="FLOAT">
      <short_desc>Gyro calibration maximum temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G0_TMIN" type="FLOAT">
      <short_desc>Gyro calibration minimum temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="25.0" name="TC_G0_TREF" type="FLOAT">
      <short_desc>Gyro calibration reference temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G0_X0_0" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^0 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G0_X0_1" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^0 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G0_X0_2" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^0 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G0_X1_0" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^1 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G0_X1_1" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^1 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G0_X1_2" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^1 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G0_X2_0" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^2 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G0_X2_1" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^2 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G0_X2_2" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^2 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G0_X3_0" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^3 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G0_X3_1" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^3 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G0_X3_2" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^3 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="TC_G1_ID" type="INT32">
      <short_desc>ID of Gyro that the calibration is for</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="TC_G1_SCL_0" type="FLOAT">
      <short_desc>Gyro scale factor - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="TC_G1_SCL_1" type="FLOAT">
      <short_desc>Gyro scale factor - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="TC_G1_SCL_2" type="FLOAT">
      <short_desc>Gyro scale factor - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="100.0" name="TC_G1_TMAX" type="FLOAT">
      <short_desc>Gyro calibration maximum temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G1_TMIN" type="FLOAT">
      <short_desc>Gyro calibration minimum temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="25.0" name="TC_G1_TREF" type="FLOAT">
      <short_desc>Gyro calibration reference temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G1_X0_0" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^0 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G1_X0_1" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^0 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G1_X0_2" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^0 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G1_X1_0" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^1 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G1_X1_1" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^1 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G1_X1_2" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^1 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G1_X2_0" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^2 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G1_X2_1" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^2 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G1_X2_2" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^2 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G1_X3_0" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^3 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G1_X3_1" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^3 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G1_X3_2" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^3 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="TC_G2_ID" type="INT32">
      <short_desc>ID of Gyro that the calibration is for</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="TC_G2_SCL_0" type="FLOAT">
      <short_desc>Gyro scale factor - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="TC_G2_SCL_1" type="FLOAT">
      <short_desc>Gyro scale factor - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="1.0" name="TC_G2_SCL_2" type="FLOAT">
      <short_desc>Gyro scale factor - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="100.0" name="TC_G2_TMAX" type="FLOAT">
      <short_desc>Gyro calibration maximum temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G2_TMIN" type="FLOAT">
      <short_desc>Gyro calibration minimum temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="25.0" name="TC_G2_TREF" type="FLOAT">
      <short_desc>Gyro calibration reference temperature</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G2_X0_0" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^0 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G2_X0_1" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^0 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G2_X0_2" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^0 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G2_X1_0" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^1 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G2_X1_1" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^1 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G2_X1_2" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^1 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G2_X2_0" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^2 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G2_X2_1" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^2 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G2_X2_2" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^2 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G2_X3_0" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^3 polynomial coefficient - X axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G2_X3_1" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^3 polynomial coefficient - Y axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0.0" name="TC_G2_X3_2" type="FLOAT">
      <short_desc>Gyro rate offset temperature ^3 polynomial coefficient - Z axis</short_desc>
      <scope>modules/sensors</scope>
    </parameter>
    <parameter default="0" name="TC_G_ENABLE" type="INT32">
      <short_desc>Thermal compensation for rate gyro sensors</short_desc>
      <min>0</min>
      <max>1</max>
      <boolean />
      <scope>modules/sensors</scope>
    </parameter>
  </group>
  <group name="UAVCAN">
    <parameter default="1000000" name="CANNODE_BITRATE" type="INT32">
      <short_desc>UAVCAN CAN bus bitrate</short_desc>
      <min>20000</min>
      <max>1000000</max>
      <scope>modules/uavcannode</scope>
    </parameter>
    <parameter default="120" name="CANNODE_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>
      <scope>modules/uavcannode</scope>
    </parameter>
    <parameter default="1000000" name="ESC_BITRATE" type="INT32">
      <short_desc>UAVCAN CAN bus bitrate</short_desc>
      <min>20000</min>
      <max>1000000</max>
      <scope>modules/uavcanesc</scope>
    </parameter>
    <parameter default="120" name="ESC_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>
      <scope>modules/uavcanesc</scope>
    </parameter>
    <parameter default="1000000" name="UAVCAN_BITRATE" type="INT32">
      <short_desc>UAVCAN CAN bus bitrate</short_desc>
      <min>20000</min>
      <max>1000000</max>
      <unit>bit/s</unit>
      <reboot_required>true</reboot_required>
      <scope>modules/uavcan</scope>
    </parameter>
    <parameter default="0" name="UAVCAN_ENABLE" type="INT32">
      <short_desc>UAVCAN mode</short_desc>
      <long_desc>0 - UAVCAN disabled. 1 - Enables support for UAVCAN sensors without dynamic node ID allocation and firmware update. 2 - Enables support for UAVCAN sensors with dynamic node ID allocation and firmware update. 3 - Enables support for UAVCAN sensors and actuators with dynamic node ID allocation and firmware update. Also sets the motor control outputs to UAVCAN.</long_desc>
      <min>0</min>
      <max>3</max>
      <reboot_required>true</reboot_required>
      <scope>modules/uavcan</scope>
      <values>
        <value code="0">Disabled</value>
        <value code="1">Sensors Manual Config</value>
        <value code="2">Sensors Automatic Config</value>
        <value code="3">Sensors and Actuators (ESCs) Automatic Config</value>
      </values>
    </parameter>
    <parameter default="1" name="UAVCAN_ESC_IDLT" type="INT32">
      <short_desc>UAVCAN ESC will spin at idle throttle when armed, even if the mixer outputs zero setpoints</short_desc>
      <boolean />
      <reboot_required>true</reboot_required>
      <scope>modules/uavcan</scope>
    </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>
      <reboot_required>true</reboot_required>
      <scope>modules/uavcan</scope>
    </parameter>
  </group>
  <group name="VTOL Attitude Control">
    <parameter default="8.0" name="VT_ARSP_BLEND" type="FLOAT">
      <short_desc>Transition blending airspeed</short_desc>
      <long_desc>Airspeed at which we can start blending both fw and mc controls. Set to 0 to disable.</long_desc>
      <min>0.00</min>
      <max>30.00</max>
      <unit>m/s</unit>
      <decimal>2</decimal>
      <increment>1</increment>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="10.0" name="VT_ARSP_TRANS" type="FLOAT">
      <short_desc>Transition airspeed</short_desc>
      <long_desc>Airspeed at which we can switch to fw mode</long_desc>
      <min>0.00</min>
      <max>30.00</max>
      <unit>m/s</unit>
      <decimal>2</decimal>
      <increment>1</increment>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="2.0" name="VT_B_DEC_MSS" type="FLOAT">
      <short_desc>Approximate deceleration during back transition</short_desc>
      <long_desc>The approximate deceleration during a back transition in m/s/s Used to calculate back transition distance in mission mode. A lower value will make the VTOL transition further from the destination waypoint.</long_desc>
      <min>0.00</min>
      <max>20.00</max>
      <unit>m/s/s</unit>
      <decimal>2</decimal>
      <increment>1</increment>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="0.0" name="VT_B_REV_DEL" type="FLOAT">
      <short_desc>Delay in seconds before applying back transition throttle
Set this to a value greater than 0 to give the motor time to spin down</short_desc>
      <long_desc>unit s</long_desc>
      <min>0</min>
      <max>10</max>
      <decimal>2</decimal>
      <increment>1</increment>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="0.0" name="VT_B_REV_OUT" type="FLOAT">
      <short_desc>Output on airbrakes channel during back transition
Used for airbrakes or with ESCs that have reverse thrust enabled on a seperate channel
Airbrakes need to be enables for your selected model/mixer</short_desc>
      <min>0</min>
      <max>1</max>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="4.0" name="VT_B_TRANS_DUR" type="FLOAT">
      <short_desc>Duration of a back transition</short_desc>
      <long_desc>Time in seconds used for a back transition</long_desc>
      <min>0.00</min>
      <max>20.00</max>
      <unit>s</unit>
      <decimal>2</decimal>
      <increment>1</increment>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="3.0" name="VT_B_TRANS_RAMP" type="FLOAT">
      <short_desc>Back transition MC motor ramp up time</short_desc>
      <long_desc>This sets the duration during wich the MC motors ramp up to the commanded thrust during the back transition stage.</long_desc>
      <min>0.0</min>
      <max>20.0</max>
      <unit>s</unit>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="0.0" name="VT_B_TRANS_THR" type="FLOAT">
      <short_desc>Target throttle value for the transition to hover flight.
standard vtol: pusher
tailsitter, tiltrotor: main throttle</short_desc>
      <long_desc>Note for standard vtol: For ESCs and mixers that support reverse thrust on low PWM values set this to a negative value to apply active breaking For ESCs that support thrust reversal with a control channel please set VT_B_REV_OUT and set this to a positive value to apply active breaking</long_desc>
      <min>-1</min>
      <max>1</max>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="5.0" name="VT_DWN_PITCH_MAX" type="FLOAT">
      <short_desc>Maximum allowed down-pitch the controller is able to demand. This prevents large, negative
lift values being created when facing strong winds. The vehicle will use the pusher motor
to accelerate forward if necessary</short_desc>
      <min>0.0</min>
      <max>45.0</max>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="1" name="VT_ELEV_MC_LOCK" type="INT32">
      <short_desc>Lock elevons in multicopter mode</short_desc>
      <long_desc>If set to 1 the elevons are locked in multicopter mode</long_desc>
      <boolean />
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="0.0" name="VT_FWD_THRUST_SC" type="FLOAT">
      <short_desc>Fixed wing thrust scale for hover forward flight</short_desc>
      <long_desc>Scale applied to fixed wing thrust being used as source for forward acceleration in multirotor mode. This technique can be used to avoid the plane having to pitch down a lot in order to move forward. Setting this value to 0 (default) will disable this strategy.</long_desc>
      <min>0.0</min>
      <max>2.0</max>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="0.0" name="VT_FW_ALT_ERR" type="FLOAT">
      <short_desc>Adaptive QuadChute</short_desc>
      <long_desc>Maximum negative altitude error for fixed wing flight. If the altitude drops below this value below the altitude setpoint the vehicle will transition back to MC mode and enter failsafe RTL.</long_desc>
      <min>0.0</min>
      <max>200.0</max>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="0" name="VT_FW_DIFTHR_EN" type="INT32">
      <short_desc>Differential thrust in forwards flight</short_desc>
      <long_desc>Set to 1 to enable differential thrust in fixed-wing flight.</long_desc>
      <min>0</min>
      <max>1</max>
      <decimal>0</decimal>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="0.1" name="VT_FW_DIFTHR_SC" type="FLOAT">
      <short_desc>Differential thrust scaling factor</short_desc>
      <long_desc>This factor specifies how the yaw input gets mapped to differential thrust in forwards flight.</long_desc>
      <min>0.0</min>
      <max>1.0</max>
      <decimal>2</decimal>
      <increment>0.1</increment>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="0.0" name="VT_FW_MIN_ALT" type="FLOAT">
      <short_desc>QuadChute Altitude</short_desc>
      <long_desc>Minimum altitude for fixed wing flight, when in fixed wing the altitude drops below this altitude the vehicle will transition back to MC mode and enter failsafe RTL</long_desc>
      <min>0.0</min>
      <max>200.0</max>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="0" name="VT_FW_MOT_OFFID" type="INT32">
      <short_desc>The channel number of motors that must be turned off in fixed wing mode</short_desc>
      <min>0</min>
      <max>12345678</max>
      <decimal>0</decimal>
      <increment>1</increment>
      <scope>modules/vtol_att_control</scope>
    </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>
      <boolean />
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="0" name="VT_FW_QC_P" type="INT32">
      <short_desc>QuadChute Max Pitch</short_desc>
      <long_desc>Maximum pitch angle before QuadChute engages Above this the vehicle will transition back to MC mode and enter failsafe RTL</long_desc>
      <min>0</min>
      <max>180</max>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="0" name="VT_FW_QC_R" type="INT32">
      <short_desc>QuadChute Max Roll</short_desc>
      <long_desc>Maximum roll angle before QuadChute engages Above this the vehicle will transition back to MC mode and enter failsafe RTL</long_desc>
      <min>0</min>
      <max>180</max>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="5.0" name="VT_F_TRANS_DUR" type="FLOAT">
      <short_desc>Duration of a front transition</short_desc>
      <long_desc>Time in seconds used for a transition</long_desc>
      <min>0.00</min>
      <max>20.00</max>
      <unit>s</unit>
      <decimal>2</decimal>
      <increment>1</increment>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="1.0" name="VT_F_TRANS_THR" type="FLOAT">
      <short_desc>Target throttle value for the transition to fixed wing flight.
standard vtol: pusher
tailsitter, tiltrotor: main throttle</short_desc>
      <min>0.0</min>
      <max>1.0</max>
      <decimal>3</decimal>
      <increment>0.01</increment>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="6.0" name="VT_F_TR_OL_TM" type="FLOAT">
      <short_desc>Airspeed less front transition time (open loop)</short_desc>
      <long_desc>The duration of the front transition when there is no airspeed feedback available.</long_desc>
      <min>1.0</min>
      <max>30.0</max>
      <unit>seconds</unit>
      <scope>modules/vtol_att_control</scope>
    </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>
      <max>2000</max>
      <unit>us</unit>
      <decimal>0</decimal>
      <increment>1</increment>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="0" name="VT_MOT_COUNT" type="INT32">
      <short_desc>VTOL number of engines</short_desc>
      <min>0</min>
      <max>8</max>
      <decimal>0</decimal>
      <increment>1</increment>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="3.0" name="VT_PSHER_RMP_DT" type="FLOAT">
      <short_desc>Defines the time window during which the pusher throttle will be ramped up linearly to VT_F_TRANS_THR during a transition
to fixed wing mode. Zero or negative values will produce an instant throttle rise to VT_F_TRANS_THR</short_desc>
      <max>20</max>
      <decimal>2</decimal>
      <increment>0.01</increment>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="1.0" name="VT_TILT_FW" type="FLOAT">
      <short_desc>Position of tilt servo in fw mode</short_desc>
      <min>0.0</min>
      <max>1.0</max>
      <decimal>3</decimal>
      <increment>0.01</increment>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="0.0" name="VT_TILT_MC" type="FLOAT">
      <short_desc>Position of tilt servo in mc mode</short_desc>
      <min>0.0</min>
      <max>1.0</max>
      <decimal>3</decimal>
      <increment>0.01</increment>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="0.3" name="VT_TILT_TRANS" type="FLOAT">
      <short_desc>Position of tilt servo in transition mode</short_desc>
      <min>0.0</min>
      <max>1.0</max>
      <decimal>3</decimal>
      <increment>0.01</increment>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="2.0" name="VT_TRANS_MIN_TM" type="FLOAT">
      <short_desc>Front transition minimum time</short_desc>
      <long_desc>Minimum time in seconds for front transition.</long_desc>
      <min>0.0</min>
      <max>20.0</max>
      <unit>s</unit>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="0.5" name="VT_TRANS_P2_DUR" type="FLOAT">
      <short_desc>Duration of front transition phase 2</short_desc>
      <long_desc>Time in seconds it should take for the rotors to rotate forward completely from the point when the plane has picked up enough airspeed and is ready to go into fixed wind mode.</long_desc>
      <min>0.1</min>
      <max>5.0</max>
      <unit>s</unit>
      <decimal>3</decimal>
      <increment>0.01</increment>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="15.0" name="VT_TRANS_TIMEOUT" type="FLOAT">
      <short_desc>Front transition timeout</short_desc>
      <long_desc>Time in seconds after which transition will be cancelled. Disabled if set to 0.</long_desc>
      <min>0.00</min>
      <max>30.00</max>
      <unit>s</unit>
      <decimal>2</decimal>
      <increment>1</increment>
      <scope>modules/vtol_att_control</scope>
    </parameter>
    <parameter default="0" name="VT_TYPE" type="INT32">
      <short_desc>VTOL Type (Tailsitter=0, Tiltrotor=1, Standard=2)</short_desc>
      <min>0</min>
      <max>2</max>
      <decimal>0</decimal>
      <scope>modules/vtol_att_control</scope>
      <values>
        <value code="0">Tailsitter</value>
        <value code="1">Tiltrotor</value>
        <value code="2">Standard</value>
      </values>
    </parameter>
    <parameter default="0.15" name="VT_WV_YAWR_SCL" type="FLOAT">
      <short_desc>Weather-vane yaw rate scale</short_desc>
      <long_desc>The desired yawrate from the controller will be scaled in order to avoid yaw fighting against the wind.</long_desc>
      <min>0.0</min>
      <max>1.0</max>
      <decimal>3</decimal>
      <increment>0.01</increment>
      <scope>modules/vtol_att_control</scope>
    </parameter>
  </group>
  <group name="Wind Estimator">
    <parameter default="1" name="WEST_BETA_GATE" type="INT32">
      <short_desc>Gate size for true sideslip fusion</short_desc>
      <long_desc>Sets the number of standard deviations used by the innovation consistency test.</long_desc>
      <min>1</min>
      <max>5</max>
      <unit>SD</unit>
      <scope>modules/wind_estimator</scope>
    </parameter>
    <parameter default="0.3" name="WEST_BETA_NOISE" type="FLOAT">
      <short_desc>Wind estimator sideslip measurement noise</short_desc>
      <min>0</min>
      <max>1</max>
      <unit>rad</unit>
      <scope>modules/wind_estimator</scope>
    </parameter>
    <parameter default="0.0001" name="WEST_SC_P_NOISE" type="FLOAT">
      <short_desc>Wind estimator true airspeed scale process noise</short_desc>
      <min>0</min>
      <max>0.1</max>
      <scope>modules/wind_estimator</scope>
    </parameter>
    <parameter default="3" name="WEST_TAS_GATE" type="INT32">
      <short_desc>Gate size for true airspeed fusion</short_desc>
      <long_desc>Sets the number of standard deviations used by the innovation consistency test.</long_desc>
      <min>1</min>
      <max>5</max>
      <unit>SD</unit>
      <scope>modules/wind_estimator</scope>
    </parameter>
    <parameter default="1.4" name="WEST_TAS_NOISE" type="FLOAT">
      <short_desc>Wind estimator true airspeed measurement noise</short_desc>
      <min>0</min>
      <max>4</max>
      <unit>m/s</unit>
      <scope>modules/wind_estimator</scope>
    </parameter>
    <parameter default="0.1" name="WEST_W_P_NOISE" type="FLOAT">
      <short_desc>Wind estimator wind process noise</short_desc>
      <min>0</min>
      <max>1</max>
      <unit>m/s/s</unit>
      <scope>modules/wind_estimator</scope>
    </parameter>
  </group>
  <group name="Miscellaneous">
    <parameter default="0.1" name="EXFW_HDNG_P" type="FLOAT">
      <short_desc>EXFW_HDNG_P</short_desc>
      <scope>examples/fixedwing_control</scope>
    </parameter>
    <parameter default="0.2" name="EXFW_PITCH_P" type="FLOAT">
      <short_desc>EXFW_PITCH_P</short_desc>
      <scope>examples/fixedwing_control</scope>
    </parameter>
    <parameter default="0.2" name="EXFW_ROLL_P" type="FLOAT">
      <short_desc>EXFW_ROLL_P</short_desc>
      <scope>examples/fixedwing_control</scope>
    </parameter>
    <parameter default="0.1" name="RV_YAW_P" type="FLOAT">
      <short_desc>RV_YAW_P</short_desc>
      <scope>examples/rover_steering_control</scope>
    </parameter>
    <parameter default="1.0" name="SEG_Q2V" type="FLOAT">
      <short_desc>SEG_Q2V</short_desc>
      <scope>examples/segway</scope>
    </parameter>
    <parameter default="0.0" name="SEG_TH2V_I" type="FLOAT">
      <short_desc>SEG_TH2V_I</short_desc>
      <scope>examples/segway</scope>
    </parameter>
    <parameter default="0.0" name="SEG_TH2V_I_MAX" type="FLOAT">
      <short_desc>SEG_TH2V_I_MAX</short_desc>
      <scope>examples/segway</scope>
    </parameter>
    <parameter default="10.0" name="SEG_TH2V_P" type="FLOAT">
      <short_desc>SEG_TH2V_P</short_desc>
      <scope>examples/segway</scope>
    </parameter>
  </group>
</parameters>