4#define MAVLINK_MSG_ID_STATUS_GPS 194
7typedef struct __mavlink_status_gps_t {
15}) mavlink_status_gps_t;
17#define MAVLINK_MSG_ID_STATUS_GPS_LEN 11
18#define MAVLINK_MSG_ID_STATUS_GPS_MIN_LEN 11
19#define MAVLINK_MSG_ID_194_LEN 11
20#define MAVLINK_MSG_ID_194_MIN_LEN 11
22#define MAVLINK_MSG_ID_STATUS_GPS_CRC 51
23#define MAVLINK_MSG_ID_194_CRC 51
27#if MAVLINK_COMMAND_24BIT
28#define MAVLINK_MESSAGE_INFO_STATUS_GPS { \
32 { { "csFails", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_status_gps_t, csFails) }, \
33 { "gpsQuality", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_status_gps_t, gpsQuality) }, \
34 { "msgsType", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_status_gps_t, msgsType) }, \
35 { "posStatus", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_status_gps_t, posStatus) }, \
36 { "magVar", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_status_gps_t, magVar) }, \
37 { "magDir", NULL, MAVLINK_TYPE_INT8_T, 0, 9, offsetof(mavlink_status_gps_t, magDir) }, \
38 { "modeInd", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_status_gps_t, modeInd) }, \
42#define MAVLINK_MESSAGE_INFO_STATUS_GPS { \
45 { { "csFails", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_status_gps_t, csFails) }, \
46 { "gpsQuality", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_status_gps_t, gpsQuality) }, \
47 { "msgsType", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_status_gps_t, msgsType) }, \
48 { "posStatus", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_status_gps_t, posStatus) }, \
49 { "magVar", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_status_gps_t, magVar) }, \
50 { "magDir", NULL, MAVLINK_TYPE_INT8_T, 0, 9, offsetof(mavlink_status_gps_t, magDir) }, \
51 { "modeInd", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_status_gps_t, modeInd) }, \
71static inline uint16_t mavlink_msg_status_gps_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
72 uint16_t csFails, uint8_t gpsQuality, uint8_t msgsType, uint8_t posStatus,
float magVar, int8_t magDir, uint8_t modeInd)
74#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
75 char buf[MAVLINK_MSG_ID_STATUS_GPS_LEN];
76 _mav_put_float(buf, 0, magVar);
77 _mav_put_uint16_t(buf, 4, csFails);
78 _mav_put_uint8_t(buf, 6, gpsQuality);
79 _mav_put_uint8_t(buf, 7, msgsType);
80 _mav_put_uint8_t(buf, 8, posStatus);
81 _mav_put_int8_t(buf, 9, magDir);
82 _mav_put_uint8_t(buf, 10, modeInd);
84 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STATUS_GPS_LEN);
86 mavlink_status_gps_t packet;
87 packet.magVar = magVar;
88 packet.csFails = csFails;
89 packet.gpsQuality = gpsQuality;
90 packet.msgsType = msgsType;
91 packet.posStatus = posStatus;
92 packet.magDir = magDir;
93 packet.modeInd = modeInd;
95 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STATUS_GPS_LEN);
98 msg->msgid = MAVLINK_MSG_ID_STATUS_GPS;
99 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STATUS_GPS_MIN_LEN, MAVLINK_MSG_ID_STATUS_GPS_LEN, MAVLINK_MSG_ID_STATUS_GPS_CRC);
117static inline uint16_t mavlink_msg_status_gps_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
118 mavlink_message_t* msg,
119 uint16_t csFails,uint8_t gpsQuality,uint8_t msgsType,uint8_t posStatus,
float magVar,int8_t magDir,uint8_t modeInd)
121#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
122 char buf[MAVLINK_MSG_ID_STATUS_GPS_LEN];
123 _mav_put_float(buf, 0, magVar);
124 _mav_put_uint16_t(buf, 4, csFails);
125 _mav_put_uint8_t(buf, 6, gpsQuality);
126 _mav_put_uint8_t(buf, 7, msgsType);
127 _mav_put_uint8_t(buf, 8, posStatus);
128 _mav_put_int8_t(buf, 9, magDir);
129 _mav_put_uint8_t(buf, 10, modeInd);
131 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STATUS_GPS_LEN);
133 mavlink_status_gps_t packet;
134 packet.magVar = magVar;
135 packet.csFails = csFails;
136 packet.gpsQuality = gpsQuality;
137 packet.msgsType = msgsType;
138 packet.posStatus = posStatus;
139 packet.magDir = magDir;
140 packet.modeInd = modeInd;
142 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STATUS_GPS_LEN);
145 msg->msgid = MAVLINK_MSG_ID_STATUS_GPS;
146 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STATUS_GPS_MIN_LEN, MAVLINK_MSG_ID_STATUS_GPS_LEN, MAVLINK_MSG_ID_STATUS_GPS_CRC);
157static inline uint16_t mavlink_msg_status_gps_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_status_gps_t* status_gps)
159 return mavlink_msg_status_gps_pack(system_id, component_id, msg, status_gps->csFails, status_gps->gpsQuality, status_gps->msgsType, status_gps->posStatus, status_gps->magVar, status_gps->magDir, status_gps->modeInd);
171static inline uint16_t mavlink_msg_status_gps_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_status_gps_t* status_gps)
173 return mavlink_msg_status_gps_pack_chan(system_id, component_id, chan, msg, status_gps->csFails, status_gps->gpsQuality, status_gps->msgsType, status_gps->posStatus, status_gps->magVar, status_gps->magDir, status_gps->modeInd);
188#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
190static inline void mavlink_msg_status_gps_send(mavlink_channel_t chan, uint16_t csFails, uint8_t gpsQuality, uint8_t msgsType, uint8_t posStatus,
float magVar, int8_t magDir, uint8_t modeInd)
192#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
193 char buf[MAVLINK_MSG_ID_STATUS_GPS_LEN];
194 _mav_put_float(buf, 0, magVar);
195 _mav_put_uint16_t(buf, 4, csFails);
196 _mav_put_uint8_t(buf, 6, gpsQuality);
197 _mav_put_uint8_t(buf, 7, msgsType);
198 _mav_put_uint8_t(buf, 8, posStatus);
199 _mav_put_int8_t(buf, 9, magDir);
200 _mav_put_uint8_t(buf, 10, modeInd);
202 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUS_GPS, buf, MAVLINK_MSG_ID_STATUS_GPS_MIN_LEN, MAVLINK_MSG_ID_STATUS_GPS_LEN, MAVLINK_MSG_ID_STATUS_GPS_CRC);
204 mavlink_status_gps_t packet;
205 packet.magVar = magVar;
206 packet.csFails = csFails;
207 packet.gpsQuality = gpsQuality;
208 packet.msgsType = msgsType;
209 packet.posStatus = posStatus;
210 packet.magDir = magDir;
211 packet.modeInd = modeInd;
213 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUS_GPS, (
const char *)&packet, MAVLINK_MSG_ID_STATUS_GPS_MIN_LEN, MAVLINK_MSG_ID_STATUS_GPS_LEN, MAVLINK_MSG_ID_STATUS_GPS_CRC);
222static inline void mavlink_msg_status_gps_send_struct(mavlink_channel_t chan,
const mavlink_status_gps_t* status_gps)
224#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
225 mavlink_msg_status_gps_send(chan, status_gps->csFails, status_gps->gpsQuality, status_gps->msgsType, status_gps->posStatus, status_gps->magVar, status_gps->magDir, status_gps->modeInd);
227 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUS_GPS, (
const char *)status_gps, MAVLINK_MSG_ID_STATUS_GPS_MIN_LEN, MAVLINK_MSG_ID_STATUS_GPS_LEN, MAVLINK_MSG_ID_STATUS_GPS_CRC);
231#if MAVLINK_MSG_ID_STATUS_GPS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
239static inline void mavlink_msg_status_gps_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t csFails, uint8_t gpsQuality, uint8_t msgsType, uint8_t posStatus,
float magVar, int8_t magDir, uint8_t modeInd)
241#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
242 char *buf = (
char *)msgbuf;
243 _mav_put_float(buf, 0, magVar);
244 _mav_put_uint16_t(buf, 4, csFails);
245 _mav_put_uint8_t(buf, 6, gpsQuality);
246 _mav_put_uint8_t(buf, 7, msgsType);
247 _mav_put_uint8_t(buf, 8, posStatus);
248 _mav_put_int8_t(buf, 9, magDir);
249 _mav_put_uint8_t(buf, 10, modeInd);
251 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUS_GPS, buf, MAVLINK_MSG_ID_STATUS_GPS_MIN_LEN, MAVLINK_MSG_ID_STATUS_GPS_LEN, MAVLINK_MSG_ID_STATUS_GPS_CRC);
253 mavlink_status_gps_t *packet = (mavlink_status_gps_t *)msgbuf;
254 packet->magVar = magVar;
255 packet->csFails = csFails;
256 packet->gpsQuality = gpsQuality;
257 packet->msgsType = msgsType;
258 packet->posStatus = posStatus;
259 packet->magDir = magDir;
260 packet->modeInd = modeInd;
262 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUS_GPS, (
const char *)packet, MAVLINK_MSG_ID_STATUS_GPS_MIN_LEN, MAVLINK_MSG_ID_STATUS_GPS_LEN, MAVLINK_MSG_ID_STATUS_GPS_CRC);
277static inline uint16_t mavlink_msg_status_gps_get_csFails(
const mavlink_message_t* msg)
279 return _MAV_RETURN_uint16_t(msg, 4);
287static inline uint8_t mavlink_msg_status_gps_get_gpsQuality(
const mavlink_message_t* msg)
289 return _MAV_RETURN_uint8_t(msg, 6);
297static inline uint8_t mavlink_msg_status_gps_get_msgsType(
const mavlink_message_t* msg)
299 return _MAV_RETURN_uint8_t(msg, 7);
307static inline uint8_t mavlink_msg_status_gps_get_posStatus(
const mavlink_message_t* msg)
309 return _MAV_RETURN_uint8_t(msg, 8);
317static inline float mavlink_msg_status_gps_get_magVar(
const mavlink_message_t* msg)
319 return _MAV_RETURN_float(msg, 0);
327static inline int8_t mavlink_msg_status_gps_get_magDir(
const mavlink_message_t* msg)
329 return _MAV_RETURN_int8_t(msg, 9);
337static inline uint8_t mavlink_msg_status_gps_get_modeInd(
const mavlink_message_t* msg)
339 return _MAV_RETURN_uint8_t(msg, 10);
348static inline void mavlink_msg_status_gps_decode(
const mavlink_message_t* msg, mavlink_status_gps_t* status_gps)
350#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
351 status_gps->magVar = mavlink_msg_status_gps_get_magVar(msg);
352 status_gps->csFails = mavlink_msg_status_gps_get_csFails(msg);
353 status_gps->gpsQuality = mavlink_msg_status_gps_get_gpsQuality(msg);
354 status_gps->msgsType = mavlink_msg_status_gps_get_msgsType(msg);
355 status_gps->posStatus = mavlink_msg_status_gps_get_posStatus(msg);
356 status_gps->magDir = mavlink_msg_status_gps_get_magDir(msg);
357 status_gps->modeInd = mavlink_msg_status_gps_get_modeInd(msg);
359 uint8_t len = msg->len < MAVLINK_MSG_ID_STATUS_GPS_LEN? msg->len : MAVLINK_MSG_ID_STATUS_GPS_LEN;
360 memset(status_gps, 0, MAVLINK_MSG_ID_STATUS_GPS_LEN);
361 memcpy(status_gps, _MAV_PAYLOAD(msg), len);