4#define MAVLINK_MSG_ID_NOVATEL_DIAG 195
7typedef struct __mavlink_novatel_diag_t {
8 uint32_t receiverStatus;
15}) mavlink_novatel_diag_t;
17#define MAVLINK_MSG_ID_NOVATEL_DIAG_LEN 14
18#define MAVLINK_MSG_ID_NOVATEL_DIAG_MIN_LEN 14
19#define MAVLINK_MSG_ID_195_LEN 14
20#define MAVLINK_MSG_ID_195_MIN_LEN 14
22#define MAVLINK_MSG_ID_NOVATEL_DIAG_CRC 59
23#define MAVLINK_MSG_ID_195_CRC 59
27#if MAVLINK_COMMAND_24BIT
28#define MAVLINK_MESSAGE_INFO_NOVATEL_DIAG { \
32 { { "timeStatus", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_novatel_diag_t, timeStatus) }, \
33 { "receiverStatus", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_novatel_diag_t, receiverStatus) }, \
34 { "solStatus", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_novatel_diag_t, solStatus) }, \
35 { "posType", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_novatel_diag_t, posType) }, \
36 { "velType", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_novatel_diag_t, velType) }, \
37 { "posSolAge", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_novatel_diag_t, posSolAge) }, \
38 { "csFails", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_novatel_diag_t, csFails) }, \
42#define MAVLINK_MESSAGE_INFO_NOVATEL_DIAG { \
45 { { "timeStatus", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_novatel_diag_t, timeStatus) }, \
46 { "receiverStatus", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_novatel_diag_t, receiverStatus) }, \
47 { "solStatus", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_novatel_diag_t, solStatus) }, \
48 { "posType", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_novatel_diag_t, posType) }, \
49 { "velType", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_novatel_diag_t, velType) }, \
50 { "posSolAge", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_novatel_diag_t, posSolAge) }, \
51 { "csFails", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_novatel_diag_t, csFails) }, \
71static inline uint16_t mavlink_msg_novatel_diag_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
72 uint8_t timeStatus, uint32_t receiverStatus, uint8_t solStatus, uint8_t posType, uint8_t velType,
float posSolAge, uint16_t csFails)
74#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
75 char buf[MAVLINK_MSG_ID_NOVATEL_DIAG_LEN];
76 _mav_put_uint32_t(buf, 0, receiverStatus);
77 _mav_put_float(buf, 4, posSolAge);
78 _mav_put_uint16_t(buf, 8, csFails);
79 _mav_put_uint8_t(buf, 10, timeStatus);
80 _mav_put_uint8_t(buf, 11, solStatus);
81 _mav_put_uint8_t(buf, 12, posType);
82 _mav_put_uint8_t(buf, 13, velType);
84 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NOVATEL_DIAG_LEN);
86 mavlink_novatel_diag_t packet;
87 packet.receiverStatus = receiverStatus;
88 packet.posSolAge = posSolAge;
89 packet.csFails = csFails;
90 packet.timeStatus = timeStatus;
91 packet.solStatus = solStatus;
92 packet.posType = posType;
93 packet.velType = velType;
95 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NOVATEL_DIAG_LEN);
98 msg->msgid = MAVLINK_MSG_ID_NOVATEL_DIAG;
99 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NOVATEL_DIAG_MIN_LEN, MAVLINK_MSG_ID_NOVATEL_DIAG_LEN, MAVLINK_MSG_ID_NOVATEL_DIAG_CRC);
117static inline uint16_t mavlink_msg_novatel_diag_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
118 mavlink_message_t* msg,
119 uint8_t timeStatus,uint32_t receiverStatus,uint8_t solStatus,uint8_t posType,uint8_t velType,
float posSolAge,uint16_t csFails)
121#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
122 char buf[MAVLINK_MSG_ID_NOVATEL_DIAG_LEN];
123 _mav_put_uint32_t(buf, 0, receiverStatus);
124 _mav_put_float(buf, 4, posSolAge);
125 _mav_put_uint16_t(buf, 8, csFails);
126 _mav_put_uint8_t(buf, 10, timeStatus);
127 _mav_put_uint8_t(buf, 11, solStatus);
128 _mav_put_uint8_t(buf, 12, posType);
129 _mav_put_uint8_t(buf, 13, velType);
131 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NOVATEL_DIAG_LEN);
133 mavlink_novatel_diag_t packet;
134 packet.receiverStatus = receiverStatus;
135 packet.posSolAge = posSolAge;
136 packet.csFails = csFails;
137 packet.timeStatus = timeStatus;
138 packet.solStatus = solStatus;
139 packet.posType = posType;
140 packet.velType = velType;
142 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NOVATEL_DIAG_LEN);
145 msg->msgid = MAVLINK_MSG_ID_NOVATEL_DIAG;
146 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NOVATEL_DIAG_MIN_LEN, MAVLINK_MSG_ID_NOVATEL_DIAG_LEN, MAVLINK_MSG_ID_NOVATEL_DIAG_CRC);
157static inline uint16_t mavlink_msg_novatel_diag_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_novatel_diag_t* novatel_diag)
159 return mavlink_msg_novatel_diag_pack(system_id, component_id, msg, novatel_diag->timeStatus, novatel_diag->receiverStatus, novatel_diag->solStatus, novatel_diag->posType, novatel_diag->velType, novatel_diag->posSolAge, novatel_diag->csFails);
171static inline uint16_t mavlink_msg_novatel_diag_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_novatel_diag_t* novatel_diag)
173 return mavlink_msg_novatel_diag_pack_chan(system_id, component_id, chan, msg, novatel_diag->timeStatus, novatel_diag->receiverStatus, novatel_diag->solStatus, novatel_diag->posType, novatel_diag->velType, novatel_diag->posSolAge, novatel_diag->csFails);
188#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
190static inline void mavlink_msg_novatel_diag_send(mavlink_channel_t chan, uint8_t timeStatus, uint32_t receiverStatus, uint8_t solStatus, uint8_t posType, uint8_t velType,
float posSolAge, uint16_t csFails)
192#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
193 char buf[MAVLINK_MSG_ID_NOVATEL_DIAG_LEN];
194 _mav_put_uint32_t(buf, 0, receiverStatus);
195 _mav_put_float(buf, 4, posSolAge);
196 _mav_put_uint16_t(buf, 8, csFails);
197 _mav_put_uint8_t(buf, 10, timeStatus);
198 _mav_put_uint8_t(buf, 11, solStatus);
199 _mav_put_uint8_t(buf, 12, posType);
200 _mav_put_uint8_t(buf, 13, velType);
202 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOVATEL_DIAG, buf, MAVLINK_MSG_ID_NOVATEL_DIAG_MIN_LEN, MAVLINK_MSG_ID_NOVATEL_DIAG_LEN, MAVLINK_MSG_ID_NOVATEL_DIAG_CRC);
204 mavlink_novatel_diag_t packet;
205 packet.receiverStatus = receiverStatus;
206 packet.posSolAge = posSolAge;
207 packet.csFails = csFails;
208 packet.timeStatus = timeStatus;
209 packet.solStatus = solStatus;
210 packet.posType = posType;
211 packet.velType = velType;
213 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOVATEL_DIAG, (
const char *)&packet, MAVLINK_MSG_ID_NOVATEL_DIAG_MIN_LEN, MAVLINK_MSG_ID_NOVATEL_DIAG_LEN, MAVLINK_MSG_ID_NOVATEL_DIAG_CRC);
222static inline void mavlink_msg_novatel_diag_send_struct(mavlink_channel_t chan,
const mavlink_novatel_diag_t* novatel_diag)
224#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
225 mavlink_msg_novatel_diag_send(chan, novatel_diag->timeStatus, novatel_diag->receiverStatus, novatel_diag->solStatus, novatel_diag->posType, novatel_diag->velType, novatel_diag->posSolAge, novatel_diag->csFails);
227 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOVATEL_DIAG, (
const char *)novatel_diag, MAVLINK_MSG_ID_NOVATEL_DIAG_MIN_LEN, MAVLINK_MSG_ID_NOVATEL_DIAG_LEN, MAVLINK_MSG_ID_NOVATEL_DIAG_CRC);
231#if MAVLINK_MSG_ID_NOVATEL_DIAG_LEN <= MAVLINK_MAX_PAYLOAD_LEN
239static inline void mavlink_msg_novatel_diag_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t timeStatus, uint32_t receiverStatus, uint8_t solStatus, uint8_t posType, uint8_t velType,
float posSolAge, uint16_t csFails)
241#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
242 char *buf = (
char *)msgbuf;
243 _mav_put_uint32_t(buf, 0, receiverStatus);
244 _mav_put_float(buf, 4, posSolAge);
245 _mav_put_uint16_t(buf, 8, csFails);
246 _mav_put_uint8_t(buf, 10, timeStatus);
247 _mav_put_uint8_t(buf, 11, solStatus);
248 _mav_put_uint8_t(buf, 12, posType);
249 _mav_put_uint8_t(buf, 13, velType);
251 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOVATEL_DIAG, buf, MAVLINK_MSG_ID_NOVATEL_DIAG_MIN_LEN, MAVLINK_MSG_ID_NOVATEL_DIAG_LEN, MAVLINK_MSG_ID_NOVATEL_DIAG_CRC);
253 mavlink_novatel_diag_t *packet = (mavlink_novatel_diag_t *)msgbuf;
254 packet->receiverStatus = receiverStatus;
255 packet->posSolAge = posSolAge;
256 packet->csFails = csFails;
257 packet->timeStatus = timeStatus;
258 packet->solStatus = solStatus;
259 packet->posType = posType;
260 packet->velType = velType;
262 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOVATEL_DIAG, (
const char *)packet, MAVLINK_MSG_ID_NOVATEL_DIAG_MIN_LEN, MAVLINK_MSG_ID_NOVATEL_DIAG_LEN, MAVLINK_MSG_ID_NOVATEL_DIAG_CRC);
277static inline uint8_t mavlink_msg_novatel_diag_get_timeStatus(
const mavlink_message_t* msg)
279 return _MAV_RETURN_uint8_t(msg, 10);
287static inline uint32_t mavlink_msg_novatel_diag_get_receiverStatus(
const mavlink_message_t* msg)
289 return _MAV_RETURN_uint32_t(msg, 0);
297static inline uint8_t mavlink_msg_novatel_diag_get_solStatus(
const mavlink_message_t* msg)
299 return _MAV_RETURN_uint8_t(msg, 11);
307static inline uint8_t mavlink_msg_novatel_diag_get_posType(
const mavlink_message_t* msg)
309 return _MAV_RETURN_uint8_t(msg, 12);
317static inline uint8_t mavlink_msg_novatel_diag_get_velType(
const mavlink_message_t* msg)
319 return _MAV_RETURN_uint8_t(msg, 13);
327static inline float mavlink_msg_novatel_diag_get_posSolAge(
const mavlink_message_t* msg)
329 return _MAV_RETURN_float(msg, 4);
337static inline uint16_t mavlink_msg_novatel_diag_get_csFails(
const mavlink_message_t* msg)
339 return _MAV_RETURN_uint16_t(msg, 8);
348static inline void mavlink_msg_novatel_diag_decode(
const mavlink_message_t* msg, mavlink_novatel_diag_t* novatel_diag)
350#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
351 novatel_diag->receiverStatus = mavlink_msg_novatel_diag_get_receiverStatus(msg);
352 novatel_diag->posSolAge = mavlink_msg_novatel_diag_get_posSolAge(msg);
353 novatel_diag->csFails = mavlink_msg_novatel_diag_get_csFails(msg);
354 novatel_diag->timeStatus = mavlink_msg_novatel_diag_get_timeStatus(msg);
355 novatel_diag->solStatus = mavlink_msg_novatel_diag_get_solStatus(msg);
356 novatel_diag->posType = mavlink_msg_novatel_diag_get_posType(msg);
357 novatel_diag->velType = mavlink_msg_novatel_diag_get_velType(msg);
359 uint8_t len = msg->len < MAVLINK_MSG_ID_NOVATEL_DIAG_LEN? msg->len : MAVLINK_MSG_ID_NOVATEL_DIAG_LEN;
360 memset(novatel_diag, 0, MAVLINK_MSG_ID_NOVATEL_DIAG_LEN);
361 memcpy(novatel_diag, _MAV_PAYLOAD(msg), len);