4#define MAVLINK_MSG_ID_DIAGNOSTIC 173
7typedef struct __mavlink_diagnostic_t {
14}) mavlink_diagnostic_t;
16#define MAVLINK_MSG_ID_DIAGNOSTIC_LEN 18
17#define MAVLINK_MSG_ID_DIAGNOSTIC_MIN_LEN 18
18#define MAVLINK_MSG_ID_173_LEN 18
19#define MAVLINK_MSG_ID_173_MIN_LEN 18
21#define MAVLINK_MSG_ID_DIAGNOSTIC_CRC 2
22#define MAVLINK_MSG_ID_173_CRC 2
26#if MAVLINK_COMMAND_24BIT
27#define MAVLINK_MESSAGE_INFO_DIAGNOSTIC { \
31 { { "diagFl1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_diagnostic_t, diagFl1) }, \
32 { "diagFl2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_diagnostic_t, diagFl2) }, \
33 { "diagFl3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_diagnostic_t, diagFl3) }, \
34 { "diagSh1", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_diagnostic_t, diagSh1) }, \
35 { "diagSh2", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_diagnostic_t, diagSh2) }, \
36 { "diagSh3", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_diagnostic_t, diagSh3) }, \
40#define MAVLINK_MESSAGE_INFO_DIAGNOSTIC { \
43 { { "diagFl1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_diagnostic_t, diagFl1) }, \
44 { "diagFl2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_diagnostic_t, diagFl2) }, \
45 { "diagFl3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_diagnostic_t, diagFl3) }, \
46 { "diagSh1", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_diagnostic_t, diagSh1) }, \
47 { "diagSh2", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_diagnostic_t, diagSh2) }, \
48 { "diagSh3", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_diagnostic_t, diagSh3) }, \
67static inline uint16_t mavlink_msg_diagnostic_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
68 float diagFl1,
float diagFl2,
float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3)
70#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
71 char buf[MAVLINK_MSG_ID_DIAGNOSTIC_LEN];
72 _mav_put_float(buf, 0, diagFl1);
73 _mav_put_float(buf, 4, diagFl2);
74 _mav_put_float(buf, 8, diagFl3);
75 _mav_put_int16_t(buf, 12, diagSh1);
76 _mav_put_int16_t(buf, 14, diagSh2);
77 _mav_put_int16_t(buf, 16, diagSh3);
79 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIAGNOSTIC_LEN);
81 mavlink_diagnostic_t packet;
82 packet.diagFl1 = diagFl1;
83 packet.diagFl2 = diagFl2;
84 packet.diagFl3 = diagFl3;
85 packet.diagSh1 = diagSh1;
86 packet.diagSh2 = diagSh2;
87 packet.diagSh3 = diagSh3;
89 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIAGNOSTIC_LEN);
92 msg->msgid = MAVLINK_MSG_ID_DIAGNOSTIC;
93 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DIAGNOSTIC_MIN_LEN, MAVLINK_MSG_ID_DIAGNOSTIC_LEN, MAVLINK_MSG_ID_DIAGNOSTIC_CRC);
110static inline uint16_t mavlink_msg_diagnostic_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
111 mavlink_message_t* msg,
112 float diagFl1,
float diagFl2,
float diagFl3,int16_t diagSh1,int16_t diagSh2,int16_t diagSh3)
114#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
115 char buf[MAVLINK_MSG_ID_DIAGNOSTIC_LEN];
116 _mav_put_float(buf, 0, diagFl1);
117 _mav_put_float(buf, 4, diagFl2);
118 _mav_put_float(buf, 8, diagFl3);
119 _mav_put_int16_t(buf, 12, diagSh1);
120 _mav_put_int16_t(buf, 14, diagSh2);
121 _mav_put_int16_t(buf, 16, diagSh3);
123 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIAGNOSTIC_LEN);
125 mavlink_diagnostic_t packet;
126 packet.diagFl1 = diagFl1;
127 packet.diagFl2 = diagFl2;
128 packet.diagFl3 = diagFl3;
129 packet.diagSh1 = diagSh1;
130 packet.diagSh2 = diagSh2;
131 packet.diagSh3 = diagSh3;
133 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIAGNOSTIC_LEN);
136 msg->msgid = MAVLINK_MSG_ID_DIAGNOSTIC;
137 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DIAGNOSTIC_MIN_LEN, MAVLINK_MSG_ID_DIAGNOSTIC_LEN, MAVLINK_MSG_ID_DIAGNOSTIC_CRC);
148static inline uint16_t mavlink_msg_diagnostic_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_diagnostic_t* diagnostic)
150 return mavlink_msg_diagnostic_pack(system_id, component_id, msg, diagnostic->diagFl1, diagnostic->diagFl2, diagnostic->diagFl3, diagnostic->diagSh1, diagnostic->diagSh2, diagnostic->diagSh3);
162static inline uint16_t mavlink_msg_diagnostic_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_diagnostic_t* diagnostic)
164 return mavlink_msg_diagnostic_pack_chan(system_id, component_id, chan, msg, diagnostic->diagFl1, diagnostic->diagFl2, diagnostic->diagFl3, diagnostic->diagSh1, diagnostic->diagSh2, diagnostic->diagSh3);
178#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
180static inline void mavlink_msg_diagnostic_send(mavlink_channel_t chan,
float diagFl1,
float diagFl2,
float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3)
182#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
183 char buf[MAVLINK_MSG_ID_DIAGNOSTIC_LEN];
184 _mav_put_float(buf, 0, diagFl1);
185 _mav_put_float(buf, 4, diagFl2);
186 _mav_put_float(buf, 8, diagFl3);
187 _mav_put_int16_t(buf, 12, diagSh1);
188 _mav_put_int16_t(buf, 14, diagSh2);
189 _mav_put_int16_t(buf, 16, diagSh3);
191 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIAGNOSTIC, buf, MAVLINK_MSG_ID_DIAGNOSTIC_MIN_LEN, MAVLINK_MSG_ID_DIAGNOSTIC_LEN, MAVLINK_MSG_ID_DIAGNOSTIC_CRC);
193 mavlink_diagnostic_t packet;
194 packet.diagFl1 = diagFl1;
195 packet.diagFl2 = diagFl2;
196 packet.diagFl3 = diagFl3;
197 packet.diagSh1 = diagSh1;
198 packet.diagSh2 = diagSh2;
199 packet.diagSh3 = diagSh3;
201 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIAGNOSTIC, (
const char *)&packet, MAVLINK_MSG_ID_DIAGNOSTIC_MIN_LEN, MAVLINK_MSG_ID_DIAGNOSTIC_LEN, MAVLINK_MSG_ID_DIAGNOSTIC_CRC);
210static inline void mavlink_msg_diagnostic_send_struct(mavlink_channel_t chan,
const mavlink_diagnostic_t* diagnostic)
212#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
213 mavlink_msg_diagnostic_send(chan, diagnostic->diagFl1, diagnostic->diagFl2, diagnostic->diagFl3, diagnostic->diagSh1, diagnostic->diagSh2, diagnostic->diagSh3);
215 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIAGNOSTIC, (
const char *)diagnostic, MAVLINK_MSG_ID_DIAGNOSTIC_MIN_LEN, MAVLINK_MSG_ID_DIAGNOSTIC_LEN, MAVLINK_MSG_ID_DIAGNOSTIC_CRC);
219#if MAVLINK_MSG_ID_DIAGNOSTIC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
227static inline void mavlink_msg_diagnostic_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,
float diagFl1,
float diagFl2,
float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3)
229#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
230 char *buf = (
char *)msgbuf;
231 _mav_put_float(buf, 0, diagFl1);
232 _mav_put_float(buf, 4, diagFl2);
233 _mav_put_float(buf, 8, diagFl3);
234 _mav_put_int16_t(buf, 12, diagSh1);
235 _mav_put_int16_t(buf, 14, diagSh2);
236 _mav_put_int16_t(buf, 16, diagSh3);
238 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIAGNOSTIC, buf, MAVLINK_MSG_ID_DIAGNOSTIC_MIN_LEN, MAVLINK_MSG_ID_DIAGNOSTIC_LEN, MAVLINK_MSG_ID_DIAGNOSTIC_CRC);
240 mavlink_diagnostic_t *packet = (mavlink_diagnostic_t *)msgbuf;
241 packet->diagFl1 = diagFl1;
242 packet->diagFl2 = diagFl2;
243 packet->diagFl3 = diagFl3;
244 packet->diagSh1 = diagSh1;
245 packet->diagSh2 = diagSh2;
246 packet->diagSh3 = diagSh3;
248 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIAGNOSTIC, (
const char *)packet, MAVLINK_MSG_ID_DIAGNOSTIC_MIN_LEN, MAVLINK_MSG_ID_DIAGNOSTIC_LEN, MAVLINK_MSG_ID_DIAGNOSTIC_CRC);
263static inline float mavlink_msg_diagnostic_get_diagFl1(
const mavlink_message_t* msg)
265 return _MAV_RETURN_float(msg, 0);
273static inline float mavlink_msg_diagnostic_get_diagFl2(
const mavlink_message_t* msg)
275 return _MAV_RETURN_float(msg, 4);
283static inline float mavlink_msg_diagnostic_get_diagFl3(
const mavlink_message_t* msg)
285 return _MAV_RETURN_float(msg, 8);
293static inline int16_t mavlink_msg_diagnostic_get_diagSh1(
const mavlink_message_t* msg)
295 return _MAV_RETURN_int16_t(msg, 12);
303static inline int16_t mavlink_msg_diagnostic_get_diagSh2(
const mavlink_message_t* msg)
305 return _MAV_RETURN_int16_t(msg, 14);
313static inline int16_t mavlink_msg_diagnostic_get_diagSh3(
const mavlink_message_t* msg)
315 return _MAV_RETURN_int16_t(msg, 16);
324static inline void mavlink_msg_diagnostic_decode(
const mavlink_message_t* msg, mavlink_diagnostic_t* diagnostic)
326#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
327 diagnostic->diagFl1 = mavlink_msg_diagnostic_get_diagFl1(msg);
328 diagnostic->diagFl2 = mavlink_msg_diagnostic_get_diagFl2(msg);
329 diagnostic->diagFl3 = mavlink_msg_diagnostic_get_diagFl3(msg);
330 diagnostic->diagSh1 = mavlink_msg_diagnostic_get_diagSh1(msg);
331 diagnostic->diagSh2 = mavlink_msg_diagnostic_get_diagSh2(msg);
332 diagnostic->diagSh3 = mavlink_msg_diagnostic_get_diagSh3(msg);
334 uint8_t len = msg->len < MAVLINK_MSG_ID_DIAGNOSTIC_LEN? msg->len : MAVLINK_MSG_ID_DIAGNOSTIC_LEN;
335 memset(diagnostic, 0, MAVLINK_MSG_ID_DIAGNOSTIC_LEN);
336 memcpy(diagnostic, _MAV_PAYLOAD(msg), len);