Classes | Macros | Typedefs | Functions
mavlink_msg_mission_current.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_mission_current_t
 

Macros

#define MAVLINK_MESSAGE_INFO_MISSION_CURRENT
 
#define MAVLINK_MSG_ID_42_CRC   28
 
#define MAVLINK_MSG_ID_42_LEN   2
 
#define MAVLINK_MSG_ID_MISSION_CURRENT   42
 
#define MAVLINK_MSG_ID_MISSION_CURRENT_CRC   28
 
#define MAVLINK_MSG_ID_MISSION_CURRENT_LEN   2
 

Typedefs

typedef struct __mavlink_mission_current_t mavlink_mission_current_t
 

Functions

static void mavlink_msg_mission_current_decode (const mavlink_message_t *msg, mavlink_mission_current_t *mission_current)
 Decode a mission_current message into a struct. More...
 
static uint16_t mavlink_msg_mission_current_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_mission_current_t *mission_current)
 Encode a mission_current struct. More...
 
static uint16_t mavlink_msg_mission_current_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_mission_current_t *mission_current)
 Encode a mission_current struct on a channel. More...
 
static uint16_t mavlink_msg_mission_current_get_seq (const mavlink_message_t *msg)
 Send a mission_current message. More...
 
static uint16_t mavlink_msg_mission_current_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint16_t seq)
 Pack a mission_current message. More...
 
static uint16_t mavlink_msg_mission_current_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint16_t seq)
 Pack a mission_current message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_MISSION_CURRENT
Value:
{ \
"MISSION_CURRENT", \
1, \
{ { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_current_t, seq) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 18 of file mavlink_msg_mission_current.h.

#define MAVLINK_MSG_ID_42_CRC   28

Definition at line 14 of file mavlink_msg_mission_current.h.

#define MAVLINK_MSG_ID_42_LEN   2

Definition at line 11 of file mavlink_msg_mission_current.h.

#define MAVLINK_MSG_ID_MISSION_CURRENT   42

Definition at line 3 of file mavlink_msg_mission_current.h.

#define MAVLINK_MSG_ID_MISSION_CURRENT_CRC   28

Definition at line 13 of file mavlink_msg_mission_current.h.

#define MAVLINK_MSG_ID_MISSION_CURRENT_LEN   2

Definition at line 10 of file mavlink_msg_mission_current.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_mission_current_decode ( const mavlink_message_t *  msg,
mavlink_mission_current_t mission_current 
)
inlinestatic

Decode a mission_current message into a struct.

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

Definition at line 202 of file mavlink_msg_mission_current.h.

static uint16_t mavlink_msg_mission_current_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_mission_current_t mission_current 
)
inlinestatic

Encode a mission_current 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
mission_currentC-struct to read the message contents from

Definition at line 99 of file mavlink_msg_mission_current.h.

static uint16_t mavlink_msg_mission_current_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_mission_current_t mission_current 
)
inlinestatic

Encode a mission_current 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
mission_currentC-struct to read the message contents from

Definition at line 113 of file mavlink_msg_mission_current.h.

static uint16_t mavlink_msg_mission_current_get_seq ( const mavlink_message_t *  msg)
inlinestatic

Send a mission_current message.

Parameters
chanMAVLink channel to send the message
seqSequence Get field seq from mission_current message
Returns
Sequence

Definition at line 191 of file mavlink_msg_mission_current.h.

static uint16_t mavlink_msg_mission_current_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint16_t  seq 
)
inlinestatic

Pack a mission_current 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
seqSequence
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 35 of file mavlink_msg_mission_current.h.

static uint16_t mavlink_msg_mission_current_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint16_t  seq 
)
inlinestatic

Pack a mission_current 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
seqSequence
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 67 of file mavlink_msg_mission_current.h.



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