mavlink_msg_raw_pressure.h 8.58 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3 4
// MESSAGE RAW_PRESSURE PACKING

#define MAVLINK_MSG_ID_RAW_PRESSURE 29

lm's avatar
lm committed
5
typedef struct __mavlink_raw_pressure_t
James Goppert's avatar
James Goppert committed
6
{
lm's avatar
lm committed
7 8 9 10 11
 uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
 int16_t press_abs; ///< Absolute pressure (raw)
 int16_t press_diff1; ///< Differential pressure 1 (raw)
 int16_t press_diff2; ///< Differential pressure 2 (raw)
 int16_t temperature; ///< Raw Temperature measurement (raw)
James Goppert's avatar
James Goppert committed
12 13
} mavlink_raw_pressure_t;

lm's avatar
lm committed
14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30
#define MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16
#define MAVLINK_MSG_ID_29_LEN 16



#define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \
	"RAW_PRESSURE", \
	5, \
	{  { "usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, usec) }, \
         { "press_abs", MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \
         { "press_diff1", MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \
         { "press_diff2", MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \
         { "temperature", MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \
         } \
}


James Goppert's avatar
James Goppert committed
31 32 33 34 35 36 37
/**
 * @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 usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
James Goppert's avatar
James Goppert committed
38 39 40 41
 * @param press_abs Absolute pressure (raw)
 * @param press_diff1 Differential pressure 1 (raw)
 * @param press_diff2 Differential pressure 2 (raw)
 * @param temperature Raw Temperature measurement (raw)
James Goppert's avatar
James Goppert committed
42 43
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
44 45
static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
						       uint64_t usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
James Goppert's avatar
James Goppert committed
46 47 48
{
	msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;

lm's avatar
lm committed
49 50 51 52 53
	put_uint64_t_by_index(msg, 0, usec); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	put_int16_t_by_index(msg, 8, press_abs); // Absolute pressure (raw)
	put_int16_t_by_index(msg, 10, press_diff1); // Differential pressure 1 (raw)
	put_int16_t_by_index(msg, 12, press_diff2); // Differential pressure 2 (raw)
	put_int16_t_by_index(msg, 14, temperature); // Raw Temperature measurement (raw)
James Goppert's avatar
James Goppert committed
54

lm's avatar
lm committed
55
	return mavlink_finalize_message(msg, system_id, component_id, 16, 136);
James Goppert's avatar
James Goppert committed
56 57 58
}

/**
lm's avatar
lm committed
59
 * @brief Pack a raw_pressure message on a channel
James Goppert's avatar
James Goppert committed
60 61 62 63 64
 * @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 was sent over
 * @param msg The MAVLink message to compress the data into
 * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
James Goppert's avatar
James Goppert committed
65 66 67 68
 * @param press_abs Absolute pressure (raw)
 * @param press_diff1 Differential pressure 1 (raw)
 * @param press_diff2 Differential pressure 2 (raw)
 * @param temperature Raw Temperature measurement (raw)
James Goppert's avatar
James Goppert committed
69 70
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
71 72 73
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 usec,int16_t press_abs,int16_t press_diff1,int16_t press_diff2,int16_t temperature)
James Goppert's avatar
James Goppert committed
74 75 76
{
	msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;

lm's avatar
lm committed
77 78 79 80 81
	put_uint64_t_by_index(msg, 0, usec); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	put_int16_t_by_index(msg, 8, press_abs); // Absolute pressure (raw)
	put_int16_t_by_index(msg, 10, press_diff1); // Differential pressure 1 (raw)
	put_int16_t_by_index(msg, 12, press_diff2); // Differential pressure 2 (raw)
	put_int16_t_by_index(msg, 14, temperature); // Raw Temperature measurement (raw)
James Goppert's avatar
James Goppert committed
82

lm's avatar
lm committed
83
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16, 136);
James Goppert's avatar
James Goppert committed
84 85
}

lm's avatar
lm committed
86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

/**
 * @brief Pack a raw_pressure message on a channel and send
 * @param chan The MAVLink channel this message was sent over
 * @param msg The MAVLink message to compress the data into
 * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
 * @param press_abs Absolute pressure (raw)
 * @param press_diff1 Differential pressure 1 (raw)
 * @param press_diff2 Differential pressure 2 (raw)
 * @param temperature Raw Temperature measurement (raw)
 */
static inline void mavlink_msg_raw_pressure_pack_chan_send(mavlink_channel_t chan,
							   mavlink_message_t* msg,
						           uint64_t usec,int16_t press_abs,int16_t press_diff1,int16_t press_diff2,int16_t temperature)
{
	msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;

	put_uint64_t_by_index(msg, 0, usec); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	put_int16_t_by_index(msg, 8, press_abs); // Absolute pressure (raw)
	put_int16_t_by_index(msg, 10, press_diff1); // Differential pressure 1 (raw)
	put_int16_t_by_index(msg, 12, press_diff2); // Differential pressure 2 (raw)
	put_int16_t_by_index(msg, 14, temperature); // Raw Temperature measurement (raw)

	mavlink_finalize_message_chan_send(msg, chan, 16, 136);
}
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS


James Goppert's avatar
James Goppert committed
115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132
/**
 * @brief Encode a raw_pressure struct into a 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 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->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 usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
James Goppert's avatar
James Goppert committed
133 134 135 136
 * @param press_abs Absolute pressure (raw)
 * @param press_diff1 Differential pressure 1 (raw)
 * @param press_diff2 Differential pressure 2 (raw)
 * @param temperature Raw Temperature measurement (raw)
James Goppert's avatar
James Goppert committed
137
 */
lm's avatar
lm committed
138 139
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

lm's avatar
lm committed
140 141
static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
{
lm's avatar
lm committed
142 143
	MAVLINK_ALIGNED_MESSAGE(msg, 16);
	mavlink_msg_raw_pressure_pack_chan_send(chan, msg, usec, press_abs, press_diff1, press_diff2, temperature);
James Goppert's avatar
James Goppert committed
144 145 146
}

#endif
lm's avatar
lm committed
147

James Goppert's avatar
James Goppert committed
148 149
// MESSAGE RAW_PRESSURE UNPACKING

lm's avatar
lm committed
150

James Goppert's avatar
James Goppert committed
151 152 153 154 155 156 157
/**
 * @brief Get field usec from raw_pressure message
 *
 * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
 */
static inline uint64_t mavlink_msg_raw_pressure_get_usec(const mavlink_message_t* msg)
{
lm's avatar
lm committed
158
	return MAVLINK_MSG_RETURN_uint64_t(msg,  0);
James Goppert's avatar
James Goppert committed
159 160 161 162 163
}

/**
 * @brief Get field press_abs from raw_pressure message
 *
James Goppert's avatar
James Goppert committed
164
 * @return Absolute pressure (raw)
James Goppert's avatar
James Goppert committed
165
 */
James Goppert's avatar
James Goppert committed
166
static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
167
{
lm's avatar
lm committed
168
	return MAVLINK_MSG_RETURN_int16_t(msg,  8);
James Goppert's avatar
James Goppert committed
169 170 171 172 173
}

/**
 * @brief Get field press_diff1 from raw_pressure message
 *
James Goppert's avatar
James Goppert committed
174
 * @return Differential pressure 1 (raw)
James Goppert's avatar
James Goppert committed
175
 */
James Goppert's avatar
James Goppert committed
176
static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
177
{
lm's avatar
lm committed
178
	return MAVLINK_MSG_RETURN_int16_t(msg,  10);
James Goppert's avatar
James Goppert committed
179 180 181 182 183
}

/**
 * @brief Get field press_diff2 from raw_pressure message
 *
James Goppert's avatar
James Goppert committed
184
 * @return Differential pressure 2 (raw)
James Goppert's avatar
James Goppert committed
185
 */
James Goppert's avatar
James Goppert committed
186
static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
187
{
lm's avatar
lm committed
188
	return MAVLINK_MSG_RETURN_int16_t(msg,  12);
James Goppert's avatar
James Goppert committed
189 190 191 192 193
}

/**
 * @brief Get field temperature from raw_pressure message
 *
James Goppert's avatar
James Goppert committed
194
 * @return Raw Temperature measurement (raw)
James Goppert's avatar
James Goppert committed
195 196 197
 */
static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg)
{
lm's avatar
lm committed
198
	return MAVLINK_MSG_RETURN_int16_t(msg,  14);
James Goppert's avatar
James Goppert committed
199 200 201 202 203 204 205 206 207 208
}

/**
 * @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)
{
lm's avatar
lm committed
209 210 211 212 213 214 215 216 217
#if MAVLINK_NEED_BYTE_SWAP
	raw_pressure->usec = mavlink_msg_raw_pressure_get_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
	memcpy(raw_pressure, MAVLINK_PAYLOAD(msg), 16);
#endif
James Goppert's avatar
James Goppert committed
218
}