1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-18 03:52:11 +01:00

Categorizing all UAVObjects into 5 main categories:

State, Sensors, System, Navigation, Control
This commit is contained in:
Corvus Corax 2013-06-22 19:58:54 +02:00
parent 6163c5f53a
commit 6f38e26a53
68 changed files with 81 additions and 81 deletions

View File

@ -1,5 +1,5 @@
<xml>
<object name="AccessoryDesired" singleinstance="false" settings="false">
<object name="AccessoryDesired" singleinstance="false" settings="false" category="Control">
<description>Desired Auxillary actuator settings. Comes from @ref ManualControlModule.</description>
<field name="AccessoryVal" units="" type="float" elements="1"/>
<access gcs="readwrite" flight="readwrite"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="ActuatorCommand" singleinstance="true" settings="false">
<object name="ActuatorCommand" singleinstance="true" settings="false" category="Control">
<description>Contains the pulse duration sent to each of the channels. Set by @ref ActuatorModule</description>
<field name="Channel" units="us" type="int16" elements="12"/>
<field name="UpdateTime" units="ms" type="uint16" elements="1"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="ActuatorDesired" singleinstance="true" settings="false">
<object name="ActuatorDesired" singleinstance="true" settings="false" category="Control">
<description>Desired raw, pitch and yaw actuator settings. Comes from either @ref StabilizationModule or @ref ManualControlModule depending on FlightMode.</description>
<field name="Roll" units="%" type="float" elements="1"/>
<field name="Pitch" units="%" type="float" elements="1"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="ActuatorSettings" singleinstance="true" settings="true">
<object name="ActuatorSettings" singleinstance="true" settings="true" category="Control">
<description>Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType</description>
<field name="ChannelUpdateFreq" units="Hz" type="uint16" elements="6" defaultvalue="50"/>
<field name="ChannelMax" units="us" type="int16" elements="12" defaultvalue="1000"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="AirspeedSettings" singleinstance="true" settings="true">
<object name="AirspeedSettings" singleinstance="true" settings="true" category="Sensors">
<description>Settings for the @ref BaroAirspeed module used on CopterControl or Revolution</description>
<field name="SamplePeriod" units="ms" type="uint8" elements="1" defaultvalue="100"/>
<field name="ZeroPoint" units="raw" type="uint16" elements="1" defaultvalue="0"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="AltHoldSmoothed" singleinstance="true" settings="false">
<object name="AltHoldSmoothed" singleinstance="true" settings="false" category="State">
<description>The output on the kalman filter on altitude.</description>
<field name="Altitude" units="m" type="float" elements="1"/>
<field name="Velocity" units="m/s" type="float" elements="1"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="AltitudeHoldDesired" singleinstance="true" settings="false">
<object name="AltitudeHoldDesired" singleinstance="true" settings="false" category="Control">
<description>Holds the desired altitude (from manual control) as well as the desired attitude to pass through</description>
<field name="Altitude" units="m" type="float" elements="1"/>
<field name="Roll" units="deg" type="float" elements="1"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="AltitudeHoldSettings" singleinstance="true" settings="true">
<object name="AltitudeHoldSettings" singleinstance="true" settings="true" category="Control">
<description>Settings for the @ref AltitudeHold module</description>
<field name="Kp" units="throttle/m" type="float" elements="1" defaultvalue="0.0001"/>
<field name="Ki" units="throttle/m" type="float" elements="1" defaultvalue="0"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="AttitudeSettings" singleinstance="true" settings="true">
<object name="AttitudeSettings" singleinstance="true" settings="true" category="State">
<description>Settings for the @ref Attitude module used on CopterControl</description>
<field name="AccelBias" units="lsb" type="int16" elementnames="X,Y,Z" defaultvalue="0"/>
<field name="GyroBias" units="deg/s * 100" type="int16" elementnames="X,Y,Z" defaultvalue="0"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="AttitudeSimulated" singleinstance="true" settings="false">
<object name="AttitudeSimulated" singleinstance="true" settings="false" category="State">
<description>The simulated Attitude estimation from @ref Sensors.</description>
<field name="q1" units="" type="float" elements="1"/>
<field name="q2" units="" type="float" elements="1"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="CameraDesired" singleinstance="true" settings="false">
<object name="CameraDesired" singleinstance="true" settings="false" category="Control">
<description>Desired camera outputs. Comes from @ref CameraStabilization module.</description>
<field name="RollOrServo1" units="" type="float" elements="1"/>
<field name="PitchOrServo2" units="" type="float" elements="1"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="CameraStabSettings" singleinstance="true" settings="true">
<object name="CameraStabSettings" singleinstance="true" settings="true" category="Control">
<description>Settings for the @ref CameraStab mmodule</description>
<field name="Input" units="channel" type="enum" elementnames="Roll,Pitch,Yaw" options="Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5,None" defaultvalue="None"/>
<field name="InputRange" units="deg" type="uint8" elementnames="Roll,Pitch,Yaw" defaultvalue="20"/>

View File

@ -1,9 +1,9 @@
<xml>
<object name="EKFConfiguration" singleinstance="true" settings="true">
<object name="EKFConfiguration" singleinstance="true" settings="true" category="State">
<description>Extended Kalman Filter initialisation</description>
<field name="P" units="1^2" type="float" defaultvalue="
25.0, 25.0, 25.0,
5.0, 5.0, 5.0,
10.0, 10.0, 10.0,
1.0, 1.0, 1.0,
0.007, 0.007, 0.007, 0.007,
0.0001, 0.0001, 0.0001">
<elementnames>
@ -23,9 +23,9 @@
</elementnames>
</field>
<field name="Q" units="1^2" type="float" defaultvalue="
0.001, 0.001, 0.001,
0.01, 0.01, 0.01,
0.1, 0.1, 0.1,
0.000000002, 0.000000002, 0.000000002">
0.0000001, 0.0000001, 0.0000001">
<elementnames>
<elementname>GyroX</elementname>
<elementname>GyroY</elementname>
@ -39,10 +39,10 @@
</elementnames>
</field>
<field name="R" units="1^2" type="float" defaultvalue="
1.0, 1.0, 1.0,
0.1, 0.1, 0.1,
10000.0, 10000.0, 10000.0,
0.1">
10, 10, 1000,
1, 1, 1,
1000, 1000, 1000,
1">
<elementnames>
<elementname>GPSPosNorth</elementname>
<elementname>GPSPosEast</elementname>
@ -57,9 +57,9 @@
</elementnames>
</field>
<field name="FakeR" type="float" units="1^2" defaultvalue="
10000,
1000,
100">
10,
1,
1000">
<elementnames>
<elementname>FakeGPSPosIndoor</elementname>
<elementname>FakeGPSVelIndoor</elementname>

View File

@ -1,5 +1,5 @@
<xml>
<object name="EKFStateVariance" singleinstance="true" settings="false">
<object name="EKFStateVariance" singleinstance="true" settings="false" category="State">
<description>Extended Kalman Filter state covariance</description>
<field name="P" units="1^2" type="float">
<elementnames>

View File

@ -1,5 +1,5 @@
<xml>
<object name="FaultSettings" singleinstance="true" settings="true">
<object name="FaultSettings" singleinstance="true" settings="true" category="System">
<description>Allows testers to simulate various fault scenarios.</description>
<field name="ActivateFault" units="fault" type="enum" elements="1" options="NoFault,ModuleInitAssert,InitOutOfMemory,InitBusError,RunawayTask,TaskOutOfMemory" defaultvalue="NoFault"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="FirmwareIAPObj" singleinstance="true" settings="false">
<object name="FirmwareIAPObj" singleinstance="true" settings="false" category="System">
<description>Queries board for SN, model, revision, and sends reset command</description>
<field name="Command" units="" type="uint16" elements="1"/>
<field name="Description" units="" type="uint8" elements="100"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="FixedWingPathFollowerSettings" singleinstance="true" settings="true">
<object name="FixedWingPathFollowerSettings" singleinstance="true" settings="true" category="Control">
<description>Settings for the @ref FixedWingPathFollowerModule</description>
<!-- these coefficients control desired movement in airspace -->

View File

@ -1,5 +1,5 @@
<xml>
<object name="FixedWingPathFollowerStatus" singleinstance="true" settings="false">
<object name="FixedWingPathFollowerStatus" singleinstance="true" settings="false" category="Control">
<description>Object Storing Debugging Information on PID internals</description>
<field name="Error" units="" type="float" elementnames="Bearing,Speed,Power" />
<field name="ErrorInt" units="" type="float" elementnames="Bearing,Speed,Power" />

View File

@ -1,5 +1,5 @@
<xml>
<object name="FlightBatterySettings" singleinstance="true" settings="true">
<object name="FlightBatterySettings" singleinstance="true" settings="true" category="Sensors">
<description>Flight Battery configuration.</description>
<field name="Type" units="" type="enum" elements="1" options="LiPo,A123,LiCo,LiFeSO4,None" defaultvalue="LiPo"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="FlightBatteryState" singleinstance="true" settings="false">
<object name="FlightBatteryState" singleinstance="true" settings="false" category="Sensors">
<description>Battery status information.</description>
<field name="Voltage" units="V" type="float" elements="1" defaultvalue="0.0"/>
<field name="Current" units="A" type="float" elements="1" defaultvalue="0.0"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="FlightPlanControl" singleinstance="true" settings="false">
<object name="FlightPlanControl" singleinstance="true" settings="false" category="Navigation">
<description>Control the flight plan script</description>
<field name="Command" units="" type="enum" options="Start,Stop,Kill" defaultvalue="Start" elements="1"/>
<access gcs="readwrite" flight="readwrite"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="FlightPlanSettings" singleinstance="true" settings="true">
<object name="FlightPlanSettings" singleinstance="true" settings="true" category="Navigation">
<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"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="FlightPlanStatus" singleinstance="true" settings="false">
<object name="FlightPlanStatus" singleinstance="true" settings="false" category="Navigation">
<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"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="FlightStatus" singleinstance="true" settings="false">
<object name="FlightStatus" singleinstance="true" settings="false" category="Control">
<description>Contains major flight status information for other modules.</description>
<field name="Armed" units="" type="enum" elements="1" options="Disarmed,Arming,Armed" defaultvalue="Disarmed"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="FlightTelemetryStats" singleinstance="true" settings="false">
<object name="FlightTelemetryStats" singleinstance="true" settings="false" category="System">
<description>Maintains the telemetry statistics from the OpenPilot flight computer.</description>
<field name="Status" units="" type="enum" elements="1" options="Disconnected,HandshakeReq,HandshakeAck,Connected"/>
<field name="TxDataRate" units="bytes/sec" type="float" elements="1"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="GCSReceiver" singleinstance="true" settings="false">
<object name="GCSReceiver" singleinstance="true" settings="false" category="Control">
<description>A receiver channel group carried over the telemetry link.</description>
<field name="Channel" units="us" type="uint16" elements="8"/>
<access gcs="readwrite" flight="readwrite"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="GCSTelemetryStats" singleinstance="true" settings="false">
<object name="GCSTelemetryStats" singleinstance="true" settings="false" category="System">
<description>The telemetry statistics from the ground computer</description>
<field name="Status" units="" type="enum" elements="1" options="Disconnected,HandshakeReq,HandshakeAck,Connected"/>
<field name="TxDataRate" units="bytes/sec" type="float" elements="1"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="GPSSatellites" singleinstance="true" settings="false">
<object name="GPSSatellites" singleinstance="true" settings="false" category="Sensors">
<description>Contains information about the GPS satellites in view from @ref GPSModule.</description>
<field name="SatsInView" units="" type="int8" elements="1"/>
<field name="PRN" units="" type="int8" elements="16"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="GPSTime" singleinstance="true" settings="false">
<object name="GPSTime" singleinstance="true" settings="false" category="Sensors">
<description>Contains the GPS time from @ref GPSModule. Required to compute the world magnetic model correctly when setting the home location.</description>
<field name="Month" units="" type="int8" elements="1"/>
<field name="Day" units="" type="int8" elements="1"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="GroundTruth" singleinstance="true" settings="false">
<object name="GroundTruth" singleinstance="true" settings="false" category="State">
<description>Ground truth data output by a simulator.</description>
<field name="AccelerationXYZ" units="m/s^2" type="float" elements="3"/>
<field name="PositionNED" units="m" type="float" elements="3"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="HomeLocation" singleinstance="true" settings="true">
<object name="HomeLocation" singleinstance="true" settings="true" category="Navigation">
<description>HomeLocation setting which contains the constants to tranlate from longitutde and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule.</description>
<field name="Set" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
<field name="Latitude" units="deg * 10e6" type="int32" elements="1" defaultvalue="0"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="HwSettings" singleinstance="true" settings="true">
<object name="HwSettings" singleinstance="true" settings="true" category="System">
<description>Selection of optional hardware configurations.</description>
<field name="CC_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+PWM,PPM+Outputs,Outputs" defaultvalue="PWM"/>
<field name="CC_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM2,DSMX (10bit),DSMX (11bit),DebugConsole,ComBridge,OsdHk" defaultvalue="Telemetry"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="I2CStats" singleinstance="true" settings="false">
<object name="I2CStats" singleinstance="true" settings="false" category="System">
<description>Tracks statistics on the I2C bus.</description>
<field name="event_errors" units="" type="uint8" elements="1"/>
<field name="fsm_errors" units="" type="uint8" elements="1"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="ManualControlCommand" singleinstance="true" settings="false">
<object name="ManualControlCommand" singleinstance="true" settings="false" category="Control">
<description>The output from the @ref ManualControlModule which descodes the receiver inputs. Overriden by GCS for fly-by-wire control.</description>
<field name="Connected" units="" type="enum" elements="1" options="False,True"/>
<field name="Throttle" units="%" type="float" elements="1"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="ManualControlSettings" singleinstance="true" settings="true">
<object name="ManualControlSettings" singleinstance="true" settings="true" category="Control">
<description>Settings to indicate how to decode receiver input by @ref ManualControlModule.</description>
<field name="ChannelGroups" units="Channel Group" type="enum"
elementnames="Throttle,Roll,Pitch,Yaw,FlightMode,Collective,Accessory0,Accessory1,Accessory2"

View File

@ -1,5 +1,5 @@
<xml>
<object name="MixerSettings" singleinstance="true" settings="true">
<object name="MixerSettings" singleinstance="true" settings="true" category="Control">
<description>Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType</description>
<field name="MaxAccel" units="units/sec" type="float" elements="1" defaultvalue="1000"/>
<field name="FeedForward" units="" type="float" elements="1" defaultvalue="0"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="MixerStatus" singleinstance="true" settings="false">
<object name="MixerStatus" singleinstance="true" settings="false" category="Control">
<description>Status for the matrix mixer showing the output of each mixer after all scaling</description>
<field name="Mixer1" units="" type="float" elements="1"/>
<field name="Mixer2" units="" type="float" elements="1"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="NedAccel" singleinstance="true" settings="false">
<object name="NedAccel" singleinstance="true" settings="false" category="State">
<description>The projection of acceleration in the NED reference frame used by @ref Guidance.</description>
<field name="North" units="m/s^2" type="float" elements="1"/>
<field name="East" units="m/s^2" type="float" elements="1"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="ObjectPersistence" singleinstance="true" settings="false">
<object name="ObjectPersistence" singleinstance="true" settings="false" category="System">
<description>Someone who knows please enter this</description>
<field name="Operation" units="" type="enum" elements="1" options="NOP,Load,Save,Delete,FullErase,Completed,Error"/>
<field name="Selection" units="" type="enum" elements="1" options="SingleObject,AllSettings,AllMetaObjects,AllObjects"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="OPLinkSettings" singleinstance="true" settings="true">
<object name="OPLinkSettings" singleinstance="true" settings="true" category="System">
<description>OPLink configurations options.</description>
<field name="Bindings" units="hex" type="uint32" elements="8" defaultvalue="0"/>
<field name="RemoteMainPort" units="" type="enum" elements="8" options="Disabled,Serial,PPM" defaultvalue="Disabled"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="OPLinkStatus" singleinstance="true" settings="false">
<object name="OPLinkStatus" singleinstance="true" settings="false" category="System">
<description>OPLink device status.</description>
<field name="Description" units="" type="uint8" elements="40"/>
<field name="CPUSerial" units="hex" type="uint8" elements="12" />

View File

@ -1,5 +1,5 @@
<xml>
<object name="OsdSettings" singleinstance="true" settings="true">
<object name="OsdSettings" singleinstance="true" settings="true" category="System">
<description>OSD settings used by the OSDgen module</description>
<field name="Attitude" units="" type="enum" elements="1" options="Disabled,Enabled" defaultvalue="Enabled"/>
<field name="AttitudeSetup" units="" type="int16" elements="2" elementnames="X,Y" defaultvalue="168,135"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="OveroSyncSettings" singleinstance="true" settings="true">
<object name="OveroSyncSettings" singleinstance="true" settings="true" category="System">
<description>Settings to control the behavior of the overo sync module</description>
<field name="LogOn" units="" type="enum" options="Never,Always,Armed" elements="1" defaultvalue="Armed"/>
<access gcs="readwrite" flight="readwrite"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="OveroSyncStats" singleinstance="true" settings="false">
<object name="OveroSyncStats" singleinstance="true" settings="false" category="System">
<description>Maintains statistics on transfer rate to and from over</description>
<field name="Connected" units="" type="enum" options="False,True" elements="1" default="False"/>
<field name="Send" units="B/s" type="uint32" elements="1"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="PathAction" singleinstance="false" settings="false">
<object name="PathAction" singleinstance="false" settings="false" category="Navigation">
<description>A waypoint command the pathplanner is to use at a certain waypoint</description>
<field name="Mode" units="" type="enum" elements="1" options="FlyEndpoint,FlyVector,FlyCircleRight,FlyCircleLeft,
DriveEndpoint,DriveVector,DriveCircleLeft,DriveCircleRight,

View File

@ -1,5 +1,5 @@
<xml>
<object name="PathDesired" singleinstance="true" settings="false">
<object name="PathDesired" singleinstance="true" settings="false" category="Navigation">
<description>The endpoint or path the craft is trying to achieve. Can come from @ref ManualControl or @ref PathPlanner </description>
<field name="Start" units="m" type="float" elementnames="North,East,Down" default="0"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="PathStatus" singleinstance="true" settings="false">
<object name="PathStatus" singleinstance="true" settings="false" category="Navigation">
<description>Status of the current path mode Can come from any @ref PathFollower module</description>
<field name="UID" units="" type="int16" elements="1" default="0"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="PoiLearnSettings" singleinstance="true" settings="true">
<object name="PoiLearnSettings" singleinstance="true" settings="true" category="Control">
<description>Settings for the @ref Point of Interest feature</description>
<field name="Input" units="channel" type="enum" elements="1" options="Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5,None" defaultvalue="None"/>
<access gcs="readwrite" flight="readwrite"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="PoiLocation" singleinstance="true" settings="false">
<object name="PoiLocation" singleinstance="true" settings="false" category="Control">
<description>Contains the current Point of interest relative to @ref HomeLocation</description>
<field name="North" units="m" type="float" elements="1"/>
<field name="East" units="m" type="float" elements="1"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="RateDesired" singleinstance="true" settings="false">
<object name="RateDesired" singleinstance="true" settings="false" category="Control">
<description>Status for the matrix mixer showing the output of each mixer after all scaling</description>
<field name="Roll" units="deg/s" type="float" elements="1"/>
<field name="Pitch" units="deg/s" type="float" elements="1"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="ReceiverActivity" singleinstance="true" settings="false">
<object name="ReceiverActivity" singleinstance="true" settings="false" category="System">
<description>Monitors which receiver channels have been active within the last second.</description>
<field name="ActiveGroup" units="Channel Group" type="enum" elements="1"
options="PWM,PPM,DSM (MainPort),DSM (FlexiPort),S.Bus,GCS,OPLink,None"

View File

@ -1,5 +1,5 @@
<xml>
<object name="RelayTuning" singleinstance="true" settings="false">
<object name="RelayTuning" singleinstance="true" settings="false" category="Control">
<description>The input to the relay tuning.</description>
<field name="Period" units="ms" type="float" elementnames="Roll,Pitch,Yaw"/>
<field name="Gain" units="(deg/s)/output" type="float" elementnames="Roll,Pitch,Yaw"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="RelayTuningSettings" singleinstance="true" settings="true">
<object name="RelayTuningSettings" singleinstance="true" settings="true" category="Control">
<description>Setting to run a relay tuning algorithm</description>
<field name="RateGain" units="" type="float" elements="1" defaultvalue="0.3333"/>
<field name="AttitudeGain" units="" type="float" elements="1" defaultvalue="0.2"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="RevoCalibration" singleinstance="true" settings="true">
<object name="RevoCalibration" singleinstance="true" settings="true" category="Sensors">
<description>Settings for the INS to control the algorithm and what is updated</description>

View File

@ -1,5 +1,5 @@
<xml>
<object name="RevoSettings" singleinstance="true" settings="true">
<object name="RevoSettings" singleinstance="true" settings="true" category="State">
<description>Settings for the revo to control the algorithm and what is updated</description>
<field name="FusionAlgorithm" units="" type="enum" elements="1" options="None,Complementary,Complementary+Mag,INS13Indoor,INS13Outdoor,INS16Indoor,INS16Outdoor" defaultvalue="Complementary"/>
<access gcs="readwrite" flight="readwrite"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="SonarAltitude" singleinstance="true" settings="false">
<object name="SonarAltitude" singleinstance="true" settings="false" category="Sensors">
<description>The raw data from the ultrasound sonar sensor with altitude estimate.</description>
<field name="Altitude" units="m" type="float" elements="1"/>
<access gcs="readwrite" flight="readwrite"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="StabilizationDesired" singleinstance="true" settings="false">
<object name="StabilizationDesired" singleinstance="true" settings="false" category="Control">
<description>The desired attitude that @ref StabilizationModule will try and achieve if FlightMode is Stabilized. Comes from @ref ManaulControlModule.</description>
<field name="Roll" units="degrees" type="float" elements="1"/>
<field name="Pitch" units="degrees" type="float" elements="1"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="StabilizationSettings" singleinstance="true" settings="true">
<object name="StabilizationSettings" singleinstance="true" settings="true" category="Control">
<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="42" limits="%BE:0:180"/>
<field name="PitchMax" units="degrees" type="uint8" elements="1" defaultvalue="42" limits="%BE:0:180"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="SystemAlarms" singleinstance="true" settings="false">
<object name="SystemAlarms" singleinstance="true" settings="false" category="System">
<description>Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules. Some modules may have a module defined Status and Substatus fields that details its condition.</description>
<field name="Alarm" units="" type="enum" options="Uninitialised,OK,Warning,Error,Critical" defaultvalue="Uninitialised">
<elementnames>

View File

@ -1,5 +1,5 @@
<xml>
<object name="SystemSettings" singleinstance="true" settings="true">
<object name="SystemSettings" singleinstance="true" settings="true" category="System">
<description>Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand</description>
<field name="AirframeType" units="" type="enum" elements="1" options="FixedWing,FixedWingElevon,FixedWingVtail,VTOL,HeliCP,QuadX,QuadP,Hexa,Octo,Custom,HexaX,OctoV,OctoCoaxP,OctoCoaxX,HexaCoax,Tri,GroundVehicleCar,GroundVehicleDifferential,GroundVehicleMotorcycle" defaultvalue="QuadX"/>
<field name="GUIConfigData" units="bits" type="uint32" elements="4" defaultvalue="0"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="SystemStats" singleinstance="true" settings="false">
<object name="SystemStats" singleinstance="true" settings="false" category="System">
<description>CPU and memory usage from OpenPilot computer. </description>
<field name="FlightTime" units="ms" type="uint32" elements="1"/>
<field name="HeapRemaining" units="bytes" type="uint16" elements="1"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="TaskInfo" singleinstance="true" settings="false">
<object name="TaskInfo" singleinstance="true" settings="false" category="System">
<description>Task information</description>
<field name="StackRemaining" units="bytes" type="uint16">
<elementnames>

View File

@ -1,5 +1,5 @@
<xml>
<object name="TxPIDSettings" singleinstance="true" settings="true">
<object name="TxPIDSettings" singleinstance="true" settings="true" category="Control">
<description>Settings used by @ref TxPID optional module to tune PID settings using R/C transmitter</description>
<field name="UpdateMode" units="option" type="enum" elements="1" options="Never,When Armed,Always" defaultvalue="When Armed"/>
<field name="Inputs" units="channel" type="enum"

View File

@ -1,5 +1,5 @@
<xml>
<object name="VelocityDesired" singleinstance="true" settings="false">
<object name="VelocityDesired" singleinstance="true" settings="false" category="Control">
<description>Used within @ref GuidanceModule to communicate between the task computing the desired velocity and the PID loop to achieve it (running at different rates).</description>
<field name="North" units="m/s" type="float" elements="1"/>
<field name="East" units="m/s" type="float" elements="1"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="VtolPathFollowerSettings" singleinstance="true" settings="true">
<object name="VtolPathFollowerSettings" singleinstance="true" settings="true" category="Control">
<description>Settings for the @ref VtolPathFollowerModule</description>
<field name="GuidanceMode" units="" type="enum" elements="1" options="DUAL_LOOP,VELOCITY_CONTROL" defaultvalue="DUAL_LOOP"/>
<field name="HorizontalVelMax" units="m/s" type="uint16" elements="1" defaultvalue="10"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="WatchdogStatus" singleinstance="true" settings="false">
<object name="WatchdogStatus" singleinstance="true" settings="false" category="System">
<description>For monitoring the flags in the watchdog and especially the bootup flags</description>
<field name="BootupFlags" units="" type="uint16" elements="1"/>
<field name="ActiveFlags" units="" type="uint16" elements="1"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="Waypoint" singleinstance="false" settings="false">
<object name="Waypoint" singleinstance="false" settings="false" category="Navigation">
<description>A waypoint the aircraft can try and hit. Used by the @ref PathPlanner module</description>
<field name="Position" units="m" type="float" elementnames="North, East, Down"/>
<field name="Velocity" units="m/s" type="float" elements="1"/>

View File

@ -1,5 +1,5 @@
<xml>
<object name="WaypointActive" singleinstance="true" settings="false">
<object name="WaypointActive" singleinstance="true" settings="false" category="Navigation">
<description>Indicates the currently active waypoint</description>
<field name="Index" units="" type="int16" elements="1"/>
<access gcs="readwrite" flight="readwrite"/>