Classes | Macros | Typedefs | Functions
mavlink_msg_heartbeat.h File Reference
This graph shows which files directly or indirectly include this file:

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...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_HEARTBEAT
Value:
{ \
"HEARTBEAT", \
6, \
{ { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \
{ "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \
{ "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \
{ "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \
{ "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

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 Documentation

Function Documentation

static void mavlink_msg_heartbeat_decode ( const mavlink_message_t *  msg,
mavlink_heartbeat_t heartbeat 
)
inlinestatic

Decode a heartbeat message into a struct.

Parameters
msgThe message to decode
heartbeatC-struct to decode the message contents into

Definition at line 314 of file mavlink_msg_heartbeat.h.

static uint16_t mavlink_msg_heartbeat_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_heartbeat_t heartbeat 
)
inlinestatic

Encode a heartbeat struct.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
heartbeatC-struct to read the message contents from

Definition at line 137 of file mavlink_msg_heartbeat.h.

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 
)
inlinestatic

Encode a heartbeat struct on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
heartbeatC-struct to read the message contents from

Definition at line 151 of file mavlink_msg_heartbeat.h.

static uint8_t mavlink_msg_heartbeat_get_autopilot ( const mavlink_message_t *  msg)
inlinestatic

Get field autopilot from heartbeat message.

Returns
Autopilot type / class. defined in MAV_AUTOPILOT ENUM

Definition at line 263 of file mavlink_msg_heartbeat.h.

static uint8_t mavlink_msg_heartbeat_get_base_mode ( const mavlink_message_t *  msg)
inlinestatic

Get field base_mode from heartbeat message.

Returns
System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h

Definition at line 273 of file mavlink_msg_heartbeat.h.

static uint32_t mavlink_msg_heartbeat_get_custom_mode ( const mavlink_message_t *  msg)
inlinestatic

Get field custom_mode from heartbeat message.

Returns
A bitfield for use for autopilot-specific flags.

Definition at line 283 of file mavlink_msg_heartbeat.h.

static uint8_t mavlink_msg_heartbeat_get_mavlink_version ( const mavlink_message_t *  msg)
inlinestatic

Get field mavlink_version from heartbeat message.

Returns
MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version

Definition at line 303 of file mavlink_msg_heartbeat.h.

static uint8_t mavlink_msg_heartbeat_get_system_status ( const mavlink_message_t *  msg)
inlinestatic

Get field system_status from heartbeat message.

Returns
System status flag, see MAV_STATE ENUM

Definition at line 293 of file mavlink_msg_heartbeat.h.

static uint8_t mavlink_msg_heartbeat_get_type ( const mavlink_message_t *  msg)
inlinestatic

Send a heartbeat message.

Parameters
chanMAVLink channel to send the message
typeType of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
autopilotAutopilot type / class. defined in MAV_AUTOPILOT ENUM
base_modeSystem mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h
custom_modeA bitfield for use for autopilot-specific flags.
system_statusSystem status flag, see MAV_STATE ENUM Get field type from heartbeat message
Returns
Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)

Definition at line 253 of file mavlink_msg_heartbeat.h.

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 
)
inlinestatic

Pack a heartbeat message.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
typeType of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
autopilotAutopilot type / class. defined in MAV_AUTOPILOT ENUM
base_modeSystem mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h
custom_modeA bitfield for use for autopilot-specific flags.
system_statusSystem status flag, see MAV_STATE ENUM
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 49 of file mavlink_msg_heartbeat.h.

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 
)
inlinestatic

Pack a heartbeat message on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
typeType of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
autopilotAutopilot type / class. defined in MAV_AUTOPILOT ENUM
base_modeSystem mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h
custom_modeA bitfield for use for autopilot-specific flags.
system_statusSystem status flag, see MAV_STATE ENUM
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 95 of file mavlink_msg_heartbeat.h.



rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:51