mavlink_msg_log_request_data.h
Go to the documentation of this file.
00001 // MESSAGE LOG_REQUEST_DATA PACKING
00002 
00003 #define MAVLINK_MSG_ID_LOG_REQUEST_DATA 119
00004 
00005 typedef struct __mavlink_log_request_data_t
00006 {
00007  uint32_t ofs; /*< Offset into the log*/
00008  uint32_t count; /*< Number of bytes*/
00009  uint16_t id; /*< Log id (from LOG_ENTRY reply)*/
00010  uint8_t target_system; /*< System ID*/
00011  uint8_t target_component; /*< Component ID*/
00012 } mavlink_log_request_data_t;
00013 
00014 #define MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN 12
00015 #define MAVLINK_MSG_ID_119_LEN 12
00016 
00017 #define MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC 116
00018 #define MAVLINK_MSG_ID_119_CRC 116
00019 
00020 
00021 
00022 #define MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA { \
00023         "LOG_REQUEST_DATA", \
00024         5, \
00025         {  { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \
00026          { "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \
00027          { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \
00028          { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \
00029          { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_log_request_data_t, target_component) }, \
00030          } \
00031 }
00032 
00033 
00047 static inline uint16_t mavlink_msg_log_request_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00048                                                        uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count)
00049 {
00050 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00051         char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN];
00052         _mav_put_uint32_t(buf, 0, ofs);
00053         _mav_put_uint32_t(buf, 4, count);
00054         _mav_put_uint16_t(buf, 8, id);
00055         _mav_put_uint8_t(buf, 10, target_system);
00056         _mav_put_uint8_t(buf, 11, target_component);
00057 
00058         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
00059 #else
00060         mavlink_log_request_data_t packet;
00061         packet.ofs = ofs;
00062         packet.count = count;
00063         packet.id = id;
00064         packet.target_system = target_system;
00065         packet.target_component = target_component;
00066 
00067         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
00068 #endif
00069 
00070         msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_DATA;
00071 #if MAVLINK_CRC_EXTRA
00072     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC);
00073 #else
00074     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
00075 #endif
00076 }
00077 
00091 static inline uint16_t mavlink_msg_log_request_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00092                                                            mavlink_message_t* msg,
00093                                                            uint8_t target_system,uint8_t target_component,uint16_t id,uint32_t ofs,uint32_t count)
00094 {
00095 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00096         char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN];
00097         _mav_put_uint32_t(buf, 0, ofs);
00098         _mav_put_uint32_t(buf, 4, count);
00099         _mav_put_uint16_t(buf, 8, id);
00100         _mav_put_uint8_t(buf, 10, target_system);
00101         _mav_put_uint8_t(buf, 11, target_component);
00102 
00103         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
00104 #else
00105         mavlink_log_request_data_t packet;
00106         packet.ofs = ofs;
00107         packet.count = count;
00108         packet.id = id;
00109         packet.target_system = target_system;
00110         packet.target_component = target_component;
00111 
00112         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
00113 #endif
00114 
00115         msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_DATA;
00116 #if MAVLINK_CRC_EXTRA
00117     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC);
00118 #else
00119     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
00120 #endif
00121 }
00122 
00131 static inline uint16_t mavlink_msg_log_request_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_data_t* log_request_data)
00132 {
00133         return mavlink_msg_log_request_data_pack(system_id, component_id, msg, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count);
00134 }
00135 
00145 static inline uint16_t mavlink_msg_log_request_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_data_t* log_request_data)
00146 {
00147         return mavlink_msg_log_request_data_pack_chan(system_id, component_id, chan, msg, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count);
00148 }
00149 
00160 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00161 
00162 static inline void mavlink_msg_log_request_data_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count)
00163 {
00164 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00165         char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN];
00166         _mav_put_uint32_t(buf, 0, ofs);
00167         _mav_put_uint32_t(buf, 4, count);
00168         _mav_put_uint16_t(buf, 8, id);
00169         _mav_put_uint8_t(buf, 10, target_system);
00170         _mav_put_uint8_t(buf, 11, target_component);
00171 
00172 #if MAVLINK_CRC_EXTRA
00173     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC);
00174 #else
00175     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
00176 #endif
00177 #else
00178         mavlink_log_request_data_t packet;
00179         packet.ofs = ofs;
00180         packet.count = count;
00181         packet.id = id;
00182         packet.target_system = target_system;
00183         packet.target_component = target_component;
00184 
00185 #if MAVLINK_CRC_EXTRA
00186     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC);
00187 #else
00188     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
00189 #endif
00190 #endif
00191 }
00192 
00193 #if MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00194 /*
00195   This varient of _send() can be used to save stack space by re-using
00196   memory from the receive buffer.  The caller provides a
00197   mavlink_message_t which is the size of a full mavlink message. This
00198   is usually the receive buffer for the channel, and allows a reply to an
00199   incoming message with minimum stack space usage.
00200  */
00201 static inline void mavlink_msg_log_request_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count)
00202 {
00203 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00204         char *buf = (char *)msgbuf;
00205         _mav_put_uint32_t(buf, 0, ofs);
00206         _mav_put_uint32_t(buf, 4, count);
00207         _mav_put_uint16_t(buf, 8, id);
00208         _mav_put_uint8_t(buf, 10, target_system);
00209         _mav_put_uint8_t(buf, 11, target_component);
00210 
00211 #if MAVLINK_CRC_EXTRA
00212     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC);
00213 #else
00214     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
00215 #endif
00216 #else
00217         mavlink_log_request_data_t *packet = (mavlink_log_request_data_t *)msgbuf;
00218         packet->ofs = ofs;
00219         packet->count = count;
00220         packet->id = id;
00221         packet->target_system = target_system;
00222         packet->target_component = target_component;
00223 
00224 #if MAVLINK_CRC_EXTRA
00225     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC);
00226 #else
00227     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
00228 #endif
00229 #endif
00230 }
00231 #endif
00232 
00233 #endif
00234 
00235 // MESSAGE LOG_REQUEST_DATA UNPACKING
00236 
00237 
00243 static inline uint8_t mavlink_msg_log_request_data_get_target_system(const mavlink_message_t* msg)
00244 {
00245         return _MAV_RETURN_uint8_t(msg,  10);
00246 }
00247 
00253 static inline uint8_t mavlink_msg_log_request_data_get_target_component(const mavlink_message_t* msg)
00254 {
00255         return _MAV_RETURN_uint8_t(msg,  11);
00256 }
00257 
00263 static inline uint16_t mavlink_msg_log_request_data_get_id(const mavlink_message_t* msg)
00264 {
00265         return _MAV_RETURN_uint16_t(msg,  8);
00266 }
00267 
00273 static inline uint32_t mavlink_msg_log_request_data_get_ofs(const mavlink_message_t* msg)
00274 {
00275         return _MAV_RETURN_uint32_t(msg,  0);
00276 }
00277 
00283 static inline uint32_t mavlink_msg_log_request_data_get_count(const mavlink_message_t* msg)
00284 {
00285         return _MAV_RETURN_uint32_t(msg,  4);
00286 }
00287 
00294 static inline void mavlink_msg_log_request_data_decode(const mavlink_message_t* msg, mavlink_log_request_data_t* log_request_data)
00295 {
00296 #if MAVLINK_NEED_BYTE_SWAP
00297         log_request_data->ofs = mavlink_msg_log_request_data_get_ofs(msg);
00298         log_request_data->count = mavlink_msg_log_request_data_get_count(msg);
00299         log_request_data->id = mavlink_msg_log_request_data_get_id(msg);
00300         log_request_data->target_system = mavlink_msg_log_request_data_get_target_system(msg);
00301         log_request_data->target_component = mavlink_msg_log_request_data_get_target_component(msg);
00302 #else
00303         memcpy(log_request_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
00304 #endif
00305 }


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