Classes | Macros | Typedefs | Functions
mavlink_msg_gps2_rtk.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_rtk_t
 

Macros

#define MAVLINK_MESSAGE_INFO_GPS2_RTK
 
#define MAVLINK_MSG_ID_128_CRC   226
 
#define MAVLINK_MSG_ID_128_LEN   35
 
#define MAVLINK_MSG_ID_GPS2_RTK   128
 
#define MAVLINK_MSG_ID_GPS2_RTK_CRC   226
 
#define MAVLINK_MSG_ID_GPS2_RTK_LEN   35
 

Typedefs

typedef struct __mavlink_gps2_rtk_t mavlink_gps2_rtk_t
 

Functions

static void mavlink_msg_gps2_rtk_decode (const mavlink_message_t *msg, mavlink_gps2_rtk_t *gps2_rtk)
 Decode a gps2_rtk message into a struct. More...
 
static uint16_t mavlink_msg_gps2_rtk_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_gps2_rtk_t *gps2_rtk)
 Encode a gps2_rtk struct. More...
 
static uint16_t mavlink_msg_gps2_rtk_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_gps2_rtk_t *gps2_rtk)
 Encode a gps2_rtk struct on a channel. More...
 
static uint32_t mavlink_msg_gps2_rtk_get_accuracy (const mavlink_message_t *msg)
 Get field accuracy from gps2_rtk message. More...
 
static int32_t mavlink_msg_gps2_rtk_get_baseline_a_mm (const mavlink_message_t *msg)
 Get field baseline_a_mm from gps2_rtk message. More...
 
static int32_t mavlink_msg_gps2_rtk_get_baseline_b_mm (const mavlink_message_t *msg)
 Get field baseline_b_mm from gps2_rtk message. More...
 
static int32_t mavlink_msg_gps2_rtk_get_baseline_c_mm (const mavlink_message_t *msg)
 Get field baseline_c_mm from gps2_rtk message. More...
 
static uint8_t mavlink_msg_gps2_rtk_get_baseline_coords_type (const mavlink_message_t *msg)
 Get field baseline_coords_type from gps2_rtk message. More...
 
static int32_t mavlink_msg_gps2_rtk_get_iar_num_hypotheses (const mavlink_message_t *msg)
 Get field iar_num_hypotheses from gps2_rtk message. More...
 
static uint8_t mavlink_msg_gps2_rtk_get_nsats (const mavlink_message_t *msg)
 Get field nsats from gps2_rtk message. More...
 
static uint8_t mavlink_msg_gps2_rtk_get_rtk_health (const mavlink_message_t *msg)
 Get field rtk_health from gps2_rtk message. More...
 
static uint8_t mavlink_msg_gps2_rtk_get_rtk_rate (const mavlink_message_t *msg)
 Get field rtk_rate from gps2_rtk message. More...
 
static uint8_t mavlink_msg_gps2_rtk_get_rtk_receiver_id (const mavlink_message_t *msg)
 Get field rtk_receiver_id from gps2_rtk message. More...
 
static uint32_t mavlink_msg_gps2_rtk_get_time_last_baseline_ms (const mavlink_message_t *msg)
 Send a gps2_rtk message. More...
 
static uint32_t mavlink_msg_gps2_rtk_get_tow (const mavlink_message_t *msg)
 Get field tow from gps2_rtk message. More...
 
static uint16_t mavlink_msg_gps2_rtk_get_wn (const mavlink_message_t *msg)
 Get field wn from gps2_rtk message. More...
 
static uint16_t mavlink_msg_gps2_rtk_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses)
 Pack a gps2_rtk message. More...
 
static uint16_t mavlink_msg_gps2_rtk_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses)
 Pack a gps2_rtk message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_GPS2_RTK
Value:
{ \
"GPS2_RTK", \
13, \
{ { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps2_rtk_t, time_last_baseline_ms) }, \
{ "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps2_rtk_t, tow) }, \
{ "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_rtk_t, baseline_a_mm) }, \
{ "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_rtk_t, baseline_b_mm) }, \
{ "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_rtk_t, baseline_c_mm) }, \
{ "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_rtk_t, accuracy) }, \
{ "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps2_rtk_t, iar_num_hypotheses) }, \
{ "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \
{ "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \
{ "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \
{ "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \
{ "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \
{ "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 30 of file mavlink_msg_gps2_rtk.h.

#define MAVLINK_MSG_ID_128_CRC   226

Definition at line 26 of file mavlink_msg_gps2_rtk.h.

#define MAVLINK_MSG_ID_128_LEN   35

Definition at line 23 of file mavlink_msg_gps2_rtk.h.

#define MAVLINK_MSG_ID_GPS2_RTK   128

Definition at line 3 of file mavlink_msg_gps2_rtk.h.

#define MAVLINK_MSG_ID_GPS2_RTK_CRC   226

Definition at line 25 of file mavlink_msg_gps2_rtk.h.

#define MAVLINK_MSG_ID_GPS2_RTK_LEN   35

Definition at line 22 of file mavlink_msg_gps2_rtk.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_gps2_rtk_decode ( const mavlink_message_t *  msg,
mavlink_gps2_rtk_t gps2_rtk 
)
inlinestatic

Decode a gps2_rtk message into a struct.

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

Definition at line 478 of file mavlink_msg_gps2_rtk.h.

static uint16_t mavlink_msg_gps2_rtk_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_gps2_rtk_t gps2_rtk 
)
inlinestatic

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

Definition at line 195 of file mavlink_msg_gps2_rtk.h.

static uint16_t mavlink_msg_gps2_rtk_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_gps2_rtk_t gps2_rtk 
)
inlinestatic

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

Definition at line 209 of file mavlink_msg_gps2_rtk.h.

static uint32_t mavlink_msg_gps2_rtk_get_accuracy ( const mavlink_message_t *  msg)
inlinestatic

Get field accuracy from gps2_rtk message.

Returns
Current estimate of baseline accuracy.

Definition at line 457 of file mavlink_msg_gps2_rtk.h.

static int32_t mavlink_msg_gps2_rtk_get_baseline_a_mm ( const mavlink_message_t *  msg)
inlinestatic

Get field baseline_a_mm from gps2_rtk message.

Returns
Current baseline in ECEF x or NED north component in mm.

Definition at line 427 of file mavlink_msg_gps2_rtk.h.

static int32_t mavlink_msg_gps2_rtk_get_baseline_b_mm ( const mavlink_message_t *  msg)
inlinestatic

Get field baseline_b_mm from gps2_rtk message.

Returns
Current baseline in ECEF y or NED east component in mm.

Definition at line 437 of file mavlink_msg_gps2_rtk.h.

static int32_t mavlink_msg_gps2_rtk_get_baseline_c_mm ( const mavlink_message_t *  msg)
inlinestatic

Get field baseline_c_mm from gps2_rtk message.

Returns
Current baseline in ECEF z or NED down component in mm.

Definition at line 447 of file mavlink_msg_gps2_rtk.h.

static uint8_t mavlink_msg_gps2_rtk_get_baseline_coords_type ( const mavlink_message_t *  msg)
inlinestatic

Get field baseline_coords_type from gps2_rtk message.

Returns
Coordinate system of baseline. 0 == ECEF, 1 == NED

Definition at line 417 of file mavlink_msg_gps2_rtk.h.

static int32_t mavlink_msg_gps2_rtk_get_iar_num_hypotheses ( const mavlink_message_t *  msg)
inlinestatic

Get field iar_num_hypotheses from gps2_rtk message.

Returns
Current number of integer ambiguity hypotheses.

Definition at line 467 of file mavlink_msg_gps2_rtk.h.

static uint8_t mavlink_msg_gps2_rtk_get_nsats ( const mavlink_message_t *  msg)
inlinestatic

Get field nsats from gps2_rtk message.

Returns
Current number of sats used for RTK calculation.

Definition at line 407 of file mavlink_msg_gps2_rtk.h.

static uint8_t mavlink_msg_gps2_rtk_get_rtk_health ( const mavlink_message_t *  msg)
inlinestatic

Get field rtk_health from gps2_rtk message.

Returns
GPS-specific health report for RTK data.

Definition at line 387 of file mavlink_msg_gps2_rtk.h.

static uint8_t mavlink_msg_gps2_rtk_get_rtk_rate ( const mavlink_message_t *  msg)
inlinestatic

Get field rtk_rate from gps2_rtk message.

Returns
Rate of baseline messages being received by GPS, in HZ

Definition at line 397 of file mavlink_msg_gps2_rtk.h.

static uint8_t mavlink_msg_gps2_rtk_get_rtk_receiver_id ( const mavlink_message_t *  msg)
inlinestatic

Get field rtk_receiver_id from gps2_rtk message.

Returns
Identification of connected RTK receiver.

Definition at line 357 of file mavlink_msg_gps2_rtk.h.

static uint32_t mavlink_msg_gps2_rtk_get_time_last_baseline_ms ( const mavlink_message_t *  msg)
inlinestatic

Send a gps2_rtk message.

Parameters
chanMAVLink channel to send the message
time_last_baseline_msTime since boot of last baseline message received in ms.
rtk_receiver_idIdentification of connected RTK receiver.
wnGPS Week Number of last baseline
towGPS Time of Week of last baseline
rtk_healthGPS-specific health report for RTK data.
rtk_rateRate of baseline messages being received by GPS, in HZ
nsatsCurrent number of sats used for RTK calculation.
baseline_coords_typeCoordinate system of baseline. 0 == ECEF, 1 == NED
baseline_a_mmCurrent baseline in ECEF x or NED north component in mm.
baseline_b_mmCurrent baseline in ECEF y or NED east component in mm.
baseline_c_mmCurrent baseline in ECEF z or NED down component in mm.
accuracyCurrent estimate of baseline accuracy.
iar_num_hypothesesCurrent number of integer ambiguity hypotheses. Get field time_last_baseline_ms from gps2_rtk message
Returns
Time since boot of last baseline message received in ms.

Definition at line 347 of file mavlink_msg_gps2_rtk.h.

static uint32_t mavlink_msg_gps2_rtk_get_tow ( const mavlink_message_t *  msg)
inlinestatic

Get field tow from gps2_rtk message.

Returns
GPS Time of Week of last baseline

Definition at line 377 of file mavlink_msg_gps2_rtk.h.

static uint16_t mavlink_msg_gps2_rtk_get_wn ( const mavlink_message_t *  msg)
inlinestatic

Get field wn from gps2_rtk message.

Returns
GPS Week Number of last baseline

Definition at line 367 of file mavlink_msg_gps2_rtk.h.

static uint16_t mavlink_msg_gps2_rtk_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint32_t  time_last_baseline_ms,
uint8_t  rtk_receiver_id,
uint16_t  wn,
uint32_t  tow,
uint8_t  rtk_health,
uint8_t  rtk_rate,
uint8_t  nsats,
uint8_t  baseline_coords_type,
int32_t  baseline_a_mm,
int32_t  baseline_b_mm,
int32_t  baseline_c_mm,
uint32_t  accuracy,
int32_t  iar_num_hypotheses 
)
inlinestatic

Pack a gps2_rtk 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_last_baseline_msTime since boot of last baseline message received in ms.
rtk_receiver_idIdentification of connected RTK receiver.
wnGPS Week Number of last baseline
towGPS Time of Week of last baseline
rtk_healthGPS-specific health report for RTK data.
rtk_rateRate of baseline messages being received by GPS, in HZ
nsatsCurrent number of sats used for RTK calculation.
baseline_coords_typeCoordinate system of baseline. 0 == ECEF, 1 == NED
baseline_a_mmCurrent baseline in ECEF x or NED north component in mm.
baseline_b_mmCurrent baseline in ECEF y or NED east component in mm.
baseline_c_mmCurrent baseline in ECEF z or NED down component in mm.
accuracyCurrent estimate of baseline accuracy.
iar_num_hypothesesCurrent number of integer ambiguity hypotheses.
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 71 of file mavlink_msg_gps2_rtk.h.

static uint16_t mavlink_msg_gps2_rtk_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint32_t  time_last_baseline_ms,
uint8_t  rtk_receiver_id,
uint16_t  wn,
uint32_t  tow,
uint8_t  rtk_health,
uint8_t  rtk_rate,
uint8_t  nsats,
uint8_t  baseline_coords_type,
int32_t  baseline_a_mm,
int32_t  baseline_b_mm,
int32_t  baseline_c_mm,
uint32_t  accuracy,
int32_t  iar_num_hypotheses 
)
inlinestatic

Pack a gps2_rtk 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_last_baseline_msTime since boot of last baseline message received in ms.
rtk_receiver_idIdentification of connected RTK receiver.
wnGPS Week Number of last baseline
towGPS Time of Week of last baseline
rtk_healthGPS-specific health report for RTK data.
rtk_rateRate of baseline messages being received by GPS, in HZ
nsatsCurrent number of sats used for RTK calculation.
baseline_coords_typeCoordinate system of baseline. 0 == ECEF, 1 == NED
baseline_a_mmCurrent baseline in ECEF x or NED north component in mm.
baseline_b_mmCurrent baseline in ECEF y or NED east component in mm.
baseline_c_mmCurrent baseline in ECEF z or NED down component in mm.
accuracyCurrent estimate of baseline accuracy.
iar_num_hypothesesCurrent number of integer ambiguity hypotheses.
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 139 of file mavlink_msg_gps2_rtk.h.



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