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;
84 crc_accumulate_buffer(&msg->checksum,
_MAV_PAYLOAD(msg), msg->len);
86 crc_accumulate(crc_extra, &msg->checksum);
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;
137 crc_accumulate_buffer(&checksum, packet, length);
138 #if MAVLINK_CRC_EXTRA
139 crc_accumulate(crc_extra, &checksum);
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);
198 crc_init(&msg->checksum);
203 crc_accumulate(c, &msg->checksum);
253 #if MAVLINK_CRC_EXTRA
254 #ifndef MAVLINK_MESSAGE_CRC
256 #define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid]
266 #ifdef MAVLINK_CHECK_MESSAGE_LENGTH
267 #ifndef MAVLINK_MESSAGE_LENGTH
269 #define MAVLINK_MESSAGE_LENGTH(msgid) mavlink_message_lengths[msgid]
335 #ifdef MAVLINK_CHECK_MESSAGE_LENGTH
336 if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(c))
365 #if MAVLINK_CRC_EXTRA
368 if (c != (rxmsg->checksum & 0xFF)) {
388 if (c != (rxmsg->checksum >> 8)) {
406 memcpy(r_message, rxmsg,
sizeof(mavlink_message_t));
427 r_message->len = rxmsg->len;
449 uint16_t bits_remain = bits;
452 uint8_t i_bit_index, i_byte_index, curr_bits_n;
453 #if MAVLINK_NEED_BYTE_SWAP
459 bout.b[0] = bin.b[3];
460 bout.b[1] = bin.b[2];
461 bout.b[2] = bin.b[1];
462 bout.b[3] = bin.b[0];
484 i_bit_index = bit_index;
485 i_byte_index = packet_index;
494 while (bits_remain > 0)
503 if (bits_remain <= (uint8_t)(8 - i_bit_index))
506 curr_bits_n = (uint8_t)bits_remain;
510 curr_bits_n = (8 - i_bit_index);
515 buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n));
517 buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v);
520 i_bit_index += curr_bits_n;
523 bits_remain -= curr_bits_n;
532 *r_bit_index = i_bit_index;
534 if (i_bit_index != 7) i_byte_index++;
535 return i_byte_index - packet_index;
538 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
563 #ifdef MAVLINK_SEND_UART_BYTES
566 MAVLINK_SEND_UART_BYTES(chan, (
const uint8_t *)buf, len);
570 for (i = 0; i < len; i++) {
571 comm_send_ch(chan, (uint8_t)buf[i]);
575 #endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
int8_t int8
Definition: mavlink_helpers.h:188
MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan)
Reset the status of a channel.
Definition: mavlink_helpers.h:49
Definition: mavlink_types.h:179
MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t *r_message, mavlink_status_t *r_mavlink_status)
Definition: mavlink_helpers.h:247
Definition: mavlink_types.h:211
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.
Definition: mavlink_helpers.h:447
ubx_nav_status status
Definition: gps.c:829
MAVLINK_HELPER mavlink_message_t * mavlink_get_channel_buffer(uint8_t chan)
Definition: mavlink_helpers.h:33
MAVLINK_HELPER mavlink_status_t * mavlink_get_channel_status(uint8_t chan)
Definition: mavlink_helpers.h:17
#define mavlink_ck_a(msg)
Definition: mavlink_types.h:175
#define MAVLINK_NUM_NON_PAYLOAD_BYTES
Definition: mavlink_types.h:31
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.
Definition: mavlink_helpers.h:105
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
#define MAVLINK_START_UART_SEND(chan, length)
Definition: protocol.h:30
uint8_t msg_received
Number of received messages.
Definition: mavlink_types.h:212
mavlink_parse_state_t parse_state
Parsing state machine.
Definition: mavlink_types.h:215
mavlink_channel_t
Definition: mavlink_types.h:178
Definition: mavlink_types.h:204
#define MAVLINK_CORE_HEADER_LEN
Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + mes...
Definition: mavlink_types.h:28
#define MAVLINK_STX
Definition: mavlink.h:9
uint32_t uint32
Definition: mavlink_helpers.h:191
#define mavlink_ck_b(msg)
Definition: mavlink_types.h:176
uint8_t parse_error
Number of parse errors.
Definition: mavlink_types.h:214
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
uint16_t packet_rx_drop_count
Number of packet drops.
Definition: mavlink_types.h:220
#define MAVLINK_MAX_PAYLOAD_LEN
Maximum payload length.
Definition: mavlink_types.h:25
uint16_t packet_rx_success_count
Received packets.
Definition: mavlink_types.h:219
Definition: mavlink_types.h:206
Definition: mavlink_types.h:199
Definition: mavlink_helpers.h:186
Definition: mavlink_types.h:207
#define MAVLINK_NUM_HEADER_BYTES
Length of all header bytes, including core and checksum.
Definition: mavlink_types.h:29
MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t *msg, uint8_t c)
Definition: mavlink_helpers.h:201
Definition: mavlink_types.h:203
uint8_t packet_idx
Index in current packet.
Definition: mavlink_types.h:216
uint8_t uint8
Definition: mavlink_helpers.h:187
uint8_t current_rx_seq
Sequence number of last packet received.
Definition: mavlink_types.h:217
int32_t int32
Definition: mavlink_helpers.h:192
#define MAVLINK_END_UART_SEND(chan, length)
Definition: protocol.h:34
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.
Definition: mavlink_helpers.h:174
Definition: mavlink_types.h:208
Definition: mavlink_types.h:200
uint8_t buffer_overrun
Number of buffer overruns.
Definition: mavlink_types.h:213
#define MAVLINK_MESSAGE_CRCS
Definition: ardupilotmega.h:23
Definition: mavlink_types.h:202
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t *msg)
Definition: mavlink_helpers.h:196
uint8_t current_tx_seq
Sequence number of last packet sent.
Definition: mavlink_types.h:218
uint16_t uint16
Definition: mavlink_helpers.h:189
Definition: mavlink_types.h:201
Definition: mavlink_types.h:205
int16_t int16
Definition: mavlink_helpers.h:190
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.
Definition: mavlink_helpers.h:71
#define MAVLINK_HELPER
Definition: mavlink_helpers.h:10
#define MAVLINK_COMM_NUM_BUFFERS
Definition: mavlink_types.h:194
#define MAVLINK_MESSAGE_LENGTHS
Definition: ardupilotmega.h:19