Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
mavlink_msg_att_pos_mocap.h
00001 #pragma once 00002 // MESSAGE ATT_POS_MOCAP PACKING 00003 00004 #define MAVLINK_MSG_ID_ATT_POS_MOCAP 138 00005 00006 MAVPACKED( 00007 typedef struct __mavlink_att_pos_mocap_t { 00008 uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ 00009 float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ 00010 float x; /*< X position in meters (NED)*/ 00011 float y; /*< Y position in meters (NED)*/ 00012 float z; /*< Z position in meters (NED)*/ 00013 }) mavlink_att_pos_mocap_t; 00014 00015 #define MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN 36 00016 #define MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN 36 00017 #define MAVLINK_MSG_ID_138_LEN 36 00018 #define MAVLINK_MSG_ID_138_MIN_LEN 36 00019 00020 #define MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC 109 00021 #define MAVLINK_MSG_ID_138_CRC 109 00022 00023 #define MAVLINK_MSG_ATT_POS_MOCAP_FIELD_Q_LEN 4 00024 00025 #if MAVLINK_COMMAND_24BIT 00026 #define MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP { \ 00027 138, \ 00028 "ATT_POS_MOCAP", \ 00029 5, \ 00030 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_att_pos_mocap_t, time_usec) }, \ 00031 { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_att_pos_mocap_t, q) }, \ 00032 { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_att_pos_mocap_t, x) }, \ 00033 { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_att_pos_mocap_t, y) }, \ 00034 { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_att_pos_mocap_t, z) }, \ 00035 } \ 00036 } 00037 #else 00038 #define MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP { \ 00039 "ATT_POS_MOCAP", \ 00040 5, \ 00041 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_att_pos_mocap_t, time_usec) }, \ 00042 { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_att_pos_mocap_t, q) }, \ 00043 { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_att_pos_mocap_t, x) }, \ 00044 { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_att_pos_mocap_t, y) }, \ 00045 { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_att_pos_mocap_t, z) }, \ 00046 } \ 00047 } 00048 #endif 00049 00050 /** 00051 * @brief Pack a att_pos_mocap message 00052 * @param system_id ID of this system 00053 * @param component_id ID of this component (e.g. 200 for IMU) 00054 * @param msg The MAVLink message to compress the data into 00055 * 00056 * @param time_usec Timestamp (micros since boot or Unix epoch) 00057 * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) 00058 * @param x X position in meters (NED) 00059 * @param y Y position in meters (NED) 00060 * @param z Z position in meters (NED) 00061 * @return length of the message in bytes (excluding serial stream start sign) 00062 */ 00063 static inline uint16_t mavlink_msg_att_pos_mocap_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, 00064 uint64_t time_usec, const float *q, float x, float y, float z) 00065 { 00066 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 00067 char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN]; 00068 _mav_put_uint64_t(buf, 0, time_usec); 00069 _mav_put_float(buf, 24, x); 00070 _mav_put_float(buf, 28, y); 00071 _mav_put_float(buf, 32, z); 00072 _mav_put_float_array(buf, 8, q, 4); 00073 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); 00074 #else 00075 mavlink_att_pos_mocap_t packet; 00076 packet.time_usec = time_usec; 00077 packet.x = x; 00078 packet.y = y; 00079 packet.z = z; 00080 mav_array_memcpy(packet.q, q, sizeof(float)*4); 00081 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); 00082 #endif 00083 00084 msg->msgid = MAVLINK_MSG_ID_ATT_POS_MOCAP; 00085 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); 00086 } 00087 00088 /** 00089 * @brief Pack a att_pos_mocap message on a channel 00090 * @param system_id ID of this system 00091 * @param component_id ID of this component (e.g. 200 for IMU) 00092 * @param chan The MAVLink channel this message will be sent over 00093 * @param msg The MAVLink message to compress the data into 00094 * @param time_usec Timestamp (micros since boot or Unix epoch) 00095 * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) 00096 * @param x X position in meters (NED) 00097 * @param y Y position in meters (NED) 00098 * @param z Z position in meters (NED) 00099 * @return length of the message in bytes (excluding serial stream start sign) 00100 */ 00101 static inline uint16_t mavlink_msg_att_pos_mocap_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, 00102 mavlink_message_t* msg, 00103 uint64_t time_usec,const float *q,float x,float y,float z) 00104 { 00105 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 00106 char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN]; 00107 _mav_put_uint64_t(buf, 0, time_usec); 00108 _mav_put_float(buf, 24, x); 00109 _mav_put_float(buf, 28, y); 00110 _mav_put_float(buf, 32, z); 00111 _mav_put_float_array(buf, 8, q, 4); 00112 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); 00113 #else 00114 mavlink_att_pos_mocap_t packet; 00115 packet.time_usec = time_usec; 00116 packet.x = x; 00117 packet.y = y; 00118 packet.z = z; 00119 mav_array_memcpy(packet.q, q, sizeof(float)*4); 00120 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); 00121 #endif 00122 00123 msg->msgid = MAVLINK_MSG_ID_ATT_POS_MOCAP; 00124 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); 00125 } 00126 00127 /** 00128 * @brief Encode a att_pos_mocap struct 00129 * 00130 * @param system_id ID of this system 00131 * @param component_id ID of this component (e.g. 200 for IMU) 00132 * @param msg The MAVLink message to compress the data into 00133 * @param att_pos_mocap C-struct to read the message contents from 00134 */ 00135 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) 00136 { 00137 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); 00138 } 00139 00140 /** 00141 * @brief Encode a att_pos_mocap struct on a channel 00142 * 00143 * @param system_id ID of this system 00144 * @param component_id ID of this component (e.g. 200 for IMU) 00145 * @param chan The MAVLink channel this message will be sent over 00146 * @param msg The MAVLink message to compress the data into 00147 * @param att_pos_mocap C-struct to read the message contents from 00148 */ 00149 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) 00150 { 00151 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); 00152 } 00153 00154 /** 00155 * @brief Send a att_pos_mocap message 00156 * @param chan MAVLink channel to send the message 00157 * 00158 * @param time_usec Timestamp (micros since boot or Unix epoch) 00159 * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) 00160 * @param x X position in meters (NED) 00161 * @param y Y position in meters (NED) 00162 * @param z Z position in meters (NED) 00163 */ 00164 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 00165 00166 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) 00167 { 00168 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 00169 char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN]; 00170 _mav_put_uint64_t(buf, 0, time_usec); 00171 _mav_put_float(buf, 24, x); 00172 _mav_put_float(buf, 28, y); 00173 _mav_put_float(buf, 32, z); 00174 _mav_put_float_array(buf, 8, q, 4); 00175 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); 00176 #else 00177 mavlink_att_pos_mocap_t packet; 00178 packet.time_usec = time_usec; 00179 packet.x = x; 00180 packet.y = y; 00181 packet.z = z; 00182 mav_array_memcpy(packet.q, q, sizeof(float)*4); 00183 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)&packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); 00184 #endif 00185 } 00186 00187 /** 00188 * @brief Send a att_pos_mocap message 00189 * @param chan MAVLink channel to send the message 00190 * @param struct The MAVLink struct to serialize 00191 */ 00192 static inline void mavlink_msg_att_pos_mocap_send_struct(mavlink_channel_t chan, const mavlink_att_pos_mocap_t* att_pos_mocap) 00193 { 00194 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 00195 mavlink_msg_att_pos_mocap_send(chan, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z); 00196 #else 00197 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)att_pos_mocap, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); 00198 #endif 00199 } 00200 00201 #if MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN <= MAVLINK_MAX_PAYLOAD_LEN 00202 /* 00203 This varient of _send() can be used to save stack space by re-using 00204 memory from the receive buffer. The caller provides a 00205 mavlink_message_t which is the size of a full mavlink message. This 00206 is usually the receive buffer for the channel, and allows a reply to an 00207 incoming message with minimum stack space usage. 00208 */ 00209 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) 00210 { 00211 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 00212 char *buf = (char *)msgbuf; 00213 _mav_put_uint64_t(buf, 0, time_usec); 00214 _mav_put_float(buf, 24, x); 00215 _mav_put_float(buf, 28, y); 00216 _mav_put_float(buf, 32, z); 00217 _mav_put_float_array(buf, 8, q, 4); 00218 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); 00219 #else 00220 mavlink_att_pos_mocap_t *packet = (mavlink_att_pos_mocap_t *)msgbuf; 00221 packet->time_usec = time_usec; 00222 packet->x = x; 00223 packet->y = y; 00224 packet->z = z; 00225 mav_array_memcpy(packet->q, q, sizeof(float)*4); 00226 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); 00227 #endif 00228 } 00229 #endif 00230 00231 #endif 00232 00233 // MESSAGE ATT_POS_MOCAP UNPACKING 00234 00235 00236 /** 00237 * @brief Get field time_usec from att_pos_mocap message 00238 * 00239 * @return Timestamp (micros since boot or Unix epoch) 00240 */ 00241 static inline uint64_t mavlink_msg_att_pos_mocap_get_time_usec(const mavlink_message_t* msg) 00242 { 00243 return _MAV_RETURN_uint64_t(msg, 0); 00244 } 00245 00246 /** 00247 * @brief Get field q from att_pos_mocap message 00248 * 00249 * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) 00250 */ 00251 static inline uint16_t mavlink_msg_att_pos_mocap_get_q(const mavlink_message_t* msg, float *q) 00252 { 00253 return _MAV_RETURN_float_array(msg, q, 4, 8); 00254 } 00255 00256 /** 00257 * @brief Get field x from att_pos_mocap message 00258 * 00259 * @return X position in meters (NED) 00260 */ 00261 static inline float mavlink_msg_att_pos_mocap_get_x(const mavlink_message_t* msg) 00262 { 00263 return _MAV_RETURN_float(msg, 24); 00264 } 00265 00266 /** 00267 * @brief Get field y from att_pos_mocap message 00268 * 00269 * @return Y position in meters (NED) 00270 */ 00271 static inline float mavlink_msg_att_pos_mocap_get_y(const mavlink_message_t* msg) 00272 { 00273 return _MAV_RETURN_float(msg, 28); 00274 } 00275 00276 /** 00277 * @brief Get field z from att_pos_mocap message 00278 * 00279 * @return Z position in meters (NED) 00280 */ 00281 static inline float mavlink_msg_att_pos_mocap_get_z(const mavlink_message_t* msg) 00282 { 00283 return _MAV_RETURN_float(msg, 32); 00284 } 00285 00286 /** 00287 * @brief Decode a att_pos_mocap message into a struct 00288 * 00289 * @param msg The message to decode 00290 * @param att_pos_mocap C-struct to decode the message contents into 00291 */ 00292 static inline void mavlink_msg_att_pos_mocap_decode(const mavlink_message_t* msg, mavlink_att_pos_mocap_t* att_pos_mocap) 00293 { 00294 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 00295 att_pos_mocap->time_usec = mavlink_msg_att_pos_mocap_get_time_usec(msg); 00296 mavlink_msg_att_pos_mocap_get_q(msg, att_pos_mocap->q); 00297 att_pos_mocap->x = mavlink_msg_att_pos_mocap_get_x(msg); 00298 att_pos_mocap->y = mavlink_msg_att_pos_mocap_get_y(msg); 00299 att_pos_mocap->z = mavlink_msg_att_pos_mocap_get_z(msg); 00300 #else 00301 uint8_t len = msg->len < MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN? msg->len : MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN; 00302 memset(att_pos_mocap, 0, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); 00303 memcpy(att_pos_mocap, _MAV_PAYLOAD(msg), len); 00304 #endif 00305 } 00306
Generated on Wed Jul 13 2022 05:12:03 by
