3 #define MAVLINK_MSG_ID_RAW_PRESSURE 28 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) }, \ 50 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 92 mavlink_message_t* msg,
95 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 116 #if MAVLINK_CRC_EXTRA 160 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 164 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 172 #if MAVLINK_CRC_EXTRA 185 #if MAVLINK_CRC_EXTRA 193 #if MAVLINK_MSG_ID_RAW_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN 203 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 204 char *buf = (
char *)msgbuf;
211 #if MAVLINK_CRC_EXTRA 224 #if MAVLINK_CRC_EXTRA 245 return _MAV_RETURN_uint64_t(msg, 0);
255 return _MAV_RETURN_int16_t(msg, 8);
265 return _MAV_RETURN_int16_t(msg, 10);
275 return _MAV_RETURN_int16_t(msg, 12);
285 return _MAV_RETURN_int16_t(msg, 14);
296 #if MAVLINK_NEED_BYTE_SWAP static int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t *msg)
Get field temperature from raw_pressure message.
static 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)
Encode a raw_pressure struct on a channel.
static uint64_t mavlink_msg_raw_pressure_get_time_usec(const mavlink_message_t *msg)
Send a raw_pressure message.
struct __mavlink_raw_pressure_t mavlink_raw_pressure_t
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.
#define _mav_put_uint64_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
#define MAVLINK_MSG_ID_RAW_PRESSURE_LEN
static int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t *msg)
Get field press_diff1 from raw_pressure message.
static uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
Pack a raw_pressure message.
#define _MAV_PAYLOAD(msg)
static 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)
Encode a raw_pressure struct.
static void mavlink_msg_raw_pressure_decode(const mavlink_message_t *msg, mavlink_raw_pressure_t *raw_pressure)
Decode a raw_pressure message into a struct.
#define MAVLINK_MSG_ID_RAW_PRESSURE
static int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t *msg)
Get field press_diff2 from raw_pressure message.
#define MAVLINK_MSG_ID_RAW_PRESSURE_CRC
static uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
Pack a raw_pressure message on a channel.
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.
#define _mav_put_int16_t(buf, wire_offset, b)
static int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t *msg)
Get field press_abs from raw_pressure message.