Go to the source code of this file.
Classes | |
struct | __mavlink_command_int_t |
Macros | |
#define | MAVLINK_MESSAGE_INFO_COMMAND_INT |
#define | MAVLINK_MSG_ID_75_CRC 158 |
#define | MAVLINK_MSG_ID_75_LEN 35 |
#define | MAVLINK_MSG_ID_COMMAND_INT 75 |
#define | MAVLINK_MSG_ID_COMMAND_INT_CRC 158 |
#define | MAVLINK_MSG_ID_COMMAND_INT_LEN 35 |
Typedefs | |
typedef struct __mavlink_command_int_t | mavlink_command_int_t |
Functions | |
static void | mavlink_msg_command_int_decode (const mavlink_message_t *msg, mavlink_command_int_t *command_int) |
Decode a command_int message into a struct. More... | |
static uint16_t | mavlink_msg_command_int_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_command_int_t *command_int) |
Encode a command_int struct. More... | |
static uint16_t | mavlink_msg_command_int_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_command_int_t *command_int) |
Encode a command_int struct on a channel. More... | |
static uint8_t | mavlink_msg_command_int_get_autocontinue (const mavlink_message_t *msg) |
Get field autocontinue from command_int message. More... | |
static uint16_t | mavlink_msg_command_int_get_command (const mavlink_message_t *msg) |
Get field command from command_int message. More... | |
static uint8_t | mavlink_msg_command_int_get_current (const mavlink_message_t *msg) |
Get field current from command_int message. More... | |
static uint8_t | mavlink_msg_command_int_get_frame (const mavlink_message_t *msg) |
Get field frame from command_int message. More... | |
static float | mavlink_msg_command_int_get_param1 (const mavlink_message_t *msg) |
Get field param1 from command_int message. More... | |
static float | mavlink_msg_command_int_get_param2 (const mavlink_message_t *msg) |
Get field param2 from command_int message. More... | |
static float | mavlink_msg_command_int_get_param3 (const mavlink_message_t *msg) |
Get field param3 from command_int message. More... | |
static float | mavlink_msg_command_int_get_param4 (const mavlink_message_t *msg) |
Get field param4 from command_int message. More... | |
static uint8_t | mavlink_msg_command_int_get_target_component (const mavlink_message_t *msg) |
Get field target_component from command_int message. More... | |
static uint8_t | mavlink_msg_command_int_get_target_system (const mavlink_message_t *msg) |
Send a command_int message. More... | |
static int32_t | mavlink_msg_command_int_get_x (const mavlink_message_t *msg) |
Get field x from command_int message. More... | |
static int32_t | mavlink_msg_command_int_get_y (const mavlink_message_t *msg) |
Get field y from command_int message. More... | |
static float | mavlink_msg_command_int_get_z (const mavlink_message_t *msg) |
Get field z from command_int message. More... | |
static uint16_t | mavlink_msg_command_int_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) |
Pack a command_int message. More... | |
static uint16_t | mavlink_msg_command_int_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, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) |
Pack a command_int message on a channel. More... | |
#define MAVLINK_MESSAGE_INFO_COMMAND_INT |
Definition at line 30 of file mavlink_msg_command_int.h.
#define MAVLINK_MSG_ID_75_CRC 158 |
Definition at line 26 of file mavlink_msg_command_int.h.
#define MAVLINK_MSG_ID_75_LEN 35 |
Definition at line 23 of file mavlink_msg_command_int.h.
#define MAVLINK_MSG_ID_COMMAND_INT 75 |
Definition at line 3 of file mavlink_msg_command_int.h.
#define MAVLINK_MSG_ID_COMMAND_INT_CRC 158 |
Definition at line 25 of file mavlink_msg_command_int.h.
#define MAVLINK_MSG_ID_COMMAND_INT_LEN 35 |
Definition at line 22 of file mavlink_msg_command_int.h.
typedef struct __mavlink_command_int_t mavlink_command_int_t |
|
inlinestatic |
Decode a command_int message into a struct.
msg | The message to decode |
command_int | C-struct to decode the message contents into |
Definition at line 478 of file mavlink_msg_command_int.h.
|
inlinestatic |
Encode a command_int struct.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
command_int | C-struct to read the message contents from |
Definition at line 195 of file mavlink_msg_command_int.h.
|
inlinestatic |
Encode a command_int struct on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
command_int | C-struct to read the message contents from |
Definition at line 209 of file mavlink_msg_command_int.h.
|
inlinestatic |
Get field autocontinue from command_int message.
Definition at line 397 of file mavlink_msg_command_int.h.
|
inlinestatic |
Get field command from command_int message.
Definition at line 377 of file mavlink_msg_command_int.h.
|
inlinestatic |
Get field current from command_int message.
Definition at line 387 of file mavlink_msg_command_int.h.
|
inlinestatic |
Get field frame from command_int message.
Definition at line 367 of file mavlink_msg_command_int.h.
|
inlinestatic |
Get field param1 from command_int message.
Definition at line 407 of file mavlink_msg_command_int.h.
|
inlinestatic |
Get field param2 from command_int message.
Definition at line 417 of file mavlink_msg_command_int.h.
|
inlinestatic |
Get field param3 from command_int message.
Definition at line 427 of file mavlink_msg_command_int.h.
|
inlinestatic |
Get field param4 from command_int message.
Definition at line 437 of file mavlink_msg_command_int.h.
|
inlinestatic |
Get field target_component from command_int message.
Definition at line 357 of file mavlink_msg_command_int.h.
|
inlinestatic |
Send a command_int message.
chan | MAVLink channel to send the message |
target_system | System ID |
target_component | Component ID |
frame | The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h |
command | The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs |
current | false:0, true:1 |
autocontinue | autocontinue to next wp |
param1 | PARAM1, see MAV_CMD enum |
param2 | PARAM2, see MAV_CMD enum |
param3 | PARAM3, see MAV_CMD enum |
param4 | PARAM4, see MAV_CMD enum |
x | PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 |
y | PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 |
z | PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. Get field target_system from command_int message |
Definition at line 347 of file mavlink_msg_command_int.h.
|
inlinestatic |
Get field x from command_int message.
Definition at line 447 of file mavlink_msg_command_int.h.
|
inlinestatic |
Get field y from command_int message.
Definition at line 457 of file mavlink_msg_command_int.h.
|
inlinestatic |
Get field z from command_int message.
Definition at line 467 of file mavlink_msg_command_int.h.
|
inlinestatic |
Pack a command_int message.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
target_system | System ID |
target_component | Component ID |
frame | The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h |
command | The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs |
current | false:0, true:1 |
autocontinue | autocontinue to next wp |
param1 | PARAM1, see MAV_CMD enum |
param2 | PARAM2, see MAV_CMD enum |
param3 | PARAM3, see MAV_CMD enum |
param4 | PARAM4, see MAV_CMD enum |
x | PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 |
y | PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 |
z | PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. |
Definition at line 71 of file mavlink_msg_command_int.h.
|
inlinestatic |
Pack a command_int message on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
target_system | System ID |
target_component | Component ID |
frame | The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h |
command | The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs |
current | false:0, true:1 |
autocontinue | autocontinue to next wp |
param1 | PARAM1, see MAV_CMD enum |
param2 | PARAM2, see MAV_CMD enum |
param3 | PARAM3, see MAV_CMD enum |
param4 | PARAM4, see MAV_CMD enum |
x | PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 |
y | PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 |
z | PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. |
Definition at line 139 of file mavlink_msg_command_int.h.