Go to the source code of this file.
Classes | |
struct | __mavlink_heartbeat_t |
Macros | |
#define | MAVLINK_MESSAGE_INFO_HEARTBEAT |
#define | MAVLINK_MSG_ID_0_CRC 50 |
#define | MAVLINK_MSG_ID_0_LEN 9 |
#define | MAVLINK_MSG_ID_HEARTBEAT 0 |
#define | MAVLINK_MSG_ID_HEARTBEAT_CRC 50 |
#define | MAVLINK_MSG_ID_HEARTBEAT_LEN 9 |
Typedefs | |
typedef struct __mavlink_heartbeat_t | mavlink_heartbeat_t |
Functions | |
static void | mavlink_msg_heartbeat_decode (const mavlink_message_t *msg, mavlink_heartbeat_t *heartbeat) |
Decode a heartbeat message into a struct. More... | |
static uint16_t | mavlink_msg_heartbeat_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_heartbeat_t *heartbeat) |
Encode a heartbeat struct. More... | |
static 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) |
Encode a heartbeat struct on a channel. More... | |
static uint8_t | mavlink_msg_heartbeat_get_autopilot (const mavlink_message_t *msg) |
Get field autopilot from heartbeat message. More... | |
static uint8_t | mavlink_msg_heartbeat_get_base_mode (const mavlink_message_t *msg) |
Get field base_mode from heartbeat message. More... | |
static uint32_t | mavlink_msg_heartbeat_get_custom_mode (const mavlink_message_t *msg) |
Get field custom_mode from heartbeat message. More... | |
static uint8_t | mavlink_msg_heartbeat_get_mavlink_version (const mavlink_message_t *msg) |
Get field mavlink_version from heartbeat message. More... | |
static uint8_t | mavlink_msg_heartbeat_get_system_status (const mavlink_message_t *msg) |
Get field system_status from heartbeat message. More... | |
static uint8_t | mavlink_msg_heartbeat_get_type (const mavlink_message_t *msg) |
Send a heartbeat message. More... | |
static uint16_t | mavlink_msg_heartbeat_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) |
Pack a heartbeat message. More... | |
static 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, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) |
Pack a heartbeat message on a channel. More... | |
#define MAVLINK_MESSAGE_INFO_HEARTBEAT |
Definition at line 23 of file mavlink_msg_heartbeat.h.
#define MAVLINK_MSG_ID_0_CRC 50 |
Definition at line 19 of file mavlink_msg_heartbeat.h.
#define MAVLINK_MSG_ID_0_LEN 9 |
Definition at line 16 of file mavlink_msg_heartbeat.h.
#define MAVLINK_MSG_ID_HEARTBEAT 0 |
Definition at line 3 of file mavlink_msg_heartbeat.h.
#define MAVLINK_MSG_ID_HEARTBEAT_CRC 50 |
Definition at line 18 of file mavlink_msg_heartbeat.h.
#define MAVLINK_MSG_ID_HEARTBEAT_LEN 9 |
Definition at line 15 of file mavlink_msg_heartbeat.h.
typedef struct __mavlink_heartbeat_t mavlink_heartbeat_t |
|
inlinestatic |
Decode a heartbeat message into a struct.
msg | The message to decode |
heartbeat | C-struct to decode the message contents into |
Definition at line 314 of file mavlink_msg_heartbeat.h.
|
inlinestatic |
Encode a heartbeat struct.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
heartbeat | C-struct to read the message contents from |
Definition at line 137 of file mavlink_msg_heartbeat.h.
|
inlinestatic |
Encode a heartbeat struct on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
heartbeat | C-struct to read the message contents from |
Definition at line 151 of file mavlink_msg_heartbeat.h.
|
inlinestatic |
Get field autopilot from heartbeat message.
Definition at line 263 of file mavlink_msg_heartbeat.h.
|
inlinestatic |
Get field base_mode from heartbeat message.
Definition at line 273 of file mavlink_msg_heartbeat.h.
|
inlinestatic |
Get field custom_mode from heartbeat message.
Definition at line 283 of file mavlink_msg_heartbeat.h.
|
inlinestatic |
Get field mavlink_version from heartbeat message.
Definition at line 303 of file mavlink_msg_heartbeat.h.
|
inlinestatic |
Get field system_status from heartbeat message.
Definition at line 293 of file mavlink_msg_heartbeat.h.
|
inlinestatic |
Send a heartbeat message.
chan | MAVLink channel to send the message |
type | Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) |
autopilot | Autopilot type / class. defined in MAV_AUTOPILOT ENUM |
base_mode | System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h |
custom_mode | A bitfield for use for autopilot-specific flags. |
system_status | System status flag, see MAV_STATE ENUM Get field type from heartbeat message |
Definition at line 253 of file mavlink_msg_heartbeat.h.
|
inlinestatic |
Pack a heartbeat message.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
type | Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) |
autopilot | Autopilot type / class. defined in MAV_AUTOPILOT ENUM |
base_mode | System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h |
custom_mode | A bitfield for use for autopilot-specific flags. |
system_status | System status flag, see MAV_STATE ENUM |
Definition at line 49 of file mavlink_msg_heartbeat.h.
|
inlinestatic |
Pack a heartbeat message on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
type | Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) |
autopilot | Autopilot type / class. defined in MAV_AUTOPILOT ENUM |
base_mode | System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h |
custom_mode | A bitfield for use for autopilot-specific flags. |
system_status | System status flag, see MAV_STATE ENUM |
Definition at line 95 of file mavlink_msg_heartbeat.h.