mavlink_msg_vibration.h
Go to the documentation of this file.
00001 // MESSAGE VIBRATION PACKING
00002 
00003 #define MAVLINK_MSG_ID_VIBRATION 241
00004 
00005 typedef struct __mavlink_vibration_t
00006 {
00007  uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/
00008  float vibration_x; /*< Vibration levels on X-axis*/
00009  float vibration_y; /*< Vibration levels on Y-axis*/
00010  float vibration_z; /*< Vibration levels on Z-axis*/
00011  uint32_t clipping_0; /*< first accelerometer clipping count*/
00012  uint32_t clipping_1; /*< second accelerometer clipping count*/
00013  uint32_t clipping_2; /*< third accelerometer clipping count*/
00014 } mavlink_vibration_t;
00015 
00016 #define MAVLINK_MSG_ID_VIBRATION_LEN 32
00017 #define MAVLINK_MSG_ID_241_LEN 32
00018 
00019 #define MAVLINK_MSG_ID_VIBRATION_CRC 90
00020 #define MAVLINK_MSG_ID_241_CRC 90
00021 
00022 
00023 
00024 #define MAVLINK_MESSAGE_INFO_VIBRATION { \
00025         "VIBRATION", \
00026         7, \
00027         {  { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vibration_t, time_usec) }, \
00028          { "vibration_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vibration_t, vibration_x) }, \
00029          { "vibration_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vibration_t, vibration_y) }, \
00030          { "vibration_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vibration_t, vibration_z) }, \
00031          { "clipping_0", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_vibration_t, clipping_0) }, \
00032          { "clipping_1", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_vibration_t, clipping_1) }, \
00033          { "clipping_2", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_vibration_t, clipping_2) }, \
00034          } \
00035 }
00036 
00037 
00053 static inline uint16_t mavlink_msg_vibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00054                                                        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)
00055 {
00056 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00057         char buf[MAVLINK_MSG_ID_VIBRATION_LEN];
00058         _mav_put_uint64_t(buf, 0, time_usec);
00059         _mav_put_float(buf, 8, vibration_x);
00060         _mav_put_float(buf, 12, vibration_y);
00061         _mav_put_float(buf, 16, vibration_z);
00062         _mav_put_uint32_t(buf, 20, clipping_0);
00063         _mav_put_uint32_t(buf, 24, clipping_1);
00064         _mav_put_uint32_t(buf, 28, clipping_2);
00065 
00066         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIBRATION_LEN);
00067 #else
00068         mavlink_vibration_t packet;
00069         packet.time_usec = time_usec;
00070         packet.vibration_x = vibration_x;
00071         packet.vibration_y = vibration_y;
00072         packet.vibration_z = vibration_z;
00073         packet.clipping_0 = clipping_0;
00074         packet.clipping_1 = clipping_1;
00075         packet.clipping_2 = clipping_2;
00076 
00077         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIBRATION_LEN);
00078 #endif
00079 
00080         msg->msgid = MAVLINK_MSG_ID_VIBRATION;
00081 #if MAVLINK_CRC_EXTRA
00082     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC);
00083 #else
00084     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VIBRATION_LEN);
00085 #endif
00086 }
00087 
00103 static inline uint16_t mavlink_msg_vibration_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00104                                                            mavlink_message_t* msg,
00105                                                            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)
00106 {
00107 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00108         char buf[MAVLINK_MSG_ID_VIBRATION_LEN];
00109         _mav_put_uint64_t(buf, 0, time_usec);
00110         _mav_put_float(buf, 8, vibration_x);
00111         _mav_put_float(buf, 12, vibration_y);
00112         _mav_put_float(buf, 16, vibration_z);
00113         _mav_put_uint32_t(buf, 20, clipping_0);
00114         _mav_put_uint32_t(buf, 24, clipping_1);
00115         _mav_put_uint32_t(buf, 28, clipping_2);
00116 
00117         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIBRATION_LEN);
00118 #else
00119         mavlink_vibration_t packet;
00120         packet.time_usec = time_usec;
00121         packet.vibration_x = vibration_x;
00122         packet.vibration_y = vibration_y;
00123         packet.vibration_z = vibration_z;
00124         packet.clipping_0 = clipping_0;
00125         packet.clipping_1 = clipping_1;
00126         packet.clipping_2 = clipping_2;
00127 
00128         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIBRATION_LEN);
00129 #endif
00130 
00131         msg->msgid = MAVLINK_MSG_ID_VIBRATION;
00132 #if MAVLINK_CRC_EXTRA
00133     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC);
00134 #else
00135     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VIBRATION_LEN);
00136 #endif
00137 }
00138 
00147 static inline uint16_t mavlink_msg_vibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vibration_t* vibration)
00148 {
00149         return mavlink_msg_vibration_pack(system_id, component_id, msg, vibration->time_usec, vibration->vibration_x, vibration->vibration_y, vibration->vibration_z, vibration->clipping_0, vibration->clipping_1, vibration->clipping_2);
00150 }
00151 
00161 static inline 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)
00162 {
00163         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);
00164 }
00165 
00178 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00179 
00180 static inline void mavlink_msg_vibration_send(mavlink_channel_t chan, 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)
00181 {
00182 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00183         char buf[MAVLINK_MSG_ID_VIBRATION_LEN];
00184         _mav_put_uint64_t(buf, 0, time_usec);
00185         _mav_put_float(buf, 8, vibration_x);
00186         _mav_put_float(buf, 12, vibration_y);
00187         _mav_put_float(buf, 16, vibration_z);
00188         _mav_put_uint32_t(buf, 20, clipping_0);
00189         _mav_put_uint32_t(buf, 24, clipping_1);
00190         _mav_put_uint32_t(buf, 28, clipping_2);
00191 
00192 #if MAVLINK_CRC_EXTRA
00193     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, buf, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC);
00194 #else
00195     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, buf, MAVLINK_MSG_ID_VIBRATION_LEN);
00196 #endif
00197 #else
00198         mavlink_vibration_t packet;
00199         packet.time_usec = time_usec;
00200         packet.vibration_x = vibration_x;
00201         packet.vibration_y = vibration_y;
00202         packet.vibration_z = vibration_z;
00203         packet.clipping_0 = clipping_0;
00204         packet.clipping_1 = clipping_1;
00205         packet.clipping_2 = clipping_2;
00206 
00207 #if MAVLINK_CRC_EXTRA
00208     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)&packet, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC);
00209 #else
00210     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)&packet, MAVLINK_MSG_ID_VIBRATION_LEN);
00211 #endif
00212 #endif
00213 }
00214 
00215 #if MAVLINK_MSG_ID_VIBRATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00216 /*
00217   This varient of _send() can be used to save stack space by re-using
00218   memory from the receive buffer.  The caller provides a
00219   mavlink_message_t which is the size of a full mavlink message. This
00220   is usually the receive buffer for the channel, and allows a reply to an
00221   incoming message with minimum stack space usage.
00222  */
00223 static inline void mavlink_msg_vibration_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  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)
00224 {
00225 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00226         char *buf = (char *)msgbuf;
00227         _mav_put_uint64_t(buf, 0, time_usec);
00228         _mav_put_float(buf, 8, vibration_x);
00229         _mav_put_float(buf, 12, vibration_y);
00230         _mav_put_float(buf, 16, vibration_z);
00231         _mav_put_uint32_t(buf, 20, clipping_0);
00232         _mav_put_uint32_t(buf, 24, clipping_1);
00233         _mav_put_uint32_t(buf, 28, clipping_2);
00234 
00235 #if MAVLINK_CRC_EXTRA
00236     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, buf, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC);
00237 #else
00238     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, buf, MAVLINK_MSG_ID_VIBRATION_LEN);
00239 #endif
00240 #else
00241         mavlink_vibration_t *packet = (mavlink_vibration_t *)msgbuf;
00242         packet->time_usec = time_usec;
00243         packet->vibration_x = vibration_x;
00244         packet->vibration_y = vibration_y;
00245         packet->vibration_z = vibration_z;
00246         packet->clipping_0 = clipping_0;
00247         packet->clipping_1 = clipping_1;
00248         packet->clipping_2 = clipping_2;
00249 
00250 #if MAVLINK_CRC_EXTRA
00251     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)packet, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC);
00252 #else
00253     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)packet, MAVLINK_MSG_ID_VIBRATION_LEN);
00254 #endif
00255 #endif
00256 }
00257 #endif
00258 
00259 #endif
00260 
00261 // MESSAGE VIBRATION UNPACKING
00262 
00263 
00269 static inline uint64_t mavlink_msg_vibration_get_time_usec(const mavlink_message_t* msg)
00270 {
00271         return _MAV_RETURN_uint64_t(msg,  0);
00272 }
00273 
00279 static inline float mavlink_msg_vibration_get_vibration_x(const mavlink_message_t* msg)
00280 {
00281         return _MAV_RETURN_float(msg,  8);
00282 }
00283 
00289 static inline float mavlink_msg_vibration_get_vibration_y(const mavlink_message_t* msg)
00290 {
00291         return _MAV_RETURN_float(msg,  12);
00292 }
00293 
00299 static inline float mavlink_msg_vibration_get_vibration_z(const mavlink_message_t* msg)
00300 {
00301         return _MAV_RETURN_float(msg,  16);
00302 }
00303 
00309 static inline uint32_t mavlink_msg_vibration_get_clipping_0(const mavlink_message_t* msg)
00310 {
00311         return _MAV_RETURN_uint32_t(msg,  20);
00312 }
00313 
00319 static inline uint32_t mavlink_msg_vibration_get_clipping_1(const mavlink_message_t* msg)
00320 {
00321         return _MAV_RETURN_uint32_t(msg,  24);
00322 }
00323 
00329 static inline uint32_t mavlink_msg_vibration_get_clipping_2(const mavlink_message_t* msg)
00330 {
00331         return _MAV_RETURN_uint32_t(msg,  28);
00332 }
00333 
00340 static inline void mavlink_msg_vibration_decode(const mavlink_message_t* msg, mavlink_vibration_t* vibration)
00341 {
00342 #if MAVLINK_NEED_BYTE_SWAP
00343         vibration->time_usec = mavlink_msg_vibration_get_time_usec(msg);
00344         vibration->vibration_x = mavlink_msg_vibration_get_vibration_x(msg);
00345         vibration->vibration_y = mavlink_msg_vibration_get_vibration_y(msg);
00346         vibration->vibration_z = mavlink_msg_vibration_get_vibration_z(msg);
00347         vibration->clipping_0 = mavlink_msg_vibration_get_clipping_0(msg);
00348         vibration->clipping_1 = mavlink_msg_vibration_get_clipping_1(msg);
00349         vibration->clipping_2 = mavlink_msg_vibration_get_clipping_2(msg);
00350 #else
00351         memcpy(vibration, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VIBRATION_LEN);
00352 #endif
00353 }


dji_sdk_dji2mav
Author(s):
autogenerated on Thu Jun 6 2019 17:55:35