mavlink_msg_landing_target.h
Go to the documentation of this file.
1 // MESSAGE LANDING_TARGET PACKING
2 
3 #define MAVLINK_MSG_ID_LANDING_TARGET 149
4 
6 {
7  uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/
8  float angle_x; /*< X-axis angular offset (in radians) of the target from the center of the image*/
9  float angle_y; /*< Y-axis angular offset (in radians) of the target from the center of the image*/
10  float distance; /*< Distance to the target from the vehicle in meters*/
11  float size_x; /*< Size in radians of target along x-axis*/
12  float size_y; /*< Size in radians of target along y-axis*/
13  uint8_t target_num; /*< The ID of the target if multiple targets are present*/
14  uint8_t frame; /*< MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc.*/
16 
17 #define MAVLINK_MSG_ID_LANDING_TARGET_LEN 30
18 #define MAVLINK_MSG_ID_149_LEN 30
19 
20 #define MAVLINK_MSG_ID_LANDING_TARGET_CRC 200
21 #define MAVLINK_MSG_ID_149_CRC 200
22 
23 
24 
25 #define MAVLINK_MESSAGE_INFO_LANDING_TARGET { \
26  "LANDING_TARGET", \
27  8, \
28  { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_landing_target_t, time_usec) }, \
29  { "angle_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_landing_target_t, angle_x) }, \
30  { "angle_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_landing_target_t, angle_y) }, \
31  { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_landing_target_t, distance) }, \
32  { "size_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_landing_target_t, size_x) }, \
33  { "size_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_landing_target_t, size_y) }, \
34  { "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \
35  { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \
36  } \
37 }
38 
39 
56 static inline uint16_t mavlink_msg_landing_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
57  uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y)
58 {
59 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
61  _mav_put_uint64_t(buf, 0, time_usec);
62  _mav_put_float(buf, 8, angle_x);
63  _mav_put_float(buf, 12, angle_y);
64  _mav_put_float(buf, 16, distance);
65  _mav_put_float(buf, 20, size_x);
66  _mav_put_float(buf, 24, size_y);
67  _mav_put_uint8_t(buf, 28, target_num);
68  _mav_put_uint8_t(buf, 29, frame);
69 
71 #else
73  packet.time_usec = time_usec;
74  packet.angle_x = angle_x;
75  packet.angle_y = angle_y;
76  packet.distance = distance;
77  packet.size_x = size_x;
78  packet.size_y = size_y;
79  packet.target_num = target_num;
80  packet.frame = frame;
81 
83 #endif
84 
85  msg->msgid = MAVLINK_MSG_ID_LANDING_TARGET;
86 #if MAVLINK_CRC_EXTRA
88 #else
89  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
90 #endif
91 }
92 
109 static inline uint16_t mavlink_msg_landing_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
110  mavlink_message_t* msg,
111  uint64_t time_usec,uint8_t target_num,uint8_t frame,float angle_x,float angle_y,float distance,float size_x,float size_y)
112 {
113 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
115  _mav_put_uint64_t(buf, 0, time_usec);
116  _mav_put_float(buf, 8, angle_x);
117  _mav_put_float(buf, 12, angle_y);
118  _mav_put_float(buf, 16, distance);
119  _mav_put_float(buf, 20, size_x);
120  _mav_put_float(buf, 24, size_y);
121  _mav_put_uint8_t(buf, 28, target_num);
122  _mav_put_uint8_t(buf, 29, frame);
123 
125 #else
127  packet.time_usec = time_usec;
128  packet.angle_x = angle_x;
129  packet.angle_y = angle_y;
130  packet.distance = distance;
131  packet.size_x = size_x;
132  packet.size_y = size_y;
133  packet.target_num = target_num;
134  packet.frame = frame;
135 
137 #endif
138 
139  msg->msgid = MAVLINK_MSG_ID_LANDING_TARGET;
140 #if MAVLINK_CRC_EXTRA
142 #else
143  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
144 #endif
145 }
146 
155 static inline uint16_t mavlink_msg_landing_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_landing_target_t* landing_target)
156 {
157  return mavlink_msg_landing_target_pack(system_id, component_id, msg, landing_target->time_usec, landing_target->target_num, landing_target->frame, landing_target->angle_x, landing_target->angle_y, landing_target->distance, landing_target->size_x, landing_target->size_y);
158 }
159 
169 static inline uint16_t mavlink_msg_landing_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_landing_target_t* landing_target)
170 {
171  return mavlink_msg_landing_target_pack_chan(system_id, component_id, chan, msg, landing_target->time_usec, landing_target->target_num, landing_target->frame, landing_target->angle_x, landing_target->angle_y, landing_target->distance, landing_target->size_x, landing_target->size_y);
172 }
173 
187 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
188 
189 static inline void mavlink_msg_landing_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y)
190 {
191 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
193  _mav_put_uint64_t(buf, 0, time_usec);
194  _mav_put_float(buf, 8, angle_x);
195  _mav_put_float(buf, 12, angle_y);
196  _mav_put_float(buf, 16, distance);
197  _mav_put_float(buf, 20, size_x);
198  _mav_put_float(buf, 24, size_y);
199  _mav_put_uint8_t(buf, 28, target_num);
200  _mav_put_uint8_t(buf, 29, frame);
201 
202 #if MAVLINK_CRC_EXTRA
204 #else
205  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
206 #endif
207 #else
209  packet.time_usec = time_usec;
210  packet.angle_x = angle_x;
211  packet.angle_y = angle_y;
212  packet.distance = distance;
213  packet.size_x = size_x;
214  packet.size_y = size_y;
215  packet.target_num = target_num;
216  packet.frame = frame;
217 
218 #if MAVLINK_CRC_EXTRA
219  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)&packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC);
220 #else
221  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)&packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
222 #endif
223 #endif
224 }
225 
226 #if MAVLINK_MSG_ID_LANDING_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
227 /*
228  This varient of _send() can be used to save stack space by re-using
229  memory from the receive buffer. The caller provides a
230  mavlink_message_t which is the size of a full mavlink message. This
231  is usually the receive buffer for the channel, and allows a reply to an
232  incoming message with minimum stack space usage.
233  */
234 static inline void mavlink_msg_landing_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y)
235 {
236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
237  char *buf = (char *)msgbuf;
238  _mav_put_uint64_t(buf, 0, time_usec);
239  _mav_put_float(buf, 8, angle_x);
240  _mav_put_float(buf, 12, angle_y);
241  _mav_put_float(buf, 16, distance);
242  _mav_put_float(buf, 20, size_x);
243  _mav_put_float(buf, 24, size_y);
244  _mav_put_uint8_t(buf, 28, target_num);
245  _mav_put_uint8_t(buf, 29, frame);
246 
247 #if MAVLINK_CRC_EXTRA
249 #else
250  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
251 #endif
252 #else
254  packet->time_usec = time_usec;
255  packet->angle_x = angle_x;
256  packet->angle_y = angle_y;
257  packet->distance = distance;
258  packet->size_x = size_x;
259  packet->size_y = size_y;
260  packet->target_num = target_num;
261  packet->frame = frame;
262 
263 #if MAVLINK_CRC_EXTRA
264  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC);
265 #else
266  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
267 #endif
268 #endif
269 }
270 #endif
271 
272 #endif
273 
274 // MESSAGE LANDING_TARGET UNPACKING
275 
276 
282 static inline uint64_t mavlink_msg_landing_target_get_time_usec(const mavlink_message_t* msg)
283 {
284  return _MAV_RETURN_uint64_t(msg, 0);
285 }
286 
292 static inline uint8_t mavlink_msg_landing_target_get_target_num(const mavlink_message_t* msg)
293 {
294  return _MAV_RETURN_uint8_t(msg, 28);
295 }
296 
302 static inline uint8_t mavlink_msg_landing_target_get_frame(const mavlink_message_t* msg)
303 {
304  return _MAV_RETURN_uint8_t(msg, 29);
305 }
306 
312 static inline float mavlink_msg_landing_target_get_angle_x(const mavlink_message_t* msg)
313 {
314  return _MAV_RETURN_float(msg, 8);
315 }
316 
322 static inline float mavlink_msg_landing_target_get_angle_y(const mavlink_message_t* msg)
323 {
324  return _MAV_RETURN_float(msg, 12);
325 }
326 
332 static inline float mavlink_msg_landing_target_get_distance(const mavlink_message_t* msg)
333 {
334  return _MAV_RETURN_float(msg, 16);
335 }
336 
342 static inline float mavlink_msg_landing_target_get_size_x(const mavlink_message_t* msg)
343 {
344  return _MAV_RETURN_float(msg, 20);
345 }
346 
352 static inline float mavlink_msg_landing_target_get_size_y(const mavlink_message_t* msg)
353 {
354  return _MAV_RETURN_float(msg, 24);
355 }
356 
363 static inline void mavlink_msg_landing_target_decode(const mavlink_message_t* msg, mavlink_landing_target_t* landing_target)
364 {
365 #if MAVLINK_NEED_BYTE_SWAP
367  landing_target->angle_x = mavlink_msg_landing_target_get_angle_x(msg);
368  landing_target->angle_y = mavlink_msg_landing_target_get_angle_y(msg);
369  landing_target->distance = mavlink_msg_landing_target_get_distance(msg);
370  landing_target->size_x = mavlink_msg_landing_target_get_size_x(msg);
371  landing_target->size_y = mavlink_msg_landing_target_get_size_y(msg);
373  landing_target->frame = mavlink_msg_landing_target_get_frame(msg);
374 #else
375  memcpy(landing_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LANDING_TARGET_LEN);
376 #endif
377 }
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:151
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:244
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:140
#define _mav_put_uint64_t(buf, wire_offset, b)
Definition: protocol.h:149


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 19:59:25