3 #define MAVLINK_MSG_ID_VIBRATION 241    16 #define MAVLINK_MSG_ID_VIBRATION_LEN 32    17 #define MAVLINK_MSG_ID_241_LEN 32    19 #define MAVLINK_MSG_ID_VIBRATION_CRC 90    20 #define MAVLINK_MSG_ID_241_CRC 90    24 #define MAVLINK_MESSAGE_INFO_VIBRATION { \    27         {  { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vibration_t, time_usec) }, \    28          { "vibration_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vibration_t, vibration_x) }, \    29          { "vibration_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vibration_t, vibration_y) }, \    30          { "vibration_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vibration_t, vibration_z) }, \    31          { "clipping_0", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_vibration_t, clipping_0) }, \    32          { "clipping_1", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_vibration_t, clipping_1) }, \    33          { "clipping_2", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_vibration_t, clipping_2) }, \    56 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS   104                                                            mavlink_message_t* msg,
   107 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS   132 #if MAVLINK_CRC_EXTRA   163         return mavlink_msg_vibration_pack_chan(system_id, component_id, chan, msg, vibration->
time_usec, vibration->
vibration_x, vibration->
vibration_y, vibration->
vibration_z, vibration->
clipping_0, vibration->
clipping_1, vibration->
clipping_2);
   178 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS   182 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS   192 #if MAVLINK_CRC_EXTRA   207 #if MAVLINK_CRC_EXTRA   215 #if MAVLINK_MSG_ID_VIBRATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN   225 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS   226         char *buf = (
char *)msgbuf;
   235 #if MAVLINK_CRC_EXTRA   250 #if MAVLINK_CRC_EXTRA   271         return _MAV_RETURN_uint64_t(msg,  0);
   281         return _MAV_RETURN_float(msg,  8);
   291         return _MAV_RETURN_float(msg,  12);
   301         return _MAV_RETURN_float(msg,  16);
   311         return _MAV_RETURN_uint32_t(msg,  20);
   321         return _MAV_RETURN_uint32_t(msg,  24);
   331         return _MAV_RETURN_uint32_t(msg,  28);
   342 #if MAVLINK_NEED_BYTE_SWAP #define _mav_put_float(buf, wire_offset, b)
static float mavlink_msg_vibration_get_vibration_x(const mavlink_message_t *msg)
Get field vibration_x from vibration message. 
static void mavlink_msg_vibration_decode(const mavlink_message_t *msg, mavlink_vibration_t *vibration)
Decode a vibration message into a struct. 
#define MAVLINK_MSG_ID_VIBRATION_LEN
static float mavlink_msg_vibration_get_vibration_y(const mavlink_message_t *msg)
Get field vibration_y from vibration message. 
static uint32_t mavlink_msg_vibration_get_clipping_0(const mavlink_message_t *msg)
Get field clipping_0 from vibration message. 
static uint16_t mavlink_msg_vibration_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_vibration_t *vibration)
Encode a vibration 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. 
static uint16_t mavlink_msg_vibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_vibration_t *vibration)
Encode a vibration struct. 
#define _mav_put_uint64_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
#define _MAV_PAYLOAD(msg)
struct __mavlink_vibration_t mavlink_vibration_t
static uint32_t mavlink_msg_vibration_get_clipping_1(const mavlink_message_t *msg)
Get field clipping_1 from vibration message. 
static uint16_t mavlink_msg_vibration_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2)
Pack a vibration message on a channel. 
static uint16_t mavlink_msg_vibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2)
Pack a vibration message. 
#define MAVLINK_MSG_ID_VIBRATION_CRC
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 uint32_t mavlink_msg_vibration_get_clipping_2(const mavlink_message_t *msg)
Get field clipping_2 from vibration message. 
#define MAVLINK_MSG_ID_VIBRATION
static uint64_t mavlink_msg_vibration_get_time_usec(const mavlink_message_t *msg)
Send a vibration message. 
static float mavlink_msg_vibration_get_vibration_z(const mavlink_message_t *msg)
Get field vibration_z from vibration message. 
#define _mav_put_uint32_t(buf, wire_offset, b)