mavlink_msg_message_interval.h
Go to the documentation of this file.
00001 // MESSAGE MESSAGE_INTERVAL PACKING
00002 
00003 #define MAVLINK_MSG_ID_MESSAGE_INTERVAL 244
00004 
00005 typedef struct __mavlink_message_interval_t
00006 {
00007  int32_t interval_us; /*< The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.*/
00008  uint16_t message_id; /*< The ID of the requested MAVLink message. v1.0 is limited to 254 messages.*/
00009 } mavlink_message_interval_t;
00010 
00011 #define MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN 6
00012 #define MAVLINK_MSG_ID_244_LEN 6
00013 
00014 #define MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC 95
00015 #define MAVLINK_MSG_ID_244_CRC 95
00016 
00017 
00018 
00019 #define MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL { \
00020         "MESSAGE_INTERVAL", \
00021         2, \
00022         {  { "interval_us", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_message_interval_t, interval_us) }, \
00023          { "message_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_message_interval_t, message_id) }, \
00024          } \
00025 }
00026 
00027 
00038 static inline uint16_t mavlink_msg_message_interval_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00039                                                        uint16_t message_id, int32_t interval_us)
00040 {
00041 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00042         char buf[MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN];
00043         _mav_put_int32_t(buf, 0, interval_us);
00044         _mav_put_uint16_t(buf, 4, message_id);
00045 
00046         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN);
00047 #else
00048         mavlink_message_interval_t packet;
00049         packet.interval_us = interval_us;
00050         packet.message_id = message_id;
00051 
00052         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN);
00053 #endif
00054 
00055         msg->msgid = MAVLINK_MSG_ID_MESSAGE_INTERVAL;
00056 #if MAVLINK_CRC_EXTRA
00057     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC);
00058 #else
00059     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN);
00060 #endif
00061 }
00062 
00073 static inline uint16_t mavlink_msg_message_interval_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00074                                                            mavlink_message_t* msg,
00075                                                            uint16_t message_id,int32_t interval_us)
00076 {
00077 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00078         char buf[MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN];
00079         _mav_put_int32_t(buf, 0, interval_us);
00080         _mav_put_uint16_t(buf, 4, message_id);
00081 
00082         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN);
00083 #else
00084         mavlink_message_interval_t packet;
00085         packet.interval_us = interval_us;
00086         packet.message_id = message_id;
00087 
00088         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN);
00089 #endif
00090 
00091         msg->msgid = MAVLINK_MSG_ID_MESSAGE_INTERVAL;
00092 #if MAVLINK_CRC_EXTRA
00093     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC);
00094 #else
00095     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN);
00096 #endif
00097 }
00098 
00107 static inline uint16_t mavlink_msg_message_interval_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_message_interval_t* message_interval)
00108 {
00109         return mavlink_msg_message_interval_pack(system_id, component_id, msg, message_interval->message_id, message_interval->interval_us);
00110 }
00111 
00121 static inline uint16_t mavlink_msg_message_interval_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_message_interval_t* message_interval)
00122 {
00123         return mavlink_msg_message_interval_pack_chan(system_id, component_id, chan, msg, message_interval->message_id, message_interval->interval_us);
00124 }
00125 
00133 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00134 
00135 static inline void mavlink_msg_message_interval_send(mavlink_channel_t chan, uint16_t message_id, int32_t interval_us)
00136 {
00137 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00138         char buf[MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN];
00139         _mav_put_int32_t(buf, 0, interval_us);
00140         _mav_put_uint16_t(buf, 4, message_id);
00141 
00142 #if MAVLINK_CRC_EXTRA
00143     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC);
00144 #else
00145     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN);
00146 #endif
00147 #else
00148         mavlink_message_interval_t packet;
00149         packet.interval_us = interval_us;
00150         packet.message_id = message_id;
00151 
00152 #if MAVLINK_CRC_EXTRA
00153     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, (const char *)&packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC);
00154 #else
00155     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, (const char *)&packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN);
00156 #endif
00157 #endif
00158 }
00159 
00160 #if MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00161 /*
00162   This varient of _send() can be used to save stack space by re-using
00163   memory from the receive buffer.  The caller provides a
00164   mavlink_message_t which is the size of a full mavlink message. This
00165   is usually the receive buffer for the channel, and allows a reply to an
00166   incoming message with minimum stack space usage.
00167  */
00168 static inline void mavlink_msg_message_interval_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint16_t message_id, int32_t interval_us)
00169 {
00170 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00171         char *buf = (char *)msgbuf;
00172         _mav_put_int32_t(buf, 0, interval_us);
00173         _mav_put_uint16_t(buf, 4, message_id);
00174 
00175 #if MAVLINK_CRC_EXTRA
00176     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC);
00177 #else
00178     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN);
00179 #endif
00180 #else
00181         mavlink_message_interval_t *packet = (mavlink_message_interval_t *)msgbuf;
00182         packet->interval_us = interval_us;
00183         packet->message_id = message_id;
00184 
00185 #if MAVLINK_CRC_EXTRA
00186     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, (const char *)packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC);
00187 #else
00188     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, (const char *)packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN);
00189 #endif
00190 #endif
00191 }
00192 #endif
00193 
00194 #endif
00195 
00196 // MESSAGE MESSAGE_INTERVAL UNPACKING
00197 
00198 
00204 static inline uint16_t mavlink_msg_message_interval_get_message_id(const mavlink_message_t* msg)
00205 {
00206         return _MAV_RETURN_uint16_t(msg,  4);
00207 }
00208 
00214 static inline int32_t mavlink_msg_message_interval_get_interval_us(const mavlink_message_t* msg)
00215 {
00216         return _MAV_RETURN_int32_t(msg,  0);
00217 }
00218 
00225 static inline void mavlink_msg_message_interval_decode(const mavlink_message_t* msg, mavlink_message_interval_t* message_interval)
00226 {
00227 #if MAVLINK_NEED_BYTE_SWAP
00228         message_interval->interval_us = mavlink_msg_message_interval_get_interval_us(msg);
00229         message_interval->message_id = mavlink_msg_message_interval_get_message_id(msg);
00230 #else
00231         memcpy(message_interval, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN);
00232 #endif
00233 }


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