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

lm's avatar
lm committed
3
#define MAVLINK_MSG_ID_GPS_STATUS 25
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
lm's avatar
lm committed
16
#define MAVLINK_MSG_ID_25_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
#define MAVLINK_MESSAGE_INFO_GPS_STATUS { \
	"GPS_STATUS", \
	6, \
lm's avatar
lm committed
27 28 29 30 31 32
	{  { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \
         { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \
         { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \
         { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \
         { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \
         { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \
lm's avatar
lm committed
33 34 35 36
         } \
}


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
{
LM's avatar
LM committed
54 55 56 57 58 59 60 61
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[101];
	_mav_put_uint8_t(buf, 0, satellites_visible);
	_mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
	_mav_put_uint8_t_array(buf, 21, satellite_used, 20);
	_mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
	_mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
	_mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
62
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 101);
LM's avatar
LM committed
63 64 65
#else
	mavlink_gps_status_t packet;
	packet.satellites_visible = satellites_visible;
66 67 68 69 70
	mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20);
	mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20);
	mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
	mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
	mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20);
71
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 101);
LM's avatar
LM committed
72
#endif
James Goppert's avatar
James Goppert committed
73

LM's avatar
LM committed
74
	msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
lm's avatar
lm committed
75
	return mavlink_finalize_message(msg, system_id, component_id, 101, 23);
James Goppert's avatar
James Goppert committed
76 77 78
}

/**
lm's avatar
lm committed
79
 * @brief Pack a gps_status message on a channel
James Goppert's avatar
James Goppert committed
80 81 82 83 84 85 86 87 88 89 90 91
 * @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
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)
{
LM's avatar
LM committed
96 97 98 99 100 101 102 103
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[101];
	_mav_put_uint8_t(buf, 0, satellites_visible);
	_mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
	_mav_put_uint8_t_array(buf, 21, satellite_used, 20);
	_mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
	_mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
	_mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
104
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 101);
LM's avatar
LM committed
105 106 107
#else
	mavlink_gps_status_t packet;
	packet.satellites_visible = satellites_visible;
108 109 110 111 112
	mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20);
	mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20);
	mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
	mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
	mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20);
113
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 101);
LM's avatar
LM committed
114
#endif
lm's avatar
lm committed
115

LM's avatar
LM committed
116
	msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
lm's avatar
lm committed
117 118 119
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 101, 23);
}

James Goppert's avatar
James Goppert committed
120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143
/**
 * @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
144 145 146
#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
147
{
LM's avatar
LM committed
148 149 150 151 152 153 154 155 156 157 158 159
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[101];
	_mav_put_uint8_t(buf, 0, satellites_visible);
	_mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
	_mav_put_uint8_t_array(buf, 21, satellite_used, 20);
	_mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
	_mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
	_mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, 101, 23);
#else
	mavlink_gps_status_t packet;
	packet.satellites_visible = satellites_visible;
160 161 162 163 164
	mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20);
	mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20);
	mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
	mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
	mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20);
LM's avatar
LM committed
165 166
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, 101, 23);
#endif
James Goppert's avatar
James Goppert committed
167 168 169
}

#endif
lm's avatar
lm committed
170

James Goppert's avatar
James Goppert committed
171 172
// MESSAGE GPS_STATUS UNPACKING

lm's avatar
lm committed
173

James Goppert's avatar
James Goppert committed
174 175 176 177 178 179 180
/**
 * @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
181
	return _MAV_RETURN_uint8_t(msg,  0);
James Goppert's avatar
James Goppert committed
182 183 184 185 186 187 188
}

/**
 * @brief Get field satellite_prn from gps_status message
 *
 * @return Global satellite ID
 */
lm's avatar
lm committed
189
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
190
{
LM's avatar
LM committed
191
	return _MAV_RETURN_uint8_t_array(msg, satellite_prn, 20,  1);
James Goppert's avatar
James Goppert committed
192 193 194 195 196 197 198
}

/**
 * @brief Get field satellite_used from gps_status message
 *
 * @return 0: Satellite not used, 1: used for localization
 */
lm's avatar
lm committed
199
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
200
{
LM's avatar
LM committed
201
	return _MAV_RETURN_uint8_t_array(msg, satellite_used, 20,  21);
James Goppert's avatar
James Goppert committed
202 203 204 205 206 207 208
}

/**
 * @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
209
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
210
{
LM's avatar
LM committed
211
	return _MAV_RETURN_uint8_t_array(msg, satellite_elevation, 20,  41);
James Goppert's avatar
James Goppert committed
212 213 214 215 216 217 218
}

/**
 * @brief Get field satellite_azimuth from gps_status message
 *
 * @return Direction of satellite, 0: 0 deg, 255: 360 deg.
 */
lm's avatar
lm committed
219
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
220
{
LM's avatar
LM committed
221
	return _MAV_RETURN_uint8_t_array(msg, satellite_azimuth, 20,  61);
James Goppert's avatar
James Goppert committed
222 223 224 225 226 227 228
}

/**
 * @brief Get field satellite_snr from gps_status message
 *
 * @return Signal to noise ratio of satellite
 */
lm's avatar
lm committed
229
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
230
{
LM's avatar
LM committed
231
	return _MAV_RETURN_uint8_t_array(msg, satellite_snr, 20,  81);
James Goppert's avatar
James Goppert committed
232 233 234 235 236 237 238 239 240 241
}

/**
 * @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
242 243 244 245 246 247 248 249
#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
LM's avatar
LM committed
250
	memcpy(gps_status, _MAV_PAYLOAD(msg), 101);
lm's avatar
lm committed
251
#endif
James Goppert's avatar
James Goppert committed
252
}