3 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31
17 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32
18 #define MAVLINK_MSG_ID_31_LEN 32
20 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC 246
21 #define MAVLINK_MSG_ID_31_CRC 246
25 #define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \
26 "ATTITUDE_QUATERNION", \
28 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \
29 { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \
30 { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \
31 { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \
32 { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \
33 { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \
34 { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \
35 { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \
56 static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
57 uint32_t time_boot_ms,
float q1,
float q2,
float q3,
float q4,
float rollspeed,
float pitchspeed,
float yawspeed)
59 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
109 static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
110 mavlink_message_t* msg,
111 uint32_t time_boot_ms,
float q1,
float q2,
float q3,
float q4,
float rollspeed,
float pitchspeed,
float yawspeed)
113 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
140 #if MAVLINK_CRC_EXTRA
155 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)
157 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);
169 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)
171 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);
187 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
189 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)
191 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
202 #if MAVLINK_CRC_EXTRA
218 #if MAVLINK_CRC_EXTRA
226 #if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
234 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)
236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
237 char *buf = (
char *)msgbuf;
247 #if MAVLINK_CRC_EXTRA
263 #if MAVLINK_CRC_EXTRA
282 static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(
const mavlink_message_t* msg)
284 return _MAV_RETURN_uint32_t(msg, 0);
292 static inline float mavlink_msg_attitude_quaternion_get_q1(
const mavlink_message_t* msg)
294 return _MAV_RETURN_float(msg, 4);
302 static inline float mavlink_msg_attitude_quaternion_get_q2(
const mavlink_message_t* msg)
304 return _MAV_RETURN_float(msg, 8);
312 static inline float mavlink_msg_attitude_quaternion_get_q3(
const mavlink_message_t* msg)
314 return _MAV_RETURN_float(msg, 12);
322 static inline float mavlink_msg_attitude_quaternion_get_q4(
const mavlink_message_t* msg)
324 return _MAV_RETURN_float(msg, 16);
332 static inline float mavlink_msg_attitude_quaternion_get_rollspeed(
const mavlink_message_t* msg)
334 return _MAV_RETURN_float(msg, 20);
342 static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(
const mavlink_message_t* msg)
344 return _MAV_RETURN_float(msg, 24);
352 static inline float mavlink_msg_attitude_quaternion_get_yawspeed(
const mavlink_message_t* msg)
354 return _MAV_RETURN_float(msg, 28);
365 #if MAVLINK_NEED_BYTE_SWAP
366 attitude_quaternion->
time_boot_ms = mavlink_msg_attitude_quaternion_get_time_boot_ms(msg);
367 attitude_quaternion->
q1 = mavlink_msg_attitude_quaternion_get_q1(msg);
368 attitude_quaternion->
q2 = mavlink_msg_attitude_quaternion_get_q2(msg);
369 attitude_quaternion->
q3 = mavlink_msg_attitude_quaternion_get_q3(msg);
370 attitude_quaternion->
q4 = mavlink_msg_attitude_quaternion_get_q4(msg);
371 attitude_quaternion->
rollspeed = mavlink_msg_attitude_quaternion_get_rollspeed(msg);
372 attitude_quaternion->
pitchspeed = mavlink_msg_attitude_quaternion_get_pitchspeed(msg);
373 attitude_quaternion->
yawspeed = mavlink_msg_attitude_quaternion_get_yawspeed(msg);
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION
Definition: mavlink_msg_attitude_quaternion.h:3
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
float q1
Quaternion component 1, w (1 in null-rotation)
Definition: mavlink_msg_attitude_quaternion.h:8
float rollspeed
Roll angular speed (rad/s)
Definition: mavlink_msg_attitude_quaternion.h:12
float pitchspeed
Pitch angular speed (rad/s)
Definition: mavlink_msg_attitude_quaternion.h:13
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
Definition: mavlink_helpers.h:105
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
mavlink_channel_t
Definition: mavlink_types.h:178
float q3
Quaternion component 3, y (0 in null-rotation)
Definition: mavlink_msg_attitude_quaternion.h:10
uint32_t time_boot_ms
Timestamp (milliseconds since system boot)
Definition: mavlink_msg_attitude_quaternion.h:7
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
Definition: mavlink_msg_attitude_quaternion.h:5
float q2
Quaternion component 2, x (0 in null-rotation)
Definition: mavlink_msg_attitude_quaternion.h:9
struct __mavlink_attitude_quaternion_t mavlink_attitude_quaternion_t
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC
Definition: mavlink_msg_attitude_quaternion.h:20
float q4
Quaternion component 4, z (0 in null-rotation)
Definition: mavlink_msg_attitude_quaternion.h:11
float yawspeed
Yaw angular speed (rad/s)
Definition: mavlink_msg_attitude_quaternion.h:14
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
Definition: mavlink_helpers.h:71
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:141
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
Definition: mavlink_msg_attitude_quaternion.h:17