Go to the source code of this file.
Classes | |
struct | __mavlink_set_mode_t |
Defines | |
#define | MAVLINK_MESSAGE_INFO_SET_MODE |
#define | MAVLINK_MSG_ID_11_CRC 89 |
#define | MAVLINK_MSG_ID_11_LEN 6 |
#define | MAVLINK_MSG_ID_SET_MODE 11 |
#define | MAVLINK_MSG_ID_SET_MODE_CRC 89 |
#define | MAVLINK_MSG_ID_SET_MODE_LEN 6 |
Typedefs | |
typedef struct __mavlink_set_mode_t | mavlink_set_mode_t |
Functions | |
static void | mavlink_msg_set_mode_decode (const mavlink_message_t *msg, mavlink_set_mode_t *set_mode) |
Decode a set_mode message into a struct. | |
static uint16_t | mavlink_msg_set_mode_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_set_mode_t *set_mode) |
Encode a set_mode struct. | |
static uint16_t | mavlink_msg_set_mode_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_set_mode_t *set_mode) |
Encode a set_mode struct on a channel. | |
static uint8_t | mavlink_msg_set_mode_get_base_mode (const mavlink_message_t *msg) |
Get field base_mode from set_mode message. | |
static uint32_t | mavlink_msg_set_mode_get_custom_mode (const mavlink_message_t *msg) |
Get field custom_mode from set_mode message. | |
static uint8_t | mavlink_msg_set_mode_get_target_system (const mavlink_message_t *msg) |
Send a set_mode message. | |
static uint16_t | mavlink_msg_set_mode_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) |
Pack a set_mode message. | |
static uint16_t | mavlink_msg_set_mode_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) |
Pack a set_mode message on a channel. |
#define MAVLINK_MESSAGE_INFO_SET_MODE |
{ \ "SET_MODE", \ 3, \ { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \ { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_set_mode_t, base_mode) }, \ } \ }
Definition at line 20 of file mavlink_msg_set_mode.h.
#define MAVLINK_MSG_ID_11_CRC 89 |
Definition at line 16 of file mavlink_msg_set_mode.h.
#define MAVLINK_MSG_ID_11_LEN 6 |
Definition at line 13 of file mavlink_msg_set_mode.h.
#define MAVLINK_MSG_ID_SET_MODE 11 |
Definition at line 3 of file mavlink_msg_set_mode.h.
#define MAVLINK_MSG_ID_SET_MODE_CRC 89 |
Definition at line 15 of file mavlink_msg_set_mode.h.
#define MAVLINK_MSG_ID_SET_MODE_LEN 6 |
Definition at line 12 of file mavlink_msg_set_mode.h.
typedef struct __mavlink_set_mode_t mavlink_set_mode_t |
static void mavlink_msg_set_mode_decode | ( | const mavlink_message_t * | msg, |
mavlink_set_mode_t * | set_mode | ||
) | [inline, static] |
Decode a set_mode message into a struct.
msg | The message to decode |
set_mode | C-struct to decode the message contents into |
Definition at line 248 of file mavlink_msg_set_mode.h.
static uint16_t mavlink_msg_set_mode_encode | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
mavlink_message_t * | msg, | ||
const mavlink_set_mode_t * | set_mode | ||
) | [inline, static] |
Encode a set_mode 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 |
set_mode | C-struct to read the message contents from |
Definition at line 115 of file mavlink_msg_set_mode.h.
static uint16_t mavlink_msg_set_mode_encode_chan | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
uint8_t | chan, | ||
mavlink_message_t * | msg, | ||
const mavlink_set_mode_t * | set_mode | ||
) | [inline, static] |
Encode a set_mode 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 |
set_mode | C-struct to read the message contents from |
Definition at line 129 of file mavlink_msg_set_mode.h.
static uint8_t mavlink_msg_set_mode_get_base_mode | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field base_mode from set_mode message.
Definition at line 227 of file mavlink_msg_set_mode.h.
static uint32_t mavlink_msg_set_mode_get_custom_mode | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field custom_mode from set_mode message.
Definition at line 237 of file mavlink_msg_set_mode.h.
static uint8_t mavlink_msg_set_mode_get_target_system | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Send a set_mode message.
chan | MAVLink channel to send the message |
target_system | The system setting the mode |
base_mode | The new base mode |
custom_mode | The new autopilot-specific mode. This field can be ignored by an autopilot. Get field target_system from set_mode message |
Definition at line 217 of file mavlink_msg_set_mode.h.
static uint16_t mavlink_msg_set_mode_pack | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
mavlink_message_t * | msg, | ||
uint8_t | target_system, | ||
uint8_t | base_mode, | ||
uint32_t | custom_mode | ||
) | [inline, static] |
Pack a set_mode 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 | The system setting the mode |
base_mode | The new base mode |
custom_mode | The new autopilot-specific mode. This field can be ignored by an autopilot. |
Definition at line 41 of file mavlink_msg_set_mode.h.
static uint16_t mavlink_msg_set_mode_pack_chan | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
uint8_t | chan, | ||
mavlink_message_t * | msg, | ||
uint8_t | target_system, | ||
uint8_t | base_mode, | ||
uint32_t | custom_mode | ||
) | [inline, static] |
Pack a set_mode 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 | The system setting the mode |
base_mode | The new base mode |
custom_mode | The new autopilot-specific mode. This field can be ignored by an autopilot. |
Definition at line 79 of file mavlink_msg_set_mode.h.