3 #define MAVLINK_MSG_ID_SMALL_IMU 181 17 #define MAVLINK_MSG_ID_SMALL_IMU_LEN 36 18 #define MAVLINK_MSG_ID_181_LEN 36 20 #define MAVLINK_MSG_ID_SMALL_IMU_CRC 67 21 #define MAVLINK_MSG_ID_181_CRC 67 25 #define MAVLINK_MESSAGE_INFO_SMALL_IMU { \ 28 { { "time_boot_us", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_small_imu_t, time_boot_us) }, \ 29 { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_small_imu_t, xacc) }, \ 30 { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_small_imu_t, yacc) }, \ 31 { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_small_imu_t, zacc) }, \ 32 { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_small_imu_t, xgyro) }, \ 33 { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_small_imu_t, ygyro) }, \ 34 { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_small_imu_t, zgyro) }, \ 35 { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_small_imu_t, temperature) }, \ 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_small_imu_pack(system_id, component_id, msg, small_imu->
time_boot_us, small_imu->
xacc, small_imu->
yacc, small_imu->
zacc, small_imu->
xgyro, small_imu->
ygyro, small_imu->
zgyro, small_imu->
temperature);
171 return mavlink_msg_small_imu_pack_chan(system_id, component_id, chan, msg, small_imu->
time_boot_us, small_imu->
xacc, small_imu->
yacc, small_imu->
zacc, small_imu->
xgyro, small_imu->
ygyro, small_imu->
zgyro, small_imu->
temperature);
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_SMALL_IMU_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_uint64_t(msg, 0);
294 return _MAV_RETURN_float(msg, 8);
304 return _MAV_RETURN_float(msg, 12);
314 return _MAV_RETURN_float(msg, 16);
324 return _MAV_RETURN_float(msg, 20);
334 return _MAV_RETURN_float(msg, 24);
344 return _MAV_RETURN_float(msg, 28);
354 return _MAV_RETURN_float(msg, 32);
365 #if MAVLINK_NEED_BYTE_SWAP #define _mav_put_float(buf, wire_offset, b)
#define MAVLINK_MSG_ID_SMALL_IMU
static float mavlink_msg_small_imu_get_ygyro(const mavlink_message_t *msg)
Get field ygyro from small_imu message.
static uint16_t mavlink_msg_small_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t time_boot_us, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float temperature)
Pack a small_imu message on a channel.
static float mavlink_msg_small_imu_get_zgyro(const mavlink_message_t *msg)
Get field zgyro from small_imu message.
static float mavlink_msg_small_imu_get_xacc(const mavlink_message_t *msg)
Get field xacc from small_imu message.
static float mavlink_msg_small_imu_get_temperature(const mavlink_message_t *msg)
Get field temperature from small_imu message.
static void mavlink_msg_small_imu_decode(const mavlink_message_t *msg, mavlink_small_imu_t *small_imu)
Decode a small_imu message into a struct.
static uint16_t mavlink_msg_small_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_small_imu_t *small_imu)
Encode a small_imu 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_put_uint64_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
struct __mavlink_small_imu_t mavlink_small_imu_t
static uint16_t mavlink_msg_small_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_small_imu_t *small_imu)
Encode a small_imu struct.
#define _MAV_PAYLOAD(msg)
#define MAVLINK_MSG_ID_SMALL_IMU_LEN
#define MAVLINK_MSG_ID_SMALL_IMU_CRC
static float mavlink_msg_small_imu_get_xgyro(const mavlink_message_t *msg)
Get field xgyro from small_imu message.
static uint16_t mavlink_msg_small_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t time_boot_us, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float temperature)
Pack a small_imu message.
static float mavlink_msg_small_imu_get_yacc(const mavlink_message_t *msg)
Get field yacc from small_imu message.
static float mavlink_msg_small_imu_get_zacc(const mavlink_message_t *msg)
Get field zacc from small_imu message.
static uint64_t mavlink_msg_small_imu_get_time_boot_us(const mavlink_message_t *msg)
Send a small_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.