00001
00002
00003 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV 61
00004
00005 typedef struct __mavlink_attitude_quaternion_cov_t
00006 {
00007 uint32_t time_boot_ms;
00008 float q[4];
00009 float rollspeed;
00010 float pitchspeed;
00011 float yawspeed;
00012 float covariance[9];
00013 } mavlink_attitude_quaternion_cov_t;
00014
00015 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN 68
00016 #define MAVLINK_MSG_ID_61_LEN 68
00017
00018 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC 153
00019 #define MAVLINK_MSG_ID_61_CRC 153
00020
00021 #define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_Q_LEN 4
00022 #define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_COVARIANCE_LEN 9
00023
00024 #define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV { \
00025 "ATTITUDE_QUATERNION_COV", \
00026 6, \
00027 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_cov_t, time_boot_ms) }, \
00028 { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_quaternion_cov_t, q) }, \
00029 { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_cov_t, rollspeed) }, \
00030 { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_cov_t, pitchspeed) }, \
00031 { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_cov_t, yawspeed) }, \
00032 { "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 32, offsetof(mavlink_attitude_quaternion_cov_t, covariance) }, \
00033 } \
00034 }
00035
00036
00051 static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00052 uint32_t time_boot_ms, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance)
00053 {
00054 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00055 char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN];
00056 _mav_put_uint32_t(buf, 0, time_boot_ms);
00057 _mav_put_float(buf, 20, rollspeed);
00058 _mav_put_float(buf, 24, pitchspeed);
00059 _mav_put_float(buf, 28, yawspeed);
00060 _mav_put_float_array(buf, 4, q, 4);
00061 _mav_put_float_array(buf, 32, covariance, 9);
00062 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
00063 #else
00064 mavlink_attitude_quaternion_cov_t packet;
00065 packet.time_boot_ms = time_boot_ms;
00066 packet.rollspeed = rollspeed;
00067 packet.pitchspeed = pitchspeed;
00068 packet.yawspeed = yawspeed;
00069 mav_array_memcpy(packet.q, q, sizeof(float)*4);
00070 mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9);
00071 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
00072 #endif
00073
00074 msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV;
00075 #if MAVLINK_CRC_EXTRA
00076 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
00077 #else
00078 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
00079 #endif
00080 }
00081
00096 static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00097 mavlink_message_t* msg,
00098 uint32_t time_boot_ms,const float *q,float rollspeed,float pitchspeed,float yawspeed,const float *covariance)
00099 {
00100 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00101 char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN];
00102 _mav_put_uint32_t(buf, 0, time_boot_ms);
00103 _mav_put_float(buf, 20, rollspeed);
00104 _mav_put_float(buf, 24, pitchspeed);
00105 _mav_put_float(buf, 28, yawspeed);
00106 _mav_put_float_array(buf, 4, q, 4);
00107 _mav_put_float_array(buf, 32, covariance, 9);
00108 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
00109 #else
00110 mavlink_attitude_quaternion_cov_t packet;
00111 packet.time_boot_ms = time_boot_ms;
00112 packet.rollspeed = rollspeed;
00113 packet.pitchspeed = pitchspeed;
00114 packet.yawspeed = yawspeed;
00115 mav_array_memcpy(packet.q, q, sizeof(float)*4);
00116 mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9);
00117 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
00118 #endif
00119
00120 msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV;
00121 #if MAVLINK_CRC_EXTRA
00122 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
00123 #else
00124 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
00125 #endif
00126 }
00127
00136 static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov)
00137 {
00138 return mavlink_msg_attitude_quaternion_cov_pack(system_id, component_id, msg, attitude_quaternion_cov->time_boot_ms, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance);
00139 }
00140
00150 static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov)
00151 {
00152 return mavlink_msg_attitude_quaternion_cov_pack_chan(system_id, component_id, chan, msg, attitude_quaternion_cov->time_boot_ms, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance);
00153 }
00154
00166 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00167
00168 static inline void mavlink_msg_attitude_quaternion_cov_send(mavlink_channel_t chan, uint32_t time_boot_ms, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance)
00169 {
00170 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00171 char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN];
00172 _mav_put_uint32_t(buf, 0, time_boot_ms);
00173 _mav_put_float(buf, 20, rollspeed);
00174 _mav_put_float(buf, 24, pitchspeed);
00175 _mav_put_float(buf, 28, yawspeed);
00176 _mav_put_float_array(buf, 4, q, 4);
00177 _mav_put_float_array(buf, 32, covariance, 9);
00178 #if MAVLINK_CRC_EXTRA
00179 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
00180 #else
00181 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
00182 #endif
00183 #else
00184 mavlink_attitude_quaternion_cov_t packet;
00185 packet.time_boot_ms = time_boot_ms;
00186 packet.rollspeed = rollspeed;
00187 packet.pitchspeed = pitchspeed;
00188 packet.yawspeed = yawspeed;
00189 mav_array_memcpy(packet.q, q, sizeof(float)*4);
00190 mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9);
00191 #if MAVLINK_CRC_EXTRA
00192 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
00193 #else
00194 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
00195 #endif
00196 #endif
00197 }
00198
00199 #if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00200
00201
00202
00203
00204
00205
00206
00207 static inline void mavlink_msg_attitude_quaternion_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance)
00208 {
00209 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00210 char *buf = (char *)msgbuf;
00211 _mav_put_uint32_t(buf, 0, time_boot_ms);
00212 _mav_put_float(buf, 20, rollspeed);
00213 _mav_put_float(buf, 24, pitchspeed);
00214 _mav_put_float(buf, 28, yawspeed);
00215 _mav_put_float_array(buf, 4, q, 4);
00216 _mav_put_float_array(buf, 32, covariance, 9);
00217 #if MAVLINK_CRC_EXTRA
00218 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
00219 #else
00220 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
00221 #endif
00222 #else
00223 mavlink_attitude_quaternion_cov_t *packet = (mavlink_attitude_quaternion_cov_t *)msgbuf;
00224 packet->time_boot_ms = time_boot_ms;
00225 packet->rollspeed = rollspeed;
00226 packet->pitchspeed = pitchspeed;
00227 packet->yawspeed = yawspeed;
00228 mav_array_memcpy(packet->q, q, sizeof(float)*4);
00229 mav_array_memcpy(packet->covariance, covariance, sizeof(float)*9);
00230 #if MAVLINK_CRC_EXTRA
00231 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
00232 #else
00233 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
00234 #endif
00235 #endif
00236 }
00237 #endif
00238
00239 #endif
00240
00241
00242
00243
00249 static inline uint32_t mavlink_msg_attitude_quaternion_cov_get_time_boot_ms(const mavlink_message_t* msg)
00250 {
00251 return _MAV_RETURN_uint32_t(msg, 0);
00252 }
00253
00259 static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_q(const mavlink_message_t* msg, float *q)
00260 {
00261 return _MAV_RETURN_float_array(msg, q, 4, 4);
00262 }
00263
00269 static inline float mavlink_msg_attitude_quaternion_cov_get_rollspeed(const mavlink_message_t* msg)
00270 {
00271 return _MAV_RETURN_float(msg, 20);
00272 }
00273
00279 static inline float mavlink_msg_attitude_quaternion_cov_get_pitchspeed(const mavlink_message_t* msg)
00280 {
00281 return _MAV_RETURN_float(msg, 24);
00282 }
00283
00289 static inline float mavlink_msg_attitude_quaternion_cov_get_yawspeed(const mavlink_message_t* msg)
00290 {
00291 return _MAV_RETURN_float(msg, 28);
00292 }
00293
00299 static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_covariance(const mavlink_message_t* msg, float *covariance)
00300 {
00301 return _MAV_RETURN_float_array(msg, covariance, 9, 32);
00302 }
00303
00310 static inline void mavlink_msg_attitude_quaternion_cov_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov)
00311 {
00312 #if MAVLINK_NEED_BYTE_SWAP
00313 attitude_quaternion_cov->time_boot_ms = mavlink_msg_attitude_quaternion_cov_get_time_boot_ms(msg);
00314 mavlink_msg_attitude_quaternion_cov_get_q(msg, attitude_quaternion_cov->q);
00315 attitude_quaternion_cov->rollspeed = mavlink_msg_attitude_quaternion_cov_get_rollspeed(msg);
00316 attitude_quaternion_cov->pitchspeed = mavlink_msg_attitude_quaternion_cov_get_pitchspeed(msg);
00317 attitude_quaternion_cov->yawspeed = mavlink_msg_attitude_quaternion_cov_get_yawspeed(msg);
00318 mavlink_msg_attitude_quaternion_cov_get_covariance(msg, attitude_quaternion_cov->covariance);
00319 #else
00320 memcpy(attitude_quaternion_cov, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
00321 #endif
00322 }