3 #define MAVLINK_MSG_ID_SCALED_PRESSURE 29
13 #define MAVLINK_MSG_ID_SCALED_PRESSURE_LEN 14
14 #define MAVLINK_MSG_ID_29_LEN 14
16 #define MAVLINK_MSG_ID_SCALED_PRESSURE_CRC 115
17 #define MAVLINK_MSG_ID_29_CRC 115
21 #define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE { \
24 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure_t, time_boot_ms) }, \
25 { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure_t, press_abs) }, \
26 { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure_t, press_diff) }, \
27 { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure_t, temperature) }, \
44 static inline uint16_t mavlink_msg_scaled_pressure_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
48 char buf[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN];
49 _mav_put_uint32_t(buf, 0, time_boot_ms);
50 _mav_put_float(buf, 4, press_abs);
51 _mav_put_float(buf, 8, press_diff);
52 _mav_put_int16_t(buf, 12, temperature);
54 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
62 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
65 msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE;
67 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC);
69 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
85 static inline uint16_t mavlink_msg_scaled_pressure_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
90 char buf[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN];
91 _mav_put_uint32_t(buf, 0, time_boot_ms);
92 _mav_put_float(buf, 4, press_abs);
93 _mav_put_float(buf, 8, press_diff);
94 _mav_put_int16_t(buf, 12, temperature);
96 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
104 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
107 msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE;
108 #if MAVLINK_CRC_EXTRA
109 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC);
111 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
123 static inline uint16_t mavlink_msg_scaled_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_scaled_pressure_t* scaled_pressure)
137 static inline uint16_t mavlink_msg_scaled_pressure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_scaled_pressure_t* scaled_pressure)
151 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
153 static inline void mavlink_msg_scaled_pressure_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
156 char buf[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN];
157 _mav_put_uint32_t(buf, 0, time_boot_ms);
158 _mav_put_float(buf, 4, press_abs);
159 _mav_put_float(buf, 8, press_diff);
160 _mav_put_int16_t(buf, 12, temperature);
162 #if MAVLINK_CRC_EXTRA
163 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC);
165 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
174 #if MAVLINK_CRC_EXTRA
175 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (
const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC);
177 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (
const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
182 #if MAVLINK_MSG_ID_SCALED_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
190 static inline void mavlink_msg_scaled_pressure_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;
194 _mav_put_uint32_t(buf, 0, time_boot_ms);
195 _mav_put_float(buf, 4, press_abs);
196 _mav_put_float(buf, 8, press_diff);
197 _mav_put_int16_t(buf, 12, temperature);
199 #if MAVLINK_CRC_EXTRA
200 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC);
202 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
211 #if MAVLINK_CRC_EXTRA
212 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (
const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC);
214 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (
const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
230 static inline uint32_t mavlink_msg_scaled_pressure_get_time_boot_ms(
const mavlink_message_t* msg)
232 return _MAV_RETURN_uint32_t(msg, 0);
240 static inline float mavlink_msg_scaled_pressure_get_press_abs(
const mavlink_message_t* msg)
242 return _MAV_RETURN_float(msg, 4);
250 static inline float mavlink_msg_scaled_pressure_get_press_diff(
const mavlink_message_t* msg)
252 return _MAV_RETURN_float(msg, 8);
260 static inline int16_t mavlink_msg_scaled_pressure_get_temperature(
const mavlink_message_t* msg)
262 return _MAV_RETURN_int16_t(msg, 12);
271 static inline void mavlink_msg_scaled_pressure_decode(
const mavlink_message_t* msg,
mavlink_scaled_pressure_t* scaled_pressure)
273 #if MAVLINK_NEED_BYTE_SWAP
274 scaled_pressure->
time_boot_ms = mavlink_msg_scaled_pressure_get_time_boot_ms(msg);
275 scaled_pressure->
press_abs = mavlink_msg_scaled_pressure_get_press_abs(msg);
276 scaled_pressure->
press_diff = mavlink_msg_scaled_pressure_get_press_diff(msg);
277 scaled_pressure->
temperature = mavlink_msg_scaled_pressure_get_temperature(msg);
279 memcpy(scaled_pressure, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
float press_abs
Absolute pressure (hectopascal)
Definition: mavlink_msg_scaled_pressure.h:8
int16_t temperature
Temperature measurement (0.01 degrees celsius)
Definition: mavlink_msg_scaled_pressure.h:10
Definition: mavlink_msg_scaled_pressure.h:5
uint32_t time_boot_ms
Timestamp (milliseconds since system boot)
Definition: mavlink_msg_scaled_pressure.h:7
float press_diff
Differential pressure 1 (hectopascal)
Definition: mavlink_msg_scaled_pressure.h:9