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
51 char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN];
52 _mav_put_uint64_t(buf, 0, time_usec);
53 _mav_put_int16_t(buf, 8, press_abs);
54 _mav_put_int16_t(buf, 10, press_diff1);
55 _mav_put_int16_t(buf, 12, press_diff2);
56 _mav_put_int16_t(buf, 14, temperature);
58 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
67 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
70 msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
72 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
74 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
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
96 char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN];
97 _mav_put_uint64_t(buf, 0, time_usec);
98 _mav_put_int16_t(buf, 8, press_abs);
99 _mav_put_int16_t(buf, 10, press_diff1);
100 _mav_put_int16_t(buf, 12, press_diff2);
101 _mav_put_int16_t(buf, 14, temperature);
103 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
112 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
115 msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
116 #if MAVLINK_CRC_EXTRA
117 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
119 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
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
165 char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN];
166 _mav_put_uint64_t(buf, 0, time_usec);
167 _mav_put_int16_t(buf, 8, press_abs);
168 _mav_put_int16_t(buf, 10, press_diff1);
169 _mav_put_int16_t(buf, 12, press_diff2);
170 _mav_put_int16_t(buf, 14, temperature);
172 #if MAVLINK_CRC_EXTRA
173 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
175 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
185 #if MAVLINK_CRC_EXTRA
186 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (
const char *)&packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
188 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (
const char *)&packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
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;
205 _mav_put_uint64_t(buf, 0, time_usec);
206 _mav_put_int16_t(buf, 8, press_abs);
207 _mav_put_int16_t(buf, 10, press_diff1);
208 _mav_put_int16_t(buf, 12, press_diff2);
209 _mav_put_int16_t(buf, 14, temperature);
211 #if MAVLINK_CRC_EXTRA
212 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
214 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
224 #if MAVLINK_CRC_EXTRA
225 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (
const char *)packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
227 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (
const char *)packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
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);
303 memcpy(raw_pressure, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
int16_t press_diff1
Differential pressure 1 (raw)
Definition: mavlink_msg_raw_pressure.h:9
Definition: mavlink_msg_raw_pressure.h:5
int16_t press_abs
Absolute pressure (raw)
Definition: mavlink_msg_raw_pressure.h:8
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
int16_t press_diff2
Differential pressure 2 (raw)
Definition: mavlink_msg_raw_pressure.h:10