123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372 |
- #pragma once
- // MESSAGE RAW_PRESSURE PACKING
- #define MAVLINK_MSG_ID_RAW_PRESSURE 28
- typedef struct __mavlink_raw_pressure_t {
- 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.*/
- int16_t press_abs; /*< Absolute pressure (raw)*/
- int16_t press_diff1; /*< Differential pressure 1 (raw, 0 if nonexistent)*/
- int16_t press_diff2; /*< Differential pressure 2 (raw, 0 if nonexistent)*/
- int16_t temperature; /*< Raw Temperature measurement (raw)*/
- } mavlink_raw_pressure_t;
- #define MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16
- #define MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN 16
- #define MAVLINK_MSG_ID_28_LEN 16
- #define MAVLINK_MSG_ID_28_MIN_LEN 16
- #define MAVLINK_MSG_ID_RAW_PRESSURE_CRC 67
- #define MAVLINK_MSG_ID_28_CRC 67
- #if MAVLINK_COMMAND_24BIT
- #define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \
- 28, \
- "RAW_PRESSURE", \
- 5, \
- { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, time_usec) }, \
- { "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \
- { "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \
- { "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \
- { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \
- } \
- }
- #else
- #define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \
- "RAW_PRESSURE", \
- 5, \
- { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, time_usec) }, \
- { "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \
- { "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \
- { "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \
- { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \
- } \
- }
- #endif
- /**
- * @brief Pack a raw_pressure message
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param msg The MAVLink message to compress the data into
- *
- * @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.
- * @param press_abs Absolute pressure (raw)
- * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistent)
- * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistent)
- * @param temperature Raw Temperature measurement (raw)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline 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)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN];
- _mav_put_uint64_t(buf, 0, time_usec);
- _mav_put_int16_t(buf, 8, press_abs);
- _mav_put_int16_t(buf, 10, press_diff1);
- _mav_put_int16_t(buf, 12, press_diff2);
- _mav_put_int16_t(buf, 14, temperature);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
- #else
- mavlink_raw_pressure_t packet;
- packet.time_usec = time_usec;
- packet.press_abs = press_abs;
- packet.press_diff1 = press_diff1;
- packet.press_diff2 = press_diff2;
- packet.temperature = temperature;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
- 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);
- }
- /**
- * @brief Pack a raw_pressure message
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param status MAVLink status structure
- * @param msg The MAVLink message to compress the data into
- *
- * @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.
- * @param press_abs Absolute pressure (raw)
- * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistent)
- * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistent)
- * @param temperature Raw Temperature measurement (raw)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_raw_pressure_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
- uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN];
- _mav_put_uint64_t(buf, 0, time_usec);
- _mav_put_int16_t(buf, 8, press_abs);
- _mav_put_int16_t(buf, 10, press_diff1);
- _mav_put_int16_t(buf, 12, press_diff2);
- _mav_put_int16_t(buf, 14, temperature);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
- #else
- mavlink_raw_pressure_t packet;
- packet.time_usec = time_usec;
- packet.press_abs = press_abs;
- packet.press_diff1 = press_diff1;
- packet.press_diff2 = press_diff2;
- packet.temperature = temperature;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
- #if MAVLINK_CRC_EXTRA
- return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
- #else
- return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
- #endif
- }
- /**
- * @brief Pack a raw_pressure message on a channel
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message will be sent over
- * @param msg The MAVLink message to compress the data into
- * @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.
- * @param press_abs Absolute pressure (raw)
- * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistent)
- * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistent)
- * @param temperature Raw Temperature measurement (raw)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline 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)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN];
- _mav_put_uint64_t(buf, 0, time_usec);
- _mav_put_int16_t(buf, 8, press_abs);
- _mav_put_int16_t(buf, 10, press_diff1);
- _mav_put_int16_t(buf, 12, press_diff2);
- _mav_put_int16_t(buf, 14, temperature);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
- #else
- mavlink_raw_pressure_t packet;
- packet.time_usec = time_usec;
- packet.press_abs = press_abs;
- packet.press_diff1 = press_diff1;
- packet.press_diff2 = press_diff2;
- packet.temperature = temperature;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
- 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);
- }
- /**
- * @brief Encode a raw_pressure struct
- *
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param msg The MAVLink message to compress the data into
- * @param raw_pressure C-struct to read the message contents from
- */
- 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)
- {
- 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);
- }
- /**
- * @brief Encode a raw_pressure struct on a channel
- *
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message will be sent over
- * @param msg The MAVLink message to compress the data into
- * @param raw_pressure C-struct to read the message contents from
- */
- 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)
- {
- 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);
- }
- /**
- * @brief Encode a raw_pressure struct with provided status structure
- *
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param status MAVLink status structure
- * @param msg The MAVLink message to compress the data into
- * @param raw_pressure C-struct to read the message contents from
- */
- static inline uint16_t mavlink_msg_raw_pressure_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure)
- {
- return mavlink_msg_raw_pressure_pack_status(system_id, component_id, _status, msg, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature);
- }
- /**
- * @brief Send a raw_pressure message
- * @param chan MAVLink channel to send the message
- *
- * @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.
- * @param press_abs Absolute pressure (raw)
- * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistent)
- * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistent)
- * @param temperature Raw Temperature measurement (raw)
- */
- #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
- 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)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN];
- _mav_put_uint64_t(buf, 0, time_usec);
- _mav_put_int16_t(buf, 8, press_abs);
- _mav_put_int16_t(buf, 10, press_diff1);
- _mav_put_int16_t(buf, 12, press_diff2);
- _mav_put_int16_t(buf, 14, temperature);
- _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);
- #else
- mavlink_raw_pressure_t packet;
- packet.time_usec = time_usec;
- packet.press_abs = press_abs;
- packet.press_diff1 = press_diff1;
- packet.press_diff2 = press_diff2;
- packet.temperature = temperature;
- _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);
- #endif
- }
- /**
- * @brief Send a raw_pressure message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
- static inline void mavlink_msg_raw_pressure_send_struct(mavlink_channel_t chan, const mavlink_raw_pressure_t* raw_pressure)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- 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);
- #else
- _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);
- #endif
- }
- #if MAVLINK_MSG_ID_RAW_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
- /*
- This variant of _send() can be used to save stack space by re-using
- memory from the receive buffer. The caller provides a
- mavlink_message_t which is the size of a full mavlink message. This
- is usually the receive buffer for the channel, and allows a reply to an
- incoming message with minimum stack space usage.
- */
- 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)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, time_usec);
- _mav_put_int16_t(buf, 8, press_abs);
- _mav_put_int16_t(buf, 10, press_diff1);
- _mav_put_int16_t(buf, 12, press_diff2);
- _mav_put_int16_t(buf, 14, temperature);
- _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);
- #else
- mavlink_raw_pressure_t *packet = (mavlink_raw_pressure_t *)msgbuf;
- packet->time_usec = time_usec;
- packet->press_abs = press_abs;
- packet->press_diff1 = press_diff1;
- packet->press_diff2 = press_diff2;
- packet->temperature = temperature;
- _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);
- #endif
- }
- #endif
- #endif
- // MESSAGE RAW_PRESSURE UNPACKING
- /**
- * @brief Get field time_usec from raw_pressure message
- *
- * @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.
- */
- static inline uint64_t mavlink_msg_raw_pressure_get_time_usec(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint64_t(msg, 0);
- }
- /**
- * @brief Get field press_abs from raw_pressure message
- *
- * @return Absolute pressure (raw)
- */
- static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_int16_t(msg, 8);
- }
- /**
- * @brief Get field press_diff1 from raw_pressure message
- *
- * @return Differential pressure 1 (raw, 0 if nonexistent)
- */
- static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_int16_t(msg, 10);
- }
- /**
- * @brief Get field press_diff2 from raw_pressure message
- *
- * @return Differential pressure 2 (raw, 0 if nonexistent)
- */
- static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_int16_t(msg, 12);
- }
- /**
- * @brief Get field temperature from raw_pressure message
- *
- * @return Raw Temperature measurement (raw)
- */
- static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_int16_t(msg, 14);
- }
- /**
- * @brief Decode a raw_pressure message into a struct
- *
- * @param msg The message to decode
- * @param raw_pressure C-struct to decode the message contents into
- */
- static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t* msg, mavlink_raw_pressure_t* raw_pressure)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- raw_pressure->time_usec = mavlink_msg_raw_pressure_get_time_usec(msg);
- raw_pressure->press_abs = mavlink_msg_raw_pressure_get_press_abs(msg);
- raw_pressure->press_diff1 = mavlink_msg_raw_pressure_get_press_diff1(msg);
- raw_pressure->press_diff2 = mavlink_msg_raw_pressure_get_press_diff2(msg);
- raw_pressure->temperature = mavlink_msg_raw_pressure_get_temperature(msg);
- #else
- uint8_t len = msg->len < MAVLINK_MSG_ID_RAW_PRESSURE_LEN? msg->len : MAVLINK_MSG_ID_RAW_PRESSURE_LEN;
- memset(raw_pressure, 0, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
- memcpy(raw_pressure, _MAV_PAYLOAD(msg), len);
- #endif
- }
|