mavlink_msg_gps_status.h 10.2 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2
// MESSAGE GPS_STATUS PACKING

3
#define MAVLINK_MSG_ID_GPS_STATUS 26
James Goppert's avatar
James Goppert committed
4

lm's avatar
lm committed
5
typedef struct __mavlink_gps_status_t
James Goppert's avatar
James Goppert committed
6
{
lm's avatar
lm committed
7 8 9 10 11 12
 uint8_t satellites_visible; ///< Number of satellites visible
 uint8_t satellite_prn[20]; ///< Global satellite ID
 uint8_t satellite_used[20]; ///< 0: Satellite not used, 1: used for localization
 uint8_t satellite_elevation[20]; ///< Elevation (0: right on top of receiver, 90: on the horizon) of satellite
 uint8_t satellite_azimuth[20]; ///< Direction of satellite, 0: 0 deg, 255: 360 deg.
 uint8_t satellite_snr[20]; ///< Signal to noise ratio of satellite
James Goppert's avatar
James Goppert committed
13
} mavlink_gps_status_t;
lm's avatar
lm committed
14 15

#define MAVLINK_MSG_ID_GPS_STATUS_LEN 101
16
#define MAVLINK_MSG_ID_26_LEN 101
lm's avatar
lm committed
17

James Goppert's avatar
James Goppert committed
18 19 20 21 22 23
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_ELEVATION_LEN 20
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_AZIMUTH_LEN 20
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_SNR_LEN 20

lm's avatar
lm committed
24 25 26 27 28 29 30 31 32 33 34 35 36
#define MAVLINK_MESSAGE_INFO_GPS_STATUS { \
	"GPS_STATUS", \
	6, \
	{  { "satellites_visible", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \
         { "satellite_prn", MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \
         { "satellite_used", MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \
         { "satellite_elevation", MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \
         { "satellite_azimuth", MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \
         { "satellite_snr", MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \
         } \
}


James Goppert's avatar
James Goppert committed
37 38 39 40 41 42 43 44 45 46 47 48 49 50
/**
 * @brief Pack a gps_status message
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 *
 * @param satellites_visible Number of satellites visible
 * @param satellite_prn Global satellite ID
 * @param satellite_used 0: Satellite not used, 1: used for localization
 * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
 * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
 * @param satellite_snr Signal to noise ratio of satellite
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
51 52
static inline 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)
James Goppert's avatar
James Goppert committed
53 54 55
{
	msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;

lm's avatar
lm committed
56 57 58 59 60 61
	put_uint8_t_by_index(msg, 0, satellites_visible); // Number of satellites visible
	put_uint8_t_array_by_index(msg, 1, satellite_prn, 20); // Global satellite ID
	put_uint8_t_array_by_index(msg, 21, satellite_used, 20); // 0: Satellite not used, 1: used for localization
	put_uint8_t_array_by_index(msg, 41, satellite_elevation, 20); // Elevation (0: right on top of receiver, 90: on the horizon) of satellite
	put_uint8_t_array_by_index(msg, 61, satellite_azimuth, 20); // Direction of satellite, 0: 0 deg, 255: 360 deg.
	put_uint8_t_array_by_index(msg, 81, satellite_snr, 20); // Signal to noise ratio of satellite
James Goppert's avatar
James Goppert committed
62

lm's avatar
lm committed
63
	return mavlink_finalize_message(msg, system_id, component_id, 101, 23);
James Goppert's avatar
James Goppert committed
64 65 66
}

/**
lm's avatar
lm committed
67
 * @brief Pack a gps_status message on a channel
James Goppert's avatar
James Goppert committed
68 69 70 71 72 73 74 75 76 77 78 79
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param chan The MAVLink channel this message was sent over
 * @param msg The MAVLink message to compress the data into
 * @param satellites_visible Number of satellites visible
 * @param satellite_prn Global satellite ID
 * @param satellite_used 0: Satellite not used, 1: used for localization
 * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
 * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
 * @param satellite_snr Signal to noise ratio of satellite
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95
static inline 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)
{
	msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;

	put_uint8_t_by_index(msg, 0, satellites_visible); // Number of satellites visible
	put_uint8_t_array_by_index(msg, 1, satellite_prn, 20); // Global satellite ID
	put_uint8_t_array_by_index(msg, 21, satellite_used, 20); // 0: Satellite not used, 1: used for localization
	put_uint8_t_array_by_index(msg, 41, satellite_elevation, 20); // Elevation (0: right on top of receiver, 90: on the horizon) of satellite
	put_uint8_t_array_by_index(msg, 61, satellite_azimuth, 20); // Direction of satellite, 0: 0 deg, 255: 360 deg.
	put_uint8_t_array_by_index(msg, 81, satellite_snr, 20); // Signal to noise ratio of satellite

	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 101, 23);
}

James Goppert's avatar
James Goppert committed
96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119
/**
 * @brief Encode a gps_status struct into a message
 *
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 * @param gps_status C-struct to read the message contents from
 */
static inline 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)
{
	return mavlink_msg_gps_status_pack(system_id, component_id, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr);
}

/**
 * @brief Send a gps_status message
 * @param chan MAVLink channel to send the message
 *
 * @param satellites_visible Number of satellites visible
 * @param satellite_prn Global satellite ID
 * @param satellite_used 0: Satellite not used, 1: used for localization
 * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
 * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
 * @param satellite_snr Signal to noise ratio of satellite
 */
lm's avatar
lm committed
120 121 122
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, 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)
lm's avatar
lm committed
123
{
lm's avatar
lm committed
124
	MAVLINK_ALIGNED_MESSAGE(msg, 101);
LM's avatar
LM committed
125 126 127 128 129 130 131 132 133 134
	msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;

	put_uint8_t_by_index(msg, 0, satellites_visible); // Number of satellites visible
	put_uint8_t_array_by_index(msg, 1, satellite_prn, 20); // Global satellite ID
	put_uint8_t_array_by_index(msg, 21, satellite_used, 20); // 0: Satellite not used, 1: used for localization
	put_uint8_t_array_by_index(msg, 41, satellite_elevation, 20); // Elevation (0: right on top of receiver, 90: on the horizon) of satellite
	put_uint8_t_array_by_index(msg, 61, satellite_azimuth, 20); // Direction of satellite, 0: 0 deg, 255: 360 deg.
	put_uint8_t_array_by_index(msg, 81, satellite_snr, 20); // Signal to noise ratio of satellite

	mavlink_finalize_message_chan_send(msg, chan, 101, 23);
James Goppert's avatar
James Goppert committed
135 136 137
}

#endif
lm's avatar
lm committed
138

James Goppert's avatar
James Goppert committed
139 140
// MESSAGE GPS_STATUS UNPACKING

lm's avatar
lm committed
141

James Goppert's avatar
James Goppert committed
142 143 144 145 146 147 148
/**
 * @brief Get field satellites_visible from gps_status message
 *
 * @return Number of satellites visible
 */
static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg)
{
lm's avatar
lm committed
149
	return MAVLINK_MSG_RETURN_uint8_t(msg,  0);
James Goppert's avatar
James Goppert committed
150 151 152 153 154 155 156
}

/**
 * @brief Get field satellite_prn from gps_status message
 *
 * @return Global satellite ID
 */
lm's avatar
lm committed
157
static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, uint8_t *satellite_prn)
James Goppert's avatar
James Goppert committed
158
{
lm's avatar
lm committed
159
	return MAVLINK_MSG_RETURN_uint8_t_array(msg, satellite_prn, 20,  1);
James Goppert's avatar
James Goppert committed
160 161 162 163 164 165 166
}

/**
 * @brief Get field satellite_used from gps_status message
 *
 * @return 0: Satellite not used, 1: used for localization
 */
lm's avatar
lm committed
167
static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, uint8_t *satellite_used)
James Goppert's avatar
James Goppert committed
168
{
lm's avatar
lm committed
169
	return MAVLINK_MSG_RETURN_uint8_t_array(msg, satellite_used, 20,  21);
James Goppert's avatar
James Goppert committed
170 171 172 173 174 175 176
}

/**
 * @brief Get field satellite_elevation from gps_status message
 *
 * @return Elevation (0: right on top of receiver, 90: on the horizon) of satellite
 */
lm's avatar
lm committed
177
static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, uint8_t *satellite_elevation)
James Goppert's avatar
James Goppert committed
178
{
lm's avatar
lm committed
179
	return MAVLINK_MSG_RETURN_uint8_t_array(msg, satellite_elevation, 20,  41);
James Goppert's avatar
James Goppert committed
180 181 182 183 184 185 186
}

/**
 * @brief Get field satellite_azimuth from gps_status message
 *
 * @return Direction of satellite, 0: 0 deg, 255: 360 deg.
 */
lm's avatar
lm committed
187
static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, uint8_t *satellite_azimuth)
James Goppert's avatar
James Goppert committed
188
{
lm's avatar
lm committed
189
	return MAVLINK_MSG_RETURN_uint8_t_array(msg, satellite_azimuth, 20,  61);
James Goppert's avatar
James Goppert committed
190 191 192 193 194 195 196
}

/**
 * @brief Get field satellite_snr from gps_status message
 *
 * @return Signal to noise ratio of satellite
 */
lm's avatar
lm committed
197
static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, uint8_t *satellite_snr)
James Goppert's avatar
James Goppert committed
198
{
lm's avatar
lm committed
199
	return MAVLINK_MSG_RETURN_uint8_t_array(msg, satellite_snr, 20,  81);
James Goppert's avatar
James Goppert committed
200 201 202 203 204 205 206 207 208 209
}

/**
 * @brief Decode a gps_status message into a struct
 *
 * @param msg The message to decode
 * @param gps_status C-struct to decode the message contents into
 */
static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_t* gps_status)
{
lm's avatar
lm committed
210 211 212 213 214 215 216 217 218 219
#if MAVLINK_NEED_BYTE_SWAP
	gps_status->satellites_visible = mavlink_msg_gps_status_get_satellites_visible(msg);
	mavlink_msg_gps_status_get_satellite_prn(msg, gps_status->satellite_prn);
	mavlink_msg_gps_status_get_satellite_used(msg, gps_status->satellite_used);
	mavlink_msg_gps_status_get_satellite_elevation(msg, gps_status->satellite_elevation);
	mavlink_msg_gps_status_get_satellite_azimuth(msg, gps_status->satellite_azimuth);
	mavlink_msg_gps_status_get_satellite_snr(msg, gps_status->satellite_snr);
#else
	memcpy(gps_status, MAVLINK_PAYLOAD(msg), 101);
#endif
James Goppert's avatar
James Goppert committed
220
}