mavlink_msg_att_pos_mocap.h
Go to the documentation of this file.
00001 // MESSAGE ATT_POS_MOCAP PACKING
00002 
00003 #define MAVLINK_MSG_ID_ATT_POS_MOCAP 138
00004 
00005 typedef struct __mavlink_att_pos_mocap_t
00006 {
00007  uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/
00008  float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/
00009  float x; /*< X position in meters (NED)*/
00010  float y; /*< Y position in meters (NED)*/
00011  float z; /*< Z position in meters (NED)*/
00012 } mavlink_att_pos_mocap_t;
00013 
00014 #define MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN 36
00015 #define MAVLINK_MSG_ID_138_LEN 36
00016 
00017 #define MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC 109
00018 #define MAVLINK_MSG_ID_138_CRC 109
00019 
00020 #define MAVLINK_MSG_ATT_POS_MOCAP_FIELD_Q_LEN 4
00021 
00022 #define MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP { \
00023         "ATT_POS_MOCAP", \
00024         5, \
00025         {  { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_att_pos_mocap_t, time_usec) }, \
00026          { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_att_pos_mocap_t, q) }, \
00027          { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_att_pos_mocap_t, x) }, \
00028          { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_att_pos_mocap_t, y) }, \
00029          { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_att_pos_mocap_t, z) }, \
00030          } \
00031 }
00032 
00033 
00047 static inline uint16_t mavlink_msg_att_pos_mocap_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00048                                                        uint64_t time_usec, const float *q, float x, float y, float z)
00049 {
00050 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00051         char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN];
00052         _mav_put_uint64_t(buf, 0, time_usec);
00053         _mav_put_float(buf, 24, x);
00054         _mav_put_float(buf, 28, y);
00055         _mav_put_float(buf, 32, z);
00056         _mav_put_float_array(buf, 8, q, 4);
00057         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
00058 #else
00059         mavlink_att_pos_mocap_t packet;
00060         packet.time_usec = time_usec;
00061         packet.x = x;
00062         packet.y = y;
00063         packet.z = z;
00064         mav_array_memcpy(packet.q, q, sizeof(float)*4);
00065         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
00066 #endif
00067 
00068         msg->msgid = MAVLINK_MSG_ID_ATT_POS_MOCAP;
00069 #if MAVLINK_CRC_EXTRA
00070     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
00071 #else
00072     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
00073 #endif
00074 }
00075 
00089 static inline uint16_t mavlink_msg_att_pos_mocap_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00090                                                            mavlink_message_t* msg,
00091                                                            uint64_t time_usec,const float *q,float x,float y,float z)
00092 {
00093 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00094         char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN];
00095         _mav_put_uint64_t(buf, 0, time_usec);
00096         _mav_put_float(buf, 24, x);
00097         _mav_put_float(buf, 28, y);
00098         _mav_put_float(buf, 32, z);
00099         _mav_put_float_array(buf, 8, q, 4);
00100         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
00101 #else
00102         mavlink_att_pos_mocap_t packet;
00103         packet.time_usec = time_usec;
00104         packet.x = x;
00105         packet.y = y;
00106         packet.z = z;
00107         mav_array_memcpy(packet.q, q, sizeof(float)*4);
00108         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
00109 #endif
00110 
00111         msg->msgid = MAVLINK_MSG_ID_ATT_POS_MOCAP;
00112 #if MAVLINK_CRC_EXTRA
00113     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
00114 #else
00115     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
00116 #endif
00117 }
00118 
00127 static inline uint16_t mavlink_msg_att_pos_mocap_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_att_pos_mocap_t* att_pos_mocap)
00128 {
00129         return mavlink_msg_att_pos_mocap_pack(system_id, component_id, msg, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z);
00130 }
00131 
00141 static inline uint16_t mavlink_msg_att_pos_mocap_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_att_pos_mocap_t* att_pos_mocap)
00142 {
00143         return mavlink_msg_att_pos_mocap_pack_chan(system_id, component_id, chan, msg, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z);
00144 }
00145 
00156 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00157 
00158 static inline void mavlink_msg_att_pos_mocap_send(mavlink_channel_t chan, uint64_t time_usec, const float *q, float x, float y, float z)
00159 {
00160 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00161         char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN];
00162         _mav_put_uint64_t(buf, 0, time_usec);
00163         _mav_put_float(buf, 24, x);
00164         _mav_put_float(buf, 28, y);
00165         _mav_put_float(buf, 32, z);
00166         _mav_put_float_array(buf, 8, q, 4);
00167 #if MAVLINK_CRC_EXTRA
00168     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
00169 #else
00170     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
00171 #endif
00172 #else
00173         mavlink_att_pos_mocap_t packet;
00174         packet.time_usec = time_usec;
00175         packet.x = x;
00176         packet.y = y;
00177         packet.z = z;
00178         mav_array_memcpy(packet.q, q, sizeof(float)*4);
00179 #if MAVLINK_CRC_EXTRA
00180     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)&packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
00181 #else
00182     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)&packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
00183 #endif
00184 #endif
00185 }
00186 
00187 #if MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00188 /*
00189   This varient of _send() can be used to save stack space by re-using
00190   memory from the receive buffer.  The caller provides a
00191   mavlink_message_t which is the size of a full mavlink message. This
00192   is usually the receive buffer for the channel, and allows a reply to an
00193   incoming message with minimum stack space usage.
00194  */
00195 static inline void mavlink_msg_att_pos_mocap_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t time_usec, const float *q, float x, float y, float z)
00196 {
00197 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00198         char *buf = (char *)msgbuf;
00199         _mav_put_uint64_t(buf, 0, time_usec);
00200         _mav_put_float(buf, 24, x);
00201         _mav_put_float(buf, 28, y);
00202         _mav_put_float(buf, 32, z);
00203         _mav_put_float_array(buf, 8, q, 4);
00204 #if MAVLINK_CRC_EXTRA
00205     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
00206 #else
00207     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
00208 #endif
00209 #else
00210         mavlink_att_pos_mocap_t *packet = (mavlink_att_pos_mocap_t *)msgbuf;
00211         packet->time_usec = time_usec;
00212         packet->x = x;
00213         packet->y = y;
00214         packet->z = z;
00215         mav_array_memcpy(packet->q, q, sizeof(float)*4);
00216 #if MAVLINK_CRC_EXTRA
00217     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
00218 #else
00219     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
00220 #endif
00221 #endif
00222 }
00223 #endif
00224 
00225 #endif
00226 
00227 // MESSAGE ATT_POS_MOCAP UNPACKING
00228 
00229 
00235 static inline uint64_t mavlink_msg_att_pos_mocap_get_time_usec(const mavlink_message_t* msg)
00236 {
00237         return _MAV_RETURN_uint64_t(msg,  0);
00238 }
00239 
00245 static inline uint16_t mavlink_msg_att_pos_mocap_get_q(const mavlink_message_t* msg, float *q)
00246 {
00247         return _MAV_RETURN_float_array(msg, q, 4,  8);
00248 }
00249 
00255 static inline float mavlink_msg_att_pos_mocap_get_x(const mavlink_message_t* msg)
00256 {
00257         return _MAV_RETURN_float(msg,  24);
00258 }
00259 
00265 static inline float mavlink_msg_att_pos_mocap_get_y(const mavlink_message_t* msg)
00266 {
00267         return _MAV_RETURN_float(msg,  28);
00268 }
00269 
00275 static inline float mavlink_msg_att_pos_mocap_get_z(const mavlink_message_t* msg)
00276 {
00277         return _MAV_RETURN_float(msg,  32);
00278 }
00279 
00286 static inline void mavlink_msg_att_pos_mocap_decode(const mavlink_message_t* msg, mavlink_att_pos_mocap_t* att_pos_mocap)
00287 {
00288 #if MAVLINK_NEED_BYTE_SWAP
00289         att_pos_mocap->time_usec = mavlink_msg_att_pos_mocap_get_time_usec(msg);
00290         mavlink_msg_att_pos_mocap_get_q(msg, att_pos_mocap->q);
00291         att_pos_mocap->x = mavlink_msg_att_pos_mocap_get_x(msg);
00292         att_pos_mocap->y = mavlink_msg_att_pos_mocap_get_y(msg);
00293         att_pos_mocap->z = mavlink_msg_att_pos_mocap_get_z(msg);
00294 #else
00295         memcpy(att_pos_mocap, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
00296 #endif
00297 }


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