Go to the source code of this file.
Classes | |
struct | __mavlink_gps2_raw_t |
Macros | |
#define | MAVLINK_MESSAGE_INFO_GPS2_RAW |
#define | MAVLINK_MSG_ID_124_CRC 87 |
#define | MAVLINK_MSG_ID_124_LEN 35 |
#define | MAVLINK_MSG_ID_GPS2_RAW 124 |
#define | MAVLINK_MSG_ID_GPS2_RAW_CRC 87 |
#define | MAVLINK_MSG_ID_GPS2_RAW_LEN 35 |
Typedefs | |
typedef struct __mavlink_gps2_raw_t | mavlink_gps2_raw_t |
Functions | |
static void | mavlink_msg_gps2_raw_decode (const mavlink_message_t *msg, mavlink_gps2_raw_t *gps2_raw) |
Decode a gps2_raw message into a struct. More... | |
static uint16_t | mavlink_msg_gps2_raw_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_gps2_raw_t *gps2_raw) |
Encode a gps2_raw struct. More... | |
static uint16_t | mavlink_msg_gps2_raw_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_gps2_raw_t *gps2_raw) |
Encode a gps2_raw struct on a channel. More... | |
static int32_t | mavlink_msg_gps2_raw_get_alt (const mavlink_message_t *msg) |
Get field alt from gps2_raw message. More... | |
static uint16_t | mavlink_msg_gps2_raw_get_cog (const mavlink_message_t *msg) |
Get field cog from gps2_raw message. More... | |
static uint32_t | mavlink_msg_gps2_raw_get_dgps_age (const mavlink_message_t *msg) |
Get field dgps_age from gps2_raw message. More... | |
static uint8_t | mavlink_msg_gps2_raw_get_dgps_numch (const mavlink_message_t *msg) |
Get field dgps_numch from gps2_raw message. More... | |
static uint16_t | mavlink_msg_gps2_raw_get_eph (const mavlink_message_t *msg) |
Get field eph from gps2_raw message. More... | |
static uint16_t | mavlink_msg_gps2_raw_get_epv (const mavlink_message_t *msg) |
Get field epv from gps2_raw message. More... | |
static uint8_t | mavlink_msg_gps2_raw_get_fix_type (const mavlink_message_t *msg) |
Get field fix_type from gps2_raw message. More... | |
static int32_t | mavlink_msg_gps2_raw_get_lat (const mavlink_message_t *msg) |
Get field lat from gps2_raw message. More... | |
static int32_t | mavlink_msg_gps2_raw_get_lon (const mavlink_message_t *msg) |
Get field lon from gps2_raw message. More... | |
static uint8_t | mavlink_msg_gps2_raw_get_satellites_visible (const mavlink_message_t *msg) |
Get field satellites_visible from gps2_raw message. More... | |
static uint64_t | mavlink_msg_gps2_raw_get_time_usec (const mavlink_message_t *msg) |
Send a gps2_raw message. More... | |
static uint16_t | mavlink_msg_gps2_raw_get_vel (const mavlink_message_t *msg) |
Get field vel from gps2_raw message. More... | |
static uint16_t | mavlink_msg_gps2_raw_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age) |
Pack a gps2_raw message. More... | |
static uint16_t | mavlink_msg_gps2_raw_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age) |
Pack a gps2_raw message on a channel. More... | |
#define MAVLINK_MESSAGE_INFO_GPS2_RAW |
Definition at line 29 of file mavlink_msg_gps2_raw.h.
#define MAVLINK_MSG_ID_124_CRC 87 |
Definition at line 25 of file mavlink_msg_gps2_raw.h.
#define MAVLINK_MSG_ID_124_LEN 35 |
Definition at line 22 of file mavlink_msg_gps2_raw.h.
#define MAVLINK_MSG_ID_GPS2_RAW 124 |
Definition at line 3 of file mavlink_msg_gps2_raw.h.
#define MAVLINK_MSG_ID_GPS2_RAW_CRC 87 |
Definition at line 24 of file mavlink_msg_gps2_raw.h.
#define MAVLINK_MSG_ID_GPS2_RAW_LEN 35 |
Definition at line 21 of file mavlink_msg_gps2_raw.h.
typedef struct __mavlink_gps2_raw_t mavlink_gps2_raw_t |
|
inlinestatic |
Decode a gps2_raw message into a struct.
msg | The message to decode |
gps2_raw | C-struct to decode the message contents into |
Definition at line 455 of file mavlink_msg_gps2_raw.h.
|
inlinestatic |
Encode a gps2_raw 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 |
gps2_raw | C-struct to read the message contents from |
Definition at line 187 of file mavlink_msg_gps2_raw.h.
|
inlinestatic |
Encode a gps2_raw 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 |
gps2_raw | C-struct to read the message contents from |
Definition at line 201 of file mavlink_msg_gps2_raw.h.
|
inlinestatic |
Get field alt from gps2_raw message.
Definition at line 374 of file mavlink_msg_gps2_raw.h.
|
inlinestatic |
Get field cog from gps2_raw message.
Definition at line 414 of file mavlink_msg_gps2_raw.h.
|
inlinestatic |
Get field dgps_age from gps2_raw message.
Definition at line 444 of file mavlink_msg_gps2_raw.h.
|
inlinestatic |
Get field dgps_numch from gps2_raw message.
Definition at line 434 of file mavlink_msg_gps2_raw.h.
|
inlinestatic |
Get field eph from gps2_raw message.
Definition at line 384 of file mavlink_msg_gps2_raw.h.
|
inlinestatic |
Get field epv from gps2_raw message.
Definition at line 394 of file mavlink_msg_gps2_raw.h.
|
inlinestatic |
Get field fix_type from gps2_raw message.
Definition at line 344 of file mavlink_msg_gps2_raw.h.
|
inlinestatic |
Get field lat from gps2_raw message.
Definition at line 354 of file mavlink_msg_gps2_raw.h.
|
inlinestatic |
Get field lon from gps2_raw message.
Definition at line 364 of file mavlink_msg_gps2_raw.h.
|
inlinestatic |
Get field satellites_visible from gps2_raw message.
Definition at line 424 of file mavlink_msg_gps2_raw.h.
|
inlinestatic |
Send a gps2_raw message.
chan | MAVLink channel to send the message |
time_usec | Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
fix_type | 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. |
lat | Latitude (WGS84), in degrees * 1E7 |
lon | Longitude (WGS84), in degrees * 1E7 |
alt | Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) |
eph | GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX |
epv | GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX |
vel | GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX |
cog | Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX |
satellites_visible | Number of satellites visible. If unknown, set to 255 |
dgps_numch | Number of DGPS satellites |
dgps_age | Age of DGPS info Get field time_usec from gps2_raw message |
Definition at line 334 of file mavlink_msg_gps2_raw.h.
|
inlinestatic |
Get field vel from gps2_raw message.
Definition at line 404 of file mavlink_msg_gps2_raw.h.
|
inlinestatic |
Pack a gps2_raw 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_usec | Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
fix_type | 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. |
lat | Latitude (WGS84), in degrees * 1E7 |
lon | Longitude (WGS84), in degrees * 1E7 |
alt | Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) |
eph | GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX |
epv | GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX |
vel | GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX |
cog | Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX |
satellites_visible | Number of satellites visible. If unknown, set to 255 |
dgps_numch | Number of DGPS satellites |
dgps_age | Age of DGPS info |
Definition at line 68 of file mavlink_msg_gps2_raw.h.
|
inlinestatic |
Pack a gps2_raw 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_usec | Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
fix_type | 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. |
lat | Latitude (WGS84), in degrees * 1E7 |
lon | Longitude (WGS84), in degrees * 1E7 |
alt | Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) |
eph | GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX |
epv | GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX |
vel | GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX |
cog | Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX |
satellites_visible | Number of satellites visible. If unknown, set to 255 |
dgps_numch | Number of DGPS satellites |
dgps_age | Age of DGPS info |
Definition at line 133 of file mavlink_msg_gps2_raw.h.