1 #ifndef  _MAVLINK_HELPERS_H_     2 #define  _MAVLINK_HELPERS_H_    10 #define MAVLINK_HELPER    16 #ifndef MAVLINK_GET_CHANNEL_STATUS    19 #ifdef MAVLINK_EXTERNAL_RX_STATUS    25         return &m_mavlink_status[chan];
    32 #ifndef MAVLINK_GET_CHANNEL_BUFFER    36 #ifdef MAVLINK_EXTERNAL_RX_BUFFER    42         return &m_mavlink_buffer[chan];
    69                                                       uint8_t chan, uint8_t length, uint8_t crc_extra)
    72                                                       uint8_t chan, uint8_t length)
    78         msg->sysid = system_id;
    79         msg->compid = component_id;
   100                                                  uint8_t length, uint8_t crc_extra)
   112 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS   118 #if MAVLINK_CRC_EXTRA   120                                                     uint8_t length, uint8_t crc_extra)
   132         buf[3] = mavlink_system.sysid;
   133         buf[4] = mavlink_system.compid;
   138 #if MAVLINK_CRC_EXTRA   141         ck[0] = (uint8_t)(checksum & 0xFF);
   142         ck[1] = (uint8_t)(checksum >> 8);
   146         _mavlink_send_uart(chan, packet, length);
   147         _mavlink_send_uart(chan, (
const char *)ck, 2);
   159         ck[0] = (uint8_t)(msg->checksum & 0xFF);
   160         ck[1] = (uint8_t)(msg->checksum >> 8);
   166         _mavlink_send_uart(chan, (
const char *)ck, 2);
   169 #endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS   180         ck[0] = (uint8_t)(msg->checksum & 0xFF);
   181         ck[1] = (uint8_t)(msg->checksum >> 8);
   243                                                  mavlink_message_t* r_message, 
   250 #if MAVLINK_CRC_EXTRA   251 #ifndef MAVLINK_MESSAGE_CRC   253 #define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid]   263 #ifdef MAVLINK_CHECK_MESSAGE_LENGTH   264 #ifndef MAVLINK_MESSAGE_LENGTH   266 #define MAVLINK_MESSAGE_LENGTH(msgid) mavlink_message_lengths[msgid]   330 #ifdef MAVLINK_CHECK_MESSAGE_LENGTH   331                 if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(c))
   360 #if MAVLINK_CRC_EXTRA   363                 if (c != (rxmsg->checksum & 0xFF)) {
   382                 memcpy(r_message, rxmsg, 
sizeof(mavlink_message_t));
   402         r_message->len = rxmsg->len; 
   548         uint16_t bits_remain = bits;
   551         uint8_t i_bit_index, i_byte_index, curr_bits_n;
   552 #if MAVLINK_NEED_BYTE_SWAP   558         bout.b[0] = bin.b[3];
   559         bout.b[1] = bin.b[2];
   560         bout.b[2] = bin.b[1];
   561         bout.b[3] = bin.b[0];
   583         i_bit_index = bit_index;
   584         i_byte_index = packet_index;
   593         while (bits_remain > 0)
   602                 if (bits_remain <= (uint8_t)(8 - i_bit_index))
   605                         curr_bits_n = (uint8_t)bits_remain;
   609                         curr_bits_n = (8 - i_bit_index);
   614                 buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n));
   616                 buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v);
   619                 i_bit_index += curr_bits_n;
   622                 bits_remain -= curr_bits_n;
   631         *r_bit_index = i_bit_index;
   633         if (i_bit_index != 7) i_byte_index++;
   634         return i_byte_index - packet_index;
   637 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS   662 #ifdef MAVLINK_SEND_UART_BYTES   665         MAVLINK_SEND_UART_BYTES(chan, (
const uint8_t *)buf, len);
   669         for (i = 0; i < len; i++) {
   670                 comm_send_ch(chan, (uint8_t)buf[i]);
   674 #endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS 
#define MAVLINK_MESSAGE_LENGTHS
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. 
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. 
MAVLINK_HELPER mavlink_message_t * mavlink_get_channel_buffer(uint8_t chan)
static uint16_t crc_calculate(const uint8_t *pBuffer, uint16_t length)
Calculates the X.25 checksum on a byte buffer. 
MAVLINK_HELPER mavlink_status_t * mavlink_get_channel_status(uint8_t chan)
#define mavlink_ck_a(msg)
#define MAVLINK_NUM_NON_PAYLOAD_BYTES
#define MAVLINK_MESSAGE_CRCS
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 crc_accumulate(uint8_t data, uint16_t *crcAccum)
Accumulate the X.25 CRC by adding one char at a time. 
#define _MAV_PAYLOAD_NON_CONST(msg)
#define MAVLINK_START_UART_SEND(chan, length)
uint8_t msg_received
Number of received messages. 
static volatile uint8_t * status
mavlink_parse_state_t parse_state
Parsing state machine. 
#define MAVLINK_CORE_HEADER_LEN
Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + mes...
#define mavlink_ck_b(msg)
uint8_t parse_error
Number of parse errors. 
#define _MAV_PAYLOAD(msg)
static void crc_init(uint16_t *crcAccum)
Initiliaze the buffer for the X.25 CRC. 
uint16_t packet_rx_drop_count
Number of packet drops. 
#define MAVLINK_MAX_PAYLOAD_LEN
Maximum payload length. 
static void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint16_t length)
Accumulate the X.25 CRC by adding an array of bytes. 
uint16_t packet_rx_success_count
Received packets. 
#define MAVLINK_NUM_HEADER_BYTES
Length of all header bytes, including core and checksum. 
MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t *msg, uint8_t c)
uint8_t packet_idx
Index in current packet. 
uint8_t current_rx_seq
Sequence number of last packet received. 
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)
#define MAVLINK_END_UART_SEND(chan, length)
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. 
uint8_t buffer_overrun
Number of buffer overruns. 
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t *msg)
uint8_t current_tx_seq
Sequence number of last packet sent. 
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. 
#define MAVLINK_COMM_NUM_BUFFERS