mavlink_msg_memory_vect.h
Go to the documentation of this file.
00001 // MESSAGE MEMORY_VECT PACKING
00002 
00003 #define MAVLINK_MSG_ID_MEMORY_VECT 249
00004 
00005 typedef struct __mavlink_memory_vect_t
00006 {
00007  uint16_t address; /*< Starting address of the debug variables*/
00008  uint8_t ver; /*< Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below*/
00009  uint8_t type; /*< Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14*/
00010  int8_t value[32]; /*< Memory contents at specified address*/
00011 } mavlink_memory_vect_t;
00012 
00013 #define MAVLINK_MSG_ID_MEMORY_VECT_LEN 36
00014 #define MAVLINK_MSG_ID_249_LEN 36
00015 
00016 #define MAVLINK_MSG_ID_MEMORY_VECT_CRC 204
00017 #define MAVLINK_MSG_ID_249_CRC 204
00018 
00019 #define MAVLINK_MSG_MEMORY_VECT_FIELD_VALUE_LEN 32
00020 
00021 #define MAVLINK_MESSAGE_INFO_MEMORY_VECT { \
00022         "MEMORY_VECT", \
00023         4, \
00024         {  { "address", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_memory_vect_t, address) }, \
00025          { "ver", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_memory_vect_t, ver) }, \
00026          { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_memory_vect_t, type) }, \
00027          { "value", NULL, MAVLINK_TYPE_INT8_T, 32, 4, offsetof(mavlink_memory_vect_t, value) }, \
00028          } \
00029 }
00030 
00031 
00044 static inline uint16_t mavlink_msg_memory_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00045                                                        uint16_t address, uint8_t ver, uint8_t type, const int8_t *value)
00046 {
00047 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00048         char buf[MAVLINK_MSG_ID_MEMORY_VECT_LEN];
00049         _mav_put_uint16_t(buf, 0, address);
00050         _mav_put_uint8_t(buf, 2, ver);
00051         _mav_put_uint8_t(buf, 3, type);
00052         _mav_put_int8_t_array(buf, 4, value, 32);
00053         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
00054 #else
00055         mavlink_memory_vect_t packet;
00056         packet.address = address;
00057         packet.ver = ver;
00058         packet.type = type;
00059         mav_array_memcpy(packet.value, value, sizeof(int8_t)*32);
00060         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
00061 #endif
00062 
00063         msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT;
00064 #if MAVLINK_CRC_EXTRA
00065     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC);
00066 #else
00067     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
00068 #endif
00069 }
00070 
00083 static inline uint16_t mavlink_msg_memory_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00084                                                            mavlink_message_t* msg,
00085                                                            uint16_t address,uint8_t ver,uint8_t type,const int8_t *value)
00086 {
00087 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00088         char buf[MAVLINK_MSG_ID_MEMORY_VECT_LEN];
00089         _mav_put_uint16_t(buf, 0, address);
00090         _mav_put_uint8_t(buf, 2, ver);
00091         _mav_put_uint8_t(buf, 3, type);
00092         _mav_put_int8_t_array(buf, 4, value, 32);
00093         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
00094 #else
00095         mavlink_memory_vect_t packet;
00096         packet.address = address;
00097         packet.ver = ver;
00098         packet.type = type;
00099         mav_array_memcpy(packet.value, value, sizeof(int8_t)*32);
00100         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
00101 #endif
00102 
00103         msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT;
00104 #if MAVLINK_CRC_EXTRA
00105     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC);
00106 #else
00107     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
00108 #endif
00109 }
00110 
00119 static inline uint16_t mavlink_msg_memory_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_memory_vect_t* memory_vect)
00120 {
00121         return mavlink_msg_memory_vect_pack(system_id, component_id, msg, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value);
00122 }
00123 
00133 static inline uint16_t mavlink_msg_memory_vect_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_memory_vect_t* memory_vect)
00134 {
00135         return mavlink_msg_memory_vect_pack_chan(system_id, component_id, chan, msg, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value);
00136 }
00137 
00147 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00148 
00149 static inline void mavlink_msg_memory_vect_send(mavlink_channel_t chan, uint16_t address, uint8_t ver, uint8_t type, const int8_t *value)
00150 {
00151 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00152         char buf[MAVLINK_MSG_ID_MEMORY_VECT_LEN];
00153         _mav_put_uint16_t(buf, 0, address);
00154         _mav_put_uint8_t(buf, 2, ver);
00155         _mav_put_uint8_t(buf, 3, type);
00156         _mav_put_int8_t_array(buf, 4, value, 32);
00157 #if MAVLINK_CRC_EXTRA
00158     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC);
00159 #else
00160     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
00161 #endif
00162 #else
00163         mavlink_memory_vect_t packet;
00164         packet.address = address;
00165         packet.ver = ver;
00166         packet.type = type;
00167         mav_array_memcpy(packet.value, value, sizeof(int8_t)*32);
00168 #if MAVLINK_CRC_EXTRA
00169     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)&packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC);
00170 #else
00171     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)&packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
00172 #endif
00173 #endif
00174 }
00175 
00176 #if MAVLINK_MSG_ID_MEMORY_VECT_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_memory_vect_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint16_t address, uint8_t ver, uint8_t type, const int8_t *value)
00185 {
00186 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00187         char *buf = (char *)msgbuf;
00188         _mav_put_uint16_t(buf, 0, address);
00189         _mav_put_uint8_t(buf, 2, ver);
00190         _mav_put_uint8_t(buf, 3, type);
00191         _mav_put_int8_t_array(buf, 4, value, 32);
00192 #if MAVLINK_CRC_EXTRA
00193     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC);
00194 #else
00195     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
00196 #endif
00197 #else
00198         mavlink_memory_vect_t *packet = (mavlink_memory_vect_t *)msgbuf;
00199         packet->address = address;
00200         packet->ver = ver;
00201         packet->type = type;
00202         mav_array_memcpy(packet->value, value, sizeof(int8_t)*32);
00203 #if MAVLINK_CRC_EXTRA
00204     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC);
00205 #else
00206     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
00207 #endif
00208 #endif
00209 }
00210 #endif
00211 
00212 #endif
00213 
00214 // MESSAGE MEMORY_VECT UNPACKING
00215 
00216 
00222 static inline uint16_t mavlink_msg_memory_vect_get_address(const mavlink_message_t* msg)
00223 {
00224         return _MAV_RETURN_uint16_t(msg,  0);
00225 }
00226 
00232 static inline uint8_t mavlink_msg_memory_vect_get_ver(const mavlink_message_t* msg)
00233 {
00234         return _MAV_RETURN_uint8_t(msg,  2);
00235 }
00236 
00242 static inline uint8_t mavlink_msg_memory_vect_get_type(const mavlink_message_t* msg)
00243 {
00244         return _MAV_RETURN_uint8_t(msg,  3);
00245 }
00246 
00252 static inline uint16_t mavlink_msg_memory_vect_get_value(const mavlink_message_t* msg, int8_t *value)
00253 {
00254         return _MAV_RETURN_int8_t_array(msg, value, 32,  4);
00255 }
00256 
00263 static inline void mavlink_msg_memory_vect_decode(const mavlink_message_t* msg, mavlink_memory_vect_t* memory_vect)
00264 {
00265 #if MAVLINK_NEED_BYTE_SWAP
00266         memory_vect->address = mavlink_msg_memory_vect_get_address(msg);
00267         memory_vect->ver = mavlink_msg_memory_vect_get_ver(msg);
00268         memory_vect->type = mavlink_msg_memory_vect_get_type(msg);
00269         mavlink_msg_memory_vect_get_value(msg, memory_vect->value);
00270 #else
00271         memcpy(memory_vect, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MEMORY_VECT_LEN);
00272 #endif
00273 }


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