2 // MESSAGE RAW_PRESSURE PACKING
4 #define MAVLINK_MSG_ID_RAW_PRESSURE 28
7 typedef struct __mavlink_raw_pressure_t
{
8 uint64_t time_usec
; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
9 int16_t press_abs
; /*< Absolute pressure (raw)*/
10 int16_t press_diff1
; /*< Differential pressure 1 (raw, 0 if nonexistent)*/
11 int16_t press_diff2
; /*< Differential pressure 2 (raw, 0 if nonexistent)*/
12 int16_t temperature
; /*< Raw Temperature measurement (raw)*/
13 } mavlink_raw_pressure_t
;
15 #define MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16
16 #define MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN 16
17 #define MAVLINK_MSG_ID_28_LEN 16
18 #define MAVLINK_MSG_ID_28_MIN_LEN 16
20 #define MAVLINK_MSG_ID_RAW_PRESSURE_CRC 67
21 #define MAVLINK_MSG_ID_28_CRC 67
25 #if MAVLINK_COMMAND_24BIT
26 #define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \
30 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, time_usec) }, \
31 { "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \
32 { "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \
33 { "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \
34 { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \
38 #define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \
41 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, time_usec) }, \
42 { "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \
43 { "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \
44 { "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \
45 { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \
51 * @brief Pack a raw_pressure message
52 * @param system_id ID of this system
53 * @param component_id ID of this component (e.g. 200 for IMU)
54 * @param msg The MAVLink message to compress the data into
56 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
57 * @param press_abs Absolute pressure (raw)
58 * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistent)
59 * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistent)
60 * @param temperature Raw Temperature measurement (raw)
61 * @return length of the message in bytes (excluding serial stream start sign)
63 static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
64 uint64_t time_usec
, int16_t press_abs
, int16_t press_diff1
, int16_t press_diff2
, int16_t temperature
)
66 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
67 char buf
[MAVLINK_MSG_ID_RAW_PRESSURE_LEN
];
68 _mav_put_uint64_t(buf
, 0, time_usec
);
69 _mav_put_int16_t(buf
, 8, press_abs
);
70 _mav_put_int16_t(buf
, 10, press_diff1
);
71 _mav_put_int16_t(buf
, 12, press_diff2
);
72 _mav_put_int16_t(buf
, 14, temperature
);
74 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_RAW_PRESSURE_LEN
);
76 mavlink_raw_pressure_t packet
;
77 packet
.time_usec
= time_usec
;
78 packet
.press_abs
= press_abs
;
79 packet
.press_diff1
= press_diff1
;
80 packet
.press_diff2
= press_diff2
;
81 packet
.temperature
= temperature
;
83 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_RAW_PRESSURE_LEN
);
86 msg
->msgid
= MAVLINK_MSG_ID_RAW_PRESSURE
;
87 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN
, MAVLINK_MSG_ID_RAW_PRESSURE_LEN
, MAVLINK_MSG_ID_RAW_PRESSURE_CRC
);
91 * @brief Pack a raw_pressure message on a channel
92 * @param system_id ID of this system
93 * @param component_id ID of this component (e.g. 200 for IMU)
94 * @param chan The MAVLink channel this message will be sent over
95 * @param msg The MAVLink message to compress the data into
96 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
97 * @param press_abs Absolute pressure (raw)
98 * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistent)
99 * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistent)
100 * @param temperature Raw Temperature measurement (raw)
101 * @return length of the message in bytes (excluding serial stream start sign)
103 static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
104 mavlink_message_t
* msg
,
105 uint64_t time_usec
,int16_t press_abs
,int16_t press_diff1
,int16_t press_diff2
,int16_t temperature
)
107 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
108 char buf
[MAVLINK_MSG_ID_RAW_PRESSURE_LEN
];
109 _mav_put_uint64_t(buf
, 0, time_usec
);
110 _mav_put_int16_t(buf
, 8, press_abs
);
111 _mav_put_int16_t(buf
, 10, press_diff1
);
112 _mav_put_int16_t(buf
, 12, press_diff2
);
113 _mav_put_int16_t(buf
, 14, temperature
);
115 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_RAW_PRESSURE_LEN
);
117 mavlink_raw_pressure_t packet
;
118 packet
.time_usec
= time_usec
;
119 packet
.press_abs
= press_abs
;
120 packet
.press_diff1
= press_diff1
;
121 packet
.press_diff2
= press_diff2
;
122 packet
.temperature
= temperature
;
124 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_RAW_PRESSURE_LEN
);
127 msg
->msgid
= MAVLINK_MSG_ID_RAW_PRESSURE
;
128 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN
, MAVLINK_MSG_ID_RAW_PRESSURE_LEN
, MAVLINK_MSG_ID_RAW_PRESSURE_CRC
);
132 * @brief Encode a raw_pressure struct
134 * @param system_id ID of this system
135 * @param component_id ID of this component (e.g. 200 for IMU)
136 * @param msg The MAVLink message to compress the data into
137 * @param raw_pressure C-struct to read the message contents from
139 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
)
141 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
);
145 * @brief Encode a raw_pressure struct on a channel
147 * @param system_id ID of this system
148 * @param component_id ID of this component (e.g. 200 for IMU)
149 * @param chan The MAVLink channel this message will be sent over
150 * @param msg The MAVLink message to compress the data into
151 * @param raw_pressure C-struct to read the message contents from
153 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
)
155 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
);
159 * @brief Send a raw_pressure message
160 * @param chan MAVLink channel to send the message
162 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
163 * @param press_abs Absolute pressure (raw)
164 * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistent)
165 * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistent)
166 * @param temperature Raw Temperature measurement (raw)
168 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
170 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
)
172 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
173 char buf
[MAVLINK_MSG_ID_RAW_PRESSURE_LEN
];
174 _mav_put_uint64_t(buf
, 0, time_usec
);
175 _mav_put_int16_t(buf
, 8, press_abs
);
176 _mav_put_int16_t(buf
, 10, press_diff1
);
177 _mav_put_int16_t(buf
, 12, press_diff2
);
178 _mav_put_int16_t(buf
, 14, temperature
);
180 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_RAW_PRESSURE
, buf
, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN
, MAVLINK_MSG_ID_RAW_PRESSURE_LEN
, MAVLINK_MSG_ID_RAW_PRESSURE_CRC
);
182 mavlink_raw_pressure_t packet
;
183 packet
.time_usec
= time_usec
;
184 packet
.press_abs
= press_abs
;
185 packet
.press_diff1
= press_diff1
;
186 packet
.press_diff2
= press_diff2
;
187 packet
.temperature
= temperature
;
189 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_RAW_PRESSURE
, (const char *)&packet
, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN
, MAVLINK_MSG_ID_RAW_PRESSURE_LEN
, MAVLINK_MSG_ID_RAW_PRESSURE_CRC
);
194 * @brief Send a raw_pressure message
195 * @param chan MAVLink channel to send the message
196 * @param struct The MAVLink struct to serialize
198 static inline void mavlink_msg_raw_pressure_send_struct(mavlink_channel_t chan
, const mavlink_raw_pressure_t
* raw_pressure
)
200 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
201 mavlink_msg_raw_pressure_send(chan
, raw_pressure
->time_usec
, raw_pressure
->press_abs
, raw_pressure
->press_diff1
, raw_pressure
->press_diff2
, raw_pressure
->temperature
);
203 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_RAW_PRESSURE
, (const char *)raw_pressure
, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN
, MAVLINK_MSG_ID_RAW_PRESSURE_LEN
, MAVLINK_MSG_ID_RAW_PRESSURE_CRC
);
207 #if MAVLINK_MSG_ID_RAW_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
209 This varient of _send() can be used to save stack space by re-using
210 memory from the receive buffer. The caller provides a
211 mavlink_message_t which is the size of a full mavlink message. This
212 is usually the receive buffer for the channel, and allows a reply to an
213 incoming message with minimum stack space usage.
215 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
)
217 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
218 char *buf
= (char *)msgbuf
;
219 _mav_put_uint64_t(buf
, 0, time_usec
);
220 _mav_put_int16_t(buf
, 8, press_abs
);
221 _mav_put_int16_t(buf
, 10, press_diff1
);
222 _mav_put_int16_t(buf
, 12, press_diff2
);
223 _mav_put_int16_t(buf
, 14, temperature
);
225 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_RAW_PRESSURE
, buf
, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN
, MAVLINK_MSG_ID_RAW_PRESSURE_LEN
, MAVLINK_MSG_ID_RAW_PRESSURE_CRC
);
227 mavlink_raw_pressure_t
*packet
= (mavlink_raw_pressure_t
*)msgbuf
;
228 packet
->time_usec
= time_usec
;
229 packet
->press_abs
= press_abs
;
230 packet
->press_diff1
= press_diff1
;
231 packet
->press_diff2
= press_diff2
;
232 packet
->temperature
= temperature
;
234 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_RAW_PRESSURE
, (const char *)packet
, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN
, MAVLINK_MSG_ID_RAW_PRESSURE_LEN
, MAVLINK_MSG_ID_RAW_PRESSURE_CRC
);
241 // MESSAGE RAW_PRESSURE UNPACKING
245 * @brief Get field time_usec from raw_pressure message
247 * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
249 static inline uint64_t mavlink_msg_raw_pressure_get_time_usec(const mavlink_message_t
* msg
)
251 return _MAV_RETURN_uint64_t(msg
, 0);
255 * @brief Get field press_abs from raw_pressure message
257 * @return Absolute pressure (raw)
259 static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t
* msg
)
261 return _MAV_RETURN_int16_t(msg
, 8);
265 * @brief Get field press_diff1 from raw_pressure message
267 * @return Differential pressure 1 (raw, 0 if nonexistent)
269 static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t
* msg
)
271 return _MAV_RETURN_int16_t(msg
, 10);
275 * @brief Get field press_diff2 from raw_pressure message
277 * @return Differential pressure 2 (raw, 0 if nonexistent)
279 static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t
* msg
)
281 return _MAV_RETURN_int16_t(msg
, 12);
285 * @brief Get field temperature from raw_pressure message
287 * @return Raw Temperature measurement (raw)
289 static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t
* msg
)
291 return _MAV_RETURN_int16_t(msg
, 14);
295 * @brief Decode a raw_pressure message into a struct
297 * @param msg The message to decode
298 * @param raw_pressure C-struct to decode the message contents into
300 static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t
* msg
, mavlink_raw_pressure_t
* raw_pressure
)
302 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
303 raw_pressure
->time_usec
= mavlink_msg_raw_pressure_get_time_usec(msg
);
304 raw_pressure
->press_abs
= mavlink_msg_raw_pressure_get_press_abs(msg
);
305 raw_pressure
->press_diff1
= mavlink_msg_raw_pressure_get_press_diff1(msg
);
306 raw_pressure
->press_diff2
= mavlink_msg_raw_pressure_get_press_diff2(msg
);
307 raw_pressure
->temperature
= mavlink_msg_raw_pressure_get_temperature(msg
);
309 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_RAW_PRESSURE_LEN
? msg
->len
: MAVLINK_MSG_ID_RAW_PRESSURE_LEN
;
310 memset(raw_pressure
, 0, MAVLINK_MSG_ID_RAW_PRESSURE_LEN
);
311 memcpy(raw_pressure
, _MAV_PAYLOAD(msg
), len
);