mavlink_msg_autopilot_version.h
Go to the documentation of this file.
00001 // MESSAGE AUTOPILOT_VERSION PACKING
00002 
00003 #define MAVLINK_MSG_ID_AUTOPILOT_VERSION 148
00004 
00005 typedef struct __mavlink_autopilot_version_t
00006 {
00007  uint64_t capabilities; /*< bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)*/
00008  uint64_t uid; /*< UID if provided by hardware*/
00009  uint32_t flight_sw_version; /*< Firmware version number*/
00010  uint32_t middleware_sw_version; /*< Middleware version number*/
00011  uint32_t os_sw_version; /*< Operating system version number*/
00012  uint32_t board_version; /*< HW / board version (last 8 bytes should be silicon ID, if any)*/
00013  uint16_t vendor_id; /*< ID of the board vendor*/
00014  uint16_t product_id; /*< ID of the product*/
00015  uint8_t flight_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/
00016  uint8_t middleware_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/
00017  uint8_t os_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/
00018 } mavlink_autopilot_version_t;
00019 
00020 #define MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN 60
00021 #define MAVLINK_MSG_ID_148_LEN 60
00022 
00023 #define MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC 178
00024 #define MAVLINK_MSG_ID_148_CRC 178
00025 
00026 #define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_FLIGHT_CUSTOM_VERSION_LEN 8
00027 #define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_MIDDLEWARE_CUSTOM_VERSION_LEN 8
00028 #define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_OS_CUSTOM_VERSION_LEN 8
00029 
00030 #define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION { \
00031         "AUTOPILOT_VERSION", \
00032         11, \
00033         {  { "capabilities", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_version_t, capabilities) }, \
00034          { "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \
00035          { "flight_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_autopilot_version_t, flight_sw_version) }, \
00036          { "middleware_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_autopilot_version_t, middleware_sw_version) }, \
00037          { "os_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_autopilot_version_t, os_sw_version) }, \
00038          { "board_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_autopilot_version_t, board_version) }, \
00039          { "vendor_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_autopilot_version_t, vendor_id) }, \
00040          { "product_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_autopilot_version_t, product_id) }, \
00041          { "flight_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 36, offsetof(mavlink_autopilot_version_t, flight_custom_version) }, \
00042          { "middleware_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 44, offsetof(mavlink_autopilot_version_t, middleware_custom_version) }, \
00043          { "os_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 52, offsetof(mavlink_autopilot_version_t, os_custom_version) }, \
00044          } \
00045 }
00046 
00047 
00067 static inline uint16_t mavlink_msg_autopilot_version_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00068                                                        uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid)
00069 {
00070 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00071         char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN];
00072         _mav_put_uint64_t(buf, 0, capabilities);
00073         _mav_put_uint64_t(buf, 8, uid);
00074         _mav_put_uint32_t(buf, 16, flight_sw_version);
00075         _mav_put_uint32_t(buf, 20, middleware_sw_version);
00076         _mav_put_uint32_t(buf, 24, os_sw_version);
00077         _mav_put_uint32_t(buf, 28, board_version);
00078         _mav_put_uint16_t(buf, 32, vendor_id);
00079         _mav_put_uint16_t(buf, 34, product_id);
00080         _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8);
00081         _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8);
00082         _mav_put_uint8_t_array(buf, 52, os_custom_version, 8);
00083         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
00084 #else
00085         mavlink_autopilot_version_t packet;
00086         packet.capabilities = capabilities;
00087         packet.uid = uid;
00088         packet.flight_sw_version = flight_sw_version;
00089         packet.middleware_sw_version = middleware_sw_version;
00090         packet.os_sw_version = os_sw_version;
00091         packet.board_version = board_version;
00092         packet.vendor_id = vendor_id;
00093         packet.product_id = product_id;
00094         mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8);
00095         mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8);
00096         mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8);
00097         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
00098 #endif
00099 
00100         msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION;
00101 #if MAVLINK_CRC_EXTRA
00102     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
00103 #else
00104     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
00105 #endif
00106 }
00107 
00127 static inline uint16_t mavlink_msg_autopilot_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00128                                                            mavlink_message_t* msg,
00129                                                            uint64_t capabilities,uint32_t flight_sw_version,uint32_t middleware_sw_version,uint32_t os_sw_version,uint32_t board_version,const uint8_t *flight_custom_version,const uint8_t *middleware_custom_version,const uint8_t *os_custom_version,uint16_t vendor_id,uint16_t product_id,uint64_t uid)
00130 {
00131 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00132         char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN];
00133         _mav_put_uint64_t(buf, 0, capabilities);
00134         _mav_put_uint64_t(buf, 8, uid);
00135         _mav_put_uint32_t(buf, 16, flight_sw_version);
00136         _mav_put_uint32_t(buf, 20, middleware_sw_version);
00137         _mav_put_uint32_t(buf, 24, os_sw_version);
00138         _mav_put_uint32_t(buf, 28, board_version);
00139         _mav_put_uint16_t(buf, 32, vendor_id);
00140         _mav_put_uint16_t(buf, 34, product_id);
00141         _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8);
00142         _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8);
00143         _mav_put_uint8_t_array(buf, 52, os_custom_version, 8);
00144         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
00145 #else
00146         mavlink_autopilot_version_t packet;
00147         packet.capabilities = capabilities;
00148         packet.uid = uid;
00149         packet.flight_sw_version = flight_sw_version;
00150         packet.middleware_sw_version = middleware_sw_version;
00151         packet.os_sw_version = os_sw_version;
00152         packet.board_version = board_version;
00153         packet.vendor_id = vendor_id;
00154         packet.product_id = product_id;
00155         mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8);
00156         mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8);
00157         mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8);
00158         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
00159 #endif
00160 
00161         msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION;
00162 #if MAVLINK_CRC_EXTRA
00163     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
00164 #else
00165     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
00166 #endif
00167 }
00168 
00177 static inline uint16_t mavlink_msg_autopilot_version_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_autopilot_version_t* autopilot_version)
00178 {
00179         return mavlink_msg_autopilot_version_pack(system_id, component_id, msg, autopilot_version->capabilities, autopilot_version->flight_sw_version, autopilot_version->middleware_sw_version, autopilot_version->os_sw_version, autopilot_version->board_version, autopilot_version->flight_custom_version, autopilot_version->middleware_custom_version, autopilot_version->os_custom_version, autopilot_version->vendor_id, autopilot_version->product_id, autopilot_version->uid);
00180 }
00181 
00191 static inline uint16_t mavlink_msg_autopilot_version_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_autopilot_version_t* autopilot_version)
00192 {
00193         return mavlink_msg_autopilot_version_pack_chan(system_id, component_id, chan, msg, autopilot_version->capabilities, autopilot_version->flight_sw_version, autopilot_version->middleware_sw_version, autopilot_version->os_sw_version, autopilot_version->board_version, autopilot_version->flight_custom_version, autopilot_version->middleware_custom_version, autopilot_version->os_custom_version, autopilot_version->vendor_id, autopilot_version->product_id, autopilot_version->uid);
00194 }
00195 
00212 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00213 
00214 static inline void mavlink_msg_autopilot_version_send(mavlink_channel_t chan, uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid)
00215 {
00216 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00217         char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN];
00218         _mav_put_uint64_t(buf, 0, capabilities);
00219         _mav_put_uint64_t(buf, 8, uid);
00220         _mav_put_uint32_t(buf, 16, flight_sw_version);
00221         _mav_put_uint32_t(buf, 20, middleware_sw_version);
00222         _mav_put_uint32_t(buf, 24, os_sw_version);
00223         _mav_put_uint32_t(buf, 28, board_version);
00224         _mav_put_uint16_t(buf, 32, vendor_id);
00225         _mav_put_uint16_t(buf, 34, product_id);
00226         _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8);
00227         _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8);
00228         _mav_put_uint8_t_array(buf, 52, os_custom_version, 8);
00229 #if MAVLINK_CRC_EXTRA
00230     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
00231 #else
00232     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
00233 #endif
00234 #else
00235         mavlink_autopilot_version_t packet;
00236         packet.capabilities = capabilities;
00237         packet.uid = uid;
00238         packet.flight_sw_version = flight_sw_version;
00239         packet.middleware_sw_version = middleware_sw_version;
00240         packet.os_sw_version = os_sw_version;
00241         packet.board_version = board_version;
00242         packet.vendor_id = vendor_id;
00243         packet.product_id = product_id;
00244         mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8);
00245         mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8);
00246         mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8);
00247 #if MAVLINK_CRC_EXTRA
00248     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
00249 #else
00250     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
00251 #endif
00252 #endif
00253 }
00254 
00255 #if MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00256 /*
00257   This varient of _send() can be used to save stack space by re-using
00258   memory from the receive buffer.  The caller provides a
00259   mavlink_message_t which is the size of a full mavlink message. This
00260   is usually the receive buffer for the channel, and allows a reply to an
00261   incoming message with minimum stack space usage.
00262  */
00263 static inline void mavlink_msg_autopilot_version_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid)
00264 {
00265 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00266         char *buf = (char *)msgbuf;
00267         _mav_put_uint64_t(buf, 0, capabilities);
00268         _mav_put_uint64_t(buf, 8, uid);
00269         _mav_put_uint32_t(buf, 16, flight_sw_version);
00270         _mav_put_uint32_t(buf, 20, middleware_sw_version);
00271         _mav_put_uint32_t(buf, 24, os_sw_version);
00272         _mav_put_uint32_t(buf, 28, board_version);
00273         _mav_put_uint16_t(buf, 32, vendor_id);
00274         _mav_put_uint16_t(buf, 34, product_id);
00275         _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8);
00276         _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8);
00277         _mav_put_uint8_t_array(buf, 52, os_custom_version, 8);
00278 #if MAVLINK_CRC_EXTRA
00279     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
00280 #else
00281     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
00282 #endif
00283 #else
00284         mavlink_autopilot_version_t *packet = (mavlink_autopilot_version_t *)msgbuf;
00285         packet->capabilities = capabilities;
00286         packet->uid = uid;
00287         packet->flight_sw_version = flight_sw_version;
00288         packet->middleware_sw_version = middleware_sw_version;
00289         packet->os_sw_version = os_sw_version;
00290         packet->board_version = board_version;
00291         packet->vendor_id = vendor_id;
00292         packet->product_id = product_id;
00293         mav_array_memcpy(packet->flight_custom_version, flight_custom_version, sizeof(uint8_t)*8);
00294         mav_array_memcpy(packet->middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8);
00295         mav_array_memcpy(packet->os_custom_version, os_custom_version, sizeof(uint8_t)*8);
00296 #if MAVLINK_CRC_EXTRA
00297     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
00298 #else
00299     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
00300 #endif
00301 #endif
00302 }
00303 #endif
00304 
00305 #endif
00306 
00307 // MESSAGE AUTOPILOT_VERSION UNPACKING
00308 
00309 
00315 static inline uint64_t mavlink_msg_autopilot_version_get_capabilities(const mavlink_message_t* msg)
00316 {
00317         return _MAV_RETURN_uint64_t(msg,  0);
00318 }
00319 
00325 static inline uint32_t mavlink_msg_autopilot_version_get_flight_sw_version(const mavlink_message_t* msg)
00326 {
00327         return _MAV_RETURN_uint32_t(msg,  16);
00328 }
00329 
00335 static inline uint32_t mavlink_msg_autopilot_version_get_middleware_sw_version(const mavlink_message_t* msg)
00336 {
00337         return _MAV_RETURN_uint32_t(msg,  20);
00338 }
00339 
00345 static inline uint32_t mavlink_msg_autopilot_version_get_os_sw_version(const mavlink_message_t* msg)
00346 {
00347         return _MAV_RETURN_uint32_t(msg,  24);
00348 }
00349 
00355 static inline uint32_t mavlink_msg_autopilot_version_get_board_version(const mavlink_message_t* msg)
00356 {
00357         return _MAV_RETURN_uint32_t(msg,  28);
00358 }
00359 
00365 static inline uint16_t mavlink_msg_autopilot_version_get_flight_custom_version(const mavlink_message_t* msg, uint8_t *flight_custom_version)
00366 {
00367         return _MAV_RETURN_uint8_t_array(msg, flight_custom_version, 8,  36);
00368 }
00369 
00375 static inline uint16_t mavlink_msg_autopilot_version_get_middleware_custom_version(const mavlink_message_t* msg, uint8_t *middleware_custom_version)
00376 {
00377         return _MAV_RETURN_uint8_t_array(msg, middleware_custom_version, 8,  44);
00378 }
00379 
00385 static inline uint16_t mavlink_msg_autopilot_version_get_os_custom_version(const mavlink_message_t* msg, uint8_t *os_custom_version)
00386 {
00387         return _MAV_RETURN_uint8_t_array(msg, os_custom_version, 8,  52);
00388 }
00389 
00395 static inline uint16_t mavlink_msg_autopilot_version_get_vendor_id(const mavlink_message_t* msg)
00396 {
00397         return _MAV_RETURN_uint16_t(msg,  32);
00398 }
00399 
00405 static inline uint16_t mavlink_msg_autopilot_version_get_product_id(const mavlink_message_t* msg)
00406 {
00407         return _MAV_RETURN_uint16_t(msg,  34);
00408 }
00409 
00415 static inline uint64_t mavlink_msg_autopilot_version_get_uid(const mavlink_message_t* msg)
00416 {
00417         return _MAV_RETURN_uint64_t(msg,  8);
00418 }
00419 
00426 static inline void mavlink_msg_autopilot_version_decode(const mavlink_message_t* msg, mavlink_autopilot_version_t* autopilot_version)
00427 {
00428 #if MAVLINK_NEED_BYTE_SWAP
00429         autopilot_version->capabilities = mavlink_msg_autopilot_version_get_capabilities(msg);
00430         autopilot_version->uid = mavlink_msg_autopilot_version_get_uid(msg);
00431         autopilot_version->flight_sw_version = mavlink_msg_autopilot_version_get_flight_sw_version(msg);
00432         autopilot_version->middleware_sw_version = mavlink_msg_autopilot_version_get_middleware_sw_version(msg);
00433         autopilot_version->os_sw_version = mavlink_msg_autopilot_version_get_os_sw_version(msg);
00434         autopilot_version->board_version = mavlink_msg_autopilot_version_get_board_version(msg);
00435         autopilot_version->vendor_id = mavlink_msg_autopilot_version_get_vendor_id(msg);
00436         autopilot_version->product_id = mavlink_msg_autopilot_version_get_product_id(msg);
00437         mavlink_msg_autopilot_version_get_flight_custom_version(msg, autopilot_version->flight_custom_version);
00438         mavlink_msg_autopilot_version_get_middleware_custom_version(msg, autopilot_version->middleware_custom_version);
00439         mavlink_msg_autopilot_version_get_os_custom_version(msg, autopilot_version->os_custom_version);
00440 #else
00441         memcpy(autopilot_version, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
00442 #endif
00443 }


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