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 | <enums> |
||
5 | <enum name="DATA_TYPES"> |
||
6 | <description>Content Types for data transmission handshake</description> |
||
7 | <entry value="1" name="DATA_TYPE_JPEG_IMAGE"/> |
||
8 | <entry value="2" name="DATA_TYPE_RAW_IMAGE"/> |
||
9 | <entry value="3" name="DATA_TYPE_KINECT"/> |
||
10 | </enum> |
||
11 | </enums> |
||
12 | <messages> |
||
13 | <message id="151" name="SET_CAM_SHUTTER"> |
||
14 | <field type="uint8_t" name="cam_no">Camera id</field> |
||
15 | <field type="uint8_t" name="cam_mode">Camera mode: 0 = auto, 1 = manual</field> |
||
16 | <field type="uint8_t" name="trigger_pin">Trigger pin, 0-3 for PtGrey FireFly</field> |
||
17 | <field type="uint16_t" name="interval">Shutter interval, in microseconds</field> |
||
18 | <field type="uint16_t" name="exposure">Exposure time, in microseconds</field> |
||
19 | <field type="float" name="gain">Camera gain</field> |
||
20 | </message> |
||
21 | <message id="152" name="IMAGE_TRIGGERED"> |
||
22 | <field type="uint64_t" name="timestamp">Timestamp</field> |
||
23 | <field type="uint32_t" name="seq">IMU seq</field> |
||
24 | <field type="float" name="roll">Roll angle in rad</field> |
||
25 | <field type="float" name="pitch">Pitch angle in rad</field> |
||
26 | <field type="float" name="yaw">Yaw angle in rad</field> |
||
27 | <field type="float" name="local_z">Local frame Z coordinate (height over ground)</field> |
||
28 | <field type="float" name="lat">GPS X coordinate</field> |
||
29 | <field type="float" name="lon">GPS Y coordinate</field> |
||
30 | <field type="float" name="alt">Global frame altitude</field> |
||
31 | <field type="float" name="ground_x">Ground truth X</field> |
||
32 | <field type="float" name="ground_y">Ground truth Y</field> |
||
33 | <field type="float" name="ground_z">Ground truth Z</field> |
||
34 | </message> |
||
35 | <message id="153" name="IMAGE_TRIGGER_CONTROL"> |
||
36 | <field type="uint8_t" name="enable">0 to disable, 1 to enable</field> |
||
37 | </message> |
||
38 | <message id="154" name="IMAGE_AVAILABLE"> |
||
39 | <field type="uint64_t" name="cam_id">Camera id</field> |
||
40 | <field type="uint8_t" name="cam_no">Camera # (starts with 0)</field> |
||
41 | <field type="uint64_t" name="timestamp">Timestamp</field> |
||
42 | <field type="uint64_t" name="valid_until">Until which timestamp this buffer will stay valid</field> |
||
43 | <field type="uint32_t" name="img_seq">The image sequence number</field> |
||
44 | <field type="uint32_t" name="img_buf_index">Position of the image in the buffer, starts with 0</field> |
||
45 | <field type="uint16_t" name="width">Image width</field> |
||
46 | <field type="uint16_t" name="height">Image height</field> |
||
47 | <field type="uint16_t" name="depth">Image depth</field> |
||
48 | <field type="uint8_t" name="channels">Image channels</field> |
||
49 | <field type="uint32_t" name="key">Shared memory area key</field> |
||
50 | <field type="uint32_t" name="exposure">Exposure time, in microseconds</field> |
||
51 | <field type="float" name="gain">Camera gain</field> |
||
52 | <field type="float" name="roll">Roll angle in rad</field> |
||
53 | <field type="float" name="pitch">Pitch angle in rad</field> |
||
54 | <field type="float" name="yaw">Yaw angle in rad</field> |
||
55 | <field type="float" name="local_z">Local frame Z coordinate (height over ground)</field> |
||
56 | <field type="float" name="lat">GPS X coordinate</field> |
||
57 | <field type="float" name="lon">GPS Y coordinate</field> |
||
58 | <field type="float" name="alt">Global frame altitude</field> |
||
59 | <field type="float" name="ground_x">Ground truth X</field> |
||
60 | <field type="float" name="ground_y">Ground truth Y</field> |
||
61 | <field type="float" name="ground_z">Ground truth Z</field> |
||
62 | </message> |
||
63 | <message id="160" name="SET_POSITION_CONTROL_OFFSET"> |
||
64 | <description>Message sent to the MAV to set a new offset from the currently controlled position</description> |
||
65 | <field type="uint8_t" name="target_system">System ID</field> |
||
66 | <field type="uint8_t" name="target_component">Component ID</field> |
||
67 | <field type="float" name="x">x position offset</field> |
||
68 | <field type="float" name="y">y position offset</field> |
||
69 | <field type="float" name="z">z position offset</field> |
||
70 | <field type="float" name="yaw">yaw orientation offset in radians, 0 = NORTH</field> |
||
71 | </message> |
||
72 | <!-- Message sent by the MAV once it sets a new position as reference in the controller --> |
||
73 | <message id="170" name="POSITION_CONTROL_SETPOINT"> |
||
74 | <field type="uint16_t" name="id">ID of waypoint, 0 for plain position</field> |
||
75 | <field type="float" name="x">x position</field> |
||
76 | <field type="float" name="y">y position</field> |
||
77 | <field type="float" name="z">z position</field> |
||
78 | <field type="float" name="yaw">yaw orientation in radians, 0 = NORTH</field> |
||
79 | </message> |
||
80 | <message id="171" name="MARKER"> |
||
81 | <field type="uint16_t" name="id">ID</field> |
||
82 | <field type="float" name="x">x position</field> |
||
83 | <field type="float" name="y">y position</field> |
||
84 | <field type="float" name="z">z position</field> |
||
85 | <field type="float" name="roll">roll orientation</field> |
||
86 | <field type="float" name="pitch">pitch orientation</field> |
||
87 | <field type="float" name="yaw">yaw orientation</field> |
||
88 | </message> |
||
89 | <message id="172" name="RAW_AUX"> |
||
90 | <field type="uint16_t" name="adc1">ADC1 (J405 ADC3, LPC2148 AD0.6)</field> |
||
91 | <field type="uint16_t" name="adc2">ADC2 (J405 ADC5, LPC2148 AD0.2)</field> |
||
92 | <field type="uint16_t" name="adc3">ADC3 (J405 ADC6, LPC2148 AD0.1)</field> |
||
93 | <field type="uint16_t" name="adc4">ADC4 (J405 ADC7, LPC2148 AD1.3)</field> |
||
94 | <field type="uint16_t" name="vbat">Battery voltage</field> |
||
95 | <field type="int16_t" name="temp">Temperature (degrees celcius)</field> |
||
96 | <field type="int32_t" name="baro">Barometric pressure (hecto Pascal)</field> |
||
97 | </message> |
||
98 | <message id="180" name="WATCHDOG_HEARTBEAT"> |
||
99 | <field type="uint16_t" name="watchdog_id">Watchdog ID</field> |
||
100 | <field type="uint16_t" name="process_count">Number of processes</field> |
||
101 | </message> |
||
102 | <message id="181" name="WATCHDOG_PROCESS_INFO"> |
||
103 | <field type="uint16_t" name="watchdog_id">Watchdog ID</field> |
||
104 | <field type="uint16_t" name="process_id">Process ID</field> |
||
105 | <field type="char[100]" name="name">Process name</field> |
||
106 | <field type="char[147]" name="arguments">Process arguments</field> |
||
107 | <field type="int32_t" name="timeout">Timeout (seconds)</field> |
||
108 | </message> |
||
109 | <message id="182" name="WATCHDOG_PROCESS_STATUS"> |
||
110 | <field type="uint16_t" name="watchdog_id">Watchdog ID</field> |
||
111 | <field type="uint16_t" name="process_id">Process ID</field> |
||
112 | <field type="uint8_t" name="state">Is running / finished / suspended / crashed</field> |
||
113 | <field type="uint8_t" name="muted">Is muted</field> |
||
114 | <field type="int32_t" name="pid">PID</field> |
||
115 | <field type="uint16_t" name="crashes">Number of crashes</field> |
||
116 | </message> |
||
117 | <message id="183" name="WATCHDOG_COMMAND"> |
||
118 | <field type="uint8_t" name="target_system_id">Target system ID</field> |
||
119 | <field type="uint16_t" name="watchdog_id">Watchdog ID</field> |
||
120 | <field type="uint16_t" name="process_id">Process ID</field> |
||
121 | <field type="uint8_t" name="command_id">Command ID</field> |
||
122 | </message> |
||
123 | <message id="190" name="PATTERN_DETECTED"> |
||
124 | <field type="uint8_t" name="type">0: Pattern, 1: Letter</field> |
||
125 | <field type="float" name="confidence">Confidence of detection</field> |
||
126 | <field type="char[100]" name="file">Pattern file name</field> |
||
127 | <field type="uint8_t" name="detected">Accepted as true detection, 0 no, 1 yes</field> |
||
128 | </message> |
||
129 | <message id="191" name="POINT_OF_INTEREST"> |
||
130 | <description>Notifies the operator about a point of interest (POI). This can be anything detected by the |
||
131 | system. This generic message is intented to help interfacing to generic visualizations and to display |
||
132 | the POI on a map. |
||
133 | </description> |
||
134 | <field type="uint8_t" name="type">0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug</field> |
||
135 | <field type="uint8_t" name="color">0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta</field> |
||
136 | <field type="uint8_t" name="coordinate_system">0: global, 1:local</field> |
||
137 | <field type="uint16_t" name="timeout">0: no timeout, >1: timeout in seconds</field> |
||
138 | <field type="float" name="x">X Position</field> |
||
139 | <field type="float" name="y">Y Position</field> |
||
140 | <field type="float" name="z">Z Position</field> |
||
141 | <field type="char[26]" name="name">POI name</field> |
||
142 | </message> |
||
143 | <message id="192" name="POINT_OF_INTEREST_CONNECTION"> |
||
144 | <description>Notifies the operator about the connection of two point of interests (POI). This can be anything detected by the |
||
145 | system. This generic message is intented to help interfacing to generic visualizations and to display |
||
146 | the POI on a map. |
||
147 | </description> |
||
148 | <field type="uint8_t" name="type">0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug</field> |
||
149 | <field type="uint8_t" name="color">0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta</field> |
||
150 | <field type="uint8_t" name="coordinate_system">0: global, 1:local</field> |
||
151 | <field type="uint16_t" name="timeout">0: no timeout, >1: timeout in seconds</field> |
||
152 | <field type="float" name="xp1">X1 Position</field> |
||
153 | <field type="float" name="yp1">Y1 Position</field> |
||
154 | <field type="float" name="zp1">Z1 Position</field> |
||
155 | <field type="float" name="xp2">X2 Position</field> |
||
156 | <field type="float" name="yp2">Y2 Position</field> |
||
157 | <field type="float" name="zp2">Z2 Position</field> |
||
158 | <field type="char[26]" name="name">POI connection name</field> |
||
159 | </message> |
||
160 | <message id="193" name="DATA_TRANSMISSION_HANDSHAKE"> |
||
161 | <field type="uint8_t" name="type">type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)</field> |
||
162 | <field type="uint32_t" name="size">total data size in bytes (set on ACK only)</field> |
||
163 | <field type="uint16_t" name="width">Width of a matrix or image</field> |
||
164 | <field type="uint16_t" name="height">Height of a matrix or image</field> |
||
165 | <field type="uint8_t" name="packets">number of packets beeing sent (set on ACK only)</field> |
||
166 | <field type="uint8_t" name="payload">payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)</field> |
||
167 | <field type="uint8_t" name="jpg_quality">JPEG quality out of [1,100]</field> |
||
168 | </message> |
||
169 | <message id="194" name="ENCAPSULATED_DATA"> |
||
170 | <field type="uint16_t" name="seqnr">sequence number (starting with 0 on every transmission)</field> |
||
171 | <field type="uint8_t[253]" name="data">image data bytes</field> |
||
172 | </message> |
||
173 | <message id="195" name="BRIEF_FEATURE"> |
||
174 | <field type="float" name="x">x position in m</field> |
||
175 | <field type="float" name="y">y position in m</field> |
||
176 | <field type="float" name="z">z position in m</field> |
||
177 | <field type="uint8_t" name="orientation_assignment">Orientation assignment 0: false, 1:true</field> |
||
178 | <field type="uint16_t" name="size">Size in pixels</field> |
||
179 | <field type="uint16_t" name="orientation">Orientation</field> |
||
180 | <field type="uint8_t[32]" name="descriptor">Descriptor</field> |
||
181 | <field type="float" name="response">Harris operator response at this location</field> |
||
182 | </message> |
||
183 | <message id="200" name="ATTITUDE_CONTROL"> |
||
184 | <field type="uint8_t" name="target">The system to be controlled</field> |
||
185 | <field type="float" name="roll">roll</field> |
||
186 | <field type="float" name="pitch">pitch</field> |
||
187 | <field type="float" name="yaw">yaw</field> |
||
188 | <field type="float" name="thrust">thrust</field> |
||
189 | <field type="uint8_t" name="roll_manual">roll control enabled auto:0, manual:1</field> |
||
190 | <field type="uint8_t" name="pitch_manual">pitch auto:0, manual:1</field> |
||
191 | <field type="uint8_t" name="yaw_manual">yaw auto:0, manual:1</field> |
||
192 | <field type="uint8_t" name="thrust_manual">thrust auto:0, manual:1</field> |
||
193 | </message> |
||
194 | </messages> |
||
195 | </mavlink> |