mavlink_msg_heartbeat.h
Go to the documentation of this file.
00001 // MESSAGE HEARTBEAT PACKING
00002 
00003 #define MAVLINK_MSG_ID_HEARTBEAT 0
00004 
00005 typedef struct __mavlink_heartbeat_t
00006 {
00007  uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags.*/
00008  uint8_t type; /*< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)*/
00009  uint8_t autopilot; /*< Autopilot type / class. defined in MAV_AUTOPILOT ENUM*/
00010  uint8_t base_mode; /*< System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h*/
00011  uint8_t system_status; /*< System status flag, see MAV_STATE ENUM*/
00012  uint8_t mavlink_version; /*< MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version*/
00013 } mavlink_heartbeat_t;
00014 
00015 #define MAVLINK_MSG_ID_HEARTBEAT_LEN 9
00016 #define MAVLINK_MSG_ID_0_LEN 9
00017 
00018 #define MAVLINK_MSG_ID_HEARTBEAT_CRC 50
00019 #define MAVLINK_MSG_ID_0_CRC 50
00020 
00021 
00022 
00023 #define MAVLINK_MESSAGE_INFO_HEARTBEAT { \
00024         "HEARTBEAT", \
00025         6, \
00026         {  { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \
00027          { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \
00028          { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \
00029          { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \
00030          { "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \
00031          { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \
00032          } \
00033 }
00034 
00035 
00049 static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00050                                                        uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
00051 {
00052 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00053         char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN];
00054         _mav_put_uint32_t(buf, 0, custom_mode);
00055         _mav_put_uint8_t(buf, 4, type);
00056         _mav_put_uint8_t(buf, 5, autopilot);
00057         _mav_put_uint8_t(buf, 6, base_mode);
00058         _mav_put_uint8_t(buf, 7, system_status);
00059         _mav_put_uint8_t(buf, 8, 3);
00060 
00061         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN);
00062 #else
00063         mavlink_heartbeat_t packet;
00064         packet.custom_mode = custom_mode;
00065         packet.type = type;
00066         packet.autopilot = autopilot;
00067         packet.base_mode = base_mode;
00068         packet.system_status = system_status;
00069         packet.mavlink_version = 3;
00070 
00071         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HEARTBEAT_LEN);
00072 #endif
00073 
00074         msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
00075 #if MAVLINK_CRC_EXTRA
00076     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
00077 #else
00078     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HEARTBEAT_LEN);
00079 #endif
00080 }
00081 
00095 static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00096                                                            mavlink_message_t* msg,
00097                                                            uint8_t type,uint8_t autopilot,uint8_t base_mode,uint32_t custom_mode,uint8_t system_status)
00098 {
00099 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00100         char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN];
00101         _mav_put_uint32_t(buf, 0, custom_mode);
00102         _mav_put_uint8_t(buf, 4, type);
00103         _mav_put_uint8_t(buf, 5, autopilot);
00104         _mav_put_uint8_t(buf, 6, base_mode);
00105         _mav_put_uint8_t(buf, 7, system_status);
00106         _mav_put_uint8_t(buf, 8, 3);
00107 
00108         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN);
00109 #else
00110         mavlink_heartbeat_t packet;
00111         packet.custom_mode = custom_mode;
00112         packet.type = type;
00113         packet.autopilot = autopilot;
00114         packet.base_mode = base_mode;
00115         packet.system_status = system_status;
00116         packet.mavlink_version = 3;
00117 
00118         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HEARTBEAT_LEN);
00119 #endif
00120 
00121         msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
00122 #if MAVLINK_CRC_EXTRA
00123     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
00124 #else
00125     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HEARTBEAT_LEN);
00126 #endif
00127 }
00128 
00137 static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat)
00138 {
00139         return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status);
00140 }
00141 
00151 static inline uint16_t mavlink_msg_heartbeat_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat)
00152 {
00153         return mavlink_msg_heartbeat_pack_chan(system_id, component_id, chan, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status);
00154 }
00155 
00166 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00167 
00168 static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
00169 {
00170 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00171         char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN];
00172         _mav_put_uint32_t(buf, 0, custom_mode);
00173         _mav_put_uint8_t(buf, 4, type);
00174         _mav_put_uint8_t(buf, 5, autopilot);
00175         _mav_put_uint8_t(buf, 6, base_mode);
00176         _mav_put_uint8_t(buf, 7, system_status);
00177         _mav_put_uint8_t(buf, 8, 3);
00178 
00179 #if MAVLINK_CRC_EXTRA
00180     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
00181 #else
00182     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN);
00183 #endif
00184 #else
00185         mavlink_heartbeat_t packet;
00186         packet.custom_mode = custom_mode;
00187         packet.type = type;
00188         packet.autopilot = autopilot;
00189         packet.base_mode = base_mode;
00190         packet.system_status = system_status;
00191         packet.mavlink_version = 3;
00192 
00193 #if MAVLINK_CRC_EXTRA
00194     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
00195 #else
00196     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_LEN);
00197 #endif
00198 #endif
00199 }
00200 
00201 #if MAVLINK_MSG_ID_HEARTBEAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00202 /*
00203   This varient of _send() can be used to save stack space by re-using
00204   memory from the receive buffer.  The caller provides a
00205   mavlink_message_t which is the size of a full mavlink message. This
00206   is usually the receive buffer for the channel, and allows a reply to an
00207   incoming message with minimum stack space usage.
00208  */
00209 static inline void mavlink_msg_heartbeat_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
00210 {
00211 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00212         char *buf = (char *)msgbuf;
00213         _mav_put_uint32_t(buf, 0, custom_mode);
00214         _mav_put_uint8_t(buf, 4, type);
00215         _mav_put_uint8_t(buf, 5, autopilot);
00216         _mav_put_uint8_t(buf, 6, base_mode);
00217         _mav_put_uint8_t(buf, 7, system_status);
00218         _mav_put_uint8_t(buf, 8, 3);
00219 
00220 #if MAVLINK_CRC_EXTRA
00221     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
00222 #else
00223     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN);
00224 #endif
00225 #else
00226         mavlink_heartbeat_t *packet = (mavlink_heartbeat_t *)msgbuf;
00227         packet->custom_mode = custom_mode;
00228         packet->type = type;
00229         packet->autopilot = autopilot;
00230         packet->base_mode = base_mode;
00231         packet->system_status = system_status;
00232         packet->mavlink_version = 3;
00233 
00234 #if MAVLINK_CRC_EXTRA
00235     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
00236 #else
00237     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_LEN);
00238 #endif
00239 #endif
00240 }
00241 #endif
00242 
00243 #endif
00244 
00245 // MESSAGE HEARTBEAT UNPACKING
00246 
00247 
00253 static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg)
00254 {
00255         return _MAV_RETURN_uint8_t(msg,  4);
00256 }
00257 
00263 static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg)
00264 {
00265         return _MAV_RETURN_uint8_t(msg,  5);
00266 }
00267 
00273 static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg)
00274 {
00275         return _MAV_RETURN_uint8_t(msg,  6);
00276 }
00277 
00283 static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg)
00284 {
00285         return _MAV_RETURN_uint32_t(msg,  0);
00286 }
00287 
00293 static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg)
00294 {
00295         return _MAV_RETURN_uint8_t(msg,  7);
00296 }
00297 
00303 static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg)
00304 {
00305         return _MAV_RETURN_uint8_t(msg,  8);
00306 }
00307 
00314 static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat)
00315 {
00316 #if MAVLINK_NEED_BYTE_SWAP
00317         heartbeat->custom_mode = mavlink_msg_heartbeat_get_custom_mode(msg);
00318         heartbeat->type = mavlink_msg_heartbeat_get_type(msg);
00319         heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg);
00320         heartbeat->base_mode = mavlink_msg_heartbeat_get_base_mode(msg);
00321         heartbeat->system_status = mavlink_msg_heartbeat_get_system_status(msg);
00322         heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg);
00323 #else
00324         memcpy(heartbeat, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HEARTBEAT_LEN);
00325 #endif
00326 }


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