Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
#ifndef  _MAVLINK_PROTOCOL_H_
2
#define  _MAVLINK_PROTOCOL_H_
3
 
4
#include "string.h"
5
#include "mavlink_types.h"
6
 
7
/*
8
   If you want MAVLink on a system that is native big-endian,
9
   you need to define NATIVE_BIG_ENDIAN
10
*/
11
#ifdef NATIVE_BIG_ENDIAN
12
# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN)
13
#else
14
# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN)
15
#endif
16
 
17
#ifndef MAVLINK_STACK_BUFFER
18
#define MAVLINK_STACK_BUFFER 0
19
#endif
20
 
21
#ifndef MAVLINK_AVOID_GCC_STACK_BUG
22
# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__)
23
#endif
24
 
25
#ifndef MAVLINK_ASSERT
26
#define MAVLINK_ASSERT(x)
27
#endif
28
 
29
#ifndef MAVLINK_START_UART_SEND
30
#define MAVLINK_START_UART_SEND(chan, length)
31
#endif
32
 
33
#ifndef MAVLINK_END_UART_SEND
34
#define MAVLINK_END_UART_SEND(chan, length)
35
#endif
36
 
37
#ifdef MAVLINK_SEPARATE_HELPERS
38
#define MAVLINK_HELPER
39
#else
40
#define MAVLINK_HELPER static inline
41
#include "mavlink_helpers.h"
42
#endif // MAVLINK_SEPARATE_HELPERS
43
 
44
/* always include the prototypes to ensure we don't get out of sync */
45
MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan);
46
#if MAVLINK_CRC_EXTRA
47
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
48
                                                      uint8_t chan, uint8_t length, uint8_t crc_extra);
49
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
50
                                                 uint8_t length, uint8_t crc_extra);
51
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
52
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
53
                                                    uint8_t length, uint8_t crc_extra);
54
#endif
55
#else
56
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
57
                                                      uint8_t chan, uint8_t length);
58
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
59
                                                 uint8_t length);
60
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length);
61
#endif // MAVLINK_CRC_EXTRA
62
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg);
63
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg);
64
MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c);
65
MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status);
66
MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index,
67
                                               uint8_t* r_bit_index, uint8_t* buffer);
68
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
69
MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
70
#endif
71
 
72
/**
73
 * @brief Get the required buffer size for this message
74
 */
75
static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg)
76
{
77
        return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES;
78
}
79
 
80
#if MAVLINK_NEED_BYTE_SWAP
81
static inline void byte_swap_2(char *dst, const char *src)
82
{
83
        dst[0] = src[1];
84
        dst[1] = src[0];
85
}
86
static inline void byte_swap_4(char *dst, const char *src)
87
{
88
        dst[0] = src[3];
89
        dst[1] = src[2];
90
        dst[2] = src[1];
91
        dst[3] = src[0];
92
}
93
static inline void byte_swap_8(char *dst, const char *src)
94
{
95
        dst[0] = src[7];
96
        dst[1] = src[6];
97
        dst[2] = src[5];
98
        dst[3] = src[4];
99
        dst[4] = src[3];
100
        dst[5] = src[2];
101
        dst[6] = src[1];
102
        dst[7] = src[0];
103
}
104
#elif !MAVLINK_ALIGNED_FIELDS
105
static inline void byte_copy_2(char *dst, const char *src)
106
{
107
        dst[0] = src[0];
108
        dst[1] = src[1];
109
}
110
static inline void byte_copy_4(char *dst, const char *src)
111
{
112
        dst[0] = src[0];
113
        dst[1] = src[1];
114
        dst[2] = src[2];
115
        dst[3] = src[3];
116
}
117
static inline void byte_copy_8(char *dst, const char *src)
118
{
119
        memcpy(dst, src, 8);
120
}
121
#endif
122
 
123
#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b
124
#define _mav_put_int8_t(buf, wire_offset, b)  buf[wire_offset] = (int8_t)b
125
#define _mav_put_char(buf, wire_offset, b)    buf[wire_offset] = b
126
 
127
#if MAVLINK_NEED_BYTE_SWAP
128
#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b)
129
#define _mav_put_int16_t(buf, wire_offset, b)  byte_swap_2(&buf[wire_offset], (const char *)&b)
130
#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
131
#define _mav_put_int32_t(buf, wire_offset, b)  byte_swap_4(&buf[wire_offset], (const char *)&b)
132
#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
133
#define _mav_put_int64_t(buf, wire_offset, b)  byte_swap_8(&buf[wire_offset], (const char *)&b)
134
#define _mav_put_float(buf, wire_offset, b)    byte_swap_4(&buf[wire_offset], (const char *)&b)
135
#define _mav_put_double(buf, wire_offset, b)   byte_swap_8(&buf[wire_offset], (const char *)&b)
136
#elif !MAVLINK_ALIGNED_FIELDS
137
#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b)
138
#define _mav_put_int16_t(buf, wire_offset, b)  byte_copy_2(&buf[wire_offset], (const char *)&b)
139
#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
140
#define _mav_put_int32_t(buf, wire_offset, b)  byte_copy_4(&buf[wire_offset], (const char *)&b)
141
#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
142
#define _mav_put_int64_t(buf, wire_offset, b)  byte_copy_8(&buf[wire_offset], (const char *)&b)
143
#define _mav_put_float(buf, wire_offset, b)    byte_copy_4(&buf[wire_offset], (const char *)&b)
144
#define _mav_put_double(buf, wire_offset, b)   byte_copy_8(&buf[wire_offset], (const char *)&b)
145
#else
146
#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b
147
#define _mav_put_int16_t(buf, wire_offset, b)  *(int16_t *)&buf[wire_offset] = b
148
#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b
149
#define _mav_put_int32_t(buf, wire_offset, b)  *(int32_t *)&buf[wire_offset] = b
150
#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b
151
#define _mav_put_int64_t(buf, wire_offset, b)  *(int64_t *)&buf[wire_offset] = b
152
#define _mav_put_float(buf, wire_offset, b)    *(float *)&buf[wire_offset] = b
153
#define _mav_put_double(buf, wire_offset, b)   *(double *)&buf[wire_offset] = b
154
#endif
155
 
156
/*
157
  like memcpy(), but if src is NULL, do a memset to zero
158
*/
159
static void mav_array_memcpy(void *dest, const void *src, size_t n)
160
{
161
        if (src == NULL) {
162
                memset(dest, 0, n);
163
        } else {
164
                memcpy(dest, src, n);
165
        }
166
}
167
 
168
/*
169
 * Place a char array into a buffer
170
 */
171
static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length)
172
{
173
        mav_array_memcpy(&buf[wire_offset], b, array_length);
174
 
175
}
176
 
177
/*
178
 * Place a uint8_t array into a buffer
179
 */
180
static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
181
{
182
        mav_array_memcpy(&buf[wire_offset], b, array_length);
183
 
184
}
185
 
186
/*
187
 * Place a int8_t array into a buffer
188
 */
189
static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length)
190
{
191
        mav_array_memcpy(&buf[wire_offset], b, array_length);
192
 
193
}
194
 
195
#if MAVLINK_NEED_BYTE_SWAP
196
#define _MAV_PUT_ARRAY(TYPE, V) \
197
static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
198
{ \
199
        if (b == NULL) { \
200
                memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \
201
        } else { \
202
                uint16_t i; \
203
                for (i=0; i<array_length; i++) { \
204
                        _mav_put_## TYPE (buf, wire_offset+(i*sizeof(TYPE)), b[i]); \
205
                } \
206
        } \
207
}
208
#else
209
#define _MAV_PUT_ARRAY(TYPE, V)                                 \
210
static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
211
{ \
212
        mav_array_memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \
213
}
214
#endif
215
 
216
_MAV_PUT_ARRAY(uint16_t, u16)
217
_MAV_PUT_ARRAY(uint32_t, u32)
218
_MAV_PUT_ARRAY(uint64_t, u64)
219
_MAV_PUT_ARRAY(int16_t,  i16)
220
_MAV_PUT_ARRAY(int32_t,  i32)
221
_MAV_PUT_ARRAY(int64_t,  i64)
222
_MAV_PUT_ARRAY(float,    f)
223
_MAV_PUT_ARRAY(double,   d)
224
 
225
#define _MAV_RETURN_char(msg, wire_offset)             (const char)_MAV_PAYLOAD(msg)[wire_offset]
226
#define _MAV_RETURN_int8_t(msg, wire_offset)   (const int8_t)_MAV_PAYLOAD(msg)[wire_offset]
227
#define _MAV_RETURN_uint8_t(msg, wire_offset) (const uint8_t)_MAV_PAYLOAD(msg)[wire_offset]
228
 
229
#if MAVLINK_NEED_BYTE_SWAP
230
#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
231
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
232
{ TYPE r; byte_swap_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
233
 
234
_MAV_MSG_RETURN_TYPE(uint16_t, 2)
235
_MAV_MSG_RETURN_TYPE(int16_t,  2)
236
_MAV_MSG_RETURN_TYPE(uint32_t, 4)
237
_MAV_MSG_RETURN_TYPE(int32_t,  4)
238
_MAV_MSG_RETURN_TYPE(uint64_t, 8)
239
_MAV_MSG_RETURN_TYPE(int64_t,  8)
240
_MAV_MSG_RETURN_TYPE(float,    4)
241
_MAV_MSG_RETURN_TYPE(double,   8)
242
 
243
#elif !MAVLINK_ALIGNED_FIELDS
244
#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
245
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
246
{ TYPE r; byte_copy_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
247
 
248
_MAV_MSG_RETURN_TYPE(uint16_t, 2)
249
_MAV_MSG_RETURN_TYPE(int16_t,  2)
250
_MAV_MSG_RETURN_TYPE(uint32_t, 4)
251
_MAV_MSG_RETURN_TYPE(int32_t,  4)
252
_MAV_MSG_RETURN_TYPE(uint64_t, 8)
253
_MAV_MSG_RETURN_TYPE(int64_t,  8)
254
_MAV_MSG_RETURN_TYPE(float,    4)
255
_MAV_MSG_RETURN_TYPE(double,   8)
256
#else // nicely aligned, no swap
257
#define _MAV_MSG_RETURN_TYPE(TYPE) \
258
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
259
{ return *(const TYPE *)(&_MAV_PAYLOAD(msg)[ofs]);}
260
 
261
_MAV_MSG_RETURN_TYPE(uint16_t)
262
_MAV_MSG_RETURN_TYPE(int16_t)
263
_MAV_MSG_RETURN_TYPE(uint32_t)
264
_MAV_MSG_RETURN_TYPE(int32_t)
265
_MAV_MSG_RETURN_TYPE(uint64_t)
266
_MAV_MSG_RETURN_TYPE(int64_t)
267
_MAV_MSG_RETURN_TYPE(float)
268
_MAV_MSG_RETURN_TYPE(double)
269
#endif // MAVLINK_NEED_BYTE_SWAP
270
 
271
static inline uint16_t _MAV_RETURN_char_array(const mavlink_message_t *msg, char *value,
272
                                                     uint8_t array_length, uint8_t wire_offset)
273
{
274
        memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
275
        return array_length;
276
}
277
 
278
static inline uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value,
279
                                                        uint8_t array_length, uint8_t wire_offset)
280
{
281
        memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
282
        return array_length;
283
}
284
 
285
static inline uint16_t _MAV_RETURN_int8_t_array(const mavlink_message_t *msg, int8_t *value,
286
                                                       uint8_t array_length, uint8_t wire_offset)
287
{
288
        memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
289
        return array_length;
290
}
291
 
292
#if MAVLINK_NEED_BYTE_SWAP
293
#define _MAV_RETURN_ARRAY(TYPE, V) \
294
static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
295
                                                         uint8_t array_length, uint8_t wire_offset) \
296
{ \
297
        uint16_t i; \
298
        for (i=0; i<array_length; i++) { \
299
                value[i] = _MAV_RETURN_## TYPE (msg, wire_offset+(i*sizeof(value[0]))); \
300
        } \
301
        return array_length*sizeof(value[0]); \
302
}
303
#else
304
#define _MAV_RETURN_ARRAY(TYPE, V)                                      \
305
static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
306
                                                         uint8_t array_length, uint8_t wire_offset) \
307
{ \
308
        memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length*sizeof(TYPE)); \
309
        return array_length*sizeof(TYPE); \
310
}
311
#endif
312
 
313
_MAV_RETURN_ARRAY(uint16_t, u16)
314
_MAV_RETURN_ARRAY(uint32_t, u32)
315
_MAV_RETURN_ARRAY(uint64_t, u64)
316
_MAV_RETURN_ARRAY(int16_t,  i16)
317
_MAV_RETURN_ARRAY(int32_t,  i32)
318
_MAV_RETURN_ARRAY(int64_t,  i64)
319
_MAV_RETURN_ARRAY(float,    f)
320
_MAV_RETURN_ARRAY(double,   d)
321
 
322
#endif // _MAVLINK_PROTOCOL_H_