00001
00002
00003 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31
00004
00005 typedef struct __mavlink_attitude_quaternion_t
00006 {
00007 uint32_t time_boot_ms;
00008 float q1;
00009 float q2;
00010 float q3;
00011 float q4;
00012 float rollspeed;
00013 float pitchspeed;
00014 float yawspeed;
00015 } mavlink_attitude_quaternion_t;
00016
00017 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32
00018 #define MAVLINK_MSG_ID_31_LEN 32
00019
00020 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC 246
00021 #define MAVLINK_MSG_ID_31_CRC 246
00022
00023
00024
00025 #define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \
00026 "ATTITUDE_QUATERNION", \
00027 8, \
00028 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \
00029 { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \
00030 { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \
00031 { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \
00032 { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \
00033 { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \
00034 { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \
00035 { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \
00036 } \
00037 }
00038
00039
00056 static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00057 uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed)
00058 {
00059 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00060 char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN];
00061 _mav_put_uint32_t(buf, 0, time_boot_ms);
00062 _mav_put_float(buf, 4, q1);
00063 _mav_put_float(buf, 8, q2);
00064 _mav_put_float(buf, 12, q3);
00065 _mav_put_float(buf, 16, q4);
00066 _mav_put_float(buf, 20, rollspeed);
00067 _mav_put_float(buf, 24, pitchspeed);
00068 _mav_put_float(buf, 28, yawspeed);
00069
00070 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
00071 #else
00072 mavlink_attitude_quaternion_t packet;
00073 packet.time_boot_ms = time_boot_ms;
00074 packet.q1 = q1;
00075 packet.q2 = q2;
00076 packet.q3 = q3;
00077 packet.q4 = q4;
00078 packet.rollspeed = rollspeed;
00079 packet.pitchspeed = pitchspeed;
00080 packet.yawspeed = yawspeed;
00081
00082 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
00083 #endif
00084
00085 msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION;
00086 #if MAVLINK_CRC_EXTRA
00087 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
00088 #else
00089 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
00090 #endif
00091 }
00092
00109 static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00110 mavlink_message_t* msg,
00111 uint32_t time_boot_ms,float q1,float q2,float q3,float q4,float rollspeed,float pitchspeed,float yawspeed)
00112 {
00113 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00114 char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN];
00115 _mav_put_uint32_t(buf, 0, time_boot_ms);
00116 _mav_put_float(buf, 4, q1);
00117 _mav_put_float(buf, 8, q2);
00118 _mav_put_float(buf, 12, q3);
00119 _mav_put_float(buf, 16, q4);
00120 _mav_put_float(buf, 20, rollspeed);
00121 _mav_put_float(buf, 24, pitchspeed);
00122 _mav_put_float(buf, 28, yawspeed);
00123
00124 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
00125 #else
00126 mavlink_attitude_quaternion_t packet;
00127 packet.time_boot_ms = time_boot_ms;
00128 packet.q1 = q1;
00129 packet.q2 = q2;
00130 packet.q3 = q3;
00131 packet.q4 = q4;
00132 packet.rollspeed = rollspeed;
00133 packet.pitchspeed = pitchspeed;
00134 packet.yawspeed = yawspeed;
00135
00136 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
00137 #endif
00138
00139 msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION;
00140 #if MAVLINK_CRC_EXTRA
00141 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
00142 #else
00143 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
00144 #endif
00145 }
00146
00155 static inline uint16_t mavlink_msg_attitude_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion)
00156 {
00157 return mavlink_msg_attitude_quaternion_pack(system_id, component_id, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed);
00158 }
00159
00169 static inline uint16_t mavlink_msg_attitude_quaternion_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion)
00170 {
00171 return mavlink_msg_attitude_quaternion_pack_chan(system_id, component_id, chan, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed);
00172 }
00173
00187 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00188
00189 static inline void mavlink_msg_attitude_quaternion_send(mavlink_channel_t chan, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed)
00190 {
00191 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00192 char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN];
00193 _mav_put_uint32_t(buf, 0, time_boot_ms);
00194 _mav_put_float(buf, 4, q1);
00195 _mav_put_float(buf, 8, q2);
00196 _mav_put_float(buf, 12, q3);
00197 _mav_put_float(buf, 16, q4);
00198 _mav_put_float(buf, 20, rollspeed);
00199 _mav_put_float(buf, 24, pitchspeed);
00200 _mav_put_float(buf, 28, yawspeed);
00201
00202 #if MAVLINK_CRC_EXTRA
00203 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
00204 #else
00205 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
00206 #endif
00207 #else
00208 mavlink_attitude_quaternion_t packet;
00209 packet.time_boot_ms = time_boot_ms;
00210 packet.q1 = q1;
00211 packet.q2 = q2;
00212 packet.q3 = q3;
00213 packet.q4 = q4;
00214 packet.rollspeed = rollspeed;
00215 packet.pitchspeed = pitchspeed;
00216 packet.yawspeed = yawspeed;
00217
00218 #if MAVLINK_CRC_EXTRA
00219 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
00220 #else
00221 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
00222 #endif
00223 #endif
00224 }
00225
00226 #if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00227
00228
00229
00230
00231
00232
00233
00234 static inline void mavlink_msg_attitude_quaternion_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed)
00235 {
00236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00237 char *buf = (char *)msgbuf;
00238 _mav_put_uint32_t(buf, 0, time_boot_ms);
00239 _mav_put_float(buf, 4, q1);
00240 _mav_put_float(buf, 8, q2);
00241 _mav_put_float(buf, 12, q3);
00242 _mav_put_float(buf, 16, q4);
00243 _mav_put_float(buf, 20, rollspeed);
00244 _mav_put_float(buf, 24, pitchspeed);
00245 _mav_put_float(buf, 28, yawspeed);
00246
00247 #if MAVLINK_CRC_EXTRA
00248 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
00249 #else
00250 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
00251 #endif
00252 #else
00253 mavlink_attitude_quaternion_t *packet = (mavlink_attitude_quaternion_t *)msgbuf;
00254 packet->time_boot_ms = time_boot_ms;
00255 packet->q1 = q1;
00256 packet->q2 = q2;
00257 packet->q3 = q3;
00258 packet->q4 = q4;
00259 packet->rollspeed = rollspeed;
00260 packet->pitchspeed = pitchspeed;
00261 packet->yawspeed = yawspeed;
00262
00263 #if MAVLINK_CRC_EXTRA
00264 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
00265 #else
00266 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
00267 #endif
00268 #endif
00269 }
00270 #endif
00271
00272 #endif
00273
00274
00275
00276
00282 static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const mavlink_message_t* msg)
00283 {
00284 return _MAV_RETURN_uint32_t(msg, 0);
00285 }
00286
00292 static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message_t* msg)
00293 {
00294 return _MAV_RETURN_float(msg, 4);
00295 }
00296
00302 static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message_t* msg)
00303 {
00304 return _MAV_RETURN_float(msg, 8);
00305 }
00306
00312 static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message_t* msg)
00313 {
00314 return _MAV_RETURN_float(msg, 12);
00315 }
00316
00322 static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message_t* msg)
00323 {
00324 return _MAV_RETURN_float(msg, 16);
00325 }
00326
00332 static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_message_t* msg)
00333 {
00334 return _MAV_RETURN_float(msg, 20);
00335 }
00336
00342 static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink_message_t* msg)
00343 {
00344 return _MAV_RETURN_float(msg, 24);
00345 }
00346
00352 static inline float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_message_t* msg)
00353 {
00354 return _MAV_RETURN_float(msg, 28);
00355 }
00356
00363 static inline void mavlink_msg_attitude_quaternion_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_t* attitude_quaternion)
00364 {
00365 #if MAVLINK_NEED_BYTE_SWAP
00366 attitude_quaternion->time_boot_ms = mavlink_msg_attitude_quaternion_get_time_boot_ms(msg);
00367 attitude_quaternion->q1 = mavlink_msg_attitude_quaternion_get_q1(msg);
00368 attitude_quaternion->q2 = mavlink_msg_attitude_quaternion_get_q2(msg);
00369 attitude_quaternion->q3 = mavlink_msg_attitude_quaternion_get_q3(msg);
00370 attitude_quaternion->q4 = mavlink_msg_attitude_quaternion_get_q4(msg);
00371 attitude_quaternion->rollspeed = mavlink_msg_attitude_quaternion_get_rollspeed(msg);
00372 attitude_quaternion->pitchspeed = mavlink_msg_attitude_quaternion_get_pitchspeed(msg);
00373 attitude_quaternion->yawspeed = mavlink_msg_attitude_quaternion_get_yawspeed(msg);
00374 #else
00375 memcpy(attitude_quaternion, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
00376 #endif
00377 }