1 // MESSAGE RAW_PRESSURE PACKING
3 #define MAVLINK_MSG_ID_RAW_PRESSURE 28
5 typedef struct __mavlink_raw_pressure_t
7 uint64_t time_usec
; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
8 int16_t press_abs
; ///< Absolute pressure (raw)
9 int16_t press_diff1
; ///< Differential pressure 1 (raw)
10 int16_t press_diff2
; ///< Differential pressure 2 (raw)
11 int16_t temperature
; ///< Raw Temperature measurement (raw)
12 } mavlink_raw_pressure_t
;
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) }, \
35 * @brief Pack a raw_pressure message
36 * @param system_id ID of this system
37 * @param component_id ID of this component (e.g. 200 for IMU)
38 * @param msg The MAVLink message to compress the data into
40 * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
41 * @param press_abs Absolute pressure (raw)
42 * @param press_diff1 Differential pressure 1 (raw)
43 * @param press_diff2 Differential pressure 2 (raw)
44 * @param temperature Raw Temperature measurement (raw)
45 * @return length of the message in bytes (excluding serial stream start sign)
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
);
60 mavlink_raw_pressure_t packet
;
61 packet
.time_usec
= time_usec
;
62 packet
.press_abs
= press_abs
;
63 packet
.press_diff1
= press_diff1
;
64 packet
.press_diff2
= press_diff2
;
65 packet
.temperature
= temperature
;
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
);
79 * @brief Pack a raw_pressure message on a channel
80 * @param system_id ID of this system
81 * @param component_id ID of this component (e.g. 200 for IMU)
82 * @param chan The MAVLink channel this message will be sent over
83 * @param msg The MAVLink message to compress the data into
84 * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
85 * @param press_abs Absolute pressure (raw)
86 * @param press_diff1 Differential pressure 1 (raw)
87 * @param press_diff2 Differential pressure 2 (raw)
88 * @param temperature Raw Temperature measurement (raw)
89 * @return length of the message in bytes (excluding serial stream start sign)
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
);
105 mavlink_raw_pressure_t packet
;
106 packet
.time_usec
= time_usec
;
107 packet
.press_abs
= press_abs
;
108 packet
.press_diff1
= press_diff1
;
109 packet
.press_diff2
= press_diff2
;
110 packet
.temperature
= temperature
;
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
);
124 * @brief Encode a raw_pressure struct
126 * @param system_id ID of this system
127 * @param component_id ID of this component (e.g. 200 for IMU)
128 * @param msg The MAVLink message to compress the data into
129 * @param raw_pressure C-struct to read the message contents from
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
)
133 return mavlink_msg_raw_pressure_pack(system_id
, component_id
, msg
, raw_pressure
->time_usec
, raw_pressure
->press_abs
, raw_pressure
->press_diff1
, raw_pressure
->press_diff2
, raw_pressure
->temperature
);
137 * @brief Encode a raw_pressure struct on a channel
139 * @param system_id ID of this system
140 * @param component_id ID of this component (e.g. 200 for IMU)
141 * @param chan The MAVLink channel this message will be sent over
142 * @param msg The MAVLink message to compress the data into
143 * @param raw_pressure C-struct to read the message contents from
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
)
147 return mavlink_msg_raw_pressure_pack_chan(system_id
, component_id
, chan
, msg
, raw_pressure
->time_usec
, raw_pressure
->press_abs
, raw_pressure
->press_diff1
, raw_pressure
->press_diff2
, raw_pressure
->temperature
);
151 * @brief Send a raw_pressure message
152 * @param chan MAVLink channel to send the message
154 * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
155 * @param press_abs Absolute pressure (raw)
156 * @param press_diff1 Differential pressure 1 (raw)
157 * @param press_diff2 Differential pressure 2 (raw)
158 * @param temperature Raw Temperature measurement (raw)
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
);
178 mavlink_raw_pressure_t packet
;
179 packet
.time_usec
= time_usec
;
180 packet
.press_abs
= press_abs
;
181 packet
.press_diff1
= press_diff1
;
182 packet
.press_diff2
= press_diff2
;
183 packet
.temperature
= temperature
;
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
195 This varient of _send() can be used to save stack space by re-using
196 memory from the receive buffer. The caller provides a
197 mavlink_message_t which is the size of a full mavlink message. This
198 is usually the receive buffer for the channel, and allows a reply to an
199 incoming message with minimum stack space usage.
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
);
217 mavlink_raw_pressure_t
*packet
= (mavlink_raw_pressure_t
*)msgbuf
;
218 packet
->time_usec
= time_usec
;
219 packet
->press_abs
= press_abs
;
220 packet
->press_diff1
= press_diff1
;
221 packet
->press_diff2
= press_diff2
;
222 packet
->temperature
= temperature
;
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
);
235 // MESSAGE RAW_PRESSURE UNPACKING
239 * @brief Get field time_usec from raw_pressure message
241 * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
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);
249 * @brief Get field press_abs from raw_pressure message
251 * @return Absolute pressure (raw)
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);
259 * @brief Get field press_diff1 from raw_pressure message
261 * @return Differential pressure 1 (raw)
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);
269 * @brief Get field press_diff2 from raw_pressure message
271 * @return Differential pressure 2 (raw)
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);
279 * @brief Get field temperature from raw_pressure message
281 * @return Raw Temperature measurement (raw)
283 static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t
* msg
)
285 return _MAV_RETURN_int16_t(msg
, 14);
289 * @brief Decode a raw_pressure message into a struct
291 * @param msg The message to decode
292 * @param raw_pressure C-struct to decode the message contents into
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
);