00001
00002
00003 #define MAVLINK_MSG_ID_GPS_STATUS 25
00004
00005 typedef struct __mavlink_gps_status_t
00006 {
00007 uint8_t satellites_visible;
00008 uint8_t satellite_prn[20];
00009 uint8_t satellite_used[20];
00010 uint8_t satellite_elevation[20];
00011 uint8_t satellite_azimuth[20];
00012 uint8_t satellite_snr[20];
00013 } mavlink_gps_status_t;
00014
00015 #define MAVLINK_MSG_ID_GPS_STATUS_LEN 101
00016 #define MAVLINK_MSG_ID_25_LEN 101
00017
00018 #define MAVLINK_MSG_ID_GPS_STATUS_CRC 23
00019 #define MAVLINK_MSG_ID_25_CRC 23
00020
00021 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20
00022 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20
00023 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_ELEVATION_LEN 20
00024 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_AZIMUTH_LEN 20
00025 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_SNR_LEN 20
00026
00027 #define MAVLINK_MESSAGE_INFO_GPS_STATUS { \
00028 "GPS_STATUS", \
00029 6, \
00030 { { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \
00031 { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \
00032 { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \
00033 { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \
00034 { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \
00035 { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \
00036 } \
00037 }
00038
00039
00054 static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00055 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)
00056 {
00057 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00058 char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN];
00059 _mav_put_uint8_t(buf, 0, satellites_visible);
00060 _mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
00061 _mav_put_uint8_t_array(buf, 21, satellite_used, 20);
00062 _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
00063 _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
00064 _mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
00065 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_STATUS_LEN);
00066 #else
00067 mavlink_gps_status_t packet;
00068 packet.satellites_visible = satellites_visible;
00069 mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20);
00070 mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20);
00071 mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
00072 mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
00073 mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20);
00074 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_STATUS_LEN);
00075 #endif
00076
00077 msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
00078 #if MAVLINK_CRC_EXTRA
00079 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
00080 #else
00081 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_STATUS_LEN);
00082 #endif
00083 }
00084
00099 static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00100 mavlink_message_t* msg,
00101 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)
00102 {
00103 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00104 char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN];
00105 _mav_put_uint8_t(buf, 0, satellites_visible);
00106 _mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
00107 _mav_put_uint8_t_array(buf, 21, satellite_used, 20);
00108 _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
00109 _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
00110 _mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
00111 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_STATUS_LEN);
00112 #else
00113 mavlink_gps_status_t packet;
00114 packet.satellites_visible = satellites_visible;
00115 mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20);
00116 mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20);
00117 mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
00118 mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
00119 mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20);
00120 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_STATUS_LEN);
00121 #endif
00122
00123 msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
00124 #if MAVLINK_CRC_EXTRA
00125 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
00126 #else
00127 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_STATUS_LEN);
00128 #endif
00129 }
00130
00139 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)
00140 {
00141 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);
00142 }
00143
00153 static inline 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)
00154 {
00155 return mavlink_msg_gps_status_pack_chan(system_id, component_id, chan, 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);
00156 }
00157
00169 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00170
00171 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)
00172 {
00173 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00174 char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN];
00175 _mav_put_uint8_t(buf, 0, satellites_visible);
00176 _mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
00177 _mav_put_uint8_t_array(buf, 21, satellite_used, 20);
00178 _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
00179 _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
00180 _mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
00181 #if MAVLINK_CRC_EXTRA
00182 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
00183 #else
00184 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN);
00185 #endif
00186 #else
00187 mavlink_gps_status_t packet;
00188 packet.satellites_visible = satellites_visible;
00189 mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20);
00190 mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20);
00191 mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
00192 mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
00193 mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20);
00194 #if MAVLINK_CRC_EXTRA
00195 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
00196 #else
00197 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GPS_STATUS_LEN);
00198 #endif
00199 #endif
00200 }
00201
00202 #if MAVLINK_MSG_ID_GPS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00203
00204
00205
00206
00207
00208
00209
00210 static inline void mavlink_msg_gps_status_send_buf(mavlink_message_t *msgbuf, 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)
00211 {
00212 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00213 char *buf = (char *)msgbuf;
00214 _mav_put_uint8_t(buf, 0, satellites_visible);
00215 _mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
00216 _mav_put_uint8_t_array(buf, 21, satellite_used, 20);
00217 _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
00218 _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
00219 _mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
00220 #if MAVLINK_CRC_EXTRA
00221 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
00222 #else
00223 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN);
00224 #endif
00225 #else
00226 mavlink_gps_status_t *packet = (mavlink_gps_status_t *)msgbuf;
00227 packet->satellites_visible = satellites_visible;
00228 mav_array_memcpy(packet->satellite_prn, satellite_prn, sizeof(uint8_t)*20);
00229 mav_array_memcpy(packet->satellite_used, satellite_used, sizeof(uint8_t)*20);
00230 mav_array_memcpy(packet->satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
00231 mav_array_memcpy(packet->satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
00232 mav_array_memcpy(packet->satellite_snr, satellite_snr, sizeof(uint8_t)*20);
00233 #if MAVLINK_CRC_EXTRA
00234 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)packet, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
00235 #else
00236 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)packet, MAVLINK_MSG_ID_GPS_STATUS_LEN);
00237 #endif
00238 #endif
00239 }
00240 #endif
00241
00242 #endif
00243
00244
00245
00246
00252 static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg)
00253 {
00254 return _MAV_RETURN_uint8_t(msg, 0);
00255 }
00256
00262 static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, uint8_t *satellite_prn)
00263 {
00264 return _MAV_RETURN_uint8_t_array(msg, satellite_prn, 20, 1);
00265 }
00266
00272 static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, uint8_t *satellite_used)
00273 {
00274 return _MAV_RETURN_uint8_t_array(msg, satellite_used, 20, 21);
00275 }
00276
00282 static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, uint8_t *satellite_elevation)
00283 {
00284 return _MAV_RETURN_uint8_t_array(msg, satellite_elevation, 20, 41);
00285 }
00286
00292 static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, uint8_t *satellite_azimuth)
00293 {
00294 return _MAV_RETURN_uint8_t_array(msg, satellite_azimuth, 20, 61);
00295 }
00296
00302 static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, uint8_t *satellite_snr)
00303 {
00304 return _MAV_RETURN_uint8_t_array(msg, satellite_snr, 20, 81);
00305 }
00306
00313 static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_t* gps_status)
00314 {
00315 #if MAVLINK_NEED_BYTE_SWAP
00316 gps_status->satellites_visible = mavlink_msg_gps_status_get_satellites_visible(msg);
00317 mavlink_msg_gps_status_get_satellite_prn(msg, gps_status->satellite_prn);
00318 mavlink_msg_gps_status_get_satellite_used(msg, gps_status->satellite_used);
00319 mavlink_msg_gps_status_get_satellite_elevation(msg, gps_status->satellite_elevation);
00320 mavlink_msg_gps_status_get_satellite_azimuth(msg, gps_status->satellite_azimuth);
00321 mavlink_msg_gps_status_get_satellite_snr(msg, gps_status->satellite_snr);
00322 #else
00323 memcpy(gps_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_STATUS_LEN);
00324 #endif
00325 }