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

#define MAVLINK_MSG_ID_RAW_PRESSURE 29

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
8 9 10 11
	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 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 32 33 34 35
{
	uint16_t i = 0;
	msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;

	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
James Goppert's avatar
James Goppert committed
36 37 38 39
	i += put_int16_t_by_index(press_abs, i, msg->payload); // Absolute pressure (raw)
	i += put_int16_t_by_index(press_diff1, i, msg->payload); // Differential pressure 1 (raw)
	i += put_int16_t_by_index(press_diff2, i, msg->payload); // Differential pressure 2 (raw)
	i += put_int16_t_by_index(temperature, i, msg->payload); // Raw Temperature measurement (raw)
James Goppert's avatar
James Goppert committed
40 41 42 43 44 45 46 47 48 49 50

	return mavlink_finalize_message(msg, system_id, component_id, i);
}

/**
 * @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 59 60 61 62
{
	uint16_t i = 0;
	msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;

	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
James Goppert's avatar
James Goppert committed
63 64 65 66
	i += put_int16_t_by_index(press_abs, i, msg->payload); // Absolute pressure (raw)
	i += put_int16_t_by_index(press_diff1, i, msg->payload); // Differential pressure 1 (raw)
	i += put_int16_t_by_index(press_diff2, i, msg->payload); // Differential pressure 2 (raw)
	i += put_int16_t_by_index(temperature, i, msg->payload); // Raw Temperature measurement (raw)
James Goppert's avatar
James Goppert committed
67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88

	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}

/**
 * @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 95
 */
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

James Goppert's avatar
James Goppert committed
96
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
97 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
{
	mavlink_message_t msg;
	mavlink_msg_raw_pressure_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, press_abs, press_diff1, press_diff2, temperature);
	mavlink_send_uart(chan, &msg);
}

#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)
{
	generic_64bit r;
	r.b[7] = (msg->payload)[0];
	r.b[6] = (msg->payload)[1];
	r.b[5] = (msg->payload)[2];
	r.b[4] = (msg->payload)[3];
	r.b[3] = (msg->payload)[4];
	r.b[2] = (msg->payload)[5];
	r.b[1] = (msg->payload)[6];
	r.b[0] = (msg->payload)[7];
	return (uint64_t)r.ll;
}

/**
 * @brief Get field press_abs from raw_pressure message
 *
James Goppert's avatar
James Goppert committed
128
 * @return Absolute pressure (raw)
James Goppert's avatar
James Goppert committed
129
 */
James Goppert's avatar
James Goppert committed
130
static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
131
{
James Goppert's avatar
James Goppert committed
132 133 134 135
	generic_16bit r;
	r.b[1] = (msg->payload+sizeof(uint64_t))[0];
	r.b[0] = (msg->payload+sizeof(uint64_t))[1];
	return (int16_t)r.s;
James Goppert's avatar
James Goppert committed
136 137 138 139 140
}

/**
 * @brief Get field press_diff1 from raw_pressure message
 *
James Goppert's avatar
James Goppert committed
141
 * @return Differential pressure 1 (raw)
James Goppert's avatar
James Goppert committed
142
 */
James Goppert's avatar
James Goppert committed
143
static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
144
{
James Goppert's avatar
James Goppert committed
145 146 147 148
	generic_16bit r;
	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t))[0];
	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t))[1];
	return (int16_t)r.s;
James Goppert's avatar
James Goppert committed
149 150 151 152 153
}

/**
 * @brief Get field press_diff2 from raw_pressure message
 *
James Goppert's avatar
James Goppert committed
154
 * @return Differential pressure 2 (raw)
James Goppert's avatar
James Goppert committed
155
 */
James Goppert's avatar
James Goppert committed
156
static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
157
{
James Goppert's avatar
James Goppert committed
158 159 160 161
	generic_16bit r;
	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t))[0];
	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t))[1];
	return (int16_t)r.s;
James Goppert's avatar
James Goppert committed
162 163 164 165 166
}

/**
 * @brief Get field temperature from raw_pressure message
 *
James Goppert's avatar
James Goppert committed
167
 * @return Raw Temperature measurement (raw)
James Goppert's avatar
James Goppert committed
168 169 170 171
 */
static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg)
{
	generic_16bit r;
James Goppert's avatar
James Goppert committed
172 173
	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
James Goppert's avatar
James Goppert committed
174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190
	return (int16_t)r.s;
}

/**
 * @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)
{
	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);
}