Classes | Macros | Typedefs | Functions
mavlink_msg_message_interval.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_message_interval_t
 

Macros

#define MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL
 
#define MAVLINK_MSG_ID_244_CRC   95
 
#define MAVLINK_MSG_ID_244_LEN   6
 
#define MAVLINK_MSG_ID_MESSAGE_INTERVAL   244
 
#define MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC   95
 
#define MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN   6
 

Typedefs

typedef struct __mavlink_message_interval_t mavlink_message_interval_t
 

Functions

static void mavlink_msg_message_interval_decode (const mavlink_message_t *msg, mavlink_message_interval_t *message_interval)
 Decode a message_interval message into a struct. More...
 
static uint16_t mavlink_msg_message_interval_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_message_interval_t *message_interval)
 Encode a message_interval struct. More...
 
static uint16_t mavlink_msg_message_interval_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_message_interval_t *message_interval)
 Encode a message_interval struct on a channel. More...
 
static int32_t mavlink_msg_message_interval_get_interval_us (const mavlink_message_t *msg)
 Get field interval_us from message_interval message. More...
 
static uint16_t mavlink_msg_message_interval_get_message_id (const mavlink_message_t *msg)
 Send a message_interval message. More...
 
static uint16_t mavlink_msg_message_interval_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint16_t message_id, int32_t interval_us)
 Pack a message_interval message. More...
 
static uint16_t mavlink_msg_message_interval_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint16_t message_id, int32_t interval_us)
 Pack a message_interval message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL
Value:
{ \
"MESSAGE_INTERVAL", \
2, \
{ { "interval_us", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_message_interval_t, interval_us) }, \
{ "message_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_message_interval_t, message_id) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 19 of file mavlink_msg_message_interval.h.

#define MAVLINK_MSG_ID_244_CRC   95

Definition at line 15 of file mavlink_msg_message_interval.h.

#define MAVLINK_MSG_ID_244_LEN   6

Definition at line 12 of file mavlink_msg_message_interval.h.

#define MAVLINK_MSG_ID_MESSAGE_INTERVAL   244

Definition at line 3 of file mavlink_msg_message_interval.h.

#define MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC   95

Definition at line 14 of file mavlink_msg_message_interval.h.

#define MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN   6

Definition at line 11 of file mavlink_msg_message_interval.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_message_interval_decode ( const mavlink_message_t *  msg,
mavlink_message_interval_t message_interval 
)
inlinestatic

Decode a message_interval message into a struct.

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

Definition at line 225 of file mavlink_msg_message_interval.h.

static uint16_t mavlink_msg_message_interval_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_message_interval_t message_interval 
)
inlinestatic

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

Definition at line 107 of file mavlink_msg_message_interval.h.

static uint16_t mavlink_msg_message_interval_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_message_interval_t message_interval 
)
inlinestatic

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

Definition at line 121 of file mavlink_msg_message_interval.h.

static int32_t mavlink_msg_message_interval_get_interval_us ( const mavlink_message_t *  msg)
inlinestatic

Get field interval_us from message_interval message.

Returns
The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.

Definition at line 214 of file mavlink_msg_message_interval.h.

static uint16_t mavlink_msg_message_interval_get_message_id ( const mavlink_message_t *  msg)
inlinestatic

Send a message_interval message.

Parameters
chanMAVLink channel to send the message
message_idThe ID of the requested MAVLink message. v1.0 is limited to 254 messages.
interval_usThe interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. Get field message_id from message_interval message
Returns
The ID of the requested MAVLink message. v1.0 is limited to 254 messages.

Definition at line 204 of file mavlink_msg_message_interval.h.

static uint16_t mavlink_msg_message_interval_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint16_t  message_id,
int32_t  interval_us 
)
inlinestatic

Pack a message_interval 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
message_idThe ID of the requested MAVLink message. v1.0 is limited to 254 messages.
interval_usThe interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 38 of file mavlink_msg_message_interval.h.

static uint16_t mavlink_msg_message_interval_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint16_t  message_id,
int32_t  interval_us 
)
inlinestatic

Pack a message_interval 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
message_idThe ID of the requested MAVLink message. v1.0 is limited to 254 messages.
interval_usThe interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 73 of file mavlink_msg_message_interval.h.



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