Classes | Macros | Typedefs | Functions
mavlink_msg_named_command_struct.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_named_command_struct_t
 

Macros

#define MAVLINK_MESSAGE_INFO_NAMED_COMMAND_STRUCT
 
#define MAVLINK_MSG_ID_186_CRC   169
 
#define MAVLINK_MSG_ID_186_LEN   28
 
#define MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT   186
 
#define MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_CRC   169
 
#define MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN   28
 
#define MAVLINK_MSG_NAMED_COMMAND_STRUCT_FIELD_NAME_LEN   10
 

Typedefs

typedef struct __mavlink_named_command_struct_t mavlink_named_command_struct_t
 

Functions

static void mavlink_msg_named_command_struct_decode (const mavlink_message_t *msg, mavlink_named_command_struct_t *named_command_struct)
 Decode a named_command_struct message into a struct. More...
 
static uint16_t mavlink_msg_named_command_struct_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_named_command_struct_t *named_command_struct)
 Encode a named_command_struct struct. More...
 
static uint16_t mavlink_msg_named_command_struct_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_named_command_struct_t *named_command_struct)
 Encode a named_command_struct struct on a channel. More...
 
static float mavlink_msg_named_command_struct_get_F (const mavlink_message_t *msg)
 Get field F from named_command_struct message. More...
 
static uint8_t mavlink_msg_named_command_struct_get_ignore (const mavlink_message_t *msg)
 Get field ignore from named_command_struct message. More...
 
static uint16_t mavlink_msg_named_command_struct_get_name (const mavlink_message_t *msg, char *name)
 Send a named_command_struct message. More...
 
static uint8_t mavlink_msg_named_command_struct_get_type (const mavlink_message_t *msg)
 Get field type from named_command_struct message. More...
 
static float mavlink_msg_named_command_struct_get_x (const mavlink_message_t *msg)
 Get field x from named_command_struct message. More...
 
static float mavlink_msg_named_command_struct_get_y (const mavlink_message_t *msg)
 Get field y from named_command_struct message. More...
 
static float mavlink_msg_named_command_struct_get_z (const mavlink_message_t *msg)
 Get field z from named_command_struct message. More...
 
static uint16_t mavlink_msg_named_command_struct_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const char *name, uint8_t type, uint8_t ignore, float x, float y, float z, float F)
 Pack a named_command_struct message. More...
 
static uint16_t mavlink_msg_named_command_struct_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const char *name, uint8_t type, uint8_t ignore, float x, float y, float z, float F)
 Pack a named_command_struct message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_NAMED_COMMAND_STRUCT
Value:
{ \
"NAMED_COMMAND_STRUCT", \
7, \
{ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_named_command_struct_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_command_struct_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_named_command_struct_t, z) }, \
{ "F", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_named_command_struct_t, F) }, \
{ "name", NULL, MAVLINK_TYPE_CHAR, 10, 16, offsetof(mavlink_named_command_struct_t, name) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_named_command_struct_t, type) }, \
{ "ignore", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_named_command_struct_t, ignore) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 24 of file mavlink_msg_named_command_struct.h.

#define MAVLINK_MSG_ID_186_CRC   169

Definition at line 20 of file mavlink_msg_named_command_struct.h.

#define MAVLINK_MSG_ID_186_LEN   28

Definition at line 17 of file mavlink_msg_named_command_struct.h.

#define MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT   186

Definition at line 3 of file mavlink_msg_named_command_struct.h.

#define MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_CRC   169

Definition at line 19 of file mavlink_msg_named_command_struct.h.

#define MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN   28

Definition at line 16 of file mavlink_msg_named_command_struct.h.

#define MAVLINK_MSG_NAMED_COMMAND_STRUCT_FIELD_NAME_LEN   10

Definition at line 22 of file mavlink_msg_named_command_struct.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_named_command_struct_decode ( const mavlink_message_t *  msg,
mavlink_named_command_struct_t named_command_struct 
)
inlinestatic

Decode a named_command_struct message into a struct.

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

Definition at line 332 of file mavlink_msg_named_command_struct.h.

static uint16_t mavlink_msg_named_command_struct_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_named_command_struct_t named_command_struct 
)
inlinestatic

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

Definition at line 143 of file mavlink_msg_named_command_struct.h.

static uint16_t mavlink_msg_named_command_struct_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_named_command_struct_t named_command_struct 
)
inlinestatic

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

Definition at line 157 of file mavlink_msg_named_command_struct.h.

static float mavlink_msg_named_command_struct_get_F ( const mavlink_message_t *  msg)
inlinestatic

Get field F from named_command_struct message.

Returns
F value in the command struct

Definition at line 321 of file mavlink_msg_named_command_struct.h.

static uint8_t mavlink_msg_named_command_struct_get_ignore ( const mavlink_message_t *  msg)
inlinestatic

Get field ignore from named_command_struct message.

Returns
Type of command struct

Definition at line 281 of file mavlink_msg_named_command_struct.h.

static uint16_t mavlink_msg_named_command_struct_get_name ( const mavlink_message_t *  msg,
char *  name 
)
inlinestatic

Send a named_command_struct message.

Parameters
chanMAVLink channel to send the message
nameName of the command struct
typeType of command struct
ignoreType of command struct
xx value in the command struct
yy value in the command struct
zz value in the command struct
FF value in the command struct Get field name from named_command_struct message
Returns
Name of the command struct

Definition at line 261 of file mavlink_msg_named_command_struct.h.

static uint8_t mavlink_msg_named_command_struct_get_type ( const mavlink_message_t *  msg)
inlinestatic

Get field type from named_command_struct message.

Returns
Type of command struct

Definition at line 271 of file mavlink_msg_named_command_struct.h.

static float mavlink_msg_named_command_struct_get_x ( const mavlink_message_t *  msg)
inlinestatic

Get field x from named_command_struct message.

Returns
x value in the command struct

Definition at line 291 of file mavlink_msg_named_command_struct.h.

static float mavlink_msg_named_command_struct_get_y ( const mavlink_message_t *  msg)
inlinestatic

Get field y from named_command_struct message.

Returns
y value in the command struct

Definition at line 301 of file mavlink_msg_named_command_struct.h.

static float mavlink_msg_named_command_struct_get_z ( const mavlink_message_t *  msg)
inlinestatic

Get field z from named_command_struct message.

Returns
z value in the command struct

Definition at line 311 of file mavlink_msg_named_command_struct.h.

static uint16_t mavlink_msg_named_command_struct_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const char *  name,
uint8_t  type,
uint8_t  ignore,
float  x,
float  y,
float  z,
float  F 
)
inlinestatic

Pack a named_command_struct 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
nameName of the command struct
typeType of command struct
ignoreType of command struct
xx value in the command struct
yy value in the command struct
zz value in the command struct
FF value in the command struct
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 53 of file mavlink_msg_named_command_struct.h.

static uint16_t mavlink_msg_named_command_struct_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const char *  name,
uint8_t  type,
uint8_t  ignore,
float  x,
float  y,
float  z,
float  F 
)
inlinestatic

Pack a named_command_struct 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
nameName of the command struct
typeType of command struct
ignoreType of command struct
xx value in the command struct
yy value in the command struct
zz value in the command struct
FF value in the command struct
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 101 of file mavlink_msg_named_command_struct.h.



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