3 #define MAVLINK_MSG_ID_RAW_IMU 27 19 #define MAVLINK_MSG_ID_RAW_IMU_LEN 26 20 #define MAVLINK_MSG_ID_27_LEN 26 22 #define MAVLINK_MSG_ID_RAW_IMU_CRC 144 23 #define MAVLINK_MSG_ID_27_CRC 144 27 #define MAVLINK_MESSAGE_INFO_RAW_IMU { \ 30 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_imu_t, time_usec) }, \ 31 { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_imu_t, xacc) }, \ 32 { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_imu_t, yacc) }, \ 33 { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_imu_t, zacc) }, \ 34 { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_imu_t, xgyro) }, \ 35 { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_raw_imu_t, ygyro) }, \ 36 { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_raw_imu_t, zgyro) }, \ 37 { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_raw_imu_t, xmag) }, \ 38 { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_raw_imu_t, ymag) }, \ 39 { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_raw_imu_t, zmag) }, \ 65 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 122 mavlink_message_t* msg,
125 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 156 #if MAVLINK_CRC_EXTRA 173 return mavlink_msg_raw_imu_pack(system_id, component_id, msg, raw_imu->
time_usec, raw_imu->
xacc, raw_imu->
yacc, raw_imu->
zacc, raw_imu->
xgyro, raw_imu->
ygyro, raw_imu->
zgyro, raw_imu->
xmag, raw_imu->
ymag, raw_imu->
zmag);
187 return mavlink_msg_raw_imu_pack_chan(system_id, component_id, chan, msg, raw_imu->
time_usec, raw_imu->
xacc, raw_imu->
yacc, raw_imu->
zacc, raw_imu->
xgyro, raw_imu->
ygyro, raw_imu->
zgyro, raw_imu->
xmag, raw_imu->
ymag, raw_imu->
zmag);
205 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 207 static inline void mavlink_msg_raw_imu_send(
mavlink_channel_t chan, uint64_t
time_usec, int16_t
xacc, int16_t
yacc, int16_t
zacc, int16_t
xgyro, int16_t
ygyro, int16_t
zgyro, int16_t
xmag, int16_t
ymag, int16_t
zmag)
209 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 222 #if MAVLINK_CRC_EXTRA 240 #if MAVLINK_CRC_EXTRA 248 #if MAVLINK_MSG_ID_RAW_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN 256 static inline void mavlink_msg_raw_imu_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint64_t
time_usec, int16_t
xacc, int16_t
yacc, int16_t
zacc, int16_t
xgyro, int16_t
ygyro, int16_t
zgyro, int16_t
xmag, int16_t
ymag, int16_t
zmag)
258 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 259 char *buf = (
char *)msgbuf;
271 #if MAVLINK_CRC_EXTRA 289 #if MAVLINK_CRC_EXTRA 310 return _MAV_RETURN_uint64_t(msg, 0);
320 return _MAV_RETURN_int16_t(msg, 8);
330 return _MAV_RETURN_int16_t(msg, 10);
340 return _MAV_RETURN_int16_t(msg, 12);
350 return _MAV_RETURN_int16_t(msg, 14);
360 return _MAV_RETURN_int16_t(msg, 16);
370 return _MAV_RETURN_int16_t(msg, 18);
380 return _MAV_RETURN_int16_t(msg, 20);
390 return _MAV_RETURN_int16_t(msg, 22);
400 return _MAV_RETURN_int16_t(msg, 24);
411 #if MAVLINK_NEED_BYTE_SWAP
static int16_t mavlink_msg_raw_imu_get_yacc(const mavlink_message_t *msg)
Get field yacc from raw_imu message.
struct __mavlink_raw_imu_t mavlink_raw_imu_t
#define MAVLINK_MSG_ID_RAW_IMU
static int16_t mavlink_msg_raw_imu_get_xgyro(const mavlink_message_t *msg)
Get field xgyro from raw_imu message.
static int16_t mavlink_msg_raw_imu_get_xmag(const mavlink_message_t *msg)
Get field xmag from raw_imu message.
static uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
Pack a raw_imu message on a channel.
#define MAVLINK_MSG_ID_RAW_IMU_CRC
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_put_uint64_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
static int16_t mavlink_msg_raw_imu_get_ymag(const mavlink_message_t *msg)
Get field ymag from raw_imu message.
static uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_raw_imu_t *raw_imu)
Encode a raw_imu struct.
static int16_t mavlink_msg_raw_imu_get_xacc(const mavlink_message_t *msg)
Get field xacc from raw_imu message.
static void mavlink_msg_raw_imu_decode(const mavlink_message_t *msg, mavlink_raw_imu_t *raw_imu)
Decode a raw_imu message into a struct.
static int16_t mavlink_msg_raw_imu_get_zgyro(const mavlink_message_t *msg)
Get field zgyro from raw_imu message.
#define _MAV_PAYLOAD(msg)
static int16_t mavlink_msg_raw_imu_get_ygyro(const mavlink_message_t *msg)
Get field ygyro from raw_imu message.
static int16_t mavlink_msg_raw_imu_get_zacc(const mavlink_message_t *msg)
Get field zacc from raw_imu message.
#define MAVLINK_MSG_ID_RAW_IMU_LEN
static uint16_t mavlink_msg_raw_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_raw_imu_t *raw_imu)
Encode a raw_imu struct on a channel.
static uint64_t mavlink_msg_raw_imu_get_time_usec(const mavlink_message_t *msg)
Send a raw_imu message.
static int16_t mavlink_msg_raw_imu_get_zmag(const mavlink_message_t *msg)
Get field zmag from raw_imu 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 uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
Pack a raw_imu message.
#define _mav_put_int16_t(buf, wire_offset, b)