mavlink_msg_raw_aux.h 11.9 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2
// MESSAGE RAW_AUX PACKING

lm's avatar
lm committed
3
#define MAVLINK_MSG_ID_RAW_AUX 172
James Goppert's avatar
James Goppert committed
4

lm's avatar
lm committed
5
typedef struct __mavlink_raw_aux_t
James Goppert's avatar
James Goppert committed
6
{
lm's avatar
lm committed
7 8 9 10 11 12 13
 int32_t baro; ///< Barometric pressure (hecto Pascal)
 uint16_t adc1; ///< ADC1 (J405 ADC3, LPC2148 AD0.6)
 uint16_t adc2; ///< ADC2 (J405 ADC5, LPC2148 AD0.2)
 uint16_t adc3; ///< ADC3 (J405 ADC6, LPC2148 AD0.1)
 uint16_t adc4; ///< ADC4 (J405 ADC7, LPC2148 AD1.3)
 uint16_t vbat; ///< Battery voltage
 int16_t temp; ///< Temperature (degrees celcius)
James Goppert's avatar
James Goppert committed
14 15
} mavlink_raw_aux_t;

lm's avatar
lm committed
16 17 18
#define MAVLINK_MSG_ID_RAW_AUX_LEN 16
#define MAVLINK_MSG_ID_172_LEN 16

Lorenz Meier's avatar
Lorenz Meier committed
19 20 21
#define MAVLINK_MSG_ID_RAW_AUX_CRC 182
#define MAVLINK_MSG_ID_172_CRC 182

lm's avatar
lm committed
22 23 24 25 26


#define MAVLINK_MESSAGE_INFO_RAW_AUX { \
	"RAW_AUX", \
	7, \
lm's avatar
lm committed
27 28 29 30 31 32 33
	{  { "baro", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_raw_aux_t, baro) }, \
         { "adc1", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_raw_aux_t, adc1) }, \
         { "adc2", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_raw_aux_t, adc2) }, \
         { "adc3", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_raw_aux_t, adc3) }, \
         { "adc4", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_raw_aux_t, adc4) }, \
         { "vbat", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_raw_aux_t, vbat) }, \
         { "temp", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_aux_t, temp) }, \
lm's avatar
lm committed
34 35 36 37
         } \
}


James Goppert's avatar
James Goppert committed
38 39 40 41 42 43 44 45 46 47 48 49 50 51 52
/**
 * @brief Pack a raw_aux 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 adc1 ADC1 (J405 ADC3, LPC2148 AD0.6)
 * @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2)
 * @param adc3 ADC3 (J405 ADC6, LPC2148 AD0.1)
 * @param adc4 ADC4 (J405 ADC7, LPC2148 AD1.3)
 * @param vbat Battery voltage
 * @param temp Temperature (degrees celcius)
 * @param baro Barometric pressure (hecto Pascal)
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
53 54
static inline uint16_t mavlink_msg_raw_aux_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
						       uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro)
James Goppert's avatar
James Goppert committed
55
{
LM's avatar
LM committed
56
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
Lorenz Meier's avatar
Lorenz Meier committed
57
	char buf[MAVLINK_MSG_ID_RAW_AUX_LEN];
LM's avatar
LM committed
58 59 60 61 62 63 64 65
	_mav_put_int32_t(buf, 0, baro);
	_mav_put_uint16_t(buf, 4, adc1);
	_mav_put_uint16_t(buf, 6, adc2);
	_mav_put_uint16_t(buf, 8, adc3);
	_mav_put_uint16_t(buf, 10, adc4);
	_mav_put_uint16_t(buf, 12, vbat);
	_mav_put_int16_t(buf, 14, temp);

Lorenz Meier's avatar
Lorenz Meier committed
66
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_AUX_LEN);
LM's avatar
LM committed
67 68 69 70 71 72 73 74 75
#else
	mavlink_raw_aux_t packet;
	packet.baro = baro;
	packet.adc1 = adc1;
	packet.adc2 = adc2;
	packet.adc3 = adc3;
	packet.adc4 = adc4;
	packet.vbat = vbat;
	packet.temp = temp;
James Goppert's avatar
James Goppert committed
76

Lorenz Meier's avatar
Lorenz Meier committed
77
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_AUX_LEN);
LM's avatar
LM committed
78
#endif
James Goppert's avatar
James Goppert committed
79

LM's avatar
LM committed
80
	msg->msgid = MAVLINK_MSG_ID_RAW_AUX;
Lorenz Meier's avatar
Lorenz Meier committed
81 82 83 84 85
#if MAVLINK_CRC_EXTRA
    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_AUX_LEN, MAVLINK_MSG_ID_RAW_AUX_CRC);
#else
    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_AUX_LEN);
#endif
James Goppert's avatar
James Goppert committed
86 87 88
}

/**
lm's avatar
lm committed
89
 * @brief Pack a raw_aux message on a channel
James Goppert's avatar
James Goppert committed
90 91
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
Lorenz Meier's avatar
Lorenz Meier committed
92
 * @param chan The MAVLink channel this message will be sent over
James Goppert's avatar
James Goppert committed
93 94 95 96 97 98 99 100 101 102
 * @param msg The MAVLink message to compress the data into
 * @param adc1 ADC1 (J405 ADC3, LPC2148 AD0.6)
 * @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2)
 * @param adc3 ADC3 (J405 ADC6, LPC2148 AD0.1)
 * @param adc4 ADC4 (J405 ADC7, LPC2148 AD1.3)
 * @param vbat Battery voltage
 * @param temp Temperature (degrees celcius)
 * @param baro Barometric pressure (hecto Pascal)
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
103 104 105
static inline uint16_t mavlink_msg_raw_aux_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
						           uint16_t adc1,uint16_t adc2,uint16_t adc3,uint16_t adc4,uint16_t vbat,int16_t temp,int32_t baro)
James Goppert's avatar
James Goppert committed
106
{
LM's avatar
LM committed
107
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
Lorenz Meier's avatar
Lorenz Meier committed
108
	char buf[MAVLINK_MSG_ID_RAW_AUX_LEN];
LM's avatar
LM committed
109 110 111 112 113 114 115
	_mav_put_int32_t(buf, 0, baro);
	_mav_put_uint16_t(buf, 4, adc1);
	_mav_put_uint16_t(buf, 6, adc2);
	_mav_put_uint16_t(buf, 8, adc3);
	_mav_put_uint16_t(buf, 10, adc4);
	_mav_put_uint16_t(buf, 12, vbat);
	_mav_put_int16_t(buf, 14, temp);
James Goppert's avatar
James Goppert committed
116

Lorenz Meier's avatar
Lorenz Meier committed
117
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_AUX_LEN);
LM's avatar
LM committed
118 119 120 121 122 123 124 125 126
#else
	mavlink_raw_aux_t packet;
	packet.baro = baro;
	packet.adc1 = adc1;
	packet.adc2 = adc2;
	packet.adc3 = adc3;
	packet.adc4 = adc4;
	packet.vbat = vbat;
	packet.temp = temp;
James Goppert's avatar
James Goppert committed
127

Lorenz Meier's avatar
Lorenz Meier committed
128
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_AUX_LEN);
LM's avatar
LM committed
129 130 131
#endif

	msg->msgid = MAVLINK_MSG_ID_RAW_AUX;
Lorenz Meier's avatar
Lorenz Meier committed
132 133 134 135 136
#if MAVLINK_CRC_EXTRA
    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_AUX_LEN, MAVLINK_MSG_ID_RAW_AUX_CRC);
#else
    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_AUX_LEN);
#endif
James Goppert's avatar
James Goppert committed
137 138 139
}

/**
Lorenz Meier's avatar
Lorenz Meier committed
140
 * @brief Encode a raw_aux struct
James Goppert's avatar
James Goppert committed
141 142 143 144 145 146 147 148 149
 *
 * @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_aux C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_raw_aux_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_aux_t* raw_aux)
{
	return mavlink_msg_raw_aux_pack(system_id, component_id, msg, raw_aux->adc1, raw_aux->adc2, raw_aux->adc3, raw_aux->adc4, raw_aux->vbat, raw_aux->temp, raw_aux->baro);
Lorenz Meier's avatar
Lorenz Meier committed
150 151 152 153 154 155 156 157 158 159 160 161 162 163
}

/**
 * @brief Encode a raw_aux struct on a channel
 *
 * @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 will be sent over
 * @param msg The MAVLink message to compress the data into
 * @param raw_aux C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_raw_aux_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_aux_t* raw_aux)
{
	return mavlink_msg_raw_aux_pack_chan(system_id, component_id, chan, msg, raw_aux->adc1, raw_aux->adc2, raw_aux->adc3, raw_aux->adc4, raw_aux->vbat, raw_aux->temp, raw_aux->baro);
James Goppert's avatar
James Goppert committed
164 165 166 167 168 169 170 171 172 173 174 175 176 177
}

/**
 * @brief Send a raw_aux message
 * @param chan MAVLink channel to send the message
 *
 * @param adc1 ADC1 (J405 ADC3, LPC2148 AD0.6)
 * @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2)
 * @param adc3 ADC3 (J405 ADC6, LPC2148 AD0.1)
 * @param adc4 ADC4 (J405 ADC7, LPC2148 AD1.3)
 * @param vbat Battery voltage
 * @param temp Temperature (degrees celcius)
 * @param baro Barometric pressure (hecto Pascal)
 */
lm's avatar
lm committed
178 179
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

lm's avatar
lm committed
180 181
static inline void mavlink_msg_raw_aux_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro)
{
LM's avatar
LM committed
182
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
Lorenz Meier's avatar
Lorenz Meier committed
183
	char buf[MAVLINK_MSG_ID_RAW_AUX_LEN];
LM's avatar
LM committed
184 185 186 187 188 189 190
	_mav_put_int32_t(buf, 0, baro);
	_mav_put_uint16_t(buf, 4, adc1);
	_mav_put_uint16_t(buf, 6, adc2);
	_mav_put_uint16_t(buf, 8, adc3);
	_mav_put_uint16_t(buf, 10, adc4);
	_mav_put_uint16_t(buf, 12, vbat);
	_mav_put_int16_t(buf, 14, temp);
LM's avatar
LM committed
191

Lorenz Meier's avatar
Lorenz Meier committed
192 193 194 195 196
#if MAVLINK_CRC_EXTRA
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, buf, MAVLINK_MSG_ID_RAW_AUX_LEN, MAVLINK_MSG_ID_RAW_AUX_CRC);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, buf, MAVLINK_MSG_ID_RAW_AUX_LEN);
#endif
LM's avatar
LM committed
197 198 199 200 201 202 203 204 205
#else
	mavlink_raw_aux_t packet;
	packet.baro = baro;
	packet.adc1 = adc1;
	packet.adc2 = adc2;
	packet.adc3 = adc3;
	packet.adc4 = adc4;
	packet.vbat = vbat;
	packet.temp = temp;
LM's avatar
LM committed
206

Lorenz Meier's avatar
Lorenz Meier committed
207 208 209 210 211
#if MAVLINK_CRC_EXTRA
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, (const char *)&packet, MAVLINK_MSG_ID_RAW_AUX_LEN, MAVLINK_MSG_ID_RAW_AUX_CRC);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, (const char *)&packet, MAVLINK_MSG_ID_RAW_AUX_LEN);
#endif
LM's avatar
LM committed
212
#endif
James Goppert's avatar
James Goppert committed
213 214
}

215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258
#if MAVLINK_MSG_ID_RAW_AUX_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
  This varient of _send() can be used to save stack space by re-using
  memory from the receive buffer.  The caller provides a
  mavlink_message_t which is the size of a full mavlink message. This
  is usually the receive buffer for the channel, and allows a reply to an
  incoming message with minimum stack space usage.
 */
static inline void mavlink_msg_raw_aux_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char *buf = (char *)msgbuf;
	_mav_put_int32_t(buf, 0, baro);
	_mav_put_uint16_t(buf, 4, adc1);
	_mav_put_uint16_t(buf, 6, adc2);
	_mav_put_uint16_t(buf, 8, adc3);
	_mav_put_uint16_t(buf, 10, adc4);
	_mav_put_uint16_t(buf, 12, vbat);
	_mav_put_int16_t(buf, 14, temp);

#if MAVLINK_CRC_EXTRA
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, buf, MAVLINK_MSG_ID_RAW_AUX_LEN, MAVLINK_MSG_ID_RAW_AUX_CRC);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, buf, MAVLINK_MSG_ID_RAW_AUX_LEN);
#endif
#else
	mavlink_raw_aux_t *packet = (mavlink_raw_aux_t *)msgbuf;
	packet->baro = baro;
	packet->adc1 = adc1;
	packet->adc2 = adc2;
	packet->adc3 = adc3;
	packet->adc4 = adc4;
	packet->vbat = vbat;
	packet->temp = temp;

#if MAVLINK_CRC_EXTRA
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, (const char *)packet, MAVLINK_MSG_ID_RAW_AUX_LEN, MAVLINK_MSG_ID_RAW_AUX_CRC);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, (const char *)packet, MAVLINK_MSG_ID_RAW_AUX_LEN);
#endif
#endif
}
#endif

James Goppert's avatar
James Goppert committed
259
#endif
lm's avatar
lm committed
260

James Goppert's avatar
James Goppert committed
261 262
// MESSAGE RAW_AUX UNPACKING

lm's avatar
lm committed
263

James Goppert's avatar
James Goppert committed
264 265 266 267 268 269 270
/**
 * @brief Get field adc1 from raw_aux message
 *
 * @return ADC1 (J405 ADC3, LPC2148 AD0.6)
 */
static inline uint16_t mavlink_msg_raw_aux_get_adc1(const mavlink_message_t* msg)
{
LM's avatar
LM committed
271
	return _MAV_RETURN_uint16_t(msg,  4);
James Goppert's avatar
James Goppert committed
272 273 274 275 276 277 278 279 280
}

/**
 * @brief Get field adc2 from raw_aux message
 *
 * @return ADC2 (J405 ADC5, LPC2148 AD0.2)
 */
static inline uint16_t mavlink_msg_raw_aux_get_adc2(const mavlink_message_t* msg)
{
LM's avatar
LM committed
281
	return _MAV_RETURN_uint16_t(msg,  6);
James Goppert's avatar
James Goppert committed
282 283 284 285 286 287 288 289 290
}

/**
 * @brief Get field adc3 from raw_aux message
 *
 * @return ADC3 (J405 ADC6, LPC2148 AD0.1)
 */
static inline uint16_t mavlink_msg_raw_aux_get_adc3(const mavlink_message_t* msg)
{
LM's avatar
LM committed
291
	return _MAV_RETURN_uint16_t(msg,  8);
James Goppert's avatar
James Goppert committed
292 293 294 295 296 297 298 299 300
}

/**
 * @brief Get field adc4 from raw_aux message
 *
 * @return ADC4 (J405 ADC7, LPC2148 AD1.3)
 */
static inline uint16_t mavlink_msg_raw_aux_get_adc4(const mavlink_message_t* msg)
{
LM's avatar
LM committed
301
	return _MAV_RETURN_uint16_t(msg,  10);
James Goppert's avatar
James Goppert committed
302 303 304 305 306 307 308 309 310
}

/**
 * @brief Get field vbat from raw_aux message
 *
 * @return Battery voltage
 */
static inline uint16_t mavlink_msg_raw_aux_get_vbat(const mavlink_message_t* msg)
{
LM's avatar
LM committed
311
	return _MAV_RETURN_uint16_t(msg,  12);
James Goppert's avatar
James Goppert committed
312 313 314 315 316 317 318 319 320
}

/**
 * @brief Get field temp from raw_aux message
 *
 * @return Temperature (degrees celcius)
 */
static inline int16_t mavlink_msg_raw_aux_get_temp(const mavlink_message_t* msg)
{
LM's avatar
LM committed
321
	return _MAV_RETURN_int16_t(msg,  14);
James Goppert's avatar
James Goppert committed
322 323 324 325 326 327 328 329 330
}

/**
 * @brief Get field baro from raw_aux message
 *
 * @return Barometric pressure (hecto Pascal)
 */
static inline int32_t mavlink_msg_raw_aux_get_baro(const mavlink_message_t* msg)
{
LM's avatar
LM committed
331
	return _MAV_RETURN_int32_t(msg,  0);
James Goppert's avatar
James Goppert committed
332 333 334 335 336 337 338 339 340 341
}

/**
 * @brief Decode a raw_aux message into a struct
 *
 * @param msg The message to decode
 * @param raw_aux C-struct to decode the message contents into
 */
static inline void mavlink_msg_raw_aux_decode(const mavlink_message_t* msg, mavlink_raw_aux_t* raw_aux)
{
lm's avatar
lm committed
342 343 344 345 346 347 348 349 350
#if MAVLINK_NEED_BYTE_SWAP
	raw_aux->baro = mavlink_msg_raw_aux_get_baro(msg);
	raw_aux->adc1 = mavlink_msg_raw_aux_get_adc1(msg);
	raw_aux->adc2 = mavlink_msg_raw_aux_get_adc2(msg);
	raw_aux->adc3 = mavlink_msg_raw_aux_get_adc3(msg);
	raw_aux->adc4 = mavlink_msg_raw_aux_get_adc4(msg);
	raw_aux->vbat = mavlink_msg_raw_aux_get_vbat(msg);
	raw_aux->temp = mavlink_msg_raw_aux_get_temp(msg);
#else
Lorenz Meier's avatar
Lorenz Meier committed
351
	memcpy(raw_aux, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RAW_AUX_LEN);
lm's avatar
lm committed
352
#endif
James Goppert's avatar
James Goppert committed
353
}