00001 #ifndef _MAVLINK_HELPERS_H_
00002 #define _MAVLINK_HELPERS_H_
00003
00004 #include "string.h"
00005 #include "checksum.h"
00006 #include "mavlink_types.h"
00007
00008 #ifndef MAVLINK_HELPER
00009 #define MAVLINK_HELPER
00010 #endif
00011
00012
00013
00014
00015 MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan)
00016 {
00017 static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
00018 return &m_mavlink_status[chan];
00019 }
00020
00021
00022
00023
00024 MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan)
00025 {
00026
00027 #if MAVLINK_EXTERNAL_RX_BUFFER
00028
00029
00030 #ifndef m_mavlink_message
00031 #error ERROR: IF #define MAVLINK_EXTERNAL_RX_BUFFER IS SET, THE BUFFER HAS TO BE ALLOCATED OUTSIDE OF THIS FUNCTION (mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];)
00032 #endif
00033 #else
00034 static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];
00035 #endif
00036 return &m_mavlink_buffer[chan];
00037 }
00038
00051 #if MAVLINK_CRC_EXTRA
00052 MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
00053 uint8_t chan, uint8_t length, uint8_t crc_extra)
00054 #else
00055 MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
00056 uint8_t chan, uint8_t length)
00057 #endif
00058 {
00059
00060 uint16_t checksum;
00061 msg->magic = MAVLINK_STX;
00062 msg->len = length;
00063 msg->sysid = system_id;
00064 msg->compid = component_id;
00065
00066 msg->seq = mavlink_get_channel_status(chan)->current_tx_seq;
00067 mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1;
00068 checksum = crc_calculate((uint8_t*)&msg->len, length + MAVLINK_CORE_HEADER_LEN);
00069 #if MAVLINK_CRC_EXTRA
00070 crc_accumulate(crc_extra, &checksum);
00071 #endif
00072 mavlink_ck_a(msg) = (uint8_t)(checksum & 0xFF);
00073 mavlink_ck_b(msg) = (uint8_t)(checksum >> 8);
00074
00075 return length + MAVLINK_NUM_NON_PAYLOAD_BYTES;
00076 }
00077
00078
00082 #if MAVLINK_CRC_EXTRA
00083 MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
00084 uint8_t length, uint8_t crc_extra)
00085 {
00086 return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length, crc_extra);
00087 }
00088 #else
00089 MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
00090 uint8_t length)
00091 {
00092 return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length);
00093 }
00094 #endif
00095
00096 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00097 MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
00098
00102 #if MAVLINK_CRC_EXTRA
00103 MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
00104 uint8_t length, uint8_t crc_extra)
00105 #else
00106 MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length)
00107 #endif
00108 {
00109 uint16_t checksum;
00110 uint8_t buf[MAVLINK_NUM_HEADER_BYTES];
00111 uint8_t ck[2];
00112 mavlink_status_t *status = mavlink_get_channel_status(chan);
00113 buf[0] = MAVLINK_STX;
00114 buf[1] = length;
00115 buf[2] = status->current_tx_seq;
00116 buf[3] = mavlink_system.sysid;
00117 buf[4] = mavlink_system.compid;
00118 buf[5] = msgid;
00119 status->current_tx_seq++;
00120 checksum = crc_calculate((uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN);
00121 crc_accumulate_buffer(&checksum, packet, length);
00122 #if MAVLINK_CRC_EXTRA
00123 crc_accumulate(crc_extra, &checksum);
00124 #endif
00125 ck[0] = (uint8_t)(checksum & 0xFF);
00126 ck[1] = (uint8_t)(checksum >> 8);
00127
00128 MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length);
00129 _mavlink_send_uart(chan, (const char *)buf, MAVLINK_NUM_HEADER_BYTES);
00130 _mavlink_send_uart(chan, packet, length);
00131 _mavlink_send_uart(chan, (const char *)ck, 2);
00132 MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length);
00133 }
00134
00139 MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg)
00140 {
00141 uint8_t ck[2];
00142
00143 ck[0] = (uint8_t)(msg->checksum & 0xFF);
00144 ck[1] = (uint8_t)(msg->checksum >> 8);
00145
00146 MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len);
00147 _mavlink_send_uart(chan, (const char *)&msg->magic, MAVLINK_NUM_HEADER_BYTES);
00148 _mavlink_send_uart(chan, _MAV_PAYLOAD(msg), msg->len);
00149 _mavlink_send_uart(chan, (const char *)ck, 2);
00150 MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len);
00151 }
00152 #endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
00153
00157 MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg)
00158 {
00159 memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len);
00160 return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len;
00161 }
00162
00163 union __mavlink_bitfield {
00164 uint8_t uint8;
00165 int8_t int8;
00166 uint16_t uint16;
00167 int16_t int16;
00168 uint32_t uint32;
00169 int32_t int32;
00170 };
00171
00172
00173 MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg)
00174 {
00175 crc_init(&msg->checksum);
00176 }
00177
00178 MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
00179 {
00180 crc_accumulate(c, &msg->checksum);
00181 }
00182
00219 MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
00220 {
00221
00222
00223
00224
00225 #if MAVLINK_CRC_EXTRA
00226 #ifndef MAVLINK_MESSAGE_CRC
00227 static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS;
00228 #define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid]
00229 #endif
00230 #endif
00231
00232
00233
00234
00235
00236
00237
00238
00239 #if MAVLINK_CHECK_MESSAGE_LENGTH
00240 #ifndef MAVLINK_MESSAGE_LENGTH
00241 static const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS;
00242 #define MAVLINK_MESSAGE_LENGTH(msgid) mavlink_message_lengths[msgid]
00243 #endif
00244 #endif
00245
00246 mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan);
00247 mavlink_status_t* status = mavlink_get_channel_status(chan);
00248 int bufferIndex = 0;
00249
00250 status->msg_received = 0;
00251
00252 switch (status->parse_state)
00253 {
00254 case MAVLINK_PARSE_STATE_UNINIT:
00255 case MAVLINK_PARSE_STATE_IDLE:
00256 if (c == MAVLINK_STX)
00257 {
00258 status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
00259 rxmsg->len = 0;
00260 rxmsg->magic = c;
00261 mavlink_start_checksum(rxmsg);
00262 }
00263 break;
00264
00265 case MAVLINK_PARSE_STATE_GOT_STX:
00266 if (status->msg_received
00267
00268
00269 #if (MAVLINK_MAX_PAYLOAD_LEN < 255)
00270 || c > MAVLINK_MAX_PAYLOAD_LEN
00271 #endif
00272 )
00273 {
00274 status->buffer_overrun++;
00275 status->parse_error++;
00276 status->msg_received = 0;
00277 status->parse_state = MAVLINK_PARSE_STATE_IDLE;
00278 }
00279 else
00280 {
00281
00282 rxmsg->len = c;
00283 status->packet_idx = 0;
00284 mavlink_update_checksum(rxmsg, c);
00285 status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH;
00286 }
00287 break;
00288
00289 case MAVLINK_PARSE_STATE_GOT_LENGTH:
00290 rxmsg->seq = c;
00291 mavlink_update_checksum(rxmsg, c);
00292 status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ;
00293 break;
00294
00295 case MAVLINK_PARSE_STATE_GOT_SEQ:
00296 rxmsg->sysid = c;
00297 mavlink_update_checksum(rxmsg, c);
00298 status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID;
00299 break;
00300
00301 case MAVLINK_PARSE_STATE_GOT_SYSID:
00302 rxmsg->compid = c;
00303 mavlink_update_checksum(rxmsg, c);
00304 status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID;
00305 break;
00306
00307 case MAVLINK_PARSE_STATE_GOT_COMPID:
00308 #if MAVLINK_CHECK_MESSAGE_LENGTH
00309 if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(c))
00310 {
00311 status->parse_error++;
00312 status->parse_state = MAVLINK_PARSE_STATE_IDLE;
00313 break;
00314 }
00315 #endif
00316 rxmsg->msgid = c;
00317 mavlink_update_checksum(rxmsg, c);
00318 if (rxmsg->len == 0)
00319 {
00320 status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
00321 }
00322 else
00323 {
00324 status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID;
00325 }
00326 break;
00327
00328 case MAVLINK_PARSE_STATE_GOT_MSGID:
00329 _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c;
00330 mavlink_update_checksum(rxmsg, c);
00331 if (status->packet_idx == rxmsg->len)
00332 {
00333 status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
00334 }
00335 break;
00336
00337 case MAVLINK_PARSE_STATE_GOT_PAYLOAD:
00338 #if MAVLINK_CRC_EXTRA
00339 mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid));
00340 #endif
00341 if (c != (rxmsg->checksum & 0xFF)) {
00342
00343 status->parse_error++;
00344 status->msg_received = 0;
00345 status->parse_state = MAVLINK_PARSE_STATE_IDLE;
00346 if (c == MAVLINK_STX)
00347 {
00348 status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
00349 rxmsg->len = 0;
00350 mavlink_start_checksum(rxmsg);
00351 }
00352 }
00353 else
00354 {
00355 status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1;
00356 _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c;
00357 }
00358 break;
00359
00360 case MAVLINK_PARSE_STATE_GOT_CRC1:
00361 if (c != (rxmsg->checksum >> 8)) {
00362
00363 status->parse_error++;
00364 status->msg_received = 0;
00365 status->parse_state = MAVLINK_PARSE_STATE_IDLE;
00366 if (c == MAVLINK_STX)
00367 {
00368 status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
00369 rxmsg->len = 0;
00370 mavlink_start_checksum(rxmsg);
00371 }
00372 }
00373 else
00374 {
00375
00376 status->msg_received = 1;
00377 status->parse_state = MAVLINK_PARSE_STATE_IDLE;
00378 _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c;
00379 memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
00380 }
00381 break;
00382 }
00383
00384 bufferIndex++;
00385
00386 if (status->msg_received == 1)
00387 {
00388
00389
00390
00391
00392
00393 status->current_rx_seq = rxmsg->seq;
00394
00395 if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0;
00396
00397 status->packet_rx_success_count++;
00398 }
00399
00400 r_message->len = rxmsg->len;
00401 r_mavlink_status->parse_state = status->parse_state;
00402 r_mavlink_status->packet_idx = status->packet_idx;
00403 r_mavlink_status->current_rx_seq = status->current_rx_seq+1;
00404 r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count;
00405 r_mavlink_status->packet_rx_drop_count = status->parse_error;
00406 status->parse_error = 0;
00407 return status->msg_received;
00408 }
00409
00420 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)
00421 {
00422 uint16_t bits_remain = bits;
00423
00424 int32_t v;
00425 uint8_t i_bit_index, i_byte_index, curr_bits_n;
00426 #if MAVLINK_NEED_BYTE_SWAP
00427 union {
00428 int32_t i;
00429 uint8_t b[4];
00430 } bin, bout;
00431 bin.i = b;
00432 bout.b[0] = bin.b[3];
00433 bout.b[1] = bin.b[2];
00434 bout.b[2] = bin.b[1];
00435 bout.b[3] = bin.b[0];
00436 v = bout.i;
00437 #else
00438 v = b;
00439 #endif
00440
00441
00442
00443
00444
00445
00446
00447
00448
00449
00450
00451
00452
00453
00454
00455
00456
00457 i_bit_index = bit_index;
00458 i_byte_index = packet_index;
00459 if (bit_index > 0)
00460 {
00461
00462
00463 i_byte_index--;
00464 }
00465
00466
00467 while (bits_remain > 0)
00468 {
00469
00470
00471
00472
00473
00474
00475
00476 if (bits_remain <= (uint8_t)(8 - i_bit_index))
00477 {
00478
00479 curr_bits_n = (uint8_t)bits_remain;
00480 }
00481 else
00482 {
00483 curr_bits_n = (8 - i_bit_index);
00484 }
00485
00486
00487
00488 buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n));
00489
00490 buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v);
00491
00492
00493 i_bit_index += curr_bits_n;
00494
00495
00496 bits_remain -= curr_bits_n;
00497 if (bits_remain > 0)
00498 {
00499
00500 i_byte_index++;
00501 i_bit_index = 0;
00502 }
00503 }
00504
00505 *r_bit_index = i_bit_index;
00506
00507 if (i_bit_index != 7) i_byte_index++;
00508 return i_byte_index - packet_index;
00509 }
00510
00511 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00512
00513
00514
00515
00516
00517
00518
00519
00520
00521
00522
00523
00524
00525
00526
00527
00528
00529
00530
00531
00532
00533
00534 MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len)
00535 {
00536 #ifdef MAVLINK_SEND_UART_BYTES
00537
00538
00539 MAVLINK_SEND_UART_BYTES(chan, (uint8_t *)buf, len);
00540 #else
00541
00542 uint16_t i;
00543 for (i = 0; i < len; i++) {
00544 comm_send_ch(chan, (uint8_t)buf[i]);
00545 }
00546 #endif
00547 }
00548 #endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
00549
00550 #endif