Classes | Macros | Typedefs | Functions
mavlink_msg_command_long.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_command_long_t
 

Macros

#define MAVLINK_MESSAGE_INFO_COMMAND_LONG
 
#define MAVLINK_MSG_ID_76_CRC   152
 
#define MAVLINK_MSG_ID_76_LEN   33
 
#define MAVLINK_MSG_ID_COMMAND_LONG   76
 
#define MAVLINK_MSG_ID_COMMAND_LONG_CRC   152
 
#define MAVLINK_MSG_ID_COMMAND_LONG_LEN   33
 

Typedefs

typedef struct __mavlink_command_long_t mavlink_command_long_t
 

Functions

static void mavlink_msg_command_long_decode (const mavlink_message_t *msg, mavlink_command_long_t *command_long)
 Decode a command_long message into a struct. More...
 
static uint16_t mavlink_msg_command_long_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_command_long_t *command_long)
 Encode a command_long struct. More...
 
static uint16_t mavlink_msg_command_long_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_command_long_t *command_long)
 Encode a command_long struct on a channel. More...
 
static uint16_t mavlink_msg_command_long_get_command (const mavlink_message_t *msg)
 Get field command from command_long message. More...
 
static uint8_t mavlink_msg_command_long_get_confirmation (const mavlink_message_t *msg)
 Get field confirmation from command_long message. More...
 
static float mavlink_msg_command_long_get_param1 (const mavlink_message_t *msg)
 Get field param1 from command_long message. More...
 
static float mavlink_msg_command_long_get_param2 (const mavlink_message_t *msg)
 Get field param2 from command_long message. More...
 
static float mavlink_msg_command_long_get_param3 (const mavlink_message_t *msg)
 Get field param3 from command_long message. More...
 
static float mavlink_msg_command_long_get_param4 (const mavlink_message_t *msg)
 Get field param4 from command_long message. More...
 
static float mavlink_msg_command_long_get_param5 (const mavlink_message_t *msg)
 Get field param5 from command_long message. More...
 
static float mavlink_msg_command_long_get_param6 (const mavlink_message_t *msg)
 Get field param6 from command_long message. More...
 
static float mavlink_msg_command_long_get_param7 (const mavlink_message_t *msg)
 Get field param7 from command_long message. More...
 
static uint8_t mavlink_msg_command_long_get_target_component (const mavlink_message_t *msg)
 Get field target_component from command_long message. More...
 
static uint8_t mavlink_msg_command_long_get_target_system (const mavlink_message_t *msg)
 Send a command_long message. More...
 
static uint16_t mavlink_msg_command_long_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
 Pack a command_long message. More...
 
static uint16_t mavlink_msg_command_long_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
 Pack a command_long message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_COMMAND_LONG
Value:
{ \
"COMMAND_LONG", \
11, \
{ { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \
{ "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \
{ "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \
{ "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \
{ "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \
{ "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \
{ "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \
{ "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 28 of file mavlink_msg_command_long.h.

#define MAVLINK_MSG_ID_76_CRC   152

Definition at line 24 of file mavlink_msg_command_long.h.

#define MAVLINK_MSG_ID_76_LEN   33

Definition at line 21 of file mavlink_msg_command_long.h.

#define MAVLINK_MSG_ID_COMMAND_LONG   76

Definition at line 3 of file mavlink_msg_command_long.h.

#define MAVLINK_MSG_ID_COMMAND_LONG_CRC   152

Definition at line 23 of file mavlink_msg_command_long.h.

#define MAVLINK_MSG_ID_COMMAND_LONG_LEN   33

Definition at line 20 of file mavlink_msg_command_long.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_command_long_decode ( const mavlink_message_t *  msg,
mavlink_command_long_t command_long 
)
inlinestatic

Decode a command_long message into a struct.

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

Definition at line 432 of file mavlink_msg_command_long.h.

static uint16_t mavlink_msg_command_long_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_command_long_t command_long 
)
inlinestatic

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

Definition at line 179 of file mavlink_msg_command_long.h.

static uint16_t mavlink_msg_command_long_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_command_long_t command_long 
)
inlinestatic

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

Definition at line 193 of file mavlink_msg_command_long.h.

static uint16_t mavlink_msg_command_long_get_command ( const mavlink_message_t *  msg)
inlinestatic

Get field command from command_long message.

Returns
Command ID, as defined by MAV_CMD enum.

Definition at line 341 of file mavlink_msg_command_long.h.

static uint8_t mavlink_msg_command_long_get_confirmation ( const mavlink_message_t *  msg)
inlinestatic

Get field confirmation from command_long message.

Returns
0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)

Definition at line 351 of file mavlink_msg_command_long.h.

static float mavlink_msg_command_long_get_param1 ( const mavlink_message_t *  msg)
inlinestatic

Get field param1 from command_long message.

Returns
Parameter 1, as defined by MAV_CMD enum.

Definition at line 361 of file mavlink_msg_command_long.h.

static float mavlink_msg_command_long_get_param2 ( const mavlink_message_t *  msg)
inlinestatic

Get field param2 from command_long message.

Returns
Parameter 2, as defined by MAV_CMD enum.

Definition at line 371 of file mavlink_msg_command_long.h.

static float mavlink_msg_command_long_get_param3 ( const mavlink_message_t *  msg)
inlinestatic

Get field param3 from command_long message.

Returns
Parameter 3, as defined by MAV_CMD enum.

Definition at line 381 of file mavlink_msg_command_long.h.

static float mavlink_msg_command_long_get_param4 ( const mavlink_message_t *  msg)
inlinestatic

Get field param4 from command_long message.

Returns
Parameter 4, as defined by MAV_CMD enum.

Definition at line 391 of file mavlink_msg_command_long.h.

static float mavlink_msg_command_long_get_param5 ( const mavlink_message_t *  msg)
inlinestatic

Get field param5 from command_long message.

Returns
Parameter 5, as defined by MAV_CMD enum.

Definition at line 401 of file mavlink_msg_command_long.h.

static float mavlink_msg_command_long_get_param6 ( const mavlink_message_t *  msg)
inlinestatic

Get field param6 from command_long message.

Returns
Parameter 6, as defined by MAV_CMD enum.

Definition at line 411 of file mavlink_msg_command_long.h.

static float mavlink_msg_command_long_get_param7 ( const mavlink_message_t *  msg)
inlinestatic

Get field param7 from command_long message.

Returns
Parameter 7, as defined by MAV_CMD enum.

Definition at line 421 of file mavlink_msg_command_long.h.

static uint8_t mavlink_msg_command_long_get_target_component ( const mavlink_message_t *  msg)
inlinestatic

Get field target_component from command_long message.

Returns
Component which should execute the command, 0 for all components

Definition at line 331 of file mavlink_msg_command_long.h.

static uint8_t mavlink_msg_command_long_get_target_system ( const mavlink_message_t *  msg)
inlinestatic

Send a command_long message.

Parameters
chanMAVLink channel to send the message
target_systemSystem which should execute the command
target_componentComponent which should execute the command, 0 for all components
commandCommand ID, as defined by MAV_CMD enum.
confirmation0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
param1Parameter 1, as defined by MAV_CMD enum.
param2Parameter 2, as defined by MAV_CMD enum.
param3Parameter 3, as defined by MAV_CMD enum.
param4Parameter 4, as defined by MAV_CMD enum.
param5Parameter 5, as defined by MAV_CMD enum.
param6Parameter 6, as defined by MAV_CMD enum.
param7Parameter 7, as defined by MAV_CMD enum. Get field target_system from command_long message
Returns
System which should execute the command

Definition at line 321 of file mavlink_msg_command_long.h.

static uint16_t mavlink_msg_command_long_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint8_t  target_system,
uint8_t  target_component,
uint16_t  command,
uint8_t  confirmation,
float  param1,
float  param2,
float  param3,
float  param4,
float  param5,
float  param6,
float  param7 
)
inlinestatic

Pack a command_long 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_systemSystem which should execute the command
target_componentComponent which should execute the command, 0 for all components
commandCommand ID, as defined by MAV_CMD enum.
confirmation0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
param1Parameter 1, as defined by MAV_CMD enum.
param2Parameter 2, as defined by MAV_CMD enum.
param3Parameter 3, as defined by MAV_CMD enum.
param4Parameter 4, as defined by MAV_CMD enum.
param5Parameter 5, as defined by MAV_CMD enum.
param6Parameter 6, as defined by MAV_CMD enum.
param7Parameter 7, as defined by MAV_CMD enum.
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 65 of file mavlink_msg_command_long.h.

static uint16_t mavlink_msg_command_long_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint8_t  target_system,
uint8_t  target_component,
uint16_t  command,
uint8_t  confirmation,
float  param1,
float  param2,
float  param3,
float  param4,
float  param5,
float  param6,
float  param7 
)
inlinestatic

Pack a command_long 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_systemSystem which should execute the command
target_componentComponent which should execute the command, 0 for all components
commandCommand ID, as defined by MAV_CMD enum.
confirmation0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
param1Parameter 1, as defined by MAV_CMD enum.
param2Parameter 2, as defined by MAV_CMD enum.
param3Parameter 3, as defined by MAV_CMD enum.
param4Parameter 4, as defined by MAV_CMD enum.
param5Parameter 5, as defined by MAV_CMD enum.
param6Parameter 6, as defined by MAV_CMD enum.
param7Parameter 7, as defined by MAV_CMD enum.
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 127 of file mavlink_msg_command_long.h.



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