3 #define MAVLINK_MSG_ID_SCALED_IMU2 116 19 #define MAVLINK_MSG_ID_SCALED_IMU2_LEN 22 20 #define MAVLINK_MSG_ID_116_LEN 22 22 #define MAVLINK_MSG_ID_SCALED_IMU2_CRC 76 23 #define MAVLINK_MSG_ID_116_CRC 76 27 #define MAVLINK_MESSAGE_INFO_SCALED_IMU2 { \ 30 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu2_t, time_boot_ms) }, \ 31 { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu2_t, xacc) }, \ 32 { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu2_t, yacc) }, \ 33 { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu2_t, zacc) }, \ 34 { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu2_t, xgyro) }, \ 35 { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu2_t, ygyro) }, \ 36 { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu2_t, zgyro) }, \ 37 { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu2_t, xmag) }, \ 38 { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu2_t, ymag) }, \ 39 { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu2_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_scaled_imu2_pack(system_id, component_id, msg, scaled_imu2->
time_boot_ms, scaled_imu2->
xacc, scaled_imu2->
yacc, scaled_imu2->
zacc, scaled_imu2->
xgyro, scaled_imu2->
ygyro, scaled_imu2->
zgyro, scaled_imu2->
xmag, scaled_imu2->
ymag, scaled_imu2->
zmag);
187 return mavlink_msg_scaled_imu2_pack_chan(system_id, component_id, chan, msg, scaled_imu2->
time_boot_ms, scaled_imu2->
xacc, scaled_imu2->
yacc, scaled_imu2->
zacc, scaled_imu2->
xgyro, scaled_imu2->
ygyro, scaled_imu2->
zgyro, scaled_imu2->
xmag, scaled_imu2->
ymag, scaled_imu2->
zmag);
205 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 207 static inline void mavlink_msg_scaled_imu2_send(
mavlink_channel_t chan, uint32_t
time_boot_ms, 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_SCALED_IMU2_LEN <= MAVLINK_MAX_PAYLOAD_LEN 256 static inline void mavlink_msg_scaled_imu2_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint32_t
time_boot_ms, 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_uint32_t(msg, 0);
320 return _MAV_RETURN_int16_t(msg, 4);
330 return _MAV_RETURN_int16_t(msg, 6);
340 return _MAV_RETURN_int16_t(msg, 8);
350 return _MAV_RETURN_int16_t(msg, 10);
360 return _MAV_RETURN_int16_t(msg, 12);
370 return _MAV_RETURN_int16_t(msg, 14);
380 return _MAV_RETURN_int16_t(msg, 16);
390 return _MAV_RETURN_int16_t(msg, 18);
400 return _MAV_RETURN_int16_t(msg, 20);
411 #if MAVLINK_NEED_BYTE_SWAP static int16_t mavlink_msg_scaled_imu2_get_ymag(const mavlink_message_t *msg)
Get field ymag from scaled_imu2 message.
static int16_t mavlink_msg_scaled_imu2_get_zmag(const mavlink_message_t *msg)
Get field zmag from scaled_imu2 message.
static uint16_t mavlink_msg_scaled_imu2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_scaled_imu2_t *scaled_imu2)
Encode a scaled_imu2 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 int16_t mavlink_msg_scaled_imu2_get_xacc(const mavlink_message_t *msg)
Get field xacc from scaled_imu2 message.
#define MAVLINK_MSG_ID_SCALED_IMU2_CRC
static uint32_t mavlink_msg_scaled_imu2_get_time_boot_ms(const mavlink_message_t *msg)
Send a scaled_imu2 message.
struct __mavlink_scaled_imu2_t mavlink_scaled_imu2_t
#define _MAV_PAYLOAD(msg)
static int16_t mavlink_msg_scaled_imu2_get_xmag(const mavlink_message_t *msg)
Get field xmag from scaled_imu2 message.
static int16_t mavlink_msg_scaled_imu2_get_zgyro(const mavlink_message_t *msg)
Get field zgyro from scaled_imu2 message.
static uint16_t mavlink_msg_scaled_imu2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_scaled_imu2_t *scaled_imu2)
Encode a scaled_imu2 struct.
#define MAVLINK_MSG_ID_SCALED_IMU2
static uint16_t mavlink_msg_scaled_imu2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t time_boot_ms, 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 scaled_imu2 message on a channel.
static int16_t mavlink_msg_scaled_imu2_get_ygyro(const mavlink_message_t *msg)
Get field ygyro from scaled_imu2 message.
static int16_t mavlink_msg_scaled_imu2_get_zacc(const mavlink_message_t *msg)
Get field zacc from scaled_imu2 message.
static uint16_t mavlink_msg_scaled_imu2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_boot_ms, 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 scaled_imu2 message.
static void mavlink_msg_scaled_imu2_decode(const mavlink_message_t *msg, mavlink_scaled_imu2_t *scaled_imu2)
Decode a scaled_imu2 message into a struct.
static int16_t mavlink_msg_scaled_imu2_get_yacc(const mavlink_message_t *msg)
Get field yacc from scaled_imu2 message.
#define MAVLINK_MSG_ID_SCALED_IMU2_LEN
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.
#define _mav_put_int16_t(buf, wire_offset, b)
static int16_t mavlink_msg_scaled_imu2_get_xgyro(const mavlink_message_t *msg)
Get field xgyro from scaled_imu2 message.
#define _mav_put_uint32_t(buf, wire_offset, b)