mavlink_msg_scaled_pressure.h 7.2 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2
// MESSAGE SCALED_PRESSURE PACKING

3
#define MAVLINK_MSG_ID_SCALED_PRESSURE 30
James Goppert's avatar
James Goppert committed
4

lm's avatar
lm committed
5
typedef struct __mavlink_scaled_pressure_t
James Goppert's avatar
James Goppert committed
6
{
7
 uint32_t time_boot_ms; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
lm's avatar
lm committed
8 9 10
 float press_abs; ///< Absolute pressure (hectopascal)
 float press_diff; ///< Differential pressure 1 (hectopascal)
 int16_t temperature; ///< Temperature measurement (0.01 degrees celsius)
James Goppert's avatar
James Goppert committed
11 12
} mavlink_scaled_pressure_t;

13 14
#define MAVLINK_MSG_ID_SCALED_PRESSURE_LEN 14
#define MAVLINK_MSG_ID_30_LEN 14
lm's avatar
lm committed
15 16 17 18 19 20



#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE { \
	"SCALED_PRESSURE", \
	4, \
21 22 23 24
	{  { "time_boot_ms", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure_t, time_boot_ms) }, \
         { "press_abs", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure_t, press_abs) }, \
         { "press_diff", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure_t, press_diff) }, \
         { "temperature", MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure_t, temperature) }, \
lm's avatar
lm committed
25 26 27 28
         } \
}


James Goppert's avatar
James Goppert committed
29 30 31 32 33 34
/**
 * @brief Pack a scaled_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
 *
35
 * @param time_boot_ms Timestamp (microseconds since UNIX epoch or microseconds since system boot)
James Goppert's avatar
James Goppert committed
36 37 38 39 40
 * @param press_abs Absolute pressure (hectopascal)
 * @param press_diff Differential pressure 1 (hectopascal)
 * @param temperature Temperature measurement (0.01 degrees celsius)
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
41
static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
42
						       uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature)
James Goppert's avatar
James Goppert committed
43 44 45
{
	msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE;

46 47 48 49
	put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	put_float_by_index(msg, 4, press_abs); // Absolute pressure (hectopascal)
	put_float_by_index(msg, 8, press_diff); // Differential pressure 1 (hectopascal)
	put_int16_t_by_index(msg, 12, temperature); // Temperature measurement (0.01 degrees celsius)
James Goppert's avatar
James Goppert committed
50

51
	return mavlink_finalize_message(msg, system_id, component_id, 14, 115);
James Goppert's avatar
James Goppert committed
52 53 54
}

/**
lm's avatar
lm committed
55
 * @brief Pack a scaled_pressure message on a channel
James Goppert's avatar
James Goppert committed
56 57 58 59
 * @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
60
 * @param time_boot_ms Timestamp (microseconds since UNIX epoch or microseconds since system boot)
James Goppert's avatar
James Goppert committed
61 62 63 64 65
 * @param press_abs Absolute pressure (hectopascal)
 * @param press_diff Differential pressure 1 (hectopascal)
 * @param temperature Temperature measurement (0.01 degrees celsius)
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
66 67
static inline uint16_t mavlink_msg_scaled_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
68
						           uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature)
lm's avatar
lm committed
69 70 71
{
	msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE;

72 73 74 75
	put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	put_float_by_index(msg, 4, press_abs); // Absolute pressure (hectopascal)
	put_float_by_index(msg, 8, press_diff); // Differential pressure 1 (hectopascal)
	put_int16_t_by_index(msg, 12, temperature); // Temperature measurement (0.01 degrees celsius)
lm's avatar
lm committed
76

77
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 115);
lm's avatar
lm committed
78 79
}

James Goppert's avatar
James Goppert committed
80 81 82 83 84 85 86 87 88 89
/**
 * @brief Encode a scaled_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 scaled_pressure C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_scaled_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure)
{
90
	return mavlink_msg_scaled_pressure_pack(system_id, component_id, msg, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature);
James Goppert's avatar
James Goppert committed
91 92 93 94 95 96
}

/**
 * @brief Send a scaled_pressure message
 * @param chan MAVLink channel to send the message
 *
97
 * @param time_boot_ms Timestamp (microseconds since UNIX epoch or microseconds since system boot)
James Goppert's avatar
James Goppert committed
98 99 100 101
 * @param press_abs Absolute pressure (hectopascal)
 * @param press_diff Differential pressure 1 (hectopascal)
 * @param temperature Temperature measurement (0.01 degrees celsius)
 */
lm's avatar
lm committed
102 103
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

104
static inline void mavlink_msg_scaled_pressure_send(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature)
lm's avatar
lm committed
105
{
106
	MAVLINK_ALIGNED_MESSAGE(msg, 14);
LM's avatar
LM committed
107 108
	msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE;

109 110 111 112
	put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	put_float_by_index(msg, 4, press_abs); // Absolute pressure (hectopascal)
	put_float_by_index(msg, 8, press_diff); // Differential pressure 1 (hectopascal)
	put_int16_t_by_index(msg, 12, temperature); // Temperature measurement (0.01 degrees celsius)
LM's avatar
LM committed
113

114
	mavlink_finalize_message_chan_send(msg, chan, 14, 115);
James Goppert's avatar
James Goppert committed
115 116 117
}

#endif
lm's avatar
lm committed
118

James Goppert's avatar
James Goppert committed
119 120
// MESSAGE SCALED_PRESSURE UNPACKING

lm's avatar
lm committed
121

James Goppert's avatar
James Goppert committed
122
/**
123
 * @brief Get field time_boot_ms from scaled_pressure message
James Goppert's avatar
James Goppert committed
124 125 126
 *
 * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
 */
127
static inline uint32_t mavlink_msg_scaled_pressure_get_time_boot_ms(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
128
{
129
	return MAVLINK_MSG_RETURN_uint32_t(msg,  0);
James Goppert's avatar
James Goppert committed
130 131 132 133 134 135 136 137 138
}

/**
 * @brief Get field press_abs from scaled_pressure message
 *
 * @return Absolute pressure (hectopascal)
 */
static inline float mavlink_msg_scaled_pressure_get_press_abs(const mavlink_message_t* msg)
{
139
	return MAVLINK_MSG_RETURN_float(msg,  4);
James Goppert's avatar
James Goppert committed
140 141 142 143 144 145 146 147 148
}

/**
 * @brief Get field press_diff from scaled_pressure message
 *
 * @return Differential pressure 1 (hectopascal)
 */
static inline float mavlink_msg_scaled_pressure_get_press_diff(const mavlink_message_t* msg)
{
149
	return MAVLINK_MSG_RETURN_float(msg,  8);
James Goppert's avatar
James Goppert committed
150 151 152 153 154 155 156 157 158
}

/**
 * @brief Get field temperature from scaled_pressure message
 *
 * @return Temperature measurement (0.01 degrees celsius)
 */
static inline int16_t mavlink_msg_scaled_pressure_get_temperature(const mavlink_message_t* msg)
{
159
	return MAVLINK_MSG_RETURN_int16_t(msg,  12);
James Goppert's avatar
James Goppert committed
160 161 162 163 164 165 166 167 168 169
}

/**
 * @brief Decode a scaled_pressure message into a struct
 *
 * @param msg The message to decode
 * @param scaled_pressure C-struct to decode the message contents into
 */
static inline void mavlink_msg_scaled_pressure_decode(const mavlink_message_t* msg, mavlink_scaled_pressure_t* scaled_pressure)
{
lm's avatar
lm committed
170
#if MAVLINK_NEED_BYTE_SWAP
171
	scaled_pressure->time_boot_ms = mavlink_msg_scaled_pressure_get_time_boot_ms(msg);
lm's avatar
lm committed
172 173 174 175
	scaled_pressure->press_abs = mavlink_msg_scaled_pressure_get_press_abs(msg);
	scaled_pressure->press_diff = mavlink_msg_scaled_pressure_get_press_diff(msg);
	scaled_pressure->temperature = mavlink_msg_scaled_pressure_get_temperature(msg);
#else
176
	memcpy(scaled_pressure, MAVLINK_PAYLOAD(msg), 14);
lm's avatar
lm committed
177
#endif
James Goppert's avatar
James Goppert committed
178
}