Go to the source code of this file.
|
static void | mavlink_msg_gps_global_origin_decode (const mavlink_message_t *msg, mavlink_gps_global_origin_t *gps_global_origin) |
| Decode a gps_global_origin message into a struct. More...
|
|
static uint16_t | mavlink_msg_gps_global_origin_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_gps_global_origin_t *gps_global_origin) |
| Encode a gps_global_origin struct. More...
|
|
static uint16_t | mavlink_msg_gps_global_origin_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_gps_global_origin_t *gps_global_origin) |
| Encode a gps_global_origin struct on a channel. More...
|
|
static int32_t | mavlink_msg_gps_global_origin_get_altitude (const mavlink_message_t *msg) |
| Get field altitude from gps_global_origin message. More...
|
|
static int32_t | mavlink_msg_gps_global_origin_get_latitude (const mavlink_message_t *msg) |
| Send a gps_global_origin message. More...
|
|
static int32_t | mavlink_msg_gps_global_origin_get_longitude (const mavlink_message_t *msg) |
| Get field longitude from gps_global_origin message. More...
|
|
static uint16_t | mavlink_msg_gps_global_origin_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, int32_t latitude, int32_t longitude, int32_t altitude) |
| Pack a gps_global_origin message. More...
|
|
static uint16_t | mavlink_msg_gps_global_origin_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, int32_t latitude, int32_t longitude, int32_t altitude) |
| Pack a gps_global_origin message on a channel. More...
|
|
#define MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN |
#define MAVLINK_MSG_ID_49_CRC 39 |
#define MAVLINK_MSG_ID_49_LEN 12 |
#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN 49 |
#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC 39 |
#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 12 |
Decode a gps_global_origin message into a struct.
- Parameters
-
msg | The message to decode |
gps_global_origin | C-struct to decode the message contents into |
Definition at line 248 of file mavlink_msg_gps_global_origin.h.
static uint16_t mavlink_msg_gps_global_origin_encode |
( |
uint8_t |
system_id, |
|
|
uint8_t |
component_id, |
|
|
mavlink_message_t * |
msg, |
|
|
const mavlink_gps_global_origin_t * |
gps_global_origin |
|
) |
| |
|
inlinestatic |
Encode a gps_global_origin struct.
- Parameters
-
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 |
gps_global_origin | C-struct to read the message contents from |
Definition at line 115 of file mavlink_msg_gps_global_origin.h.
static uint16_t mavlink_msg_gps_global_origin_encode_chan |
( |
uint8_t |
system_id, |
|
|
uint8_t |
component_id, |
|
|
uint8_t |
chan, |
|
|
mavlink_message_t * |
msg, |
|
|
const mavlink_gps_global_origin_t * |
gps_global_origin |
|
) |
| |
|
inlinestatic |
Encode a gps_global_origin struct on a channel.
- Parameters
-
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 |
gps_global_origin | C-struct to read the message contents from |
Definition at line 129 of file mavlink_msg_gps_global_origin.h.
static int32_t mavlink_msg_gps_global_origin_get_altitude |
( |
const mavlink_message_t * |
msg | ) |
|
|
inlinestatic |
Get field altitude from gps_global_origin message.
- Returns
- Altitude (AMSL), in meters * 1000 (positive for up)
Definition at line 237 of file mavlink_msg_gps_global_origin.h.
static int32_t mavlink_msg_gps_global_origin_get_latitude |
( |
const mavlink_message_t * |
msg | ) |
|
|
inlinestatic |
Send a gps_global_origin message.
- Parameters
-
chan | MAVLink channel to send the message |
latitude | Latitude (WGS84), in degrees * 1E7 |
longitude | Longitude (WGS84), in degrees * 1E7 |
altitude | Altitude (AMSL), in meters * 1000 (positive for up) Get field latitude from gps_global_origin message |
- Returns
- Latitude (WGS84), in degrees * 1E7
Definition at line 217 of file mavlink_msg_gps_global_origin.h.
static int32_t mavlink_msg_gps_global_origin_get_longitude |
( |
const mavlink_message_t * |
msg | ) |
|
|
inlinestatic |
static uint16_t mavlink_msg_gps_global_origin_pack |
( |
uint8_t |
system_id, |
|
|
uint8_t |
component_id, |
|
|
mavlink_message_t * |
msg, |
|
|
int32_t |
latitude, |
|
|
int32_t |
longitude, |
|
|
int32_t |
altitude |
|
) |
| |
|
inlinestatic |
Pack a gps_global_origin message.
- Parameters
-
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 |
latitude | Latitude (WGS84), in degrees * 1E7 |
longitude | Longitude (WGS84), in degrees * 1E7 |
altitude | Altitude (AMSL), in meters * 1000 (positive for up) |
- Returns
- length of the message in bytes (excluding serial stream start sign)
Definition at line 41 of file mavlink_msg_gps_global_origin.h.
static uint16_t mavlink_msg_gps_global_origin_pack_chan |
( |
uint8_t |
system_id, |
|
|
uint8_t |
component_id, |
|
|
uint8_t |
chan, |
|
|
mavlink_message_t * |
msg, |
|
|
int32_t |
latitude, |
|
|
int32_t |
longitude, |
|
|
int32_t |
altitude |
|
) |
| |
|
inlinestatic |
Pack a gps_global_origin message on a channel.
- Parameters
-
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 |
latitude | Latitude (WGS84), in degrees * 1E7 |
longitude | Longitude (WGS84), in degrees * 1E7 |
altitude | Altitude (AMSL), in meters * 1000 (positive for up) |
- Returns
- length of the message in bytes (excluding serial stream start sign)
Definition at line 79 of file mavlink_msg_gps_global_origin.h.