1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2024-12-01 09:24:10 +01:00

OP-316 UAVObject Fix typo, indents, units, default values

git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2896 ebee16cc-31ac-478f-84a7-5cbb03baadba
This commit is contained in:
loris 2011-02-27 00:38:59 +00:00 committed by loris
parent ea390d0b90
commit 6e942d786a
16 changed files with 54 additions and 54 deletions

View File

@ -3,20 +3,20 @@
<description>Contains the calibration settings for the @ref AHRSCommsModule</description>
<field name="measure_var" units="" type="enum" elements="1" options="SET,MEASURE" defaultvalue="SET"/>
<field name="accel_bias" units="m/s^2" type="float" elementnames="X,Y,Z" defaultvalue="-73.5,-73.5,73.5"/>
<field name="accel_scale" units="m/s^2" type="float" elementnames="X,Y,Z" defaultvalue="0.0359,0.0359,-0.0359"/>
<field name="accel_scale" units="(m/s^2)/lsb" type="float" elementnames="X,Y,Z" defaultvalue="0.0359,0.0359,-0.0359"/>
<field name="accel_var" units="(m/s^2)^2" type="float" elementnames="X,Y,Z" defaultvalue="5e-4"/>
<field name="gyro_bias" units="rad/s" type="float" elementnames="X,Y,Z" defaultvalue="23,-23,23"/>
<field name="gyro_scale" units="rad/s" type="float" elementnames="X,Y,Z" defaultvalue="-0.017,0.017,-0.017"/>
<field name="gyro_scale" units="(rad/s)/lsb" type="float" elementnames="X,Y,Z" defaultvalue="-0.017,0.017,-0.017"/>
<field name="gyro_var" units="(rad/s)^2" type="float" elementnames="X,Y,Z" defaultvalue="1e-4"/>
<field name="gyro_tempcompfactor" units="raw/raw" type="float" elementnames="X,Y,Z" defaultvalue="0"/>
<field name="mag_bias" units="mGau" type="float" elementnames="X,Y,Z" defaultvalue="0"/>
<field name="mag_scale" units="mGau" type="float" elementnames="X,Y,Z" defaultvalue="-2"/>
<field name="mag_scale" units="(mGau)/lsb" type="float" elementnames="X,Y,Z" defaultvalue="-2"/>
<field name="mag_var" units="mGau^2" type="float" elementnames="X,Y,Z" defaultvalue="50"/>
<field name="vel_var" units="(m/s)^2" type="float" elements="1" defaultvalue="0.4"/>
<field name="pos_var" units="m^2" type="float" elements="1" defaultvalue="0.4"/>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
<telemetryflight acked="true" updatemode="onchange" period="0"/>
<logging updatemode="never" period="0"/>
<logging updatemode="never" period="0"/>
</object>
</xml>

View File

@ -9,5 +9,5 @@
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
<telemetryflight acked="true" updatemode="onchange" period="0"/>
<logging updatemode="never" period="0"/>
</object>
</object>
</xml>

View File

@ -2,9 +2,9 @@
<object name="FlightPlanSettings" singleinstance="true" settings="true">
<description>Settings for the flight plan module, control the execution of the script</description>
<field name="Test" units="" type="float" elements="1" defaultvalue="0.0"/>
<access gcs="readwrite" flight="readwrite"/>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
<telemetryflight acked="true" updatemode="onchange" period="0"/>
<logging updatemode="never" period="0"/>
</object>
</object>
</xml>

View File

@ -1,15 +1,15 @@
<xml>
<object name="FlightPlanStatus" singleinstance="true" settings="false">
<description>Status of the flight plan script</description>
<field name="Status" units="" type="enum" elements="1" options="Stopped,Running,Error" defaultvalue="Stopped"/>
<field name="ErrorType" units="" type="enum" elements="1" options="None,VMInitError,Exception,IOError,DivByZero,AssertError,AttributeError,ImportError,IndexError,KeyError,MemoryError,NameError,SyntaxError,SystemError,TypeError,ValueError,StopIteration,Warning,UnknownError" defaultvalue="None"/>
<field name="ErrorFileID" units="" type="uint32" elements="1"/>
<field name="ErrorLineNum" units="" type="uint32" elements="1"/>
<field name="Debug1" units="" type="float" elements="1" defaultvalue="0.0"/>
<field name="Debug2" units="" type="float" elements="1" defaultvalue="0.0"/>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="false" updatemode="manual" period="0"/>
<telemetryflight acked="false" updatemode="periodic" period="2000"/>
<logging updatemode="never" period="0"/>
<description>Status of the flight plan script</description>
<field name="Status" units="" type="enum" elements="1" options="Stopped,Running,Error" defaultvalue="Stopped"/>
<field name="ErrorType" units="" type="enum" elements="1" options="None,VMInitError,Exception,IOError,DivByZero,AssertError,AttributeError,ImportError,IndexError,KeyError,MemoryError,NameError,SyntaxError,SystemError,TypeError,ValueError,StopIteration,Warning,UnknownError" defaultvalue="None"/>
<field name="ErrorFileID" units="" type="uint32" elements="1"/>
<field name="ErrorLineNum" units="" type="uint32" elements="1"/>
<field name="Debug1" units="" type="float" elements="1" defaultvalue="0.0"/>
<field name="Debug2" units="" type="float" elements="1" defaultvalue="0.0"/>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="false" updatemode="manual" period="0"/>
<telemetryflight acked="false" updatemode="periodic" period="2000"/>
<logging updatemode="never" period="0"/>
</object>
</xml>

View File

@ -11,5 +11,5 @@
<telemetrygcs acked="false" updatemode="manual" period="0"/>
<telemetryflight acked="false" updatemode="periodic" period="10000"/>
<logging updatemode="periodic" period="30000"/>
</object>
</object>
</xml>

View File

@ -2,12 +2,12 @@
<object name="GuidanceSettings" singleinstance="true" settings="true">
<description>Settings for the @ref GuidanceModule</description>
<field name="GuidanceMode" units="" type="enum" elements="1" options="DUAL_LOOP,VELOCITY_CONTROL" defaultvalue="DUAL_LOOP"/>
<field name="HorizontalP" units="(m/s)/m" type="float" elements="1" elementnames="Kp,Max" defaultvalue="0.2,200"/>
<field name="HorizontalVelPID" units="" type="float" elements="4" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.1,0,0,0"/>
<field name="VerticalP" units="" type="float" elements="1" elementnames="Kp,Max" defaultvalue="0.1,200"/>
<field name="VerticalVelPID" units="(m/s)/m" type="float" elements="4" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.1,0,0,0"/>
<field name="HorizontalP" units="" type="float" elementnames="Kp,Max" defaultvalue="0.2,150"/>
<field name="HorizontalVelPID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.1,0.002,0,1000"/>
<field name="VerticalP" units="" type="float" elementnames="Kp,Max" defaultvalue="0.1,200"/>
<field name="VerticalVelPID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.1,0,0,0"/>
<field name="ThrottleControl" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
<field name="MaxRollPitch" units="deg" type="float" elements="1" defaultvalue="10"/>
<field name="MaxRollPitch" units="deg" type="float" elements="1" defaultvalue="10"/>
<field name="UpdatePeriod" units="" type="int32" elements="1" defaultvalue="100"/>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/>

View File

@ -15,5 +15,5 @@
<telemetrygcs acked="false" updatemode="manual" period="0"/>
<telemetryflight acked="false" updatemode="periodic" period="10000"/>
<logging updatemode="periodic" period="30000"/>
</object>
</object>
</xml>

View File

@ -25,5 +25,5 @@
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
<telemetryflight acked="true" updatemode="onchange" period="0"/>
<logging updatemode="never" period="0"/>
</object>
</object>
</xml>

View File

@ -27,5 +27,5 @@
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
<telemetryflight acked="true" updatemode="onchange" period="0"/>
<logging updatemode="never" period="0"/>
</object>
</object>
</xml>

View File

@ -9,5 +9,5 @@
<telemetrygcs acked="true" updatemode="manual" period="0"/>
<telemetryflight acked="true" updatemode="manual" period="0"/>
<logging updatemode="never" period="0"/>
</object>
</object>
</xml>

View File

@ -8,5 +8,5 @@
<telemetrygcs acked="false" updatemode="manual" period="0"/>
<telemetryflight acked="false" updatemode="periodic" period="1000"/>
<logging updatemode="periodic" period="1000"/>
</object>
</object>
</xml>

View File

@ -1,22 +1,22 @@
<xml>
<object name="StabilizationSettings" singleinstance="true" settings="true">
<description>PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired</description>
<field name="RollMax" units="degrees" type="uint8" elements="1" defaultvalue="35"/>
<field name="PitchMax" units="degrees" type="uint8" elements="1" defaultvalue="35"/>
<field name="YawMax" units="degrees" type="uint8" elements="1" defaultvalue="35"/>
<field name="ManualRate" units="degrees/sec" type="float" elements="3" elementnames="Roll,Pitch,Yaw" defaultvalue="150,150,150"/>
<field name="MaximumRate" units="degrees/sec" type="float" elements="3" elementnames="Roll,Pitch,Yaw" defaultvalue="300,300,300"/>
<object name="StabilizationSettings" singleinstance="true" settings="true">
<description>PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired</description>
<field name="RollMax" units="degrees" type="uint8" elements="1" defaultvalue="35"/>
<field name="PitchMax" units="degrees" type="uint8" elements="1" defaultvalue="35"/>
<field name="YawMax" units="degrees" type="uint8" elements="1" defaultvalue="35"/>
<field name="ManualRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="150,150,150"/>
<field name="MaximumRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="300,300,300"/>
<field name="RollRatePI" units="" type="float" elements="2" elementnames="Kp,Ki,ILimit" defaultvalue="0.0015,0,0.5"/>
<field name="PitchRatePI" units="" type="float" elements="2" elementnames="Kp,Ki,ILimit" defaultvalue="0.0015,0,0.5"/>
<field name="YawRatePI" units="" type="float" elements="2" elementnames="Kp,Ki,ILimit" defaultvalue="0.003,0,0.5"/>
<field name="RollPI" units="" type="float" elements="4" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,0.5"/>
<field name="PitchPI" units="" type="float" elements="4" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,0.5"/>
<field name="YawPI" units="" type="float" elements="4" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,0.5"/>
<field name="RollRatePI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="0.0015,0,0.3"/>
<field name="PitchRatePI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="0.0015,0,0.3"/>
<field name="YawRatePI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="0.003,0,0.3"/>
<field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50"/>
<field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50"/>
<field name="YawPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50"/>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
<telemetryflight acked="true" updatemode="onchange" period="0"/>
<logging updatemode="never" period="0"/>
</object>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
<telemetryflight acked="true" updatemode="onchange" period="0"/>
<logging updatemode="never" period="0"/>
</object>
</xml>

View File

@ -6,5 +6,5 @@
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
<telemetryflight acked="true" updatemode="onchange" period="0"/>
<logging updatemode="never" period="0"/>
</object>
</object>
</xml>

View File

@ -9,5 +9,5 @@
<telemetrygcs acked="false" updatemode="manual" period="0"/>
<telemetryflight acked="false" updatemode="periodic" period="1000"/>
<logging updatemode="periodic" period="1000"/>
</object>
</object>
</xml>

View File

@ -6,5 +6,5 @@
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
<telemetryflight acked="true" updatemode="onchange" period="0"/>
<logging updatemode="never" period="0"/>
</object>
</object>
</xml>

View File

@ -1,6 +1,6 @@
<xml>
<object name="VelocityActual" singleinstance="true" settings="false">
<description>Updated by @ref AHRSCommsModule and used within @ref GuidanceModulefor velocity control</description>
<description>Updated by @ref AHRSCommsModule and used within @ref GuidanceModule for velocity control</description>
<field name="North" units="cm/s" type="int32" elements="1"/>
<field name="East" units="cm/s" type="int32" elements="1"/>
<field name="Down" units="cm/s" type="int32" elements="1"/>