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) }, \ 59 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 110 mavlink_message_t* msg,
113 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 140 #if MAVLINK_CRC_EXTRA 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);
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 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 236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 237 char *buf = (
char *)msgbuf;
247 #if MAVLINK_CRC_EXTRA 263 #if MAVLINK_CRC_EXTRA 284 return _MAV_RETURN_uint32_t(msg, 0);
294 return _MAV_RETURN_float(msg, 4);
304 return _MAV_RETURN_float(msg, 8);
314 return _MAV_RETURN_float(msg, 12);
324 return _MAV_RETURN_float(msg, 16);
334 return _MAV_RETURN_float(msg, 20);
344 return _MAV_RETURN_float(msg, 24);
354 return _MAV_RETURN_float(msg, 28);
365 #if MAVLINK_NEED_BYTE_SWAP #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION
#define _mav_put_float(buf, wire_offset, b)
static 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)
Encode a attitude_quaternion struct on a channel.
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.
#define _MAV_PAYLOAD_NON_CONST(msg)
static uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed)
Pack a attitude_quaternion message on a channel.
#define _MAV_PAYLOAD(msg)
static float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message_t *msg)
Get field q2 from attitude_quaternion message.
static float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message_t *msg)
Get field q1 from attitude_quaternion message.
static float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message_t *msg)
Get field q4 from attitude_quaternion message.
static void mavlink_msg_attitude_quaternion_decode(const mavlink_message_t *msg, mavlink_attitude_quaternion_t *attitude_quaternion)
Decode a attitude_quaternion message into a struct.
struct __mavlink_attitude_quaternion_t mavlink_attitude_quaternion_t
static float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message_t *msg)
Get field q3 from attitude_quaternion message.
static float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_message_t *msg)
Get field rollspeed from attitude_quaternion message.
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC
static 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)
Encode a attitude_quaternion struct.
static uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const mavlink_message_t *msg)
Send a attitude_quaternion message.
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.
static float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink_message_t *msg)
Get field pitchspeed from attitude_quaternion message.
static float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_message_t *msg)
Get field yawspeed from attitude_quaternion message.
#define _mav_put_uint32_t(buf, wire_offset, b)
static uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed)
Pack a attitude_quaternion message.
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN