mavlink_msg_v2_extension.h
Go to the documentation of this file.
00001 // MESSAGE V2_EXTENSION PACKING
00002 
00003 #define MAVLINK_MSG_ID_V2_EXTENSION 248
00004 
00005 typedef struct __mavlink_v2_extension_t
00006 {
00007  uint16_t message_type; /*< A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings).  If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml.  Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.*/
00008  uint8_t target_network; /*< Network ID (0 for broadcast)*/
00009  uint8_t target_system; /*< System ID (0 for broadcast)*/
00010  uint8_t target_component; /*< Component ID (0 for broadcast)*/
00011  uint8_t payload[249]; /*< Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields.  The entire content of this block is opaque unless you understand any the encoding message_type.  The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.*/
00012 } mavlink_v2_extension_t;
00013 
00014 #define MAVLINK_MSG_ID_V2_EXTENSION_LEN 254
00015 #define MAVLINK_MSG_ID_248_LEN 254
00016 
00017 #define MAVLINK_MSG_ID_V2_EXTENSION_CRC 8
00018 #define MAVLINK_MSG_ID_248_CRC 8
00019 
00020 #define MAVLINK_MSG_V2_EXTENSION_FIELD_PAYLOAD_LEN 249
00021 
00022 #define MAVLINK_MESSAGE_INFO_V2_EXTENSION { \
00023         "V2_EXTENSION", \
00024         5, \
00025         {  { "message_type", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_v2_extension_t, message_type) }, \
00026          { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_v2_extension_t, target_network) }, \
00027          { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_v2_extension_t, target_system) }, \
00028          { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_v2_extension_t, target_component) }, \
00029          { "payload", NULL, MAVLINK_TYPE_UINT8_T, 249, 5, offsetof(mavlink_v2_extension_t, payload) }, \
00030          } \
00031 }
00032 
00033 
00047 static inline uint16_t mavlink_msg_v2_extension_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00048                                                        uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload)
00049 {
00050 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00051         char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN];
00052         _mav_put_uint16_t(buf, 0, message_type);
00053         _mav_put_uint8_t(buf, 2, target_network);
00054         _mav_put_uint8_t(buf, 3, target_system);
00055         _mav_put_uint8_t(buf, 4, target_component);
00056         _mav_put_uint8_t_array(buf, 5, payload, 249);
00057         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
00058 #else
00059         mavlink_v2_extension_t packet;
00060         packet.message_type = message_type;
00061         packet.target_network = target_network;
00062         packet.target_system = target_system;
00063         packet.target_component = target_component;
00064         mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249);
00065         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
00066 #endif
00067 
00068         msg->msgid = MAVLINK_MSG_ID_V2_EXTENSION;
00069 #if MAVLINK_CRC_EXTRA
00070     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC);
00071 #else
00072     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
00073 #endif
00074 }
00075 
00089 static inline uint16_t mavlink_msg_v2_extension_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00090                                                            mavlink_message_t* msg,
00091                                                            uint8_t target_network,uint8_t target_system,uint8_t target_component,uint16_t message_type,const uint8_t *payload)
00092 {
00093 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00094         char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN];
00095         _mav_put_uint16_t(buf, 0, message_type);
00096         _mav_put_uint8_t(buf, 2, target_network);
00097         _mav_put_uint8_t(buf, 3, target_system);
00098         _mav_put_uint8_t(buf, 4, target_component);
00099         _mav_put_uint8_t_array(buf, 5, payload, 249);
00100         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
00101 #else
00102         mavlink_v2_extension_t packet;
00103         packet.message_type = message_type;
00104         packet.target_network = target_network;
00105         packet.target_system = target_system;
00106         packet.target_component = target_component;
00107         mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249);
00108         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
00109 #endif
00110 
00111         msg->msgid = MAVLINK_MSG_ID_V2_EXTENSION;
00112 #if MAVLINK_CRC_EXTRA
00113     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC);
00114 #else
00115     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
00116 #endif
00117 }
00118 
00127 static inline uint16_t mavlink_msg_v2_extension_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_v2_extension_t* v2_extension)
00128 {
00129         return mavlink_msg_v2_extension_pack(system_id, component_id, msg, v2_extension->target_network, v2_extension->target_system, v2_extension->target_component, v2_extension->message_type, v2_extension->payload);
00130 }
00131 
00141 static inline uint16_t mavlink_msg_v2_extension_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_v2_extension_t* v2_extension)
00142 {
00143         return mavlink_msg_v2_extension_pack_chan(system_id, component_id, chan, msg, v2_extension->target_network, v2_extension->target_system, v2_extension->target_component, v2_extension->message_type, v2_extension->payload);
00144 }
00145 
00156 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00157 
00158 static inline void mavlink_msg_v2_extension_send(mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload)
00159 {
00160 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00161         char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN];
00162         _mav_put_uint16_t(buf, 0, message_type);
00163         _mav_put_uint8_t(buf, 2, target_network);
00164         _mav_put_uint8_t(buf, 3, target_system);
00165         _mav_put_uint8_t(buf, 4, target_component);
00166         _mav_put_uint8_t_array(buf, 5, payload, 249);
00167 #if MAVLINK_CRC_EXTRA
00168     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC);
00169 #else
00170     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
00171 #endif
00172 #else
00173         mavlink_v2_extension_t packet;
00174         packet.message_type = message_type;
00175         packet.target_network = target_network;
00176         packet.target_system = target_system;
00177         packet.target_component = target_component;
00178         mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249);
00179 #if MAVLINK_CRC_EXTRA
00180     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)&packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC);
00181 #else
00182     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)&packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
00183 #endif
00184 #endif
00185 }
00186 
00187 #if MAVLINK_MSG_ID_V2_EXTENSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00188 /*
00189   This varient of _send() can be used to save stack space by re-using
00190   memory from the receive buffer.  The caller provides a
00191   mavlink_message_t which is the size of a full mavlink message. This
00192   is usually the receive buffer for the channel, and allows a reply to an
00193   incoming message with minimum stack space usage.
00194  */
00195 static inline void mavlink_msg_v2_extension_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload)
00196 {
00197 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00198         char *buf = (char *)msgbuf;
00199         _mav_put_uint16_t(buf, 0, message_type);
00200         _mav_put_uint8_t(buf, 2, target_network);
00201         _mav_put_uint8_t(buf, 3, target_system);
00202         _mav_put_uint8_t(buf, 4, target_component);
00203         _mav_put_uint8_t_array(buf, 5, payload, 249);
00204 #if MAVLINK_CRC_EXTRA
00205     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC);
00206 #else
00207     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
00208 #endif
00209 #else
00210         mavlink_v2_extension_t *packet = (mavlink_v2_extension_t *)msgbuf;
00211         packet->message_type = message_type;
00212         packet->target_network = target_network;
00213         packet->target_system = target_system;
00214         packet->target_component = target_component;
00215         mav_array_memcpy(packet->payload, payload, sizeof(uint8_t)*249);
00216 #if MAVLINK_CRC_EXTRA
00217     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC);
00218 #else
00219     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
00220 #endif
00221 #endif
00222 }
00223 #endif
00224 
00225 #endif
00226 
00227 // MESSAGE V2_EXTENSION UNPACKING
00228 
00229 
00235 static inline uint8_t mavlink_msg_v2_extension_get_target_network(const mavlink_message_t* msg)
00236 {
00237         return _MAV_RETURN_uint8_t(msg,  2);
00238 }
00239 
00245 static inline uint8_t mavlink_msg_v2_extension_get_target_system(const mavlink_message_t* msg)
00246 {
00247         return _MAV_RETURN_uint8_t(msg,  3);
00248 }
00249 
00255 static inline uint8_t mavlink_msg_v2_extension_get_target_component(const mavlink_message_t* msg)
00256 {
00257         return _MAV_RETURN_uint8_t(msg,  4);
00258 }
00259 
00265 static inline uint16_t mavlink_msg_v2_extension_get_message_type(const mavlink_message_t* msg)
00266 {
00267         return _MAV_RETURN_uint16_t(msg,  0);
00268 }
00269 
00275 static inline uint16_t mavlink_msg_v2_extension_get_payload(const mavlink_message_t* msg, uint8_t *payload)
00276 {
00277         return _MAV_RETURN_uint8_t_array(msg, payload, 249,  5);
00278 }
00279 
00286 static inline void mavlink_msg_v2_extension_decode(const mavlink_message_t* msg, mavlink_v2_extension_t* v2_extension)
00287 {
00288 #if MAVLINK_NEED_BYTE_SWAP
00289         v2_extension->message_type = mavlink_msg_v2_extension_get_message_type(msg);
00290         v2_extension->target_network = mavlink_msg_v2_extension_get_target_network(msg);
00291         v2_extension->target_system = mavlink_msg_v2_extension_get_target_system(msg);
00292         v2_extension->target_component = mavlink_msg_v2_extension_get_target_component(msg);
00293         mavlink_msg_v2_extension_get_payload(msg, v2_extension->payload);
00294 #else
00295         memcpy(v2_extension, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_V2_EXTENSION_LEN);
00296 #endif
00297 }


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