Go to the source code of this file.
Classes | |
struct | __mavlink_global_position_int_t |
Macros | |
#define | MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT |
#define | MAVLINK_MSG_ID_33_CRC 104 |
#define | MAVLINK_MSG_ID_33_LEN 28 |
#define | MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33 |
#define | MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC 104 |
#define | MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28 |
Typedefs | |
typedef struct __mavlink_global_position_int_t | mavlink_global_position_int_t |
Functions | |
static void | mavlink_msg_global_position_int_decode (const mavlink_message_t *msg, mavlink_global_position_int_t *global_position_int) |
Decode a global_position_int message into a struct. More... | |
static uint16_t | mavlink_msg_global_position_int_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_global_position_int_t *global_position_int) |
Encode a global_position_int struct. More... | |
static uint16_t | mavlink_msg_global_position_int_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_global_position_int_t *global_position_int) |
Encode a global_position_int struct on a channel. More... | |
static int32_t | mavlink_msg_global_position_int_get_alt (const mavlink_message_t *msg) |
Get field alt from global_position_int message. More... | |
static uint16_t | mavlink_msg_global_position_int_get_hdg (const mavlink_message_t *msg) |
Get field hdg from global_position_int message. More... | |
static int32_t | mavlink_msg_global_position_int_get_lat (const mavlink_message_t *msg) |
Get field lat from global_position_int message. More... | |
static int32_t | mavlink_msg_global_position_int_get_lon (const mavlink_message_t *msg) |
Get field lon from global_position_int message. More... | |
static int32_t | mavlink_msg_global_position_int_get_relative_alt (const mavlink_message_t *msg) |
Get field relative_alt from global_position_int message. More... | |
static uint32_t | mavlink_msg_global_position_int_get_time_boot_ms (const mavlink_message_t *msg) |
Send a global_position_int message. More... | |
static int16_t | mavlink_msg_global_position_int_get_vx (const mavlink_message_t *msg) |
Get field vx from global_position_int message. More... | |
static int16_t | mavlink_msg_global_position_int_get_vy (const mavlink_message_t *msg) |
Get field vy from global_position_int message. More... | |
static int16_t | mavlink_msg_global_position_int_get_vz (const mavlink_message_t *msg) |
Get field vz from global_position_int message. More... | |
static uint16_t | mavlink_msg_global_position_int_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) |
Pack a global_position_int message. More... | |
static uint16_t | mavlink_msg_global_position_int_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) |
Pack a global_position_int message on a channel. More... | |
#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT |
Definition at line 26 of file mavlink_msg_global_position_int.h.
#define MAVLINK_MSG_ID_33_CRC 104 |
Definition at line 22 of file mavlink_msg_global_position_int.h.
#define MAVLINK_MSG_ID_33_LEN 28 |
Definition at line 19 of file mavlink_msg_global_position_int.h.
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33 |
Definition at line 3 of file mavlink_msg_global_position_int.h.
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC 104 |
Definition at line 21 of file mavlink_msg_global_position_int.h.
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28 |
Definition at line 18 of file mavlink_msg_global_position_int.h.
typedef struct __mavlink_global_position_int_t mavlink_global_position_int_t |
|
inlinestatic |
Decode a global_position_int message into a struct.
msg | The message to decode |
global_position_int | C-struct to decode the message contents into |
Definition at line 386 of file mavlink_msg_global_position_int.h.
|
inlinestatic |
Encode a global_position_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 |
global_position_int | C-struct to read the message contents from |
Definition at line 163 of file mavlink_msg_global_position_int.h.
|
inlinestatic |
Encode a global_position_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 |
global_position_int | C-struct to read the message contents from |
Definition at line 177 of file mavlink_msg_global_position_int.h.
|
inlinestatic |
Get field alt from global_position_int message.
Definition at line 325 of file mavlink_msg_global_position_int.h.
|
inlinestatic |
Get field hdg from global_position_int message.
Definition at line 375 of file mavlink_msg_global_position_int.h.
|
inlinestatic |
Get field lat from global_position_int message.
Definition at line 305 of file mavlink_msg_global_position_int.h.
|
inlinestatic |
Get field lon from global_position_int message.
Definition at line 315 of file mavlink_msg_global_position_int.h.
|
inlinestatic |
Get field relative_alt from global_position_int message.
Definition at line 335 of file mavlink_msg_global_position_int.h.
|
inlinestatic |
Send a global_position_int message.
chan | MAVLink channel to send the message |
time_boot_ms | Timestamp (milliseconds since system boot) |
lat | Latitude, expressed as degrees * 1E7 |
lon | Longitude, expressed as degrees * 1E7 |
alt | Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) |
relative_alt | Altitude above ground in meters, expressed as * 1000 (millimeters) |
vx | Ground X Speed (Latitude, positive north), expressed as m/s * 100 |
vy | Ground Y Speed (Longitude, positive east), expressed as m/s * 100 |
vz | Ground Z Speed (Altitude, positive down), expressed as m/s * 100 |
hdg | Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX Get field time_boot_ms from global_position_int message |
Definition at line 295 of file mavlink_msg_global_position_int.h.
|
inlinestatic |
Get field vx from global_position_int message.
Definition at line 345 of file mavlink_msg_global_position_int.h.
|
inlinestatic |
Get field vy from global_position_int message.
Definition at line 355 of file mavlink_msg_global_position_int.h.
|
inlinestatic |
Get field vz from global_position_int message.
Definition at line 365 of file mavlink_msg_global_position_int.h.
|
inlinestatic |
Pack a global_position_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 |
time_boot_ms | Timestamp (milliseconds since system boot) |
lat | Latitude, expressed as degrees * 1E7 |
lon | Longitude, expressed as degrees * 1E7 |
alt | Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) |
relative_alt | Altitude above ground in meters, expressed as * 1000 (millimeters) |
vx | Ground X Speed (Latitude, positive north), expressed as m/s * 100 |
vy | Ground Y Speed (Longitude, positive east), expressed as m/s * 100 |
vz | Ground Z Speed (Altitude, positive down), expressed as m/s * 100 |
hdg | Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX |
Definition at line 59 of file mavlink_msg_global_position_int.h.
|
inlinestatic |
Pack a global_position_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 |
time_boot_ms | Timestamp (milliseconds since system boot) |
lat | Latitude, expressed as degrees * 1E7 |
lon | Longitude, expressed as degrees * 1E7 |
alt | Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) |
relative_alt | Altitude above ground in meters, expressed as * 1000 (millimeters) |
vx | Ground X Speed (Latitude, positive north), expressed as m/s * 100 |
vy | Ground Y Speed (Longitude, positive east), expressed as m/s * 100 |
vz | Ground Z Speed (Altitude, positive down), expressed as m/s * 100 |
hdg | Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX |
Definition at line 115 of file mavlink_msg_global_position_int.h.