mavlink_msg_log_data.h
Go to the documentation of this file.
00001 // MESSAGE LOG_DATA PACKING
00002 
00003 #define MAVLINK_MSG_ID_LOG_DATA 120
00004 
00005 typedef struct __mavlink_log_data_t
00006 {
00007  uint32_t ofs; /*< Offset into the log*/
00008  uint16_t id; /*< Log id (from LOG_ENTRY reply)*/
00009  uint8_t count; /*< Number of bytes (zero for end of log)*/
00010  uint8_t data[90]; /*< log data*/
00011 } mavlink_log_data_t;
00012 
00013 #define MAVLINK_MSG_ID_LOG_DATA_LEN 97
00014 #define MAVLINK_MSG_ID_120_LEN 97
00015 
00016 #define MAVLINK_MSG_ID_LOG_DATA_CRC 134
00017 #define MAVLINK_MSG_ID_120_CRC 134
00018 
00019 #define MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN 90
00020 
00021 #define MAVLINK_MESSAGE_INFO_LOG_DATA { \
00022         "LOG_DATA", \
00023         4, \
00024         {  { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_data_t, ofs) }, \
00025          { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_log_data_t, id) }, \
00026          { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_log_data_t, count) }, \
00027          { "data", NULL, MAVLINK_TYPE_UINT8_T, 90, 7, offsetof(mavlink_log_data_t, data) }, \
00028          } \
00029 }
00030 
00031 
00044 static inline uint16_t mavlink_msg_log_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00045                                                        uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data)
00046 {
00047 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00048         char buf[MAVLINK_MSG_ID_LOG_DATA_LEN];
00049         _mav_put_uint32_t(buf, 0, ofs);
00050         _mav_put_uint16_t(buf, 4, id);
00051         _mav_put_uint8_t(buf, 6, count);
00052         _mav_put_uint8_t_array(buf, 7, data, 90);
00053         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_DATA_LEN);
00054 #else
00055         mavlink_log_data_t packet;
00056         packet.ofs = ofs;
00057         packet.id = id;
00058         packet.count = count;
00059         mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90);
00060         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_DATA_LEN);
00061 #endif
00062 
00063         msg->msgid = MAVLINK_MSG_ID_LOG_DATA;
00064 #if MAVLINK_CRC_EXTRA
00065     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
00066 #else
00067     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_DATA_LEN);
00068 #endif
00069 }
00070 
00083 static inline uint16_t mavlink_msg_log_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00084                                                            mavlink_message_t* msg,
00085                                                            uint16_t id,uint32_t ofs,uint8_t count,const uint8_t *data)
00086 {
00087 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00088         char buf[MAVLINK_MSG_ID_LOG_DATA_LEN];
00089         _mav_put_uint32_t(buf, 0, ofs);
00090         _mav_put_uint16_t(buf, 4, id);
00091         _mav_put_uint8_t(buf, 6, count);
00092         _mav_put_uint8_t_array(buf, 7, data, 90);
00093         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_DATA_LEN);
00094 #else
00095         mavlink_log_data_t packet;
00096         packet.ofs = ofs;
00097         packet.id = id;
00098         packet.count = count;
00099         mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90);
00100         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_DATA_LEN);
00101 #endif
00102 
00103         msg->msgid = MAVLINK_MSG_ID_LOG_DATA;
00104 #if MAVLINK_CRC_EXTRA
00105     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
00106 #else
00107     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_DATA_LEN);
00108 #endif
00109 }
00110 
00119 static inline uint16_t mavlink_msg_log_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_data_t* log_data)
00120 {
00121         return mavlink_msg_log_data_pack(system_id, component_id, msg, log_data->id, log_data->ofs, log_data->count, log_data->data);
00122 }
00123 
00133 static inline uint16_t mavlink_msg_log_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_data_t* log_data)
00134 {
00135         return mavlink_msg_log_data_pack_chan(system_id, component_id, chan, msg, log_data->id, log_data->ofs, log_data->count, log_data->data);
00136 }
00137 
00147 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00148 
00149 static inline void mavlink_msg_log_data_send(mavlink_channel_t chan, uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data)
00150 {
00151 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00152         char buf[MAVLINK_MSG_ID_LOG_DATA_LEN];
00153         _mav_put_uint32_t(buf, 0, ofs);
00154         _mav_put_uint16_t(buf, 4, id);
00155         _mav_put_uint8_t(buf, 6, count);
00156         _mav_put_uint8_t_array(buf, 7, data, 90);
00157 #if MAVLINK_CRC_EXTRA
00158     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
00159 #else
00160     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN);
00161 #endif
00162 #else
00163         mavlink_log_data_t packet;
00164         packet.ofs = ofs;
00165         packet.id = id;
00166         packet.count = count;
00167         mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90);
00168 #if MAVLINK_CRC_EXTRA
00169     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
00170 #else
00171     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_DATA_LEN);
00172 #endif
00173 #endif
00174 }
00175 
00176 #if MAVLINK_MSG_ID_LOG_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00177 /*
00178   This varient of _send() can be used to save stack space by re-using
00179   memory from the receive buffer.  The caller provides a
00180   mavlink_message_t which is the size of a full mavlink message. This
00181   is usually the receive buffer for the channel, and allows a reply to an
00182   incoming message with minimum stack space usage.
00183  */
00184 static inline void mavlink_msg_log_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data)
00185 {
00186 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00187         char *buf = (char *)msgbuf;
00188         _mav_put_uint32_t(buf, 0, ofs);
00189         _mav_put_uint16_t(buf, 4, id);
00190         _mav_put_uint8_t(buf, 6, count);
00191         _mav_put_uint8_t_array(buf, 7, data, 90);
00192 #if MAVLINK_CRC_EXTRA
00193     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
00194 #else
00195     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN);
00196 #endif
00197 #else
00198         mavlink_log_data_t *packet = (mavlink_log_data_t *)msgbuf;
00199         packet->ofs = ofs;
00200         packet->id = id;
00201         packet->count = count;
00202         mav_array_memcpy(packet->data, data, sizeof(uint8_t)*90);
00203 #if MAVLINK_CRC_EXTRA
00204     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
00205 #else
00206     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_DATA_LEN);
00207 #endif
00208 #endif
00209 }
00210 #endif
00211 
00212 #endif
00213 
00214 // MESSAGE LOG_DATA UNPACKING
00215 
00216 
00222 static inline uint16_t mavlink_msg_log_data_get_id(const mavlink_message_t* msg)
00223 {
00224         return _MAV_RETURN_uint16_t(msg,  4);
00225 }
00226 
00232 static inline uint32_t mavlink_msg_log_data_get_ofs(const mavlink_message_t* msg)
00233 {
00234         return _MAV_RETURN_uint32_t(msg,  0);
00235 }
00236 
00242 static inline uint8_t mavlink_msg_log_data_get_count(const mavlink_message_t* msg)
00243 {
00244         return _MAV_RETURN_uint8_t(msg,  6);
00245 }
00246 
00252 static inline uint16_t mavlink_msg_log_data_get_data(const mavlink_message_t* msg, uint8_t *data)
00253 {
00254         return _MAV_RETURN_uint8_t_array(msg, data, 90,  7);
00255 }
00256 
00263 static inline void mavlink_msg_log_data_decode(const mavlink_message_t* msg, mavlink_log_data_t* log_data)
00264 {
00265 #if MAVLINK_NEED_BYTE_SWAP
00266         log_data->ofs = mavlink_msg_log_data_get_ofs(msg);
00267         log_data->id = mavlink_msg_log_data_get_id(msg);
00268         log_data->count = mavlink_msg_log_data_get_count(msg);
00269         mavlink_msg_log_data_get_data(msg, log_data->data);
00270 #else
00271         memcpy(log_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_DATA_LEN);
00272 #endif
00273 }


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