LP-327 - Configurable max allowed variance parameter
[librepilot.git] / shared / uavobjectdefinition / stabilizationsettings.xml
blobebec36efb1b8093ec992c520a461813960aaf462
1 <xml>
3     <object name="StabilizationSettings" singleinstance="true" settings="true" category="Control">
4         <description>PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired</description>
6         <!-- Note: The number of elements here must match the number of available flight mode switch positions -->
7         <field name="FlightModeMap" units="" type="enum"
8             options="Bank1,Bank2,Bank3"
9             elements="6"
10             defaultvalue="Bank1,Bank1,Bank1,Bank1,Bank1,Bank1"/>
12         <field name="VbarSensitivity" units="frac" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="0.5,0.5,0.5"/>
13         <field name="VbarRollPI" units="1/(deg/s)" type="float" elementnames="Kp,Ki" defaultvalue="0.005,0.002"/>
14         <field name="VbarPitchPI" units="1/(deg/s)" type="float" elementnames="Kp,Ki" defaultvalue="0.005,0.002"/>
15         <field name="VbarYawPI" units="1/(deg/s)" type="float" elementnames="Kp,Ki" defaultvalue="0.005,0.002"/>
16         <field name="VbarTau" units="sec" type="float" elements="1" defaultvalue="0.5"/>
17         <field name="VbarGyroSuppress" units="%" type="int8" elements="1" defaultvalue="30"/>
18         <field name="VbarPiroComp" units="" type="enum" elements="1" options="False,True" defaultvalue="False"/>
19         <field name="VbarMaxAngle" units="deg" type="uint8" elements="1" defaultvalue="10"/>
21         <field name="GyroTau" units="" type="float" elements="1" defaultvalue="0.003"/>
22         <field name="DerivativeCutoff" units="Hz" type="uint8" elements="1" defaultvalue="20"/>
23         <field name="DerivativeGamma" units="" type="float" elements="1" defaultvalue="1"/>
25         <field name="AxisLockKp" units="" type="float" elements="1" defaultvalue="2.5"/>
26         <field name="MaxAxisLock" units="deg" type="uint8" elements="1" defaultvalue="30"/>
27         <field name="MaxAxisLockRate" units="deg/s" type="uint8" elements="1" defaultvalue="2"/>
29         <field name="WeakLevelingKp" units="(deg/s)/deg" type="float" elements="1" defaultvalue="0.1"/>
30         <field name="MaxWeakLevelingRate" units="deg/s" type="uint8" elements="1" defaultvalue="5"/>
32         <field name="RattitudeModeTransition" units="%" type="uint8" elements="1" defaultvalue="80"/>
34         <field name="CruiseControlMinThrust"           units="%"   type="int8"  elements="1" defaultvalue="5"/>
35         <field name="CruiseControlMaxThrust"           units="%"   type="uint8" elements="1" defaultvalue="100"/>
36         <field name="CruiseControlMaxAngle"            units="deg" type="uint8" elements="1" defaultvalue="105"/>
37         <field name="CruiseControlMaxPowerFactor"      units="x"   type="float" elements="1" defaultvalue="3.0"/>
38         <field name="CruiseControlPowerTrim"           units="%"   type="float" elements="1" defaultvalue="100.0"/>
39         <field name="CruiseControlPowerDelayComp"      units="sec" type="float" elements="1" defaultvalue="0.25"/>
40         <field name="CruiseControlFlightModeSwitchPosEnable" units="" type="enum" elements="6" options="False,True" defaultvalue="False"/>
42         <field name="CruiseControlInvertedThrustReversing" units="" type="enum" elements="1" options="Unreversed,Reversed" defaultvalue="Unreversed"/>
43         <field name="CruiseControlInvertedPowerOutput"     units="" type="enum" elements="1" options="Zero,Normal,Boosted" defaultvalue="Zero"/>
45         <field name="LowThrottleZeroIntegral" units="" type="enum" elements="1" options="False,True" defaultvalue="True"/>
47         <field name="ScaleToAirspeed" units="m/s" type="float" elements="1" defaultvalue="0"/>
48         <field name="ScaleToAirspeedLimits" units="" type="float" elementnames="Min,Max" defaultvalue="0.05,3"/>
49         <field name="FlightModeAssistMap" units="" type="enum" options="None,GPSAssist" elements="6" defaultvalue="None,None,None,None,None,None" />
51         <field name="MeasureBasedDTerm" units="" type="enum" elements="1" options="False,True" defaultvalue="True"/>
53         <access gcs="readwrite" flight="readwrite"/>
54         <telemetrygcs acked="true" updatemode="onchange" period="0"/>
55         <telemetryflight acked="true" updatemode="onchange" period="0"/>
56         <logging updatemode="manual" period="0"/>
57     </object>
58 </xml>