1 // MESSAGE RAW_PRESSURE PACKING
3 #define MAVLINK_MSG_ID_RAW_PRESSURE 28
5 typedef struct __mavlink_raw_pressure_t
{
6 uint64_t time_usec
; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
7 int16_t press_abs
; ///< Absolute pressure (raw)
8 int16_t press_diff1
; ///< Differential pressure 1 (raw)
9 int16_t press_diff2
; ///< Differential pressure 2 (raw)
10 int16_t temperature
; ///< Raw Temperature measurement (raw)
11 } mavlink_raw_pressure_t
;
13 #define MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16
14 #define MAVLINK_MSG_ID_28_LEN 16
17 #define MAVLINK_MESSAGE_INFO_RAW_PRESSURE \
22 { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, time_usec) }, \
23 { "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \
24 { "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \
25 { "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \
26 { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \
32 * @brief Pack a raw_pressure message
33 * @param system_id ID of this system
34 * @param component_id ID of this component (e.g. 200 for IMU)
35 * @param msg The MAVLink message to compress the data into
37 * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
38 * @param press_abs Absolute pressure (raw)
39 * @param press_diff1 Differential pressure 1 (raw)
40 * @param press_diff2 Differential pressure 2 (raw)
41 * @param temperature Raw Temperature measurement (raw)
42 * @return length of the message in bytes (excluding serial stream start sign)
44 static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
*msg
,
45 uint64_t time_usec
, int16_t press_abs
, int16_t press_diff1
, int16_t press_diff2
, int16_t temperature
)
47 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
49 _mav_put_uint64_t(buf
, 0, time_usec
);
50 _mav_put_int16_t(buf
, 8, press_abs
);
51 _mav_put_int16_t(buf
, 10, press_diff1
);
52 _mav_put_int16_t(buf
, 12, press_diff2
);
53 _mav_put_int16_t(buf
, 14, temperature
);
55 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 16);
57 mavlink_raw_pressure_t packet
;
58 packet
.time_usec
= time_usec
;
59 packet
.press_abs
= press_abs
;
60 packet
.press_diff1
= press_diff1
;
61 packet
.press_diff2
= press_diff2
;
62 packet
.temperature
= temperature
;
64 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 16);
67 msg
->msgid
= MAVLINK_MSG_ID_RAW_PRESSURE
;
68 return mavlink_finalize_message(msg
, system_id
, component_id
, 16, 67);
72 * @brief Pack a raw_pressure message on a channel
73 * @param system_id ID of this system
74 * @param component_id ID of this component (e.g. 200 for IMU)
75 * @param chan The MAVLink channel this message was sent over
76 * @param msg The MAVLink message to compress the data into
77 * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
78 * @param press_abs Absolute pressure (raw)
79 * @param press_diff1 Differential pressure 1 (raw)
80 * @param press_diff2 Differential pressure 2 (raw)
81 * @param temperature Raw Temperature measurement (raw)
82 * @return length of the message in bytes (excluding serial stream start sign)
84 static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
85 mavlink_message_t
*msg
,
86 uint64_t time_usec
, int16_t press_abs
, int16_t press_diff1
, int16_t press_diff2
, int16_t temperature
)
88 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
90 _mav_put_uint64_t(buf
, 0, time_usec
);
91 _mav_put_int16_t(buf
, 8, press_abs
);
92 _mav_put_int16_t(buf
, 10, press_diff1
);
93 _mav_put_int16_t(buf
, 12, press_diff2
);
94 _mav_put_int16_t(buf
, 14, temperature
);
96 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 16);
98 mavlink_raw_pressure_t packet
;
99 packet
.time_usec
= time_usec
;
100 packet
.press_abs
= press_abs
;
101 packet
.press_diff1
= press_diff1
;
102 packet
.press_diff2
= press_diff2
;
103 packet
.temperature
= temperature
;
105 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 16);
108 msg
->msgid
= MAVLINK_MSG_ID_RAW_PRESSURE
;
109 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, 16, 67);
113 * @brief Encode a raw_pressure struct into a message
115 * @param system_id ID of this system
116 * @param component_id ID of this component (e.g. 200 for IMU)
117 * @param msg The MAVLink message to compress the data into
118 * @param raw_pressure C-struct to read the message contents from
120 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
)
122 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
);
126 * @brief Send a raw_pressure message
127 * @param chan MAVLink channel to send the message
129 * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
130 * @param press_abs Absolute pressure (raw)
131 * @param press_diff1 Differential pressure 1 (raw)
132 * @param press_diff2 Differential pressure 2 (raw)
133 * @param temperature Raw Temperature measurement (raw)
135 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
137 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
)
139 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
141 _mav_put_uint64_t(buf
, 0, time_usec
);
142 _mav_put_int16_t(buf
, 8, press_abs
);
143 _mav_put_int16_t(buf
, 10, press_diff1
);
144 _mav_put_int16_t(buf
, 12, press_diff2
);
145 _mav_put_int16_t(buf
, 14, temperature
);
147 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_RAW_PRESSURE
, buf
, 16, 67);
149 mavlink_raw_pressure_t packet
;
150 packet
.time_usec
= time_usec
;
151 packet
.press_abs
= press_abs
;
152 packet
.press_diff1
= press_diff1
;
153 packet
.press_diff2
= press_diff2
;
154 packet
.temperature
= temperature
;
156 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_RAW_PRESSURE
, (const char *)&packet
, 16, 67);
160 #endif // ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
162 // MESSAGE RAW_PRESSURE UNPACKING
166 * @brief Get field time_usec from raw_pressure message
168 * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
170 static inline uint64_t mavlink_msg_raw_pressure_get_time_usec(const mavlink_message_t
*msg
)
172 return _MAV_RETURN_uint64_t(msg
, 0);
176 * @brief Get field press_abs from raw_pressure message
178 * @return Absolute pressure (raw)
180 static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t
*msg
)
182 return _MAV_RETURN_int16_t(msg
, 8);
186 * @brief Get field press_diff1 from raw_pressure message
188 * @return Differential pressure 1 (raw)
190 static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t
*msg
)
192 return _MAV_RETURN_int16_t(msg
, 10);
196 * @brief Get field press_diff2 from raw_pressure message
198 * @return Differential pressure 2 (raw)
200 static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t
*msg
)
202 return _MAV_RETURN_int16_t(msg
, 12);
206 * @brief Get field temperature from raw_pressure message
208 * @return Raw Temperature measurement (raw)
210 static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t
*msg
)
212 return _MAV_RETURN_int16_t(msg
, 14);
216 * @brief Decode a raw_pressure message into a struct
218 * @param msg The message to decode
219 * @param raw_pressure C-struct to decode the message contents into
221 static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t
*msg
, mavlink_raw_pressure_t
*raw_pressure
)
223 #if MAVLINK_NEED_BYTE_SWAP
224 raw_pressure
->time_usec
= mavlink_msg_raw_pressure_get_time_usec(msg
);
225 raw_pressure
->press_abs
= mavlink_msg_raw_pressure_get_press_abs(msg
);
226 raw_pressure
->press_diff1
= mavlink_msg_raw_pressure_get_press_diff1(msg
);
227 raw_pressure
->press_diff2
= mavlink_msg_raw_pressure_get_press_diff2(msg
);
228 raw_pressure
->temperature
= mavlink_msg_raw_pressure_get_temperature(msg
);
230 memcpy(raw_pressure
, _MAV_PAYLOAD(msg
), 16);