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

#define MAVLINK_MSG_ID_RAW_PRESSURE 29
lm's avatar
lm committed
4 5
#define MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16
#define MAVLINK_MSG_29_LEN 16
James Goppert's avatar
James Goppert committed
6 7 8 9

typedef struct __mavlink_raw_pressure_t 
{
	uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
James Goppert's avatar
James Goppert committed
10 11 12 13
	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
14 15 16 17 18 19 20 21 22 23

} mavlink_raw_pressure_t;

/**
 * @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
24 25 26 27
 * @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
28 29
 * @return length of the message in bytes (excluding serial stream start sign)
 */
James Goppert's avatar
James Goppert committed
30
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
31
{
lm's avatar
lm committed
32
	mavlink_raw_pressure_t *p = (mavlink_raw_pressure_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
33 34
	msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;

lm's avatar
lm committed
35 36 37 38 39
	p->usec = usec; // uint64_t:Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	p->press_abs = press_abs; // int16_t:Absolute pressure (raw)
	p->press_diff1 = press_diff1; // int16_t:Differential pressure 1 (raw)
	p->press_diff2 = press_diff2; // int16_t:Differential pressure 2 (raw)
	p->temperature = temperature; // int16_t:Raw Temperature measurement (raw)
James Goppert's avatar
James Goppert committed
40

lm's avatar
lm committed
41
	return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
James Goppert's avatar
James Goppert committed
42 43 44 45 46 47 48 49 50
}

/**
 * @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 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
51 52 53 54
 * @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
55 56
 * @return length of the message in bytes (excluding serial stream start sign)
 */
James Goppert's avatar
James Goppert committed
57
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
58
{
lm's avatar
lm committed
59
	mavlink_raw_pressure_t *p = (mavlink_raw_pressure_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
60 61
	msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;

lm's avatar
lm committed
62 63 64 65 66
	p->usec = usec; // uint64_t:Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	p->press_abs = press_abs; // int16_t:Absolute pressure (raw)
	p->press_diff1 = press_diff1; // int16_t:Differential pressure 1 (raw)
	p->press_diff2 = press_diff2; // int16_t:Differential pressure 2 (raw)
	p->temperature = temperature; // int16_t:Raw Temperature measurement (raw)
James Goppert's avatar
James Goppert committed
67

lm's avatar
lm committed
68
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
James Goppert's avatar
James Goppert committed
69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88
}

/**
 * @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
89 90 91 92
 * @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
93 94
 */
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
James Goppert's avatar
James Goppert committed
95
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)
James Goppert's avatar
James Goppert committed
96 97
{
	mavlink_message_t msg;
lm's avatar
lm committed
98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153
	uint16_t checksum;
	mavlink_raw_pressure_t *p = (mavlink_raw_pressure_t *)&msg.payload[0];

	p->usec = usec; // uint64_t:Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	p->press_abs = press_abs; // int16_t:Absolute pressure (raw)
	p->press_diff1 = press_diff1; // int16_t:Differential pressure 1 (raw)
	p->press_diff2 = press_diff2; // int16_t:Differential pressure 2 (raw)
	p->temperature = temperature; // int16_t:Raw Temperature measurement (raw)

	msg.STX = MAVLINK_STX;
	msg.len = MAVLINK_MSG_ID_RAW_PRESSURE_LEN;
	msg.msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
	msg.sysid = mavlink_system.sysid;
	msg.compid = mavlink_system.compid;
	msg.seq = mavlink_get_channel_status(chan)->current_tx_seq;
	mavlink_get_channel_status(chan)->current_tx_seq = msg.seq + 1;
	checksum = crc_calculate_msg(&msg, msg.len + MAVLINK_CORE_HEADER_LEN);
	msg.ck_a = (uint8_t)(checksum & 0xFF); ///< Low byte
	msg.ck_b = (uint8_t)(checksum >> 8); ///< High byte

	mavlink_send_msg(chan, &msg);
}

#endif

#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS_SMALL
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)
{
	mavlink_header_t hdr;
	mavlink_raw_pressure_t payload;
	uint16_t checksum;
	mavlink_raw_pressure_t *p = &payload;

	p->usec = usec; // uint64_t:Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	p->press_abs = press_abs; // int16_t:Absolute pressure (raw)
	p->press_diff1 = press_diff1; // int16_t:Differential pressure 1 (raw)
	p->press_diff2 = press_diff2; // int16_t:Differential pressure 2 (raw)
	p->temperature = temperature; // int16_t:Raw Temperature measurement (raw)

	hdr.STX = MAVLINK_STX;
	hdr.len = MAVLINK_MSG_ID_RAW_PRESSURE_LEN;
	hdr.msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
	hdr.sysid = mavlink_system.sysid;
	hdr.compid = mavlink_system.compid;
	hdr.seq = mavlink_get_channel_status(chan)->current_tx_seq;
	mavlink_get_channel_status(chan)->current_tx_seq = hdr.seq + 1;
	mavlink_send_mem(chan, (uint8_t *)&hdr.STX, MAVLINK_NUM_HEADER_BYTES );

	crc_init(&checksum);
	checksum = crc_calculate_mem((uint8_t *)&hdr.len, &checksum, MAVLINK_CORE_HEADER_LEN);
	checksum = crc_calculate_mem((uint8_t *)&payload, &checksum, hdr.len );
	hdr.ck_a = (uint8_t)(checksum & 0xFF); ///< Low byte
	hdr.ck_b = (uint8_t)(checksum >> 8); ///< High byte

	mavlink_send_mem(chan, (uint8_t *)&payload, hdr.len);
	mavlink_send_mem(chan, (uint8_t *)&hdr.ck_a, MAVLINK_NUM_CHECKSUM_BYTES);
James Goppert's avatar
James Goppert committed
154 155 156 157 158 159 160 161 162 163 164 165
}

#endif
// MESSAGE RAW_PRESSURE UNPACKING

/**
 * @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
166 167
	mavlink_raw_pressure_t *p = (mavlink_raw_pressure_t *)&msg->payload[0];
	return (uint64_t)(p->usec);
James Goppert's avatar
James Goppert committed
168 169 170 171 172
}

/**
 * @brief Get field press_abs from raw_pressure message
 *
James Goppert's avatar
James Goppert committed
173
 * @return Absolute pressure (raw)
James Goppert's avatar
James Goppert committed
174
 */
James Goppert's avatar
James Goppert committed
175
static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
176
{
lm's avatar
lm committed
177 178
	mavlink_raw_pressure_t *p = (mavlink_raw_pressure_t *)&msg->payload[0];
	return (int16_t)(p->press_abs);
James Goppert's avatar
James Goppert committed
179 180 181 182 183
}

/**
 * @brief Get field press_diff1 from raw_pressure message
 *
James Goppert's avatar
James Goppert committed
184
 * @return Differential pressure 1 (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_diff1(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
187
{
lm's avatar
lm committed
188 189
	mavlink_raw_pressure_t *p = (mavlink_raw_pressure_t *)&msg->payload[0];
	return (int16_t)(p->press_diff1);
James Goppert's avatar
James Goppert committed
190 191 192 193 194
}

/**
 * @brief Get field press_diff2 from raw_pressure message
 *
James Goppert's avatar
James Goppert committed
195
 * @return Differential pressure 2 (raw)
James Goppert's avatar
James Goppert committed
196
 */
James Goppert's avatar
James Goppert committed
197
static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
198
{
lm's avatar
lm committed
199 200
	mavlink_raw_pressure_t *p = (mavlink_raw_pressure_t *)&msg->payload[0];
	return (int16_t)(p->press_diff2);
James Goppert's avatar
James Goppert committed
201 202 203 204 205
}

/**
 * @brief Get field temperature from raw_pressure message
 *
James Goppert's avatar
James Goppert committed
206
 * @return Raw Temperature measurement (raw)
James Goppert's avatar
James Goppert committed
207 208 209
 */
static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg)
{
lm's avatar
lm committed
210 211
	mavlink_raw_pressure_t *p = (mavlink_raw_pressure_t *)&msg->payload[0];
	return (int16_t)(p->temperature);
James Goppert's avatar
James Goppert committed
212 213 214 215 216 217 218 219 220 221
}

/**
 * @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
222
	memcpy( raw_pressure, msg->payload, sizeof(mavlink_raw_pressure_t));
James Goppert's avatar
James Goppert committed
223
}