Classes | Macros | Typedefs | Functions
mavlink_msg_gps_raw_int.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_gps_raw_int_t
 

Macros

#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT
 
#define MAVLINK_MSG_ID_24_CRC   24
 
#define MAVLINK_MSG_ID_24_LEN   30
 
#define MAVLINK_MSG_ID_GPS_RAW_INT   24
 
#define MAVLINK_MSG_ID_GPS_RAW_INT_CRC   24
 
#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN   30
 

Typedefs

typedef struct __mavlink_gps_raw_int_t mavlink_gps_raw_int_t
 

Functions

static void mavlink_msg_gps_raw_int_decode (const mavlink_message_t *msg, mavlink_gps_raw_int_t *gps_raw_int)
 Decode a gps_raw_int message into a struct. More...
 
static uint16_t mavlink_msg_gps_raw_int_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_gps_raw_int_t *gps_raw_int)
 Encode a gps_raw_int struct. More...
 
static uint16_t mavlink_msg_gps_raw_int_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_gps_raw_int_t *gps_raw_int)
 Encode a gps_raw_int struct on a channel. More...
 
static int32_t mavlink_msg_gps_raw_int_get_alt (const mavlink_message_t *msg)
 Get field alt from gps_raw_int message. More...
 
static uint16_t mavlink_msg_gps_raw_int_get_cog (const mavlink_message_t *msg)
 Get field cog from gps_raw_int message. More...
 
static uint16_t mavlink_msg_gps_raw_int_get_eph (const mavlink_message_t *msg)
 Get field eph from gps_raw_int message. More...
 
static uint16_t mavlink_msg_gps_raw_int_get_epv (const mavlink_message_t *msg)
 Get field epv from gps_raw_int message. More...
 
static uint8_t mavlink_msg_gps_raw_int_get_fix_type (const mavlink_message_t *msg)
 Get field fix_type from gps_raw_int message. More...
 
static int32_t mavlink_msg_gps_raw_int_get_lat (const mavlink_message_t *msg)
 Get field lat from gps_raw_int message. More...
 
static int32_t mavlink_msg_gps_raw_int_get_lon (const mavlink_message_t *msg)
 Get field lon from gps_raw_int message. More...
 
static uint8_t mavlink_msg_gps_raw_int_get_satellites_visible (const mavlink_message_t *msg)
 Get field satellites_visible from gps_raw_int message. More...
 
static uint64_t mavlink_msg_gps_raw_int_get_time_usec (const mavlink_message_t *msg)
 Send a gps_raw_int message. More...
 
static uint16_t mavlink_msg_gps_raw_int_get_vel (const mavlink_message_t *msg)
 Get field vel from gps_raw_int message. More...
 
static uint16_t mavlink_msg_gps_raw_int_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)
 Pack a gps_raw_int message. More...
 
static uint16_t mavlink_msg_gps_raw_int_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)
 Pack a gps_raw_int message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT
Value:
{ \
"GPS_RAW_INT", \
10, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \
{ "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \
{ "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \
{ "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \
{ "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \
{ "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \
} \
}
float alt(float press)
Definition: turbomath.cpp:470
#define NULL
Definition: usbd_def.h:50

Definition at line 27 of file mavlink_msg_gps_raw_int.h.

#define MAVLINK_MSG_ID_24_CRC   24

Definition at line 23 of file mavlink_msg_gps_raw_int.h.

#define MAVLINK_MSG_ID_24_LEN   30

Definition at line 20 of file mavlink_msg_gps_raw_int.h.

#define MAVLINK_MSG_ID_GPS_RAW_INT   24

Definition at line 3 of file mavlink_msg_gps_raw_int.h.

#define MAVLINK_MSG_ID_GPS_RAW_INT_CRC   24

Definition at line 22 of file mavlink_msg_gps_raw_int.h.

#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN   30

Definition at line 19 of file mavlink_msg_gps_raw_int.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_gps_raw_int_decode ( const mavlink_message_t *  msg,
mavlink_gps_raw_int_t gps_raw_int 
)
inlinestatic

Decode a gps_raw_int message into a struct.

Parameters
msgThe message to decode
gps_raw_intC-struct to decode the message contents into

Definition at line 409 of file mavlink_msg_gps_raw_int.h.

static uint16_t mavlink_msg_gps_raw_int_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_gps_raw_int_t gps_raw_int 
)
inlinestatic

Encode a gps_raw_int 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
gps_raw_intC-struct to read the message contents from

Definition at line 171 of file mavlink_msg_gps_raw_int.h.

static uint16_t mavlink_msg_gps_raw_int_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_gps_raw_int_t gps_raw_int 
)
inlinestatic

Encode a gps_raw_int 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
gps_raw_intC-struct to read the message contents from

Definition at line 185 of file mavlink_msg_gps_raw_int.h.

static int32_t mavlink_msg_gps_raw_int_get_alt ( const mavlink_message_t *  msg)
inlinestatic

Get field alt from gps_raw_int message.

Returns
Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.

Definition at line 348 of file mavlink_msg_gps_raw_int.h.

static uint16_t mavlink_msg_gps_raw_int_get_cog ( const mavlink_message_t *  msg)
inlinestatic

Get field cog from gps_raw_int 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 388 of file mavlink_msg_gps_raw_int.h.

static uint16_t mavlink_msg_gps_raw_int_get_eph ( const mavlink_message_t *  msg)
inlinestatic

Get field eph from gps_raw_int message.

Returns
GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX

Definition at line 358 of file mavlink_msg_gps_raw_int.h.

static uint16_t mavlink_msg_gps_raw_int_get_epv ( const mavlink_message_t *  msg)
inlinestatic

Get field epv from gps_raw_int message.

Returns
GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX

Definition at line 368 of file mavlink_msg_gps_raw_int.h.

static uint8_t mavlink_msg_gps_raw_int_get_fix_type ( const mavlink_message_t *  msg)
inlinestatic

Get field fix_type from gps_raw_int message.

Returns
0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. 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 318 of file mavlink_msg_gps_raw_int.h.

static int32_t mavlink_msg_gps_raw_int_get_lat ( const mavlink_message_t *  msg)
inlinestatic

Get field lat from gps_raw_int message.

Returns
Latitude (WGS84), in degrees * 1E7

Definition at line 328 of file mavlink_msg_gps_raw_int.h.

static int32_t mavlink_msg_gps_raw_int_get_lon ( const mavlink_message_t *  msg)
inlinestatic

Get field lon from gps_raw_int message.

Returns
Longitude (WGS84), in degrees * 1E7

Definition at line 338 of file mavlink_msg_gps_raw_int.h.

static uint8_t mavlink_msg_gps_raw_int_get_satellites_visible ( const mavlink_message_t *  msg)
inlinestatic

Get field satellites_visible from gps_raw_int message.

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

Definition at line 398 of file mavlink_msg_gps_raw_int.h.

static uint64_t mavlink_msg_gps_raw_int_get_time_usec ( const mavlink_message_t *  msg)
inlinestatic

Send a gps_raw_int 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, 5: RTK. 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). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
ephGPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
epvGPS VDOP vertical dilution of position (unitless). 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 Get field time_usec from gps_raw_int message
Returns
Timestamp (microseconds since UNIX epoch or microseconds since system boot)

Definition at line 308 of file mavlink_msg_gps_raw_int.h.

static uint16_t mavlink_msg_gps_raw_int_get_vel ( const mavlink_message_t *  msg)
inlinestatic

Get field vel from gps_raw_int message.

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

Definition at line 378 of file mavlink_msg_gps_raw_int.h.

static uint16_t mavlink_msg_gps_raw_int_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 
)
inlinestatic

Pack a gps_raw_int 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, 5: RTK. 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). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
ephGPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
epvGPS VDOP vertical dilution of position (unitless). 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
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 62 of file mavlink_msg_gps_raw_int.h.

static uint16_t mavlink_msg_gps_raw_int_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 
)
inlinestatic

Pack a gps_raw_int 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, 5: RTK. 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). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
ephGPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
epvGPS VDOP vertical dilution of position (unitless). 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
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 121 of file mavlink_msg_gps_raw_int.h.



rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:51