Go to the source code of this file.
Classes | |
struct | __mavlink_set_home_position_t |
Macros | |
#define | MAVLINK_MESSAGE_INFO_SET_HOME_POSITION |
#define | MAVLINK_MSG_ID_243_CRC 85 |
#define | MAVLINK_MSG_ID_243_LEN 53 |
#define | MAVLINK_MSG_ID_SET_HOME_POSITION 243 |
#define | MAVLINK_MSG_ID_SET_HOME_POSITION_CRC 85 |
#define | MAVLINK_MSG_ID_SET_HOME_POSITION_LEN 53 |
#define | MAVLINK_MSG_SET_HOME_POSITION_FIELD_Q_LEN 4 |
Typedefs | |
typedef struct __mavlink_set_home_position_t | mavlink_set_home_position_t |
Functions | |
static void | mavlink_msg_set_home_position_decode (const mavlink_message_t *msg, mavlink_set_home_position_t *set_home_position) |
Decode a set_home_position message into a struct. More... | |
static uint16_t | mavlink_msg_set_home_position_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_set_home_position_t *set_home_position) |
Encode a set_home_position struct. More... | |
static uint16_t | mavlink_msg_set_home_position_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_set_home_position_t *set_home_position) |
Encode a set_home_position struct on a channel. More... | |
static int32_t | mavlink_msg_set_home_position_get_altitude (const mavlink_message_t *msg) |
Get field altitude from set_home_position message. More... | |
static float | mavlink_msg_set_home_position_get_approach_x (const mavlink_message_t *msg) |
Get field approach_x from set_home_position message. More... | |
static float | mavlink_msg_set_home_position_get_approach_y (const mavlink_message_t *msg) |
Get field approach_y from set_home_position message. More... | |
static float | mavlink_msg_set_home_position_get_approach_z (const mavlink_message_t *msg) |
Get field approach_z from set_home_position message. More... | |
static int32_t | mavlink_msg_set_home_position_get_latitude (const mavlink_message_t *msg) |
Get field latitude from set_home_position message. More... | |
static int32_t | mavlink_msg_set_home_position_get_longitude (const mavlink_message_t *msg) |
Get field longitude from set_home_position message. More... | |
static uint16_t | mavlink_msg_set_home_position_get_q (const mavlink_message_t *msg, float *q) |
Get field q from set_home_position message. More... | |
static uint8_t | mavlink_msg_set_home_position_get_target_system (const mavlink_message_t *msg) |
Send a set_home_position message. More... | |
static float | mavlink_msg_set_home_position_get_x (const mavlink_message_t *msg) |
Get field x from set_home_position message. More... | |
static float | mavlink_msg_set_home_position_get_y (const mavlink_message_t *msg) |
Get field y from set_home_position message. More... | |
static float | mavlink_msg_set_home_position_get_z (const mavlink_message_t *msg) |
Get field z from set_home_position message. More... | |
static uint16_t | mavlink_msg_set_home_position_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) |
Pack a set_home_position message. More... | |
static uint16_t | mavlink_msg_set_home_position_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) |
Pack a set_home_position message on a channel. More... | |
#define MAVLINK_MESSAGE_INFO_SET_HOME_POSITION |
Definition at line 28 of file mavlink_msg_set_home_position.h.
#define MAVLINK_MSG_ID_243_CRC 85 |
Definition at line 24 of file mavlink_msg_set_home_position.h.
#define MAVLINK_MSG_ID_243_LEN 53 |
Definition at line 21 of file mavlink_msg_set_home_position.h.
#define MAVLINK_MSG_ID_SET_HOME_POSITION 243 |
Definition at line 3 of file mavlink_msg_set_home_position.h.
#define MAVLINK_MSG_ID_SET_HOME_POSITION_CRC 85 |
Definition at line 23 of file mavlink_msg_set_home_position.h.
#define MAVLINK_MSG_ID_SET_HOME_POSITION_LEN 53 |
Definition at line 20 of file mavlink_msg_set_home_position.h.
#define MAVLINK_MSG_SET_HOME_POSITION_FIELD_Q_LEN 4 |
Definition at line 26 of file mavlink_msg_set_home_position.h.
typedef struct __mavlink_set_home_position_t mavlink_set_home_position_t |
|
inlinestatic |
Decode a set_home_position message into a struct.
msg | The message to decode |
set_home_position | C-struct to decode the message contents into |
Definition at line 424 of file mavlink_msg_set_home_position.h.
|
inlinestatic |
Encode a set_home_position 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_home_position | C-struct to read the message contents from |
Definition at line 175 of file mavlink_msg_set_home_position.h.
|
inlinestatic |
Encode a set_home_position 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_home_position | C-struct to read the message contents from |
Definition at line 189 of file mavlink_msg_set_home_position.h.
|
inlinestatic |
Get field altitude from set_home_position message.
Definition at line 343 of file mavlink_msg_set_home_position.h.
|
inlinestatic |
Get field approach_x from set_home_position message.
Definition at line 393 of file mavlink_msg_set_home_position.h.
|
inlinestatic |
Get field approach_y from set_home_position message.
Definition at line 403 of file mavlink_msg_set_home_position.h.
|
inlinestatic |
Get field approach_z from set_home_position message.
Definition at line 413 of file mavlink_msg_set_home_position.h.
|
inlinestatic |
Get field latitude from set_home_position message.
Definition at line 323 of file mavlink_msg_set_home_position.h.
|
inlinestatic |
Get field longitude from set_home_position message.
Definition at line 333 of file mavlink_msg_set_home_position.h.
|
inlinestatic |
Get field q from set_home_position message.
Definition at line 383 of file mavlink_msg_set_home_position.h.
|
inlinestatic |
Send a set_home_position message.
chan | MAVLink channel to send the message |
target_system | System ID. |
latitude | Latitude (WGS84), in degrees * 1E7 |
longitude | Longitude (WGS84, in degrees * 1E7 |
altitude | Altitude (AMSL), in meters * 1000 (positive for up) |
x | Local X position of this position in the local coordinate frame |
y | Local Y position of this position in the local coordinate frame |
z | Local Z position of this position in the local coordinate frame |
q | World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground |
approach_x | Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. |
approach_y | Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. |
approach_z | Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. Get field target_system from set_home_position message |
Definition at line 313 of file mavlink_msg_set_home_position.h.
|
inlinestatic |
Get field x from set_home_position message.
Definition at line 353 of file mavlink_msg_set_home_position.h.
|
inlinestatic |
Get field y from set_home_position message.
Definition at line 363 of file mavlink_msg_set_home_position.h.
|
inlinestatic |
Get field z from set_home_position message.
Definition at line 373 of file mavlink_msg_set_home_position.h.
|
inlinestatic |
Pack a set_home_position 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. |
latitude | Latitude (WGS84), in degrees * 1E7 |
longitude | Longitude (WGS84, in degrees * 1E7 |
altitude | Altitude (AMSL), in meters * 1000 (positive for up) |
x | Local X position of this position in the local coordinate frame |
y | Local Y position of this position in the local coordinate frame |
z | Local Z position of this position in the local coordinate frame |
q | World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground |
approach_x | Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. |
approach_y | Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. |
approach_z | Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. |
Definition at line 65 of file mavlink_msg_set_home_position.h.
|
inlinestatic |
Pack a set_home_position 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. |
latitude | Latitude (WGS84), in degrees * 1E7 |
longitude | Longitude (WGS84, in degrees * 1E7 |
altitude | Altitude (AMSL), in meters * 1000 (positive for up) |
x | Local X position of this position in the local coordinate frame |
y | Local Y position of this position in the local coordinate frame |
z | Local Z position of this position in the local coordinate frame |
q | World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground |
approach_x | Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. |
approach_y | Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. |
approach_z | Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. |
Definition at line 125 of file mavlink_msg_set_home_position.h.