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... | |
#define MAVLINK_MESSAGE_INFO_GPS2_RTK |
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 struct __mavlink_gps2_rtk_t mavlink_gps2_rtk_t |
|
inlinestatic |
Decode a gps2_rtk message into a struct.
msg | The message to decode |
gps2_rtk | C-struct to decode the message contents into |
Definition at line 478 of file mavlink_msg_gps2_rtk.h.
|
inlinestatic |
Encode a gps2_rtk 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_rtk | C-struct to read the message contents from |
Definition at line 195 of file mavlink_msg_gps2_rtk.h.
|
inlinestatic |
Encode a gps2_rtk 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_rtk | C-struct to read the message contents from |
Definition at line 209 of file mavlink_msg_gps2_rtk.h.
|
inlinestatic |
Get field accuracy from gps2_rtk message.
Definition at line 457 of file mavlink_msg_gps2_rtk.h.
|
inlinestatic |
Get field baseline_a_mm from gps2_rtk message.
Definition at line 427 of file mavlink_msg_gps2_rtk.h.
|
inlinestatic |
Get field baseline_b_mm from gps2_rtk message.
Definition at line 437 of file mavlink_msg_gps2_rtk.h.
|
inlinestatic |
Get field baseline_c_mm from gps2_rtk message.
Definition at line 447 of file mavlink_msg_gps2_rtk.h.
|
inlinestatic |
Get field baseline_coords_type from gps2_rtk message.
Definition at line 417 of file mavlink_msg_gps2_rtk.h.
|
inlinestatic |
Get field iar_num_hypotheses from gps2_rtk message.
Definition at line 467 of file mavlink_msg_gps2_rtk.h.
|
inlinestatic |
Get field nsats from gps2_rtk message.
Definition at line 407 of file mavlink_msg_gps2_rtk.h.
|
inlinestatic |
Get field rtk_health from gps2_rtk message.
Definition at line 387 of file mavlink_msg_gps2_rtk.h.
|
inlinestatic |
Get field rtk_rate from gps2_rtk message.
Definition at line 397 of file mavlink_msg_gps2_rtk.h.
|
inlinestatic |
Get field rtk_receiver_id from gps2_rtk message.
Definition at line 357 of file mavlink_msg_gps2_rtk.h.
|
inlinestatic |
Send a gps2_rtk message.
chan | MAVLink channel to send the message |
time_last_baseline_ms | Time since boot of last baseline message received in ms. |
rtk_receiver_id | Identification of connected RTK receiver. |
wn | GPS Week Number of last baseline |
tow | GPS Time of Week of last baseline |
rtk_health | GPS-specific health report for RTK data. |
rtk_rate | Rate of baseline messages being received by GPS, in HZ |
nsats | Current number of sats used for RTK calculation. |
baseline_coords_type | Coordinate system of baseline. 0 == ECEF, 1 == NED |
baseline_a_mm | Current baseline in ECEF x or NED north component in mm. |
baseline_b_mm | Current baseline in ECEF y or NED east component in mm. |
baseline_c_mm | Current baseline in ECEF z or NED down component in mm. |
accuracy | Current estimate of baseline accuracy. |
iar_num_hypotheses | Current number of integer ambiguity hypotheses. Get field time_last_baseline_ms from gps2_rtk message |
Definition at line 347 of file mavlink_msg_gps2_rtk.h.
|
inlinestatic |
Get field tow from gps2_rtk message.
Definition at line 377 of file mavlink_msg_gps2_rtk.h.
|
inlinestatic |
Get field wn from gps2_rtk message.
Definition at line 367 of file mavlink_msg_gps2_rtk.h.
|
inlinestatic |
Pack a gps2_rtk 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_last_baseline_ms | Time since boot of last baseline message received in ms. |
rtk_receiver_id | Identification of connected RTK receiver. |
wn | GPS Week Number of last baseline |
tow | GPS Time of Week of last baseline |
rtk_health | GPS-specific health report for RTK data. |
rtk_rate | Rate of baseline messages being received by GPS, in HZ |
nsats | Current number of sats used for RTK calculation. |
baseline_coords_type | Coordinate system of baseline. 0 == ECEF, 1 == NED |
baseline_a_mm | Current baseline in ECEF x or NED north component in mm. |
baseline_b_mm | Current baseline in ECEF y or NED east component in mm. |
baseline_c_mm | Current baseline in ECEF z or NED down component in mm. |
accuracy | Current estimate of baseline accuracy. |
iar_num_hypotheses | Current number of integer ambiguity hypotheses. |
Definition at line 71 of file mavlink_msg_gps2_rtk.h.
|
inlinestatic |
Pack a gps2_rtk 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_last_baseline_ms | Time since boot of last baseline message received in ms. |
rtk_receiver_id | Identification of connected RTK receiver. |
wn | GPS Week Number of last baseline |
tow | GPS Time of Week of last baseline |
rtk_health | GPS-specific health report for RTK data. |
rtk_rate | Rate of baseline messages being received by GPS, in HZ |
nsats | Current number of sats used for RTK calculation. |
baseline_coords_type | Coordinate system of baseline. 0 == ECEF, 1 == NED |
baseline_a_mm | Current baseline in ECEF x or NED north component in mm. |
baseline_b_mm | Current baseline in ECEF y or NED east component in mm. |
baseline_c_mm | Current baseline in ECEF z or NED down component in mm. |
accuracy | Current estimate of baseline accuracy. |
iar_num_hypotheses | Current number of integer ambiguity hypotheses. |
Definition at line 139 of file mavlink_msg_gps2_rtk.h.