Classes | Defines | Typedefs | Functions
mavlink_msg_gps2_raw.h File Reference
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  __mavlink_gps2_raw_t

Defines

#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.
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.
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.
static int32_t mavlink_msg_gps2_raw_get_alt (const mavlink_message_t *msg)
 Get field alt from gps2_raw message.
static uint16_t mavlink_msg_gps2_raw_get_cog (const mavlink_message_t *msg)
 Get field cog from gps2_raw message.
static uint32_t mavlink_msg_gps2_raw_get_dgps_age (const mavlink_message_t *msg)
 Get field dgps_age from gps2_raw message.
static uint8_t mavlink_msg_gps2_raw_get_dgps_numch (const mavlink_message_t *msg)
 Get field dgps_numch from gps2_raw message.
static uint16_t mavlink_msg_gps2_raw_get_eph (const mavlink_message_t *msg)
 Get field eph from gps2_raw message.
static uint16_t mavlink_msg_gps2_raw_get_epv (const mavlink_message_t *msg)
 Get field epv from gps2_raw message.
static uint8_t mavlink_msg_gps2_raw_get_fix_type (const mavlink_message_t *msg)
 Get field fix_type from gps2_raw message.
static int32_t mavlink_msg_gps2_raw_get_lat (const mavlink_message_t *msg)
 Get field lat from gps2_raw message.
static int32_t mavlink_msg_gps2_raw_get_lon (const mavlink_message_t *msg)
 Get field lon from gps2_raw message.
static uint8_t mavlink_msg_gps2_raw_get_satellites_visible (const mavlink_message_t *msg)
 Get field satellites_visible from gps2_raw message.
static uint64_t mavlink_msg_gps2_raw_get_time_usec (const mavlink_message_t *msg)
 Send a gps2_raw message.
static uint16_t mavlink_msg_gps2_raw_get_vel (const mavlink_message_t *msg)
 Get field vel from gps2_raw message.
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.
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.

Define Documentation

Value:
{ \
        "GPS2_RAW", \
        12, \
        {  { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \
         { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \
         { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \
         { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \
         { "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \
         { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \
         { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \
         { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \
         { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \
         { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \
         { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \
         { "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \
         } \
}

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 Documentation


Function Documentation

static void mavlink_msg_gps2_raw_decode ( const mavlink_message_t msg,
mavlink_gps2_raw_t gps2_raw 
) [inline, static]

Decode a gps2_raw message into a struct.

Parameters:
msgThe message to decode
gps2_rawC-struct to decode the message contents into

Definition at line 455 of file mavlink_msg_gps2_raw.h.

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 
) [inline, static]

Encode a gps2_raw struct.

Parameters:
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
gps2_rawC-struct to read the message contents from

Definition at line 187 of file mavlink_msg_gps2_raw.h.

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 
) [inline, static]

Encode a gps2_raw struct on a channel.

Parameters:
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
gps2_rawC-struct to read the message contents from

Definition at line 201 of file mavlink_msg_gps2_raw.h.

static int32_t mavlink_msg_gps2_raw_get_alt ( const mavlink_message_t msg) [inline, static]

Get field alt from gps2_raw message.

Returns:
Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)

Definition at line 374 of file mavlink_msg_gps2_raw.h.

static uint16_t mavlink_msg_gps2_raw_get_cog ( const mavlink_message_t msg) [inline, static]

Get field cog from gps2_raw message.

Returns:
Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX

Definition at line 414 of file mavlink_msg_gps2_raw.h.

static uint32_t mavlink_msg_gps2_raw_get_dgps_age ( const mavlink_message_t msg) [inline, static]

Get field dgps_age from gps2_raw message.

Returns:
Age of DGPS info

Definition at line 444 of file mavlink_msg_gps2_raw.h.

static uint8_t mavlink_msg_gps2_raw_get_dgps_numch ( const mavlink_message_t msg) [inline, static]

Get field dgps_numch from gps2_raw message.

Returns:
Number of DGPS satellites

Definition at line 434 of file mavlink_msg_gps2_raw.h.

static uint16_t mavlink_msg_gps2_raw_get_eph ( const mavlink_message_t msg) [inline, static]

Get field eph from gps2_raw message.

Returns:
GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX

Definition at line 384 of file mavlink_msg_gps2_raw.h.

static uint16_t mavlink_msg_gps2_raw_get_epv ( const mavlink_message_t msg) [inline, static]

Get field epv from gps2_raw message.

Returns:
GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX

Definition at line 394 of file mavlink_msg_gps2_raw.h.

static uint8_t mavlink_msg_gps2_raw_get_fix_type ( const mavlink_message_t msg) [inline, static]

Get field fix_type from gps2_raw message.

Returns:
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.

Definition at line 344 of file mavlink_msg_gps2_raw.h.

static int32_t mavlink_msg_gps2_raw_get_lat ( const mavlink_message_t msg) [inline, static]

Get field lat from gps2_raw message.

Returns:
Latitude (WGS84), in degrees * 1E7

Definition at line 354 of file mavlink_msg_gps2_raw.h.

static int32_t mavlink_msg_gps2_raw_get_lon ( const mavlink_message_t msg) [inline, static]

Get field lon from gps2_raw message.

Returns:
Longitude (WGS84), in degrees * 1E7

Definition at line 364 of file mavlink_msg_gps2_raw.h.

static uint8_t mavlink_msg_gps2_raw_get_satellites_visible ( const mavlink_message_t msg) [inline, static]

Get field satellites_visible from gps2_raw message.

Returns:
Number of satellites visible. If unknown, set to 255

Definition at line 424 of file mavlink_msg_gps2_raw.h.

static uint64_t mavlink_msg_gps2_raw_get_time_usec ( const mavlink_message_t msg) [inline, static]

Send a gps2_raw message.

Parameters:
chanMAVLink channel to send the message
time_usecTimestamp (microseconds since UNIX epoch or microseconds since system boot)
fix_type0-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.
latLatitude (WGS84), in degrees * 1E7
lonLongitude (WGS84), in degrees * 1E7
altAltitude (AMSL, not WGS84), in meters * 1000 (positive for up)
ephGPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
epvGPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
velGPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
cogCourse over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
satellites_visibleNumber of satellites visible. If unknown, set to 255
dgps_numchNumber of DGPS satellites
dgps_ageAge of DGPS info Get field time_usec from gps2_raw message
Returns:
Timestamp (microseconds since UNIX epoch or microseconds since system boot)

Definition at line 334 of file mavlink_msg_gps2_raw.h.

static uint16_t mavlink_msg_gps2_raw_get_vel ( const mavlink_message_t msg) [inline, static]

Get field vel from gps2_raw message.

Returns:
GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX

Definition at line 404 of file mavlink_msg_gps2_raw.h.

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 
) [inline, static]

Pack a gps2_raw message.

Parameters:
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
time_usecTimestamp (microseconds since UNIX epoch or microseconds since system boot)
fix_type0-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.
latLatitude (WGS84), in degrees * 1E7
lonLongitude (WGS84), in degrees * 1E7
altAltitude (AMSL, not WGS84), in meters * 1000 (positive for up)
ephGPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
epvGPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
velGPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
cogCourse over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
satellites_visibleNumber of satellites visible. If unknown, set to 255
dgps_numchNumber of DGPS satellites
dgps_ageAge of DGPS info
Returns:
length of the message in bytes (excluding serial stream start sign)

Definition at line 68 of file mavlink_msg_gps2_raw.h.

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 
) [inline, static]

Pack a gps2_raw message on a channel.

Parameters:
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
time_usecTimestamp (microseconds since UNIX epoch or microseconds since system boot)
fix_type0-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.
latLatitude (WGS84), in degrees * 1E7
lonLongitude (WGS84), in degrees * 1E7
altAltitude (AMSL, not WGS84), in meters * 1000 (positive for up)
ephGPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
epvGPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
velGPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
cogCourse over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
satellites_visibleNumber of satellites visible. If unknown, set to 255
dgps_numchNumber of DGPS satellites
dgps_ageAge of DGPS info
Returns:
length of the message in bytes (excluding serial stream start sign)

Definition at line 133 of file mavlink_msg_gps2_raw.h.



dji_sdk_dji2mav
Author(s):
autogenerated on Thu Jun 6 2019 17:55:35