Details | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
1702 | - | 1 | <?xml version="1.0"?> |
2 | <mavlink> |
||
3 | <include>common.xml</include> |
||
4 | |||
5 | <!-- <enums> |
||
6 | <enum name="SLUGS_ACTION" > |
||
7 | <description> Slugs Actions </description> |
||
8 | <entry name = "SLUGS_ACTION_NONE"> |
||
9 | <entry name = "SLUGS_ACTION_SUCCESS"> |
||
10 | <entry name = "SLUGS_ACTION_FAIL"> |
||
11 | <entry name = "SLUGS_ACTION_EEPROM"> |
||
12 | <entry name = "SLUGS_ACTION_MODE_CHANGE"> |
||
13 | <entry name = "SLUGS_ACTION_MODE_REPORT"> |
||
14 | <entry name = "SLUGS_ACTION_PT_CHANGE"> |
||
15 | <entry name = "SLUGS_ACTION_PT_REPORT"> |
||
16 | <entry name = "SLUGS_ACTION_PID_CHANGE"> |
||
17 | <entry name = "SLUGS_ACTION_PID_REPORT"> |
||
18 | <entry name = "SLUGS_ACTION_WP_CHANGE"> |
||
19 | <entry name = "SLUGS_ACTION_WP_REPORT"> |
||
20 | <entry name = "SLUGS_ACTION_MLC_CHANGE"> |
||
21 | <entry name = "SLUGS_ACTION_MLC_REPORT"> |
||
22 | </enum> |
||
23 | |||
24 | <enum name="WP_PROTOCOL_STATE" > |
||
25 | <description> Waypoint Protocol States </description> |
||
26 | <entry name = "WP_PROT_IDLE"> |
||
27 | <entry name = "WP_PROT_LIST_REQUESTED"> |
||
28 | <entry name = "WP_PROT_NUM_SENT"> |
||
29 | <entry name = "WP_PROT_TX_WP"> |
||
30 | <entry name = "WP_PROT_RX_WP"> |
||
31 | <entry name = "WP_PROT_SENDING_WP_IDLE"> |
||
32 | <entry name = "WP_PROT_GETTING_WP_IDLE"> |
||
33 | </enum> |
||
34 | |||
35 | </enums> --> |
||
36 | |||
37 | <messages> |
||
38 | |||
39 | <message name="CPU_LOAD" id="170"> |
||
40 | Sensor and DSC control loads. |
||
41 | <field name="sensLoad" type="uint8_t">Sensor DSC Load</field> |
||
42 | <field name="ctrlLoad" type="uint8_t">Control DSC Load</field> |
||
43 | <field name="batVolt" type="uint16_t">Battery Voltage in millivolts</field> |
||
44 | </message> |
||
45 | |||
46 | <message name="AIR_DATA" id="171"> |
||
47 | Air data for altitude and airspeed computation. |
||
48 | <field name="dynamicPressure" type="float">Dynamic pressure (Pa)</field> |
||
49 | <field name="staticPressure" type="float">Static pressure (Pa)</field> |
||
50 | <field name="temperature" type="uint16_t">Board temperature</field> |
||
51 | </message> |
||
52 | |||
53 | <message name="SENSOR_BIAS" id="172"> |
||
54 | Accelerometer and gyro biases. |
||
55 | <field name="axBias" type="float">Accelerometer X bias (m/s)</field> |
||
56 | <field name="ayBias" type="float">Accelerometer Y bias (m/s)</field> |
||
57 | <field name="azBias" type="float">Accelerometer Z bias (m/s)</field> |
||
58 | <field name="gxBias" type="float">Gyro X bias (rad/s)</field> |
||
59 | <field name="gyBias" type="float">Gyro Y bias (rad/s)</field> |
||
60 | <field name="gzBias" type="float">Gyro Z bias (rad/s)</field> |
||
61 | </message> |
||
62 | |||
63 | <message name="DIAGNOSTIC" id="173"> |
||
64 | Configurable diagnostic messages. |
||
65 | <field name="diagFl1" type="float">Diagnostic float 1</field> |
||
66 | <field name="diagFl2" type="float">Diagnostic float 2</field> |
||
67 | <field name="diagFl3" type="float">Diagnostic float 3</field> |
||
68 | <field name="diagSh1" type="int16_t">Diagnostic short 1</field> |
||
69 | <field name="diagSh2" type="int16_t">Diagnostic short 2</field> |
||
70 | <field name="diagSh3" type="int16_t">Diagnostic short 3</field> |
||
71 | </message> |
||
72 | |||
73 | <message name="SLUGS_NAVIGATION" id="176"> |
||
74 | Data used in the navigation algorithm. |
||
75 | <field name="u_m" type="float">Measured Airspeed prior to the Nav Filter</field> |
||
76 | <field name="phi_c" type="float">Commanded Roll</field> |
||
77 | <field name="theta_c" type="float">Commanded Pitch</field> |
||
78 | <field name="psiDot_c" type="float">Commanded Turn rate</field> |
||
79 | <field name="ay_body" type="float">Y component of the body acceleration</field> |
||
80 | <field name="totalDist" type="float">Total Distance to Run on this leg of Navigation</field> |
||
81 | <field name="dist2Go" type="float">Remaining distance to Run on this leg of Navigation</field> |
||
82 | <field name="fromWP" type="uint8_t">Origin WP</field> |
||
83 | <field name="toWP" type="uint8_t">Destination WP</field> |
||
84 | </message> |
||
85 | |||
86 | <message name="DATA_LOG" id="177"> |
||
87 | Configurable data log probes to be used inside Simulink |
||
88 | <field name="fl_1" type="float">Log value 1 </field> |
||
89 | <field name="fl_2" type="float">Log value 2 </field> |
||
90 | <field name="fl_3" type="float">Log value 3 </field> |
||
91 | <field name="fl_4" type="float">Log value 4 </field> |
||
92 | <field name="fl_5" type="float">Log value 5 </field> |
||
93 | <field name="fl_6" type="float">Log value 6 </field> |
||
94 | </message> |
||
95 | |||
96 | <message name="GPS_DATE_TIME" id="179"> |
||
97 | Pilot console PWM messges. |
||
98 | <field name="year" type="uint8_t">Year reported by Gps </field> |
||
99 | <field name="month" type="uint8_t">Month reported by Gps </field> |
||
100 | <field name="day" type="uint8_t">Day reported by Gps </field> |
||
101 | <field name="hour" type="uint8_t">Hour reported by Gps </field> |
||
102 | <field name="min" type="uint8_t">Min reported by Gps </field> |
||
103 | <field name="sec" type="uint8_t">Sec reported by Gps </field> |
||
104 | <field name="visSat" type="uint8_t">Visible sattelites reported by Gps </field> |
||
105 | </message> |
||
106 | |||
107 | <message name="MID_LVL_CMDS" id="180"> |
||
108 | Mid Level commands sent from the GS to the autopilot. These are only sent when being opperated in mid-level commands mode from the ground; for periodic report of these commands generated from the autopilot see message XXXX. |
||
109 | <field name="target" type="uint8_t">The system setting the commands</field> |
||
110 | <field name="hCommand" type="float">Commanded Airspeed</field> |
||
111 | <field name="uCommand" type="float">Log value 2 </field> |
||
112 | <field name="rCommand" type="float">Log value 3 </field> |
||
113 | </message> |
||
114 | |||
115 | |||
116 | <message name="CTRL_SRFC_PT" id="181"> |
||
117 | This message configures the Selective Passthrough mode. it allows to select which control surfaces the Pilot can control from his console. It is implemented as a bitfield as follows: |
||
118 | Position Bit Code |
||
119 | ================================= |
||
120 | 15-8 Reserved |
||
121 | 7 dt_pass 128 |
||
122 | 6 dla_pass 64 |
||
123 | 5 dra_pass 32 |
||
124 | 4 dr_pass 16 |
||
125 | 3 dle_pass 8 |
||
126 | 2 dre_pass 4 |
||
127 | 1 dlf_pass 2 |
||
128 | |||
129 | Where Bit 15 is the MSb. 0 = AP has control of the surface; 1 = Pilot Console has control of the surface. |
||
130 | <field name="target" type="uint8_t">The system setting the commands</field> |
||
131 | <field name="bitfieldPt" type="uint16_t">Bitfield containing the PT configuration</field> |
||
132 | </message> |
||
133 | |||
134 | |||
135 | |||
136 | <message name="SLUGS_ACTION" id="183"> |
||
137 | Action messages focused on the SLUGS AP. |
||
138 | <field name="target" type="uint8_t">The system reporting the action</field> |
||
139 | <field name="actionId" type="uint8_t">Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names</field> |
||
140 | <field name="actionVal" type="uint16_t">Value associated with the action</field> |
||
141 | </message> |
||
142 | |||
143 | </messages> |
||
144 | </mavlink> |