ardupilot/libraries/GCS_MAVLink/include/common/mavlink_msg_heartbeat.h

85 lines
3.4 KiB
C
Raw Normal View History

// MESSAGE HEARTBEAT PACKING
#define MAVLINK_MSG_ID_HEARTBEAT 0
typedef struct __mavlink_heartbeat_t
{
uint8_t type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
uint8_t autopilot; ///< Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
} mavlink_heartbeat_t;
/**
* @brief Send a heartbeat message
*
* @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
* @param autopilot Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint8_t autopilot)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
i += put_uint8_t_by_index(type, i, msg->payload); //Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
i += put_uint8_t_by_index(autopilot, i, msg->payload); //Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, uint8_t autopilot)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
i += put_uint8_t_by_index(type, i, msg->payload); //Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
i += put_uint8_t_by_index(autopilot, i, msg->payload); //Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
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)
{
return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot)
{
mavlink_message_t msg;
mavlink_msg_heartbeat_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, autopilot);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE HEARTBEAT UNPACKING
/**
* @brief Get field type from heartbeat message
*
* @return Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
*/
static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field autopilot from heartbeat message
*
* @return Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
*/
static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat)
{
heartbeat->type = mavlink_msg_heartbeat_get_type(msg);
heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg);
}