Subversion Repositories Projects

Rev

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
     <!-- note that APM specific messages should use the command id
5
      range from 150 to 250, to leave plenty of room for growth
6
      of common.xml
7
 
8
      If you prototype a message here, then you should consider if it
9
      is general enough to move into common.xml later
10
    -->
11
 
12
 
13
        <enums>
14
          <!-- Camera Mount mode Enumeration -->
15
          <enum name="MAV_MOUNT_MODE">
16
            <description>Enumeration of possible mount operation modes</description>
17
            <entry name="MAV_MOUNT_MODE_RETRACT" value="0"><description>Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization</description></entry>
18
            <entry name="MAV_MOUNT_MODE_NEUTRAL" value="1"><description>Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM.</description></entry>
19
            <entry name="MAV_MOUNT_MODE_MAVLINK_TARGETING" value="2"><description>Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization</description></entry>
20
            <entry name="MAV_MOUNT_MODE_RC_TARGETING" value="3"><description>Load neutral position and start RC Roll,Pitch,Yaw control with stabilization</description></entry>
21
            <entry name="MAV_MOUNT_MODE_GPS_POINT" value="4"><description>Load neutral position and start to point to Lat,Lon,Alt</description></entry>
22
          </enum>
23
 
24
          <enum name="MAV_CMD" >
25
            <!-- Camera Controller Mission Commands Enumeration -->
26
            <entry name="MAV_CMD_DO_DIGICAM_CONFIGURE" value="202">
27
              <description>Mission command to configure an on-board camera controller system.</description>
28
              <param index="1">Modes: P, TV, AV, M, Etc</param>
29
              <param index="2">Shutter speed: Divisor number for one second</param>
30
              <param index="3">Aperture: F stop number</param>
31
              <param index="4">ISO number e.g. 80, 100, 200, Etc</param>
32
              <param index="5">Exposure type enumerator</param>
33
              <param index="6">Command Identity</param>
34
              <param index="7">Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)</param>
35
            </entry>
36
 
37
            <entry name="MAV_CMD_DO_DIGICAM_CONTROL" value="203">
38
              <description>Mission command to control an on-board camera controller system.</description>
39
              <param index="1">Session control e.g. show/hide lens</param>
40
              <param index="2">Zoom's absolute position</param>
41
              <param index="3">Zooming step value to offset zoom from the current position</param>
42
              <param index="4">Focus Locking, Unlocking or Re-locking</param>
43
              <param index="5">Shooting Command</param>
44
              <param index="6">Command Identity</param>
45
              <param index="7">Empty</param>
46
            </entry>
47
 
48
            <!-- Camera Mount Mission Commands Enumeration -->
49
            <entry name="MAV_CMD_DO_MOUNT_CONFIGURE" value="204">
50
              <description>Mission command to configure a camera or antenna mount</description>
51
              <param index="1">Mount operation mode (see MAV_MOUNT_MODE enum)</param>
52
              <param index="2">stabilize roll? (1 = yes, 0 = no)</param>
53
              <param index="3">stabilize pitch? (1 = yes, 0 = no)</param>
54
              <param index="4">stabilize yaw? (1 = yes, 0 = no)</param>
55
              <param index="5">Empty</param>
56
              <param index="6">Empty</param>
57
              <param index="7">Empty</param>
58
            </entry>
59
 
60
            <entry name="MAV_CMD_DO_MOUNT_CONTROL" value="205">
61
              <description>Mission command to control a camera or antenna mount</description>
62
              <param index="1">pitch(deg*100) or lat, depending on mount mode.</param>
63
              <param index="2">roll(deg*100) or lon depending on mount mode</param>
64
              <param index="3">yaw(deg*100) or alt (in cm) depending on mount mode</param>
65
              <param index="4">Empty</param>
66
              <param index="5">Empty</param>
67
              <param index="6">Empty</param>
68
              <param index="7">Empty</param>
69
            </entry>
70
          </enum>
71
 
72
          <!-- fenced mode enums -->
73
          <enum name="FENCE_ACTION">
74
            <entry name="FENCE_ACTION_NONE" value="0">
75
              <description>Disable fenced mode</description>
76
            </entry>
77
            <entry name="FENCE_ACTION_GUIDED" value="1">
78
              <description>Switched to guided mode to return point (fence point 0)</description>
79
            </entry>
80
          </enum>
81
 
82
          <enum name="FENCE_BREACH">
83
            <entry name="FENCE_BREACH_NONE" value="0">
84
              <description>No last fence breach</description>
85
            </entry>
86
            <entry name="FENCE_BREACH_MINALT" value="1">
87
              <description>Breached minimum altitude</description>
88
            </entry>
89
            <entry name="FENCE_BREACH_MAXALT" value="2">
90
              <description>Breached maximum altitude</description>
91
            </entry>
92
            <entry name="FENCE_BREACH_BOUNDARY" value="3">
93
              <description>Breached fence boundary</description>
94
            </entry>
95
          </enum>
96
        </enums>
97
 
98
     <messages>
99
          <message id="150" name="SENSOR_OFFSETS">
100
               <description>Offsets and calibrations values for hardware
101
        sensors. This makes it easier to debug the calibration process.</description>
102
               <field type="int16_t" name="mag_ofs_x">magnetometer X offset</field>
103
               <field type="int16_t" name="mag_ofs_y">magnetometer Y offset</field>
104
               <field type="int16_t" name="mag_ofs_z">magnetometer Z offset</field>
105
               <field type="float" name="mag_declination">magnetic declination (radians)</field>
106
               <field type="int32_t" name="raw_press">raw pressure from barometer</field>
107
               <field type="int32_t" name="raw_temp">raw temperature from barometer</field>
108
               <field type="float" name="gyro_cal_x">gyro X calibration</field>
109
               <field type="float" name="gyro_cal_y">gyro Y calibration</field>
110
               <field type="float" name="gyro_cal_z">gyro Z calibration</field>
111
               <field type="float" name="accel_cal_x">accel X calibration</field>
112
               <field type="float" name="accel_cal_y">accel Y calibration</field>
113
               <field type="float" name="accel_cal_z">accel Z calibration</field>
114
          </message>
115
 
116
          <message id="151" name="SET_MAG_OFFSETS">
117
               <description>set the magnetometer offsets</description>
118
               <field type="uint8_t" name="target_system">System ID</field>
119
               <field type="uint8_t" name="target_component">Component ID</field>
120
               <field type="int16_t" name="mag_ofs_x">magnetometer X offset</field>
121
               <field type="int16_t" name="mag_ofs_y">magnetometer Y offset</field>
122
               <field type="int16_t" name="mag_ofs_z">magnetometer Z offset</field>
123
          </message>
124
 
125
          <message id="152" name="MEMINFO">
126
               <description>state of APM memory</description>
127
               <field type="uint16_t" name="brkval">heap top</field>
128
               <field type="uint16_t" name="freemem">free memory</field>
129
          </message>
130
 
131
          <message id="153" name="AP_ADC">
132
               <description>raw ADC output</description>
133
               <field type="uint16_t" name="adc1">ADC output 1</field>
134
               <field type="uint16_t" name="adc2">ADC output 2</field>
135
               <field type="uint16_t" name="adc3">ADC output 3</field>
136
               <field type="uint16_t" name="adc4">ADC output 4</field>
137
               <field type="uint16_t" name="adc5">ADC output 5</field>
138
               <field type="uint16_t" name="adc6">ADC output 6</field>
139
          </message>
140
 
141
          <!-- Camera Controller Messages -->
142
          <message name="DIGICAM_CONFIGURE" id="154">
143
            <description>Configure on-board Camera Control System.</description>
144
            <field name="target_system" type="uint8_t">System ID</field>
145
            <field name="target_component" type="uint8_t">Component ID</field>
146
            <field name="mode" type="uint8_t">Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)</field>
147
            <field name="shutter_speed" type="uint16_t">Divisor number //e.g. 1000 means 1/1000 (0 means ignore)</field>
148
            <field name="aperture" type="uint8_t">F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)</field>
149
            <field name="iso" type="uint8_t">ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)</field>
150
            <field name="exposure_type" type="uint8_t">Exposure type enumeration from 1 to N (0 means ignore)</field>
151
            <field name="command_id" type="uint8_t">Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once</field>
152
            <field name="engine_cut_off" type="uint8_t">Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)</field>
153
            <field name="extra_param" type="uint8_t">Extra parameters enumeration (0 means ignore)</field>
154
            <field name="extra_value" type="float">Correspondent value to given extra_param</field>
155
          </message>
156
 
157
          <message name="DIGICAM_CONTROL" id="155">
158
            <description>Control on-board Camera Control System to take shots.</description>
159
            <field name="target_system" type="uint8_t">System ID</field>
160
            <field name="target_component" type="uint8_t">Component ID</field>
161
            <field name="session" type="uint8_t">0: stop, 1: start or keep it up //Session control e.g. show/hide lens</field>
162
            <field name="zoom_pos" type="uint8_t">1 to N //Zoom's absolute position (0 means ignore)</field>
163
            <field name="zoom_step" type="int8_t">-100 to 100 //Zooming step value to offset zoom from the current position</field>
164
            <field name="focus_lock" type="uint8_t">0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus</field>
165
            <field name="shot" type="uint8_t">0: ignore, 1: shot or start filming</field>
166
            <field name="command_id" type="uint8_t">Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once</field>
167
            <field name="extra_param" type="uint8_t">Extra parameters enumeration (0 means ignore)</field>
168
            <field name="extra_value" type="float">Correspondent value to given extra_param</field>
169
          </message>
170
 
171
          <!-- Camera Mount Messages -->
172
          <message name="MOUNT_CONFIGURE" id="156">
173
            <description>Message to configure a camera mount, directional antenna, etc.</description>
174
            <field name="target_system" type="uint8_t">System ID</field>
175
            <field name="target_component" type="uint8_t">Component ID</field>
176
            <field name="mount_mode" type="uint8_t">mount operating mode (see MAV_MOUNT_MODE enum)</field>
177
            <field name="stab_roll" type="uint8_t">(1 = yes, 0 = no)</field>
178
            <field name="stab_pitch" type="uint8_t">(1 = yes, 0 = no)</field>
179
            <field name="stab_yaw" type="uint8_t">(1 = yes, 0 = no)</field>
180
          </message>
181
 
182
          <message name="MOUNT_CONTROL" id="157">
183
            <description>Message to control a camera mount, directional antenna, etc.</description>
184
            <field name="target_system" type="uint8_t">System ID</field>
185
            <field name="target_component" type="uint8_t">Component ID</field>
186
            <field name="input_a" type="int32_t">pitch(deg*100) or lat, depending on mount mode</field>
187
            <field name="input_b" type="int32_t">roll(deg*100) or lon depending on mount mode</field>
188
            <field name="input_c" type="int32_t">yaw(deg*100) or alt (in cm) depending on mount mode</field>
189
            <field name="save_position" type="uint8_t">if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)</field>
190
          </message>
191
 
192
          <message name="MOUNT_STATUS" id="158">
193
            <description>Message with some status from APM to GCS about camera or antenna mount</description>
194
            <field name="target_system" type="uint8_t">System ID</field>
195
            <field name="target_component" type="uint8_t">Component ID</field>
196
            <field name="pointing_a" type="int32_t">pitch(deg*100) or lat, depending on mount mode</field>
197
            <field name="pointing_b" type="int32_t">roll(deg*100) or lon depending on mount mode</field>
198
            <field name="pointing_c" type="int32_t">yaw(deg*100) or alt (in cm) depending on mount mode</field>
199
          </message>
200
 
201
          <!-- geo-fence messages -->
202
          <message name="FENCE_POINT" id="160">
203
            <description>A fence point. Used to set a point when from
204
              GCS -> MAV. Also used to return a point from MAV -> GCS</description>
205
            <field name="target_system" type="uint8_t">System ID</field>
206
            <field name="target_component" type="uint8_t">Component ID</field>
207
            <field name="idx" type="uint8_t">point index (first point is 1, 0 is for return point)</field>
208
            <field name="count" type="uint8_t">total number of points (for sanity checking)</field>
209
            <field name="lat" type="float">Latitude of point</field>
210
            <field name="lng" type="float">Longitude of point</field>
211
          </message>
212
 
213
          <message name="FENCE_FETCH_POINT" id="161">
214
            <description>Request a current fence point from MAV</description>
215
            <field name="target_system" type="uint8_t">System ID</field>
216
            <field name="target_component" type="uint8_t">Component ID</field>
217
            <field name="idx" type="uint8_t">point index (first point is 1, 0 is for return point)</field>
218
          </message>
219
 
220
          <message name="FENCE_STATUS" id="162">
221
            <description>Status of geo-fencing. Sent in extended
222
            status stream when fencing enabled</description>
223
            <field name="breach_status" type="uint8_t">0 if currently inside fence, 1 if outside</field>
224
            <field name="breach_count" type="uint16_t">number of fence breaches</field>
225
            <field name="breach_type" type="uint8_t">last breach type (see FENCE_BREACH_* enum)</field>
226
            <field name="breach_time" type="uint32_t">time of last breach in milliseconds since boot</field>
227
          </message>
228
 
229
          <message name="AHRS" id="163">
230
            <description>Status of DCM attitude estimator</description>
231
            <field type="float" name="omegaIx">X gyro drift estimate rad/s</field>
232
            <field type="float" name="omegaIy">Y gyro drift estimate rad/s</field>
233
            <field type="float" name="omegaIz">Z gyro drift estimate rad/s</field>
234
            <field type="float" name="accel_weight">average accel_weight</field>
235
            <field type="float" name="renorm_val">average renormalisation value</field>
236
            <field type="float" name="error_rp">average error_roll_pitch value</field>
237
            <field type="float" name="error_yaw">average error_yaw value</field>
238
          </message>
239
 
240
          <message name="SIMSTATE" id="164">
241
            <description>Status of simulation environment, if used</description>
242
            <field type="float" name="roll">Roll angle (rad)</field>
243
            <field type="float" name="pitch">Pitch angle (rad)</field>
244
            <field type="float" name="yaw">Yaw angle (rad)</field>
245
            <field type="float" name="xacc">X acceleration m/s/s</field>
246
            <field type="float" name="yacc">Y acceleration m/s/s</field>
247
            <field type="float" name="zacc">Z acceleration m/s/s</field>
248
            <field type="float" name="xgyro">Angular speed around X axis rad/s</field>
249
            <field type="float" name="ygyro">Angular speed around Y axis rad/s</field>
250
            <field type="float" name="zgyro">Angular speed around Z axis rad/s</field>
251
          </message>
252
 
253
          <message name="HWSTATUS" id="165">
254
            <description>Status of key hardware</description>
255
            <field type="uint16_t" name="Vcc">board voltage (mV)</field>
256
            <field type="uint8_t"  name="I2Cerr">I2C error count</field>
257
          </message>
258
 
259
          <message name="RADIO" id="166">
260
            <description>Status generated by radio</description>
261
            <field type="uint8_t" name="rssi">local signal strength</field>
262
            <field type="uint8_t" name="remrssi">remote signal strength</field>
263
            <field type="uint8_t" name="txbuf">how full the tx buffer is as a percentage</field>
264
            <field type="uint8_t" name="noise">background noise level</field>
265
            <field type="uint8_t" name="remnoise">remote background noise level</field>
266
            <field type="uint16_t" name="rxerrors">receive errors</field>
267
            <field type="uint16_t" name="fixed">count of error corrected packets</field>
268
          </message>
269
     </messages>
270
</mavlink>