3 #define MAVLINK_MSG_ID_SENSOR_DIAG 196
13 #define MAVLINK_MSG_ID_SENSOR_DIAG_LEN 11
14 #define MAVLINK_MSG_ID_196_LEN 11
16 #define MAVLINK_MSG_ID_SENSOR_DIAG_CRC 129
17 #define MAVLINK_MSG_ID_196_CRC 129
21 #define MAVLINK_MESSAGE_INFO_SENSOR_DIAG { \
24 { { "float1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sensor_diag_t, float1) }, \
25 { "float2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sensor_diag_t, float2) }, \
26 { "int1", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_sensor_diag_t, int1) }, \
27 { "char1", NULL, MAVLINK_TYPE_INT8_T, 0, 10, offsetof(mavlink_sensor_diag_t, char1) }, \
44 static inline uint16_t mavlink_msg_sensor_diag_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
45 float float1,
float float2, int16_t int1, int8_t char1)
47 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
85 static inline uint16_t mavlink_msg_sensor_diag_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
86 mavlink_message_t* msg,
87 float float1,
float float2,int16_t int1,int8_t char1)
89 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
102 packet.
char1 = char1;
108 #if MAVLINK_CRC_EXTRA
123 static 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)
125 return mavlink_msg_sensor_diag_pack(system_id, component_id, msg, sensor_diag->
float1, sensor_diag->
float2, sensor_diag->
int1, sensor_diag->
char1);
137 static 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)
139 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);
151 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
153 static inline void mavlink_msg_sensor_diag_send(
mavlink_channel_t chan,
float float1,
float float2, int16_t int1, int8_t char1)
155 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
162 #if MAVLINK_CRC_EXTRA
172 packet.
char1 = char1;
174 #if MAVLINK_CRC_EXTRA
182 #if MAVLINK_MSG_ID_SENSOR_DIAG_LEN <= MAVLINK_MAX_PAYLOAD_LEN
190 static 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)
192 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
193 char *buf = (
char *)msgbuf;
199 #if MAVLINK_CRC_EXTRA
209 packet->
char1 = char1;
211 #if MAVLINK_CRC_EXTRA
230 static inline float mavlink_msg_sensor_diag_get_float1(
const mavlink_message_t* msg)
232 return _MAV_RETURN_float(msg, 0);
240 static inline float mavlink_msg_sensor_diag_get_float2(
const mavlink_message_t* msg)
242 return _MAV_RETURN_float(msg, 4);
250 static inline int16_t mavlink_msg_sensor_diag_get_int1(
const mavlink_message_t* msg)
252 return _MAV_RETURN_int16_t(msg, 8);
260 static inline int8_t mavlink_msg_sensor_diag_get_char1(
const mavlink_message_t* msg)
271 static inline void mavlink_msg_sensor_diag_decode(
const mavlink_message_t* msg,
mavlink_sensor_diag_t* sensor_diag)
273 #if MAVLINK_NEED_BYTE_SWAP
274 sensor_diag->
float1 = mavlink_msg_sensor_diag_get_float1(msg);
275 sensor_diag->
float2 = mavlink_msg_sensor_diag_get_float2(msg);
276 sensor_diag->
int1 = mavlink_msg_sensor_diag_get_int1(msg);
277 sensor_diag->
char1 = mavlink_msg_sensor_diag_get_char1(msg);
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
Definition: mavlink_msg_sensor_diag.h:5
int16_t int1
Int 16 field 1.
Definition: mavlink_msg_sensor_diag.h:9
#define MAVLINK_MSG_ID_SENSOR_DIAG
Definition: mavlink_msg_sensor_diag.h:3
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
float float2
Float field 2.
Definition: mavlink_msg_sensor_diag.h:8
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
#define _MAV_RETURN_int8_t(msg, wire_offset)
Definition: protocol.h:237
mavlink_channel_t
Definition: mavlink_types.h:178
int8_t char1
Int 8 field 1.
Definition: mavlink_msg_sensor_diag.h:10
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
struct __mavlink_sensor_diag_t mavlink_sensor_diag_t
#define _mav_put_int8_t(buf, wire_offset, b)
Definition: protocol.h:135
float float1
Float field 1.
Definition: mavlink_msg_sensor_diag.h:7
#define MAVLINK_MSG_ID_SENSOR_DIAG_LEN
Definition: mavlink_msg_sensor_diag.h:13
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 _mav_put_int16_t(buf, wire_offset, b)
Definition: protocol.h:140
#define MAVLINK_MSG_ID_SENSOR_DIAG_CRC
Definition: mavlink_msg_sensor_diag.h:16