3 #define MAVLINK_MSG_ID_GPS_STATUS 25 15 #define MAVLINK_MSG_ID_GPS_STATUS_LEN 101 16 #define MAVLINK_MSG_ID_25_LEN 101 18 #define MAVLINK_MSG_ID_GPS_STATUS_CRC 23 19 #define MAVLINK_MSG_ID_25_CRC 23 21 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20 22 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20 23 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_ELEVATION_LEN 20 24 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_AZIMUTH_LEN 20 25 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_SNR_LEN 20 27 #define MAVLINK_MESSAGE_INFO_GPS_STATUS { \ 30 { { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \ 31 { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \ 32 { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \ 33 { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \ 34 { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \ 35 { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \ 57 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 100 mavlink_message_t* msg,
103 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 124 #if MAVLINK_CRC_EXTRA 169 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 173 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 181 #if MAVLINK_CRC_EXTRA 194 #if MAVLINK_CRC_EXTRA 202 #if MAVLINK_MSG_ID_GPS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN 212 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 213 char *buf = (
char *)msgbuf;
220 #if MAVLINK_CRC_EXTRA 233 #if MAVLINK_CRC_EXTRA 315 #if MAVLINK_NEED_BYTE_SWAP uint8_t satellite_used[20]
static uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t *msg, uint8_t *satellite_used)
Get field satellite_used from gps_status message.
static uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t *msg, uint8_t *satellite_prn)
Get field satellite_prn from gps_status message.
static uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t *msg)
Send a gps_status message.
#define _MAV_RETURN_uint8_t(msg, wire_offset)
static uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t *msg, uint8_t *satellite_azimuth)
Get field satellite_azimuth from gps_status message.
uint8_t satellite_prn[20]
uint8_t satellites_visible
static uint16_t mavlink_msg_gps_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_gps_status_t *gps_status)
Encode a gps_status struct on a channel.
static uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t *msg, uint8_t *satellite_snr)
Get field satellite_snr from gps_status message.
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
#define _mav_put_uint8_t(buf, wire_offset, b)
static void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
#define MAVLINK_MSG_ID_GPS_STATUS_CRC
#define _MAV_PAYLOAD_NON_CONST(msg)
static uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr)
Pack a gps_status message.
static uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_gps_status_t *gps_status)
Encode a gps_status struct.
#define MAVLINK_MSG_ID_GPS_STATUS_LEN
#define _MAV_PAYLOAD(msg)
#define MAVLINK_MSG_ID_GPS_STATUS
uint8_t satellite_elevation[20]
static uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t *msg, uint8_t *satellite_elevation)
Get field satellite_elevation from gps_status message.
static void mavlink_msg_gps_status_decode(const mavlink_message_t *msg, mavlink_gps_status_t *gps_status)
Decode a gps_status message into a struct.
static void mav_array_memcpy(void *dest, const void *src, size_t n)
static uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value, uint8_t array_length, uint8_t wire_offset)
static uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr)
Pack a gps_status message on a channel.
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
uint8_t satellite_snr[20]
struct __mavlink_gps_status_t mavlink_gps_status_t
uint8_t satellite_azimuth[20]