1 #ifndef _MAVLINK_PROTOCOL_H_ 2 #define _MAVLINK_PROTOCOL_H_ 11 #ifdef NATIVE_BIG_ENDIAN 12 # define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN) 14 # define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN) 17 #ifndef MAVLINK_STACK_BUFFER 18 #define MAVLINK_STACK_BUFFER 0 21 #ifndef MAVLINK_AVOID_GCC_STACK_BUG 22 # define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__) 25 #ifndef MAVLINK_ASSERT 26 #define MAVLINK_ASSERT(x) 29 #ifndef MAVLINK_START_UART_SEND 30 #define MAVLINK_START_UART_SEND(chan, length) 33 #ifndef MAVLINK_END_UART_SEND 34 #define MAVLINK_END_UART_SEND(chan, length) 38 #ifdef MAVLINK_SEPARATE_HELPERS 40 #define MAVLINK_HELPER 43 #ifndef MAVLINK_GET_CHANNEL_STATUS 49 uint8_t chan, uint8_t length, uint8_t crc_extra);
51 uint8_t length, uint8_t crc_extra);
52 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 54 uint8_t length, uint8_t crc_extra);
58 uint8_t chan, uint8_t length);
61 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 64 #endif // MAVLINK_CRC_EXTRA 71 mavlink_message_t* r_message,
76 uint8_t* r_bit_index, uint8_t*
buffer);
77 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 84 #define MAVLINK_HELPER static inline 87 #endif // MAVLINK_SEPARATE_HELPERS 97 #if MAVLINK_NEED_BYTE_SWAP 121 #elif !MAVLINK_ALIGNED_FIELDS 122 static inline void byte_copy_2(
char *dst,
const char *src)
127 static inline void byte_copy_4(
char *dst,
const char *src)
134 static inline void byte_copy_8(
char *dst,
const char *src)
140 #define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b 141 #define _mav_put_int8_t(buf, wire_offset, b) buf[wire_offset] = (int8_t)b 142 #define _mav_put_char(buf, wire_offset, b) buf[wire_offset] = b 144 #if MAVLINK_NEED_BYTE_SWAP 145 #define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) 146 #define _mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) 147 #define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) 148 #define _mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) 149 #define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) 150 #define _mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) 151 #define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) 152 #define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) 153 #elif !MAVLINK_ALIGNED_FIELDS 154 #define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) 155 #define _mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) 156 #define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) 157 #define _mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) 158 #define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) 159 #define _mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) 160 #define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) 161 #define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) 163 #define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b 164 #define _mav_put_int16_t(buf, wire_offset, b) *(int16_t *)&buf[wire_offset] = b 165 #define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b 166 #define _mav_put_int32_t(buf, wire_offset, b) *(int32_t *)&buf[wire_offset] = b 167 #define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b 168 #define _mav_put_int64_t(buf, wire_offset, b) *(int64_t *)&buf[wire_offset] = b 169 #define _mav_put_float(buf, wire_offset, b) *(float *)&buf[wire_offset] = b 170 #define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b 181 memcpy(dest, src, n);
188 static inline void _mav_put_char_array(
char *buf, uint8_t wire_offset,
const char *b, uint8_t array_length)
212 #if MAVLINK_NEED_BYTE_SWAP 213 #define _MAV_PUT_ARRAY(TYPE, V) \ 214 static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \ 217 memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \ 220 for (i=0; i<array_length; i++) { \ 221 _mav_put_## TYPE (buf, wire_offset+(i*sizeof(TYPE)), b[i]); \ 226 #define _MAV_PUT_ARRAY(TYPE, V) \ 227 static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \ 229 mav_array_memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \ 242 #define _MAV_RETURN_char(msg, wire_offset) (const char)_MAV_PAYLOAD(msg)[wire_offset] 243 #define _MAV_RETURN_int8_t(msg, wire_offset) (const int8_t)_MAV_PAYLOAD(msg)[wire_offset] 244 #define _MAV_RETURN_uint8_t(msg, wire_offset) (const uint8_t)_MAV_PAYLOAD(msg)[wire_offset] 246 #if MAVLINK_NEED_BYTE_SWAP 247 #define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \ 248 static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \ 249 { TYPE r; byte_swap_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; } 260 #elif !MAVLINK_ALIGNED_FIELDS 261 #define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \ 262 static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \ 263 { TYPE r; byte_copy_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; } 273 #else // nicely aligned, no swap 274 #define _MAV_MSG_RETURN_TYPE(TYPE) \ 275 static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \ 276 { return *(const TYPE *)(&_MAV_PAYLOAD(msg)[ofs]);} 286 #endif // MAVLINK_NEED_BYTE_SWAP 289 uint8_t array_length, uint8_t wire_offset)
291 memcpy(value, &
_MAV_PAYLOAD(msg)[wire_offset], array_length);
296 uint8_t array_length, uint8_t wire_offset)
298 memcpy(value, &
_MAV_PAYLOAD(msg)[wire_offset], array_length);
303 uint8_t array_length, uint8_t wire_offset)
305 memcpy(value, &
_MAV_PAYLOAD(msg)[wire_offset], array_length);
309 #if MAVLINK_NEED_BYTE_SWAP 310 #define _MAV_RETURN_ARRAY(TYPE, V) \ 311 static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \ 312 uint8_t array_length, uint8_t wire_offset) \ 315 for (i=0; i<array_length; i++) { \ 316 value[i] = _MAV_RETURN_## TYPE (msg, wire_offset+(i*sizeof(value[0]))); \ 318 return array_length*sizeof(value[0]); \ 321 #define _MAV_RETURN_ARRAY(TYPE, V) \ 322 static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \ 323 uint8_t array_length, uint8_t wire_offset) \ 325 memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length*sizeof(TYPE)); \ 326 return array_length*sizeof(TYPE); \ 339 #endif // _MAVLINK_PROTOCOL_H_ MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t *r_message, mavlink_status_t *r_mavlink_status)
MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan)
Reset the status of a channel.
static uint16_t _MAV_RETURN_int8_t_array(const mavlink_message_t *msg, int8_t *value, uint8_t array_length, uint8_t wire_offset)
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)
Put a bitfield of length 1-32 bit into the buffer.
static uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t *msg)
Get the required buffer size for this message.
#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE)
MAVLINK_HELPER mavlink_status_t * mavlink_get_channel_status(uint8_t chan)
#define MAVLINK_NUM_NON_PAYLOAD_BYTES
static uint8_t buffer[BMP280_DATA_FRAME_SIZE]
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
static void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
#define _MAV_RETURN_ARRAY(TYPE, V)
static volatile uint8_t * status
static void byte_swap_4(char *dst, const char *src)
#define _MAV_PAYLOAD(msg)
static void byte_swap_2(char *dst, const char *src)
MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t *msg, uint8_t c)
#define _MAV_PUT_ARRAY(TYPE, V)
MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t *rxmsg, mavlink_status_t *status, uint8_t c, mavlink_message_t *r_message, mavlink_status_t *r_mavlink_status)
static void mav_array_memcpy(void *dest, const void *src, size_t n)
static uint16_t _MAV_RETURN_char_array(const mavlink_message_t *msg, char *value, uint8_t array_length, uint8_t wire_offset)
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg)
Pack a message to send it over a serial byte stream.
static uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value, uint8_t array_length, uint8_t wire_offset)
static void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length)
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t *msg)
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
static void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length)
static void byte_swap_8(char *dst, const char *src)