mavlink_msg_landing_target.h
Go to the documentation of this file.
00001 // MESSAGE LANDING_TARGET PACKING
00002 
00003 #define MAVLINK_MSG_ID_LANDING_TARGET 149
00004 
00005 typedef struct __mavlink_landing_target_t
00006 {
00007  uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/
00008  float angle_x; /*< X-axis angular offset (in radians) of the target from the center of the image*/
00009  float angle_y; /*< Y-axis angular offset (in radians) of the target from the center of the image*/
00010  float distance; /*< Distance to the target from the vehicle in meters*/
00011  float size_x; /*< Size in radians of target along x-axis*/
00012  float size_y; /*< Size in radians of target along y-axis*/
00013  uint8_t target_num; /*< The ID of the target if multiple targets are present*/
00014  uint8_t frame; /*< MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc.*/
00015 } mavlink_landing_target_t;
00016 
00017 #define MAVLINK_MSG_ID_LANDING_TARGET_LEN 30
00018 #define MAVLINK_MSG_ID_149_LEN 30
00019 
00020 #define MAVLINK_MSG_ID_LANDING_TARGET_CRC 200
00021 #define MAVLINK_MSG_ID_149_CRC 200
00022 
00023 
00024 
00025 #define MAVLINK_MESSAGE_INFO_LANDING_TARGET { \
00026         "LANDING_TARGET", \
00027         8, \
00028         {  { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_landing_target_t, time_usec) }, \
00029          { "angle_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_landing_target_t, angle_x) }, \
00030          { "angle_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_landing_target_t, angle_y) }, \
00031          { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_landing_target_t, distance) }, \
00032          { "size_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_landing_target_t, size_x) }, \
00033          { "size_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_landing_target_t, size_y) }, \
00034          { "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \
00035          { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \
00036          } \
00037 }
00038 
00039 
00056 static inline uint16_t mavlink_msg_landing_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00057                                                        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)
00058 {
00059 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00060         char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN];
00061         _mav_put_uint64_t(buf, 0, time_usec);
00062         _mav_put_float(buf, 8, angle_x);
00063         _mav_put_float(buf, 12, angle_y);
00064         _mav_put_float(buf, 16, distance);
00065         _mav_put_float(buf, 20, size_x);
00066         _mav_put_float(buf, 24, size_y);
00067         _mav_put_uint8_t(buf, 28, target_num);
00068         _mav_put_uint8_t(buf, 29, frame);
00069 
00070         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
00071 #else
00072         mavlink_landing_target_t packet;
00073         packet.time_usec = time_usec;
00074         packet.angle_x = angle_x;
00075         packet.angle_y = angle_y;
00076         packet.distance = distance;
00077         packet.size_x = size_x;
00078         packet.size_y = size_y;
00079         packet.target_num = target_num;
00080         packet.frame = frame;
00081 
00082         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
00083 #endif
00084 
00085         msg->msgid = MAVLINK_MSG_ID_LANDING_TARGET;
00086 #if MAVLINK_CRC_EXTRA
00087     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC);
00088 #else
00089     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
00090 #endif
00091 }
00092 
00109 static inline uint16_t mavlink_msg_landing_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00110                                                            mavlink_message_t* msg,
00111                                                            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)
00112 {
00113 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00114         char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN];
00115         _mav_put_uint64_t(buf, 0, time_usec);
00116         _mav_put_float(buf, 8, angle_x);
00117         _mav_put_float(buf, 12, angle_y);
00118         _mav_put_float(buf, 16, distance);
00119         _mav_put_float(buf, 20, size_x);
00120         _mav_put_float(buf, 24, size_y);
00121         _mav_put_uint8_t(buf, 28, target_num);
00122         _mav_put_uint8_t(buf, 29, frame);
00123 
00124         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
00125 #else
00126         mavlink_landing_target_t packet;
00127         packet.time_usec = time_usec;
00128         packet.angle_x = angle_x;
00129         packet.angle_y = angle_y;
00130         packet.distance = distance;
00131         packet.size_x = size_x;
00132         packet.size_y = size_y;
00133         packet.target_num = target_num;
00134         packet.frame = frame;
00135 
00136         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
00137 #endif
00138 
00139         msg->msgid = MAVLINK_MSG_ID_LANDING_TARGET;
00140 #if MAVLINK_CRC_EXTRA
00141     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC);
00142 #else
00143     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
00144 #endif
00145 }
00146 
00155 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)
00156 {
00157         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);
00158 }
00159 
00169 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)
00170 {
00171         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);
00172 }
00173 
00187 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00188 
00189 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)
00190 {
00191 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00192         char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN];
00193         _mav_put_uint64_t(buf, 0, time_usec);
00194         _mav_put_float(buf, 8, angle_x);
00195         _mav_put_float(buf, 12, angle_y);
00196         _mav_put_float(buf, 16, distance);
00197         _mav_put_float(buf, 20, size_x);
00198         _mav_put_float(buf, 24, size_y);
00199         _mav_put_uint8_t(buf, 28, target_num);
00200         _mav_put_uint8_t(buf, 29, frame);
00201 
00202 #if MAVLINK_CRC_EXTRA
00203     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC);
00204 #else
00205     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
00206 #endif
00207 #else
00208         mavlink_landing_target_t packet;
00209         packet.time_usec = time_usec;
00210         packet.angle_x = angle_x;
00211         packet.angle_y = angle_y;
00212         packet.distance = distance;
00213         packet.size_x = size_x;
00214         packet.size_y = size_y;
00215         packet.target_num = target_num;
00216         packet.frame = frame;
00217 
00218 #if MAVLINK_CRC_EXTRA
00219     _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);
00220 #else
00221     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)&packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
00222 #endif
00223 #endif
00224 }
00225 
00226 #if MAVLINK_MSG_ID_LANDING_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00227 /*
00228   This varient of _send() can be used to save stack space by re-using
00229   memory from the receive buffer.  The caller provides a
00230   mavlink_message_t which is the size of a full mavlink message. This
00231   is usually the receive buffer for the channel, and allows a reply to an
00232   incoming message with minimum stack space usage.
00233  */
00234 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)
00235 {
00236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00237         char *buf = (char *)msgbuf;
00238         _mav_put_uint64_t(buf, 0, time_usec);
00239         _mav_put_float(buf, 8, angle_x);
00240         _mav_put_float(buf, 12, angle_y);
00241         _mav_put_float(buf, 16, distance);
00242         _mav_put_float(buf, 20, size_x);
00243         _mav_put_float(buf, 24, size_y);
00244         _mav_put_uint8_t(buf, 28, target_num);
00245         _mav_put_uint8_t(buf, 29, frame);
00246 
00247 #if MAVLINK_CRC_EXTRA
00248     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC);
00249 #else
00250     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
00251 #endif
00252 #else
00253         mavlink_landing_target_t *packet = (mavlink_landing_target_t *)msgbuf;
00254         packet->time_usec = time_usec;
00255         packet->angle_x = angle_x;
00256         packet->angle_y = angle_y;
00257         packet->distance = distance;
00258         packet->size_x = size_x;
00259         packet->size_y = size_y;
00260         packet->target_num = target_num;
00261         packet->frame = frame;
00262 
00263 #if MAVLINK_CRC_EXTRA
00264     _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);
00265 #else
00266     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
00267 #endif
00268 #endif
00269 }
00270 #endif
00271 
00272 #endif
00273 
00274 // MESSAGE LANDING_TARGET UNPACKING
00275 
00276 
00282 static inline uint64_t mavlink_msg_landing_target_get_time_usec(const mavlink_message_t* msg)
00283 {
00284         return _MAV_RETURN_uint64_t(msg,  0);
00285 }
00286 
00292 static inline uint8_t mavlink_msg_landing_target_get_target_num(const mavlink_message_t* msg)
00293 {
00294         return _MAV_RETURN_uint8_t(msg,  28);
00295 }
00296 
00302 static inline uint8_t mavlink_msg_landing_target_get_frame(const mavlink_message_t* msg)
00303 {
00304         return _MAV_RETURN_uint8_t(msg,  29);
00305 }
00306 
00312 static inline float mavlink_msg_landing_target_get_angle_x(const mavlink_message_t* msg)
00313 {
00314         return _MAV_RETURN_float(msg,  8);
00315 }
00316 
00322 static inline float mavlink_msg_landing_target_get_angle_y(const mavlink_message_t* msg)
00323 {
00324         return _MAV_RETURN_float(msg,  12);
00325 }
00326 
00332 static inline float mavlink_msg_landing_target_get_distance(const mavlink_message_t* msg)
00333 {
00334         return _MAV_RETURN_float(msg,  16);
00335 }
00336 
00342 static inline float mavlink_msg_landing_target_get_size_x(const mavlink_message_t* msg)
00343 {
00344         return _MAV_RETURN_float(msg,  20);
00345 }
00346 
00352 static inline float mavlink_msg_landing_target_get_size_y(const mavlink_message_t* msg)
00353 {
00354         return _MAV_RETURN_float(msg,  24);
00355 }
00356 
00363 static inline void mavlink_msg_landing_target_decode(const mavlink_message_t* msg, mavlink_landing_target_t* landing_target)
00364 {
00365 #if MAVLINK_NEED_BYTE_SWAP
00366         landing_target->time_usec = mavlink_msg_landing_target_get_time_usec(msg);
00367         landing_target->angle_x = mavlink_msg_landing_target_get_angle_x(msg);
00368         landing_target->angle_y = mavlink_msg_landing_target_get_angle_y(msg);
00369         landing_target->distance = mavlink_msg_landing_target_get_distance(msg);
00370         landing_target->size_x = mavlink_msg_landing_target_get_size_x(msg);
00371         landing_target->size_y = mavlink_msg_landing_target_get_size_y(msg);
00372         landing_target->target_num = mavlink_msg_landing_target_get_target_num(msg);
00373         landing_target->frame = mavlink_msg_landing_target_get_frame(msg);
00374 #else
00375         memcpy(landing_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LANDING_TARGET_LEN);
00376 #endif
00377 }


dji_sdk_dji2mav
Author(s):
autogenerated on Thu Jun 6 2019 17:55:35