Classes | Macros | Typedefs | Functions
mavlink_msg_v2_extension.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_v2_extension_t
 

Macros

#define MAVLINK_MESSAGE_INFO_V2_EXTENSION
 
#define MAVLINK_MSG_ID_248_CRC   8
 
#define MAVLINK_MSG_ID_248_LEN   254
 
#define MAVLINK_MSG_ID_V2_EXTENSION   248
 
#define MAVLINK_MSG_ID_V2_EXTENSION_CRC   8
 
#define MAVLINK_MSG_ID_V2_EXTENSION_LEN   254
 
#define MAVLINK_MSG_V2_EXTENSION_FIELD_PAYLOAD_LEN   249
 

Typedefs

typedef struct __mavlink_v2_extension_t mavlink_v2_extension_t
 

Functions

static void mavlink_msg_v2_extension_decode (const mavlink_message_t *msg, mavlink_v2_extension_t *v2_extension)
 Decode a v2_extension message into a struct. More...
 
static uint16_t mavlink_msg_v2_extension_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_v2_extension_t *v2_extension)
 Encode a v2_extension struct. More...
 
static uint16_t mavlink_msg_v2_extension_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_v2_extension_t *v2_extension)
 Encode a v2_extension struct on a channel. More...
 
static uint16_t mavlink_msg_v2_extension_get_message_type (const mavlink_message_t *msg)
 Get field message_type from v2_extension message. More...
 
static uint16_t mavlink_msg_v2_extension_get_payload (const mavlink_message_t *msg, uint8_t *payload)
 Get field payload from v2_extension message. More...
 
static uint8_t mavlink_msg_v2_extension_get_target_component (const mavlink_message_t *msg)
 Get field target_component from v2_extension message. More...
 
static uint8_t mavlink_msg_v2_extension_get_target_network (const mavlink_message_t *msg)
 Send a v2_extension message. More...
 
static uint8_t mavlink_msg_v2_extension_get_target_system (const mavlink_message_t *msg)
 Get field target_system from v2_extension message. More...
 
static uint16_t mavlink_msg_v2_extension_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload)
 Pack a v2_extension message. More...
 
static uint16_t mavlink_msg_v2_extension_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload)
 Pack a v2_extension message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_V2_EXTENSION
Value:
{ \
"V2_EXTENSION", \
5, \
{ { "message_type", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_v2_extension_t, message_type) }, \
{ "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_v2_extension_t, target_network) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_v2_extension_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_v2_extension_t, target_component) }, \
{ "payload", NULL, MAVLINK_TYPE_UINT8_T, 249, 5, offsetof(mavlink_v2_extension_t, payload) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 22 of file mavlink_msg_v2_extension.h.

#define MAVLINK_MSG_ID_248_CRC   8

Definition at line 18 of file mavlink_msg_v2_extension.h.

#define MAVLINK_MSG_ID_248_LEN   254

Definition at line 15 of file mavlink_msg_v2_extension.h.

#define MAVLINK_MSG_ID_V2_EXTENSION   248

Definition at line 3 of file mavlink_msg_v2_extension.h.

#define MAVLINK_MSG_ID_V2_EXTENSION_CRC   8

Definition at line 17 of file mavlink_msg_v2_extension.h.

#define MAVLINK_MSG_ID_V2_EXTENSION_LEN   254

Definition at line 14 of file mavlink_msg_v2_extension.h.

#define MAVLINK_MSG_V2_EXTENSION_FIELD_PAYLOAD_LEN   249

Definition at line 20 of file mavlink_msg_v2_extension.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_v2_extension_decode ( const mavlink_message_t *  msg,
mavlink_v2_extension_t v2_extension 
)
inlinestatic

Decode a v2_extension message into a struct.

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

Definition at line 286 of file mavlink_msg_v2_extension.h.

static uint16_t mavlink_msg_v2_extension_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_v2_extension_t v2_extension 
)
inlinestatic

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

Definition at line 127 of file mavlink_msg_v2_extension.h.

static uint16_t mavlink_msg_v2_extension_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_v2_extension_t v2_extension 
)
inlinestatic

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

Definition at line 141 of file mavlink_msg_v2_extension.h.

static uint16_t mavlink_msg_v2_extension_get_message_type ( const mavlink_message_t *  msg)
inlinestatic

Get field message_type from v2_extension message.

Returns
A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.

Definition at line 265 of file mavlink_msg_v2_extension.h.

static uint16_t mavlink_msg_v2_extension_get_payload ( const mavlink_message_t *  msg,
uint8_t *  payload 
)
inlinestatic

Get field payload from v2_extension message.

Returns
Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.

Definition at line 275 of file mavlink_msg_v2_extension.h.

static uint8_t mavlink_msg_v2_extension_get_target_component ( const mavlink_message_t *  msg)
inlinestatic

Get field target_component from v2_extension message.

Returns
Component ID (0 for broadcast)

Definition at line 255 of file mavlink_msg_v2_extension.h.

static uint8_t mavlink_msg_v2_extension_get_target_network ( const mavlink_message_t *  msg)
inlinestatic

Send a v2_extension message.

Parameters
chanMAVLink channel to send the message
target_networkNetwork ID (0 for broadcast)
target_systemSystem ID (0 for broadcast)
target_componentComponent ID (0 for broadcast)
message_typeA code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.
payloadVariable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. Get field target_network from v2_extension message
Returns
Network ID (0 for broadcast)

Definition at line 235 of file mavlink_msg_v2_extension.h.

static uint8_t mavlink_msg_v2_extension_get_target_system ( const mavlink_message_t *  msg)
inlinestatic

Get field target_system from v2_extension message.

Returns
System ID (0 for broadcast)

Definition at line 245 of file mavlink_msg_v2_extension.h.

static uint16_t mavlink_msg_v2_extension_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint8_t  target_network,
uint8_t  target_system,
uint8_t  target_component,
uint16_t  message_type,
const uint8_t *  payload 
)
inlinestatic

Pack a v2_extension 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
target_networkNetwork ID (0 for broadcast)
target_systemSystem ID (0 for broadcast)
target_componentComponent ID (0 for broadcast)
message_typeA code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.
payloadVariable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 47 of file mavlink_msg_v2_extension.h.

static uint16_t mavlink_msg_v2_extension_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint8_t  target_network,
uint8_t  target_system,
uint8_t  target_component,
uint16_t  message_type,
const uint8_t *  payload 
)
inlinestatic

Pack a v2_extension 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
target_networkNetwork ID (0 for broadcast)
target_systemSystem ID (0 for broadcast)
target_componentComponent ID (0 for broadcast)
message_typeA code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.
payloadVariable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 89 of file mavlink_msg_v2_extension.h.



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