protocol.h 11.4 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3 4 5 6
#ifndef  _MAVLINK_PROTOCOL_H_
#define  _MAVLINK_PROTOCOL_H_

#include "string.h"
#include "mavlink_types.h"

lm's avatar
lm committed
7 8 9 10 11 12 13 14 15 16 17 18 19 20
/* 
   If you want MAVLink on a system that is native big-endian,
   you need to define NATIVE_BIG_ENDIAN
*/
#ifdef NATIVE_BIG_ENDIAN
# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN)
#else
# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN)
#endif

#ifndef MAVLINK_STACK_BUFFER
#define MAVLINK_STACK_BUFFER 0
#endif

LM's avatar
LM committed
21 22 23 24
#ifndef MAVLINK_AVOID_GCC_STACK_BUG
# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__)
#endif

lm's avatar
lm committed
25 26 27 28
#ifndef MAVLINK_ASSERT
#define MAVLINK_ASSERT(x)
#endif

LM's avatar
LM committed
29 30 31 32 33 34 35 36
#ifndef MAVLINK_START_UART_SEND
#define MAVLINK_START_UART_SEND(chan, length)
#endif

#ifndef MAVLINK_END_UART_SEND
#define MAVLINK_END_UART_SEND(chan, length)
#endif

lm's avatar
lm committed
37 38 39 40 41 42 43 44 45
#ifdef MAVLINK_SEPARATE_HELPERS
#define MAVLINK_HELPER
#else
#define MAVLINK_HELPER static inline
#include "mavlink_helpers.h"
#endif // MAVLINK_SEPARATE_HELPERS

/* always include the prototypes to ensure we don't get out of sync */
MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan);
LM's avatar
LM committed
46
#if MAVLINK_CRC_EXTRA
lm's avatar
lm committed
47
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, 
lm's avatar
lm committed
48
						      uint8_t chan, uint8_t length, uint8_t crc_extra);
lm's avatar
lm committed
49
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, 
lm's avatar
lm committed
50
						 uint8_t length, uint8_t crc_extra);
51
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
LM's avatar
LM committed
52 53
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, 
						    uint8_t length, uint8_t crc_extra);
54
#endif
LM's avatar
LM committed
55 56
#else
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, 
lm's avatar
lm committed
57
						      uint8_t chan, uint8_t length);
LM's avatar
LM committed
58
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, 
lm's avatar
lm committed
59
						 uint8_t length);
LM's avatar
LM committed
60
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length);
LM's avatar
LM committed
61
#endif // MAVLINK_CRC_EXTRA
lm's avatar
lm committed
62 63 64 65 66 67 68
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg);
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg);
MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c);
MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status);
MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, 
					       uint8_t* r_bit_index, uint8_t* buffer);
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
LM's avatar
LM committed
69
MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
lm's avatar
lm committed
70 71 72 73 74 75 76 77 78 79
#endif

/**
 * @brief Get the required buffer size for this message
 */
static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg)
{
	return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES;
}

LM's avatar
LM committed
80
#if MAVLINK_NEED_BYTE_SWAP
LM's avatar
LM committed
81
static inline void byte_swap_2(char *dst, const char *src)
lm's avatar
lm committed
82
{
LM's avatar
LM committed
83 84
	dst[0] = src[1];
	dst[1] = src[0];
lm's avatar
lm committed
85
}
LM's avatar
LM committed
86
static inline void byte_swap_4(char *dst, const char *src)
lm's avatar
lm committed
87
{
LM's avatar
LM committed
88 89 90 91
	dst[0] = src[3];
	dst[1] = src[2];
	dst[2] = src[1];
	dst[3] = src[0];
lm's avatar
lm committed
92
}
LM's avatar
LM committed
93
static inline void byte_swap_8(char *dst, const char *src)
James Goppert's avatar
James Goppert committed
94
{
LM's avatar
LM committed
95 96 97 98 99 100 101 102
	dst[0] = src[7];
	dst[1] = src[6];
	dst[2] = src[5];
	dst[3] = src[4];
	dst[4] = src[3];
	dst[5] = src[2];
	dst[6] = src[1];
	dst[7] = src[0];
James Goppert's avatar
James Goppert committed
103
}
LM's avatar
LM committed
104
#elif !MAVLINK_ALIGNED_FIELDS
LM's avatar
LM committed
105
static inline void byte_copy_2(char *dst, const char *src)
James Goppert's avatar
James Goppert committed
106
{
LM's avatar
LM committed
107 108
	dst[0] = src[0];
	dst[1] = src[1];
James Goppert's avatar
James Goppert committed
109
}
LM's avatar
LM committed
110
static inline void byte_copy_4(char *dst, const char *src)
lm's avatar
lm committed
111
{
LM's avatar
LM committed
112 113 114 115
	dst[0] = src[0];
	dst[1] = src[1];
	dst[2] = src[2];
	dst[3] = src[3];
lm's avatar
lm committed
116
}
LM's avatar
LM committed
117
static inline void byte_copy_8(char *dst, const char *src)
James Goppert's avatar
James Goppert committed
118
{
LM's avatar
LM committed
119
	memcpy(dst, src, 8);
James Goppert's avatar
James Goppert committed
120
}
lm's avatar
lm committed
121 122
#endif

LM's avatar
LM committed
123 124 125
#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b
#define _mav_put_int8_t(buf, wire_offset, b)  buf[wire_offset] = (int8_t)b
#define _mav_put_char(buf, wire_offset, b)    buf[wire_offset] = b
James Goppert's avatar
James Goppert committed
126

lm's avatar
lm committed
127
#if MAVLINK_NEED_BYTE_SWAP
LM's avatar
LM committed
128 129 130 131 132 133 134 135
#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b)
#define _mav_put_int16_t(buf, wire_offset, b)  byte_swap_2(&buf[wire_offset], (const char *)&b)
#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_int32_t(buf, wire_offset, b)  byte_swap_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
#define _mav_put_int64_t(buf, wire_offset, b)  byte_swap_8(&buf[wire_offset], (const char *)&b)
#define _mav_put_float(buf, wire_offset, b)    byte_swap_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_double(buf, wire_offset, b)   byte_swap_8(&buf[wire_offset], (const char *)&b)
LM's avatar
LM committed
136
#elif !MAVLINK_ALIGNED_FIELDS
LM's avatar
LM committed
137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153
#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b)
#define _mav_put_int16_t(buf, wire_offset, b)  byte_copy_2(&buf[wire_offset], (const char *)&b)
#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_int32_t(buf, wire_offset, b)  byte_copy_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
#define _mav_put_int64_t(buf, wire_offset, b)  byte_copy_8(&buf[wire_offset], (const char *)&b)
#define _mav_put_float(buf, wire_offset, b)    byte_copy_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_double(buf, wire_offset, b)   byte_copy_8(&buf[wire_offset], (const char *)&b)
#else
#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b
#define _mav_put_int16_t(buf, wire_offset, b)  *(int16_t *)&buf[wire_offset] = b
#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b
#define _mav_put_int32_t(buf, wire_offset, b)  *(int32_t *)&buf[wire_offset] = b
#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b
#define _mav_put_int64_t(buf, wire_offset, b)  *(int64_t *)&buf[wire_offset] = b
#define _mav_put_float(buf, wire_offset, b)    *(float *)&buf[wire_offset] = b
#define _mav_put_double(buf, wire_offset, b)   *(double *)&buf[wire_offset] = b
lm's avatar
lm committed
154
#endif
James Goppert's avatar
James Goppert committed
155 156


lm's avatar
lm committed
157 158 159
/*
 * Place a char array into a buffer
 */
LM's avatar
LM committed
160
static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length)
lm's avatar
lm committed
161
{
LM's avatar
LM committed
162
	if (b == NULL) {
LM's avatar
LM committed
163
		memset(&buf[wire_offset], 0, array_length);
LM's avatar
LM committed
164
	} else {
LM's avatar
LM committed
165
		memcpy(&buf[wire_offset], b, array_length);
LM's avatar
LM committed
166
	}
lm's avatar
lm committed
167
}
James Goppert's avatar
James Goppert committed
168

lm's avatar
lm committed
169 170 171
/*
 * Place a uint8_t array into a buffer
 */
LM's avatar
LM committed
172
static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
lm's avatar
lm committed
173
{
LM's avatar
LM committed
174
	if (b == NULL) {
LM's avatar
LM committed
175
		memset(&buf[wire_offset], 0, array_length);
LM's avatar
LM committed
176
	} else {
LM's avatar
LM committed
177
		memcpy(&buf[wire_offset], b, array_length);
LM's avatar
LM committed
178
	}
lm's avatar
lm committed
179
}
James Goppert's avatar
James Goppert committed
180

lm's avatar
lm committed
181 182 183
/*
 * Place a int8_t array into a buffer
 */
LM's avatar
LM committed
184
static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length)
James Goppert's avatar
James Goppert committed
185
{
LM's avatar
LM committed
186
	if (b == NULL) {
LM's avatar
LM committed
187
		memset(&buf[wire_offset], 0, array_length);
LM's avatar
LM committed
188
	} else {
LM's avatar
LM committed
189
		memcpy(&buf[wire_offset], b, array_length);
LM's avatar
LM committed
190
	}
lm's avatar
lm committed
191 192 193
}

#if MAVLINK_NEED_BYTE_SWAP
LM's avatar
LM committed
194 195
#define _MAV_PUT_ARRAY(TYPE, V) \
static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
lm's avatar
lm committed
196
{ \
LM's avatar
LM committed
197
	if (b == NULL) { \
LM's avatar
LM committed
198
		memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \
LM's avatar
LM committed
199 200 201
	} else { \
		uint16_t i; \
		for (i=0; i<array_length; i++) { \
LM's avatar
LM committed
202
			_mav_put_## TYPE (buf, wire_offset+(i*sizeof(TYPE)), b[i]); \
LM's avatar
LM committed
203
		} \
lm's avatar
lm committed
204 205 206
	} \
}
#else
LM's avatar
LM committed
207 208
#define _MAV_PUT_ARRAY(TYPE, V)					\
static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
lm's avatar
lm committed
209
{ \
LM's avatar
LM committed
210
	if (b == NULL) { \
LM's avatar
LM committed
211
		memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \
LM's avatar
LM committed
212
	} else { \
LM's avatar
LM committed
213
		memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \
LM's avatar
LM committed
214
	} \
James Goppert's avatar
James Goppert committed
215
}
lm's avatar
lm committed
216 217
#endif

LM's avatar
LM committed
218 219 220 221 222 223 224 225
_MAV_PUT_ARRAY(uint16_t, u16)
_MAV_PUT_ARRAY(uint32_t, u32)
_MAV_PUT_ARRAY(uint64_t, u64)
_MAV_PUT_ARRAY(int16_t,  i16)
_MAV_PUT_ARRAY(int32_t,  i32)
_MAV_PUT_ARRAY(int64_t,  i64)
_MAV_PUT_ARRAY(float,    f)
_MAV_PUT_ARRAY(double,   d)
lm's avatar
lm committed
226

LM's avatar
LM committed
227 228 229
#define _MAV_RETURN_char(msg, wire_offset)             _MAV_PAYLOAD(msg)[wire_offset]
#define _MAV_RETURN_int8_t(msg, wire_offset)   (int8_t)_MAV_PAYLOAD(msg)[wire_offset]
#define _MAV_RETURN_uint8_t(msg, wire_offset) (uint8_t)_MAV_PAYLOAD(msg)[wire_offset]
James Goppert's avatar
James Goppert committed
230

lm's avatar
lm committed
231
#if MAVLINK_NEED_BYTE_SWAP
LM's avatar
LM committed
232 233 234
#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
{ TYPE r; byte_swap_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
LM's avatar
LM committed
235

LM's avatar
LM committed
236 237 238 239 240 241 242 243
_MAV_MSG_RETURN_TYPE(uint16_t, 2)
_MAV_MSG_RETURN_TYPE(int16_t,  2)
_MAV_MSG_RETURN_TYPE(uint32_t, 4)
_MAV_MSG_RETURN_TYPE(int32_t,  4)
_MAV_MSG_RETURN_TYPE(uint64_t, 8)
_MAV_MSG_RETURN_TYPE(int64_t,  8)
_MAV_MSG_RETURN_TYPE(float,    4)
_MAV_MSG_RETURN_TYPE(double,   8)
LM's avatar
LM committed
244 245

#elif !MAVLINK_ALIGNED_FIELDS
LM's avatar
LM committed
246 247 248
#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
{ TYPE r; byte_copy_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
LM's avatar
LM committed
249

LM's avatar
LM committed
250 251 252 253 254 255 256 257 258 259 260 261
_MAV_MSG_RETURN_TYPE(uint16_t, 2)
_MAV_MSG_RETURN_TYPE(int16_t,  2)
_MAV_MSG_RETURN_TYPE(uint32_t, 4)
_MAV_MSG_RETURN_TYPE(int32_t,  4)
_MAV_MSG_RETURN_TYPE(uint64_t, 8)
_MAV_MSG_RETURN_TYPE(int64_t,  8)
_MAV_MSG_RETURN_TYPE(float,    4)
_MAV_MSG_RETURN_TYPE(double,   8)
#else // nicely aligned, no swap
#define _MAV_MSG_RETURN_TYPE(TYPE) \
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
{ return *(const TYPE *)(&_MAV_PAYLOAD(msg)[ofs]);}
LM's avatar
LM committed
262

LM's avatar
LM committed
263 264 265 266 267 268 269 270
_MAV_MSG_RETURN_TYPE(uint16_t)
_MAV_MSG_RETURN_TYPE(int16_t)
_MAV_MSG_RETURN_TYPE(uint32_t)
_MAV_MSG_RETURN_TYPE(int32_t)
_MAV_MSG_RETURN_TYPE(uint64_t)
_MAV_MSG_RETURN_TYPE(int64_t)
_MAV_MSG_RETURN_TYPE(float)
_MAV_MSG_RETURN_TYPE(double)
LM's avatar
LM committed
271
#endif // MAVLINK_NEED_BYTE_SWAP
lm's avatar
lm committed
272

LM's avatar
LM committed
273
static inline uint16_t _MAV_RETURN_char_array(const mavlink_message_t *msg, char *value, 
lm's avatar
lm committed
274
						     uint8_t array_length, uint8_t wire_offset)
lm's avatar
lm committed
275
{
LM's avatar
LM committed
276
	memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
lm's avatar
lm committed
277
	return array_length;
lm's avatar
lm committed
278 279
}

LM's avatar
LM committed
280
static inline uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value, 
lm's avatar
lm committed
281
							uint8_t array_length, uint8_t wire_offset)
lm's avatar
lm committed
282
{
LM's avatar
LM committed
283
	memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
lm's avatar
lm committed
284 285 286
	return array_length;
}

LM's avatar
LM committed
287
static inline uint16_t _MAV_RETURN_int8_t_array(const mavlink_message_t *msg, int8_t *value, 
lm's avatar
lm committed
288 289
						       uint8_t array_length, uint8_t wire_offset)
{
LM's avatar
LM committed
290
	memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
lm's avatar
lm committed
291 292 293 294
	return array_length;
}

#if MAVLINK_NEED_BYTE_SWAP
LM's avatar
LM committed
295 296
#define _MAV_RETURN_ARRAY(TYPE, V) \
static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
lm's avatar
lm committed
297 298 299 300
							 uint8_t array_length, uint8_t wire_offset) \
{ \
	uint16_t i; \
	for (i=0; i<array_length; i++) { \
LM's avatar
LM committed
301
		value[i] = _MAV_RETURN_## TYPE (msg, wire_offset+(i*sizeof(value[0]))); \
lm's avatar
lm committed
302 303 304 305
	} \
	return array_length*sizeof(value[0]); \
}
#else
LM's avatar
LM committed
306 307
#define _MAV_RETURN_ARRAY(TYPE, V)					\
static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
lm's avatar
lm committed
308 309
							 uint8_t array_length, uint8_t wire_offset) \
{ \
LM's avatar
LM committed
310
	memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length*sizeof(TYPE)); \
LM's avatar
LM committed
311
	return array_length*sizeof(TYPE); \
lm's avatar
lm committed
312 313 314
}
#endif

LM's avatar
LM committed
315 316 317 318 319 320 321 322
_MAV_RETURN_ARRAY(uint16_t, u16)
_MAV_RETURN_ARRAY(uint32_t, u32)
_MAV_RETURN_ARRAY(uint64_t, u64)
_MAV_RETURN_ARRAY(int16_t,  i16)
_MAV_RETURN_ARRAY(int32_t,  i32)
_MAV_RETURN_ARRAY(int64_t,  i64)
_MAV_RETURN_ARRAY(float,    f)
_MAV_RETURN_ARRAY(double,   d)
lm's avatar
lm committed
323 324

#endif // _MAVLINK_PROTOCOL_H_