3 #define MAVLINK_MSG_ID_NOVATEL_DIAG 195
16 #define MAVLINK_MSG_ID_NOVATEL_DIAG_LEN 14
17 #define MAVLINK_MSG_ID_195_LEN 14
19 #define MAVLINK_MSG_ID_NOVATEL_DIAG_CRC 59
20 #define MAVLINK_MSG_ID_195_CRC 59
24 #define MAVLINK_MESSAGE_INFO_NOVATEL_DIAG { \
27 { { "receiverStatus", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_novatel_diag_t, receiverStatus) }, \
28 { "posSolAge", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_novatel_diag_t, posSolAge) }, \
29 { "csFails", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_novatel_diag_t, csFails) }, \
30 { "timeStatus", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_novatel_diag_t, timeStatus) }, \
31 { "solStatus", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_novatel_diag_t, solStatus) }, \
32 { "posType", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_novatel_diag_t, posType) }, \
33 { "velType", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_novatel_diag_t, velType) }, \
53 static inline uint16_t mavlink_msg_novatel_diag_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
54 uint8_t timeStatus, uint32_t receiverStatus, uint8_t solStatus, uint8_t posType, uint8_t velType,
float posSolAge, uint16_t csFails)
56 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
103 static inline uint16_t mavlink_msg_novatel_diag_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
104 mavlink_message_t* msg,
105 uint8_t timeStatus,uint32_t receiverStatus,uint8_t solStatus,uint8_t posType,uint8_t velType,
float posSolAge,uint16_t csFails)
107 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
132 #if MAVLINK_CRC_EXTRA
147 static 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)
161 static 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)
163 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);
178 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
180 static 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)
182 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
192 #if MAVLINK_CRC_EXTRA
207 #if MAVLINK_CRC_EXTRA
215 #if MAVLINK_MSG_ID_NOVATEL_DIAG_LEN <= MAVLINK_MAX_PAYLOAD_LEN
223 static 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)
225 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
226 char *buf = (
char *)msgbuf;
235 #if MAVLINK_CRC_EXTRA
250 #if MAVLINK_CRC_EXTRA
269 static inline uint8_t mavlink_msg_novatel_diag_get_timeStatus(
const mavlink_message_t* msg)
279 static inline uint32_t mavlink_msg_novatel_diag_get_receiverStatus(
const mavlink_message_t* msg)
281 return _MAV_RETURN_uint32_t(msg, 0);
289 static inline uint8_t mavlink_msg_novatel_diag_get_solStatus(
const mavlink_message_t* msg)
299 static inline uint8_t mavlink_msg_novatel_diag_get_posType(
const mavlink_message_t* msg)
309 static inline uint8_t mavlink_msg_novatel_diag_get_velType(
const mavlink_message_t* msg)
319 static inline float mavlink_msg_novatel_diag_get_posSolAge(
const mavlink_message_t* msg)
321 return _MAV_RETURN_float(msg, 4);
329 static inline uint16_t mavlink_msg_novatel_diag_get_csFails(
const mavlink_message_t* msg)
331 return _MAV_RETURN_uint16_t(msg, 8);
340 static inline void mavlink_msg_novatel_diag_decode(
const mavlink_message_t* msg,
mavlink_novatel_diag_t* novatel_diag)
342 #if MAVLINK_NEED_BYTE_SWAP
343 novatel_diag->
receiverStatus = mavlink_msg_novatel_diag_get_receiverStatus(msg);
344 novatel_diag->
posSolAge = mavlink_msg_novatel_diag_get_posSolAge(msg);
345 novatel_diag->
csFails = mavlink_msg_novatel_diag_get_csFails(msg);
346 novatel_diag->
timeStatus = mavlink_msg_novatel_diag_get_timeStatus(msg);
347 novatel_diag->
solStatus = mavlink_msg_novatel_diag_get_solStatus(msg);
348 novatel_diag->
posType = mavlink_msg_novatel_diag_get_posType(msg);
349 novatel_diag->
velType = mavlink_msg_novatel_diag_get_velType(msg);
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
uint16_t csFails
Times the CRC has failed since boot.
Definition: mavlink_msg_novatel_diag.h:9
uint8_t velType
velocity type. See table 43 page 196
Definition: mavlink_msg_novatel_diag.h:13
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:238
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
Definition: mavlink_helpers.h:105
uint8_t timeStatus
The Time Status. See Table 8 page 27 Novatel OEMStar Manual.
Definition: mavlink_msg_novatel_diag.h:10
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:134
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
#define MAVLINK_MSG_ID_NOVATEL_DIAG_CRC
Definition: mavlink_msg_novatel_diag.h:19
mavlink_channel_t
Definition: mavlink_types.h:178
uint8_t posType
position type. See table 43 page 196
Definition: mavlink_msg_novatel_diag.h:12
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
uint32_t receiverStatus
Status Bitfield. See table 69 page 350 Novatel OEMstar Manual.
Definition: mavlink_msg_novatel_diag.h:7
#define MAVLINK_MSG_ID_NOVATEL_DIAG_LEN
Definition: mavlink_msg_novatel_diag.h:16
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:139
struct __mavlink_novatel_diag_t mavlink_novatel_diag_t
Definition: mavlink_msg_novatel_diag.h:5
float posSolAge
Age of the position solution in seconds.
Definition: mavlink_msg_novatel_diag.h:8
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
Definition: mavlink_helpers.h:71
#define MAVLINK_MSG_ID_NOVATEL_DIAG
Definition: mavlink_msg_novatel_diag.h:3
uint8_t solStatus
solution Status. See table 44 page 197
Definition: mavlink_msg_novatel_diag.h:11
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:141