Details | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
1702 | - | 1 | // MESSAGE OBJECT_DETECTION_EVENT PACKING |
2 | |||
3 | #define MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT 140 |
||
4 | |||
5 | typedef struct __mavlink_object_detection_event_t |
||
6 | { |
||
7 | uint32_t time; ///< Timestamp in milliseconds since system boot |
||
8 | uint16_t object_id; ///< Object ID |
||
9 | uint8_t type; ///< Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal |
||
10 | char name[20]; ///< Name of the object as defined by the detector |
||
11 | uint8_t quality; ///< Detection quality / confidence. 0: bad, 255: maximum confidence |
||
12 | float bearing; ///< Angle of the object with respect to the body frame in NED coordinates in radians. 0: front |
||
13 | float distance; ///< Ground distance in meters |
||
14 | } mavlink_object_detection_event_t; |
||
15 | |||
16 | #define MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT_LEN 36 |
||
17 | #define MAVLINK_MSG_ID_140_LEN 36 |
||
18 | |||
19 | #define MAVLINK_MSG_OBJECT_DETECTION_EVENT_FIELD_NAME_LEN 20 |
||
20 | |||
21 | #define MAVLINK_MESSAGE_INFO_OBJECT_DETECTION_EVENT { \ |
||
22 | "OBJECT_DETECTION_EVENT", \ |
||
23 | 7, \ |
||
24 | { { "time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_object_detection_event_t, time) }, \ |
||
25 | { "object_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_object_detection_event_t, object_id) }, \ |
||
26 | { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_object_detection_event_t, type) }, \ |
||
27 | { "name", NULL, MAVLINK_TYPE_CHAR, 20, 7, offsetof(mavlink_object_detection_event_t, name) }, \ |
||
28 | { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_object_detection_event_t, quality) }, \ |
||
29 | { "bearing", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_object_detection_event_t, bearing) }, \ |
||
30 | { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_object_detection_event_t, distance) }, \ |
||
31 | } \ |
||
32 | } |
||
33 | |||
34 | |||
35 | /** |
||
36 | * @brief Pack a object_detection_event message |
||
37 | * @param system_id ID of this system |
||
38 | * @param component_id ID of this component (e.g. 200 for IMU) |
||
39 | * @param msg The MAVLink message to compress the data into |
||
40 | * |
||
41 | * @param time Timestamp in milliseconds since system boot |
||
42 | * @param object_id Object ID |
||
43 | * @param type Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal |
||
44 | * @param name Name of the object as defined by the detector |
||
45 | * @param quality Detection quality / confidence. 0: bad, 255: maximum confidence |
||
46 | * @param bearing Angle of the object with respect to the body frame in NED coordinates in radians. 0: front |
||
47 | * @param distance Ground distance in meters |
||
48 | * @return length of the message in bytes (excluding serial stream start sign) |
||
49 | */ |
||
50 | static inline uint16_t mavlink_msg_object_detection_event_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, |
||
51 | uint32_t time, uint16_t object_id, uint8_t type, const char *name, uint8_t quality, float bearing, float distance) |
||
52 | { |
||
53 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||
54 | char buf[36]; |
||
55 | _mav_put_uint32_t(buf, 0, time); |
||
56 | _mav_put_uint16_t(buf, 4, object_id); |
||
57 | _mav_put_uint8_t(buf, 6, type); |
||
58 | _mav_put_uint8_t(buf, 27, quality); |
||
59 | _mav_put_float(buf, 28, bearing); |
||
60 | _mav_put_float(buf, 32, distance); |
||
61 | _mav_put_char_array(buf, 7, name, 20); |
||
62 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); |
||
63 | #else |
||
64 | mavlink_object_detection_event_t packet; |
||
65 | packet.time = time; |
||
66 | packet.object_id = object_id; |
||
67 | packet.type = type; |
||
68 | packet.quality = quality; |
||
69 | packet.bearing = bearing; |
||
70 | packet.distance = distance; |
||
71 | mav_array_memcpy(packet.name, name, sizeof(char)*20); |
||
72 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); |
||
73 | #endif |
||
74 | |||
75 | msg->msgid = MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT; |
||
76 | return mavlink_finalize_message(msg, system_id, component_id, 36); |
||
77 | } |
||
78 | |||
79 | /** |
||
80 | * @brief Pack a object_detection_event message on a channel |
||
81 | * @param system_id ID of this system |
||
82 | * @param component_id ID of this component (e.g. 200 for IMU) |
||
83 | * @param chan The MAVLink channel this message was sent over |
||
84 | * @param msg The MAVLink message to compress the data into |
||
85 | * @param time Timestamp in milliseconds since system boot |
||
86 | * @param object_id Object ID |
||
87 | * @param type Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal |
||
88 | * @param name Name of the object as defined by the detector |
||
89 | * @param quality Detection quality / confidence. 0: bad, 255: maximum confidence |
||
90 | * @param bearing Angle of the object with respect to the body frame in NED coordinates in radians. 0: front |
||
91 | * @param distance Ground distance in meters |
||
92 | * @return length of the message in bytes (excluding serial stream start sign) |
||
93 | */ |
||
94 | static inline uint16_t mavlink_msg_object_detection_event_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, |
||
95 | mavlink_message_t* msg, |
||
96 | uint32_t time,uint16_t object_id,uint8_t type,const char *name,uint8_t quality,float bearing,float distance) |
||
97 | { |
||
98 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||
99 | char buf[36]; |
||
100 | _mav_put_uint32_t(buf, 0, time); |
||
101 | _mav_put_uint16_t(buf, 4, object_id); |
||
102 | _mav_put_uint8_t(buf, 6, type); |
||
103 | _mav_put_uint8_t(buf, 27, quality); |
||
104 | _mav_put_float(buf, 28, bearing); |
||
105 | _mav_put_float(buf, 32, distance); |
||
106 | _mav_put_char_array(buf, 7, name, 20); |
||
107 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); |
||
108 | #else |
||
109 | mavlink_object_detection_event_t packet; |
||
110 | packet.time = time; |
||
111 | packet.object_id = object_id; |
||
112 | packet.type = type; |
||
113 | packet.quality = quality; |
||
114 | packet.bearing = bearing; |
||
115 | packet.distance = distance; |
||
116 | mav_array_memcpy(packet.name, name, sizeof(char)*20); |
||
117 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); |
||
118 | #endif |
||
119 | |||
120 | msg->msgid = MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT; |
||
121 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 36); |
||
122 | } |
||
123 | |||
124 | /** |
||
125 | * @brief Encode a object_detection_event struct into a message |
||
126 | * |
||
127 | * @param system_id ID of this system |
||
128 | * @param component_id ID of this component (e.g. 200 for IMU) |
||
129 | * @param msg The MAVLink message to compress the data into |
||
130 | * @param object_detection_event C-struct to read the message contents from |
||
131 | */ |
||
132 | static inline uint16_t mavlink_msg_object_detection_event_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_object_detection_event_t* object_detection_event) |
||
133 | { |
||
134 | return mavlink_msg_object_detection_event_pack(system_id, component_id, msg, object_detection_event->time, object_detection_event->object_id, object_detection_event->type, object_detection_event->name, object_detection_event->quality, object_detection_event->bearing, object_detection_event->distance); |
||
135 | } |
||
136 | |||
137 | /** |
||
138 | * @brief Send a object_detection_event message |
||
139 | * @param chan MAVLink channel to send the message |
||
140 | * |
||
141 | * @param time Timestamp in milliseconds since system boot |
||
142 | * @param object_id Object ID |
||
143 | * @param type Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal |
||
144 | * @param name Name of the object as defined by the detector |
||
145 | * @param quality Detection quality / confidence. 0: bad, 255: maximum confidence |
||
146 | * @param bearing Angle of the object with respect to the body frame in NED coordinates in radians. 0: front |
||
147 | * @param distance Ground distance in meters |
||
148 | */ |
||
149 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
||
150 | |||
151 | static inline void mavlink_msg_object_detection_event_send(mavlink_channel_t chan, uint32_t time, uint16_t object_id, uint8_t type, const char *name, uint8_t quality, float bearing, float distance) |
||
152 | { |
||
153 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||
154 | char buf[36]; |
||
155 | _mav_put_uint32_t(buf, 0, time); |
||
156 | _mav_put_uint16_t(buf, 4, object_id); |
||
157 | _mav_put_uint8_t(buf, 6, type); |
||
158 | _mav_put_uint8_t(buf, 27, quality); |
||
159 | _mav_put_float(buf, 28, bearing); |
||
160 | _mav_put_float(buf, 32, distance); |
||
161 | _mav_put_char_array(buf, 7, name, 20); |
||
162 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT, buf, 36); |
||
163 | #else |
||
164 | mavlink_object_detection_event_t packet; |
||
165 | packet.time = time; |
||
166 | packet.object_id = object_id; |
||
167 | packet.type = type; |
||
168 | packet.quality = quality; |
||
169 | packet.bearing = bearing; |
||
170 | packet.distance = distance; |
||
171 | mav_array_memcpy(packet.name, name, sizeof(char)*20); |
||
172 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT, (const char *)&packet, 36); |
||
173 | #endif |
||
174 | } |
||
175 | |||
176 | #endif |
||
177 | |||
178 | // MESSAGE OBJECT_DETECTION_EVENT UNPACKING |
||
179 | |||
180 | |||
181 | /** |
||
182 | * @brief Get field time from object_detection_event message |
||
183 | * |
||
184 | * @return Timestamp in milliseconds since system boot |
||
185 | */ |
||
186 | static inline uint32_t mavlink_msg_object_detection_event_get_time(const mavlink_message_t* msg) |
||
187 | { |
||
188 | return _MAV_RETURN_uint32_t(msg, 0); |
||
189 | } |
||
190 | |||
191 | /** |
||
192 | * @brief Get field object_id from object_detection_event message |
||
193 | * |
||
194 | * @return Object ID |
||
195 | */ |
||
196 | static inline uint16_t mavlink_msg_object_detection_event_get_object_id(const mavlink_message_t* msg) |
||
197 | { |
||
198 | return _MAV_RETURN_uint16_t(msg, 4); |
||
199 | } |
||
200 | |||
201 | /** |
||
202 | * @brief Get field type from object_detection_event message |
||
203 | * |
||
204 | * @return Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal |
||
205 | */ |
||
206 | static inline uint8_t mavlink_msg_object_detection_event_get_type(const mavlink_message_t* msg) |
||
207 | { |
||
208 | return _MAV_RETURN_uint8_t(msg, 6); |
||
209 | } |
||
210 | |||
211 | /** |
||
212 | * @brief Get field name from object_detection_event message |
||
213 | * |
||
214 | * @return Name of the object as defined by the detector |
||
215 | */ |
||
216 | static inline uint16_t mavlink_msg_object_detection_event_get_name(const mavlink_message_t* msg, char *name) |
||
217 | { |
||
218 | return _MAV_RETURN_char_array(msg, name, 20, 7); |
||
219 | } |
||
220 | |||
221 | /** |
||
222 | * @brief Get field quality from object_detection_event message |
||
223 | * |
||
224 | * @return Detection quality / confidence. 0: bad, 255: maximum confidence |
||
225 | */ |
||
226 | static inline uint8_t mavlink_msg_object_detection_event_get_quality(const mavlink_message_t* msg) |
||
227 | { |
||
228 | return _MAV_RETURN_uint8_t(msg, 27); |
||
229 | } |
||
230 | |||
231 | /** |
||
232 | * @brief Get field bearing from object_detection_event message |
||
233 | * |
||
234 | * @return Angle of the object with respect to the body frame in NED coordinates in radians. 0: front |
||
235 | */ |
||
236 | static inline float mavlink_msg_object_detection_event_get_bearing(const mavlink_message_t* msg) |
||
237 | { |
||
238 | return _MAV_RETURN_float(msg, 28); |
||
239 | } |
||
240 | |||
241 | /** |
||
242 | * @brief Get field distance from object_detection_event message |
||
243 | * |
||
244 | * @return Ground distance in meters |
||
245 | */ |
||
246 | static inline float mavlink_msg_object_detection_event_get_distance(const mavlink_message_t* msg) |
||
247 | { |
||
248 | return _MAV_RETURN_float(msg, 32); |
||
249 | } |
||
250 | |||
251 | /** |
||
252 | * @brief Decode a object_detection_event message into a struct |
||
253 | * |
||
254 | * @param msg The message to decode |
||
255 | * @param object_detection_event C-struct to decode the message contents into |
||
256 | */ |
||
257 | static inline void mavlink_msg_object_detection_event_decode(const mavlink_message_t* msg, mavlink_object_detection_event_t* object_detection_event) |
||
258 | { |
||
259 | #if MAVLINK_NEED_BYTE_SWAP |
||
260 | object_detection_event->time = mavlink_msg_object_detection_event_get_time(msg); |
||
261 | object_detection_event->object_id = mavlink_msg_object_detection_event_get_object_id(msg); |
||
262 | object_detection_event->type = mavlink_msg_object_detection_event_get_type(msg); |
||
263 | mavlink_msg_object_detection_event_get_name(msg, object_detection_event->name); |
||
264 | object_detection_event->quality = mavlink_msg_object_detection_event_get_quality(msg); |
||
265 | object_detection_event->bearing = mavlink_msg_object_detection_event_get_bearing(msg); |
||
266 | object_detection_event->distance = mavlink_msg_object_detection_event_get_distance(msg); |
||
267 | #else |
||
268 | memcpy(object_detection_event, _MAV_PAYLOAD(msg), 36); |
||
269 | #endif |
||
270 | } |