3 #define MAVLINK_MSG_ID_RAW_PRESSURE 28
14 #define MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16
15 #define MAVLINK_MSG_ID_28_LEN 16
17 #define MAVLINK_MSG_ID_RAW_PRESSURE_CRC 67
18 #define MAVLINK_MSG_ID_28_CRC 67
22 #define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \
25 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, time_usec) }, \
26 { "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \
27 { "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \
28 { "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \
29 { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \
47 static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
48 uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
50 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
91 static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
92 mavlink_message_t* msg,
93 uint64_t time_usec,int16_t press_abs,int16_t press_diff1,int16_t press_diff2,int16_t temperature)
95 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
116 #if MAVLINK_CRC_EXTRA
131 static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_raw_pressure_t* raw_pressure)
145 static inline uint16_t mavlink_msg_raw_pressure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_raw_pressure_t* raw_pressure)
160 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
162 static inline void mavlink_msg_raw_pressure_send(
mavlink_channel_t chan, uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
164 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
172 #if MAVLINK_CRC_EXTRA
185 #if MAVLINK_CRC_EXTRA
193 #if MAVLINK_MSG_ID_RAW_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
201 static inline void mavlink_msg_raw_pressure_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
203 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
204 char *buf = (
char *)msgbuf;
211 #if MAVLINK_CRC_EXTRA
224 #if MAVLINK_CRC_EXTRA
243 static inline uint64_t mavlink_msg_raw_pressure_get_time_usec(
const mavlink_message_t* msg)
245 return _MAV_RETURN_uint64_t(msg, 0);
253 static inline int16_t mavlink_msg_raw_pressure_get_press_abs(
const mavlink_message_t* msg)
255 return _MAV_RETURN_int16_t(msg, 8);
263 static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(
const mavlink_message_t* msg)
265 return _MAV_RETURN_int16_t(msg, 10);
273 static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(
const mavlink_message_t* msg)
275 return _MAV_RETURN_int16_t(msg, 12);
283 static inline int16_t mavlink_msg_raw_pressure_get_temperature(
const mavlink_message_t* msg)
285 return _MAV_RETURN_int16_t(msg, 14);
294 static inline void mavlink_msg_raw_pressure_decode(
const mavlink_message_t* msg,
mavlink_raw_pressure_t* raw_pressure)
296 #if MAVLINK_NEED_BYTE_SWAP
297 raw_pressure->
time_usec = mavlink_msg_raw_pressure_get_time_usec(msg);
298 raw_pressure->
press_abs = mavlink_msg_raw_pressure_get_press_abs(msg);
299 raw_pressure->
press_diff1 = mavlink_msg_raw_pressure_get_press_diff1(msg);
300 raw_pressure->
press_diff2 = mavlink_msg_raw_pressure_get_press_diff2(msg);
301 raw_pressure->
temperature = mavlink_msg_raw_pressure_get_temperature(msg);
struct __mavlink_raw_pressure_t mavlink_raw_pressure_t
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
#define _mav_put_uint64_t(buf, wire_offset, b)
Definition: protocol.h:143
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
#define MAVLINK_MSG_ID_RAW_PRESSURE_LEN
Definition: mavlink_msg_raw_pressure.h:14
mavlink_channel_t
Definition: mavlink_types.h:178
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
int16_t press_diff1
Differential pressure 1 (raw)
Definition: mavlink_msg_raw_pressure.h:9
#define MAVLINK_MSG_ID_RAW_PRESSURE
Definition: mavlink_msg_raw_pressure.h:3
Definition: mavlink_msg_raw_pressure.h:5
int16_t press_abs
Absolute pressure (raw)
Definition: mavlink_msg_raw_pressure.h:8
#define MAVLINK_MSG_ID_RAW_PRESSURE_CRC
Definition: mavlink_msg_raw_pressure.h:17
int16_t temperature
Raw Temperature measurement (raw)
Definition: mavlink_msg_raw_pressure.h:11
uint64_t time_usec
Timestamp (microseconds since UNIX epoch or microseconds since system boot)
Definition: mavlink_msg_raw_pressure.h:7
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
int16_t press_diff2
Differential pressure 2 (raw)
Definition: mavlink_msg_raw_pressure.h:10