4#define MAVLINK_MSG_ID_SENSOR_DIAG 196
7typedef struct __mavlink_sensor_diag_t {
12}) mavlink_sensor_diag_t;
14#define MAVLINK_MSG_ID_SENSOR_DIAG_LEN 11
15#define MAVLINK_MSG_ID_SENSOR_DIAG_MIN_LEN 11
16#define MAVLINK_MSG_ID_196_LEN 11
17#define MAVLINK_MSG_ID_196_MIN_LEN 11
19#define MAVLINK_MSG_ID_SENSOR_DIAG_CRC 129
20#define MAVLINK_MSG_ID_196_CRC 129
24#if MAVLINK_COMMAND_24BIT
25#define MAVLINK_MESSAGE_INFO_SENSOR_DIAG { \
29 { { "float1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sensor_diag_t, float1) }, \
30 { "float2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sensor_diag_t, float2) }, \
31 { "int1", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_sensor_diag_t, int1) }, \
32 { "char1", NULL, MAVLINK_TYPE_INT8_T, 0, 10, offsetof(mavlink_sensor_diag_t, char1) }, \
36#define MAVLINK_MESSAGE_INFO_SENSOR_DIAG { \
39 { { "float1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sensor_diag_t, float1) }, \
40 { "float2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sensor_diag_t, float2) }, \
41 { "int1", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_sensor_diag_t, int1) }, \
42 { "char1", NULL, MAVLINK_TYPE_INT8_T, 0, 10, offsetof(mavlink_sensor_diag_t, char1) }, \
59static inline uint16_t mavlink_msg_sensor_diag_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
60 float float1,
float float2, int16_t int1, int8_t char1)
62#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
63 char buf[MAVLINK_MSG_ID_SENSOR_DIAG_LEN];
64 _mav_put_float(buf, 0, float1);
65 _mav_put_float(buf, 4, float2);
66 _mav_put_int16_t(buf, 8, int1);
67 _mav_put_int8_t(buf, 10, char1);
69 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_DIAG_LEN);
71 mavlink_sensor_diag_t packet;
72 packet.float1 = float1;
73 packet.float2 = float2;
77 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_DIAG_LEN);
80 msg->msgid = MAVLINK_MSG_ID_SENSOR_DIAG;
81 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SENSOR_DIAG_MIN_LEN, MAVLINK_MSG_ID_SENSOR_DIAG_LEN, MAVLINK_MSG_ID_SENSOR_DIAG_CRC);
96static inline uint16_t mavlink_msg_sensor_diag_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
97 mavlink_message_t* msg,
98 float float1,
float float2,int16_t int1,int8_t char1)
100#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
101 char buf[MAVLINK_MSG_ID_SENSOR_DIAG_LEN];
102 _mav_put_float(buf, 0, float1);
103 _mav_put_float(buf, 4, float2);
104 _mav_put_int16_t(buf, 8, int1);
105 _mav_put_int8_t(buf, 10, char1);
107 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_DIAG_LEN);
109 mavlink_sensor_diag_t packet;
110 packet.float1 = float1;
111 packet.float2 = float2;
113 packet.char1 = char1;
115 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_DIAG_LEN);
118 msg->msgid = MAVLINK_MSG_ID_SENSOR_DIAG;
119 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SENSOR_DIAG_MIN_LEN, MAVLINK_MSG_ID_SENSOR_DIAG_LEN, MAVLINK_MSG_ID_SENSOR_DIAG_CRC);
130static inline uint16_t mavlink_msg_sensor_diag_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_sensor_diag_t* sensor_diag)
132 return mavlink_msg_sensor_diag_pack(system_id, component_id, msg, sensor_diag->float1, sensor_diag->float2, sensor_diag->int1, sensor_diag->char1);
144static inline uint16_t mavlink_msg_sensor_diag_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_sensor_diag_t* sensor_diag)
146 return mavlink_msg_sensor_diag_pack_chan(system_id, component_id, chan, msg, sensor_diag->float1, sensor_diag->float2, sensor_diag->int1, sensor_diag->char1);
158#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
160static inline void mavlink_msg_sensor_diag_send(mavlink_channel_t chan,
float float1,
float float2, int16_t int1, int8_t char1)
162#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
163 char buf[MAVLINK_MSG_ID_SENSOR_DIAG_LEN];
164 _mav_put_float(buf, 0, float1);
165 _mav_put_float(buf, 4, float2);
166 _mav_put_int16_t(buf, 8, int1);
167 _mav_put_int8_t(buf, 10, char1);
169 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_DIAG, buf, MAVLINK_MSG_ID_SENSOR_DIAG_MIN_LEN, MAVLINK_MSG_ID_SENSOR_DIAG_LEN, MAVLINK_MSG_ID_SENSOR_DIAG_CRC);
171 mavlink_sensor_diag_t packet;
172 packet.float1 = float1;
173 packet.float2 = float2;
175 packet.char1 = char1;
177 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_DIAG, (
const char *)&packet, MAVLINK_MSG_ID_SENSOR_DIAG_MIN_LEN, MAVLINK_MSG_ID_SENSOR_DIAG_LEN, MAVLINK_MSG_ID_SENSOR_DIAG_CRC);
186static inline void mavlink_msg_sensor_diag_send_struct(mavlink_channel_t chan,
const mavlink_sensor_diag_t* sensor_diag)
188#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
189 mavlink_msg_sensor_diag_send(chan, sensor_diag->float1, sensor_diag->float2, sensor_diag->int1, sensor_diag->char1);
191 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_DIAG, (
const char *)sensor_diag, MAVLINK_MSG_ID_SENSOR_DIAG_MIN_LEN, MAVLINK_MSG_ID_SENSOR_DIAG_LEN, MAVLINK_MSG_ID_SENSOR_DIAG_CRC);
195#if MAVLINK_MSG_ID_SENSOR_DIAG_LEN <= MAVLINK_MAX_PAYLOAD_LEN
203static inline void mavlink_msg_sensor_diag_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,
float float1,
float float2, int16_t int1, int8_t char1)
205#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
206 char *buf = (
char *)msgbuf;
207 _mav_put_float(buf, 0, float1);
208 _mav_put_float(buf, 4, float2);
209 _mav_put_int16_t(buf, 8, int1);
210 _mav_put_int8_t(buf, 10, char1);
212 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_DIAG, buf, MAVLINK_MSG_ID_SENSOR_DIAG_MIN_LEN, MAVLINK_MSG_ID_SENSOR_DIAG_LEN, MAVLINK_MSG_ID_SENSOR_DIAG_CRC);
214 mavlink_sensor_diag_t *packet = (mavlink_sensor_diag_t *)msgbuf;
215 packet->float1 = float1;
216 packet->float2 = float2;
218 packet->char1 = char1;
220 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_DIAG, (
const char *)packet, MAVLINK_MSG_ID_SENSOR_DIAG_MIN_LEN, MAVLINK_MSG_ID_SENSOR_DIAG_LEN, MAVLINK_MSG_ID_SENSOR_DIAG_CRC);
235static inline float mavlink_msg_sensor_diag_get_float1(
const mavlink_message_t* msg)
237 return _MAV_RETURN_float(msg, 0);
245static inline float mavlink_msg_sensor_diag_get_float2(
const mavlink_message_t* msg)
247 return _MAV_RETURN_float(msg, 4);
255static inline int16_t mavlink_msg_sensor_diag_get_int1(
const mavlink_message_t* msg)
257 return _MAV_RETURN_int16_t(msg, 8);
265static inline int8_t mavlink_msg_sensor_diag_get_char1(
const mavlink_message_t* msg)
267 return _MAV_RETURN_int8_t(msg, 10);
276static inline void mavlink_msg_sensor_diag_decode(
const mavlink_message_t* msg, mavlink_sensor_diag_t* sensor_diag)
278#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
279 sensor_diag->float1 = mavlink_msg_sensor_diag_get_float1(msg);
280 sensor_diag->float2 = mavlink_msg_sensor_diag_get_float2(msg);
281 sensor_diag->int1 = mavlink_msg_sensor_diag_get_int1(msg);
282 sensor_diag->char1 = mavlink_msg_sensor_diag_get_char1(msg);
284 uint8_t len = msg->len < MAVLINK_MSG_ID_SENSOR_DIAG_LEN? msg->len : MAVLINK_MSG_ID_SENSOR_DIAG_LEN;
285 memset(sensor_diag, 0, MAVLINK_MSG_ID_SENSOR_DIAG_LEN);
286 memcpy(sensor_diag, _MAV_PAYLOAD(msg), len);