mavlink_msg_air_data.h 5.95 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3 4
// MESSAGE AIR_DATA PACKING

#define MAVLINK_MSG_ID_AIR_DATA 171

lm's avatar
lm committed
5
typedef struct __mavlink_air_data_t
James Goppert's avatar
James Goppert committed
6
{
lm's avatar
lm committed
7 8 9
 float dynamicPressure; ///< Dynamic pressure (Pa)
 float staticPressure; ///< Static pressure (Pa)
 uint16_t temperature; ///< Board temperature
James Goppert's avatar
James Goppert committed
10 11
} mavlink_air_data_t;

lm's avatar
lm committed
12 13 14 15 16 17 18 19
#define MAVLINK_MSG_ID_AIR_DATA_LEN 10
#define MAVLINK_MSG_ID_171_LEN 10



#define MAVLINK_MESSAGE_INFO_AIR_DATA { \
	"AIR_DATA", \
	3, \
lm's avatar
lm committed
20 21 22
	{  { "dynamicPressure", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_air_data_t, dynamicPressure) }, \
         { "staticPressure", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_air_data_t, staticPressure) }, \
         { "temperature", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_air_data_t, temperature) }, \
lm's avatar
lm committed
23 24 25 26
         } \
}


James Goppert's avatar
James Goppert committed
27
/**
James Goppert's avatar
James Goppert committed
28 29 30 31
 * @brief Pack a air_data 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
James Goppert's avatar
James Goppert committed
32 33 34 35 36 37
 *
 * @param dynamicPressure Dynamic pressure (Pa)
 * @param staticPressure Static pressure (Pa)
 * @param temperature Board temperature
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
38 39
static inline uint16_t mavlink_msg_air_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
						       float dynamicPressure, float staticPressure, uint16_t temperature)
James Goppert's avatar
James Goppert committed
40
{
LM's avatar
LM committed
41 42 43 44 45 46
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[10];
	_mav_put_float(buf, 0, dynamicPressure);
	_mav_put_float(buf, 4, staticPressure);
	_mav_put_uint16_t(buf, 8, temperature);

47
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 10);
LM's avatar
LM committed
48 49 50 51 52
#else
	mavlink_air_data_t packet;
	packet.dynamicPressure = dynamicPressure;
	packet.staticPressure = staticPressure;
	packet.temperature = temperature;
James Goppert's avatar
James Goppert committed
53

54
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 10);
LM's avatar
LM committed
55
#endif
James Goppert's avatar
James Goppert committed
56

LM's avatar
LM committed
57
	msg->msgid = MAVLINK_MSG_ID_AIR_DATA;
lm's avatar
lm committed
58
	return mavlink_finalize_message(msg, system_id, component_id, 10, 232);
James Goppert's avatar
James Goppert committed
59 60
}

James Goppert's avatar
James Goppert committed
61
/**
lm's avatar
lm committed
62
 * @brief Pack a air_data message on a channel
James Goppert's avatar
James Goppert committed
63 64 65 66 67 68 69 70 71
 * @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 dynamicPressure Dynamic pressure (Pa)
 * @param staticPressure Static pressure (Pa)
 * @param temperature Board temperature
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
72 73 74
static inline uint16_t mavlink_msg_air_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
						           float dynamicPressure,float staticPressure,uint16_t temperature)
James Goppert's avatar
James Goppert committed
75
{
LM's avatar
LM committed
76 77 78 79 80
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[10];
	_mav_put_float(buf, 0, dynamicPressure);
	_mav_put_float(buf, 4, staticPressure);
	_mav_put_uint16_t(buf, 8, temperature);
James Goppert's avatar
James Goppert committed
81

82
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 10);
LM's avatar
LM committed
83 84 85 86 87
#else
	mavlink_air_data_t packet;
	packet.dynamicPressure = dynamicPressure;
	packet.staticPressure = staticPressure;
	packet.temperature = temperature;
James Goppert's avatar
James Goppert committed
88

89
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 10);
LM's avatar
LM committed
90 91 92
#endif

	msg->msgid = MAVLINK_MSG_ID_AIR_DATA;
lm's avatar
lm committed
93
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 10, 232);
James Goppert's avatar
James Goppert committed
94 95
}

James Goppert's avatar
James Goppert committed
96 97 98 99 100 101 102 103
/**
 * @brief Encode a air_data 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 air_data C-struct to read the message contents from
 */
James Goppert's avatar
James Goppert committed
104 105 106 107 108
static inline uint16_t mavlink_msg_air_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_air_data_t* air_data)
{
	return mavlink_msg_air_data_pack(system_id, component_id, msg, air_data->dynamicPressure, air_data->staticPressure, air_data->temperature);
}

James Goppert's avatar
James Goppert committed
109 110 111 112 113 114 115 116
/**
 * @brief Send a air_data message
 * @param chan MAVLink channel to send the message
 *
 * @param dynamicPressure Dynamic pressure (Pa)
 * @param staticPressure Static pressure (Pa)
 * @param temperature Board temperature
 */
lm's avatar
lm committed
117 118
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

lm's avatar
lm committed
119 120
static inline void mavlink_msg_air_data_send(mavlink_channel_t chan, float dynamicPressure, float staticPressure, uint16_t temperature)
{
LM's avatar
LM committed
121 122 123 124 125
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[10];
	_mav_put_float(buf, 0, dynamicPressure);
	_mav_put_float(buf, 4, staticPressure);
	_mav_put_uint16_t(buf, 8, temperature);
LM's avatar
LM committed
126

LM's avatar
LM committed
127 128 129 130 131 132
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIR_DATA, buf, 10, 232);
#else
	mavlink_air_data_t packet;
	packet.dynamicPressure = dynamicPressure;
	packet.staticPressure = staticPressure;
	packet.temperature = temperature;
LM's avatar
LM committed
133

LM's avatar
LM committed
134 135
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIR_DATA, (const char *)&packet, 10, 232);
#endif
James Goppert's avatar
James Goppert committed
136 137 138
}

#endif
lm's avatar
lm committed
139

James Goppert's avatar
James Goppert committed
140 141
// MESSAGE AIR_DATA UNPACKING

lm's avatar
lm committed
142

James Goppert's avatar
James Goppert committed
143 144 145 146 147 148 149
/**
 * @brief Get field dynamicPressure from air_data message
 *
 * @return Dynamic pressure (Pa)
 */
static inline float mavlink_msg_air_data_get_dynamicPressure(const mavlink_message_t* msg)
{
LM's avatar
LM committed
150
	return _MAV_RETURN_float(msg,  0);
James Goppert's avatar
James Goppert committed
151 152 153 154 155 156 157 158 159
}

/**
 * @brief Get field staticPressure from air_data message
 *
 * @return Static pressure (Pa)
 */
static inline float mavlink_msg_air_data_get_staticPressure(const mavlink_message_t* msg)
{
LM's avatar
LM committed
160
	return _MAV_RETURN_float(msg,  4);
James Goppert's avatar
James Goppert committed
161 162 163 164 165 166 167 168 169
}

/**
 * @brief Get field temperature from air_data message
 *
 * @return Board temperature
 */
static inline uint16_t mavlink_msg_air_data_get_temperature(const mavlink_message_t* msg)
{
LM's avatar
LM committed
170
	return _MAV_RETURN_uint16_t(msg,  8);
James Goppert's avatar
James Goppert committed
171 172
}

James Goppert's avatar
James Goppert committed
173 174 175 176 177 178
/**
 * @brief Decode a air_data message into a struct
 *
 * @param msg The message to decode
 * @param air_data C-struct to decode the message contents into
 */
James Goppert's avatar
James Goppert committed
179 180
static inline void mavlink_msg_air_data_decode(const mavlink_message_t* msg, mavlink_air_data_t* air_data)
{
lm's avatar
lm committed
181 182 183 184 185
#if MAVLINK_NEED_BYTE_SWAP
	air_data->dynamicPressure = mavlink_msg_air_data_get_dynamicPressure(msg);
	air_data->staticPressure = mavlink_msg_air_data_get_staticPressure(msg);
	air_data->temperature = mavlink_msg_air_data_get_temperature(msg);
#else
LM's avatar
LM committed
186
	memcpy(air_data, _MAV_PAYLOAD(msg), 10);
lm's avatar
lm committed
187
#endif
James Goppert's avatar
James Goppert committed
188
}