3 #define MAVLINK_MSG_ID_SCALED_PRESSURE2 137
13 #define MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN 14
14 #define MAVLINK_MSG_ID_137_LEN 14
16 #define MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC 195
17 #define MAVLINK_MSG_ID_137_CRC 195
21 #define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2 { \
24 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure2_t, time_boot_ms) }, \
25 { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure2_t, press_abs) }, \
26 { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure2_t, press_diff) }, \
27 { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure2_t, temperature) }, \
44 static inline uint16_t mavlink_msg_scaled_pressure2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
45 uint32_t time_boot_ms,
float press_abs,
float press_diff, int16_t temperature)
47 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
85 static inline uint16_t mavlink_msg_scaled_pressure2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
86 mavlink_message_t* msg,
87 uint32_t time_boot_ms,
float press_abs,
float press_diff,int16_t temperature)
89 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
108 #if MAVLINK_CRC_EXTRA
123 static inline uint16_t mavlink_msg_scaled_pressure2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_scaled_pressure2_t* scaled_pressure2)
137 static inline uint16_t mavlink_msg_scaled_pressure2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_scaled_pressure2_t* scaled_pressure2)
151 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
153 static inline void mavlink_msg_scaled_pressure2_send(
mavlink_channel_t chan, uint32_t time_boot_ms,
float press_abs,
float press_diff, int16_t temperature)
155 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
162 #if MAVLINK_CRC_EXTRA
174 #if MAVLINK_CRC_EXTRA
182 #if MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN <= MAVLINK_MAX_PAYLOAD_LEN
190 static inline void mavlink_msg_scaled_pressure2_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint32_t time_boot_ms,
float press_abs,
float press_diff, int16_t temperature)
192 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
193 char *buf = (
char *)msgbuf;
199 #if MAVLINK_CRC_EXTRA
211 #if MAVLINK_CRC_EXTRA
230 static inline uint32_t mavlink_msg_scaled_pressure2_get_time_boot_ms(
const mavlink_message_t* msg)
232 return _MAV_RETURN_uint32_t(msg, 0);
240 static inline float mavlink_msg_scaled_pressure2_get_press_abs(
const mavlink_message_t* msg)
242 return _MAV_RETURN_float(msg, 4);
250 static inline float mavlink_msg_scaled_pressure2_get_press_diff(
const mavlink_message_t* msg)
252 return _MAV_RETURN_float(msg, 8);
260 static inline int16_t mavlink_msg_scaled_pressure2_get_temperature(
const mavlink_message_t* msg)
262 return _MAV_RETURN_int16_t(msg, 12);
271 static inline void mavlink_msg_scaled_pressure2_decode(
const mavlink_message_t* msg,
mavlink_scaled_pressure2_t* scaled_pressure2)
273 #if MAVLINK_NEED_BYTE_SWAP
274 scaled_pressure2->
time_boot_ms = mavlink_msg_scaled_pressure2_get_time_boot_ms(msg);
275 scaled_pressure2->
press_abs = mavlink_msg_scaled_pressure2_get_press_abs(msg);
276 scaled_pressure2->
press_diff = mavlink_msg_scaled_pressure2_get_press_diff(msg);
277 scaled_pressure2->
temperature = mavlink_msg_scaled_pressure2_get_temperature(msg);
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
#define MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN
Definition: mavlink_msg_scaled_pressure2.h:13
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_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
float press_abs
Absolute pressure (hectopascal)
Definition: mavlink_msg_scaled_pressure2.h:8
float press_diff
Differential pressure 1 (hectopascal)
Definition: mavlink_msg_scaled_pressure2.h:9
mavlink_channel_t
Definition: mavlink_types.h:178
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
struct __mavlink_scaled_pressure2_t mavlink_scaled_pressure2_t
#define MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC
Definition: mavlink_msg_scaled_pressure2.h:16
Definition: mavlink_msg_scaled_pressure2.h:5
#define MAVLINK_MSG_ID_SCALED_PRESSURE2
Definition: mavlink_msg_scaled_pressure2.h:3
int16_t temperature
Temperature measurement (0.01 degrees celsius)
Definition: mavlink_msg_scaled_pressure2.h:10
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
uint32_t time_boot_ms
Timestamp (milliseconds since system boot)
Definition: mavlink_msg_scaled_pressure2.h:7
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:141