MAV'RIC
mavlink_helpers.h
1 #ifndef _MAVLINK_HELPERS_H_
2 #define _MAVLINK_HELPERS_H_
3 
4 #include "string.h"
5 #include "checksum.h"
6 #include "mavlink_types.h"
7 #include "mavlink_conversions.h"
8 
9 #ifndef MAVLINK_HELPER
10 #define MAVLINK_HELPER
11 #endif
12 
13 /*
14  * Internal function to give access to the channel status for each channel
15  */
16 #ifndef MAVLINK_GET_CHANNEL_STATUS
17 MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan)
18 {
19 #ifdef MAVLINK_EXTERNAL_RX_STATUS
20  // No m_mavlink_status array defined in function,
21  // has to be defined externally
22 #else
23  static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
24 #endif
25  return &m_mavlink_status[chan];
26 }
27 #endif
28 
29 /*
30  * Internal function to give access to the channel buffer for each channel
31  */
32 #ifndef MAVLINK_GET_CHANNEL_BUFFER
33 MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan)
34 {
35 
36 #ifdef MAVLINK_EXTERNAL_RX_BUFFER
37  // No m_mavlink_buffer array defined in function,
38  // has to be defined externally
39 #else
40  static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];
41 #endif
42  return &m_mavlink_buffer[chan];
43 }
44 #endif
45 
49 MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan)
50 {
51  mavlink_status_t *status = mavlink_get_channel_status(chan);
52  status->parse_state = MAVLINK_PARSE_STATE_IDLE;
53 }
54 
67 #if MAVLINK_CRC_EXTRA
68 MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
69  uint8_t chan, uint8_t length, uint8_t crc_extra)
70 #else
71 MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
72  uint8_t chan, uint8_t length)
73 #endif
74 {
75  // This code part is the same for all messages;
76  msg->magic = MAVLINK_STX;
77  msg->len = length;
78  msg->sysid = system_id;
79  msg->compid = component_id;
80  // One sequence number per component
81  msg->seq = mavlink_get_channel_status(chan)->current_tx_seq;
82  mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1;
83  msg->checksum = crc_calculate(((const uint8_t*)(msg)) + 3, MAVLINK_CORE_HEADER_LEN);
84  crc_accumulate_buffer(&msg->checksum, _MAV_PAYLOAD(msg), msg->len);
85 #if MAVLINK_CRC_EXTRA
86  crc_accumulate(crc_extra, &msg->checksum);
87 #endif
88  mavlink_ck_a(msg) = (uint8_t)(msg->checksum & 0xFF);
89  mavlink_ck_b(msg) = (uint8_t)(msg->checksum >> 8);
90 
91  return length + MAVLINK_NUM_NON_PAYLOAD_BYTES;
92 }
93 
94 
98 #if MAVLINK_CRC_EXTRA
99 MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
100  uint8_t length, uint8_t crc_extra)
101 {
102  return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length, crc_extra);
103 }
104 #else
105 MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
106  uint8_t length)
107 {
108  return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length);
109 }
110 #endif
111 
112 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
113 MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
114 
118 #if MAVLINK_CRC_EXTRA
119 MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
120  uint8_t length, uint8_t crc_extra)
121 #else
122 MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length)
123 #endif
124 {
125  uint16_t checksum;
126  uint8_t buf[MAVLINK_NUM_HEADER_BYTES];
127  uint8_t ck[2];
128  mavlink_status_t *status = mavlink_get_channel_status(chan);
129  buf[0] = MAVLINK_STX;
130  buf[1] = length;
131  buf[2] = status->current_tx_seq;
132  buf[3] = mavlink_system.sysid;
133  buf[4] = mavlink_system.compid;
134  buf[5] = msgid;
135  status->current_tx_seq++;
136  checksum = crc_calculate((const uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN);
137  crc_accumulate_buffer(&checksum, packet, length);
138 #if MAVLINK_CRC_EXTRA
139  crc_accumulate(crc_extra, &checksum);
140 #endif
141  ck[0] = (uint8_t)(checksum & 0xFF);
142  ck[1] = (uint8_t)(checksum >> 8);
143 
144  MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length);
145  _mavlink_send_uart(chan, (const char *)buf, MAVLINK_NUM_HEADER_BYTES);
146  _mavlink_send_uart(chan, packet, length);
147  _mavlink_send_uart(chan, (const char *)ck, 2);
148  MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length);
149 }
150 
155 MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg)
156 {
157  uint8_t ck[2];
158 
159  ck[0] = (uint8_t)(msg->checksum & 0xFF);
160  ck[1] = (uint8_t)(msg->checksum >> 8);
161  // XXX use the right sequence here
162 
163  MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len);
164  _mavlink_send_uart(chan, (const char *)&msg->magic, MAVLINK_NUM_HEADER_BYTES);
165  _mavlink_send_uart(chan, _MAV_PAYLOAD(msg), msg->len);
166  _mavlink_send_uart(chan, (const char *)ck, 2);
167  MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len);
168 }
169 #endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
170 
174 MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg)
175 {
176  memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len);
177 
178  uint8_t *ck = buffer + (MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len);
179 
180  ck[0] = (uint8_t)(msg->checksum & 0xFF);
181  ck[1] = (uint8_t)(msg->checksum >> 8);
182 
183  return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len;
184 }
185 
187  uint8_t uint8;
188  int8_t int8;
189  uint16_t uint16;
190  int16_t int16;
191  uint32_t uint32;
192  int32_t int32;
193 };
194 
195 
196 MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg)
197 {
198  crc_init(&msg->checksum);
199 }
200 
201 MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
202 {
203  crc_accumulate(c, &msg->checksum);
204 }
205 
247 MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
248 {
249  /*
250  default message crc function. You can override this per-system to
251  put this data in a different memory segment
252  */
253 #if MAVLINK_CRC_EXTRA
254 #ifndef MAVLINK_MESSAGE_CRC
255  static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS;
256 #define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid]
257 #endif
258 #endif
259 
260 /* Enable this option to check the length of each message.
261  This allows invalid messages to be caught much sooner. Use if the transmission
262  medium is prone to missing (or extra) characters (e.g. a radio that fades in
263  and out). Only use if the channel will only contain messages types listed in
264  the headers.
265 */
266 #ifdef MAVLINK_CHECK_MESSAGE_LENGTH
267 #ifndef MAVLINK_MESSAGE_LENGTH
268  static const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS;
269 #define MAVLINK_MESSAGE_LENGTH(msgid) mavlink_message_lengths[msgid]
270 #endif
271 #endif
272 
273  mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan);
274  mavlink_status_t* status = mavlink_get_channel_status(chan);
275  int bufferIndex = 0;
276 
277  status->msg_received = 0;
278 
279  switch (status->parse_state)
280  {
281  case MAVLINK_PARSE_STATE_UNINIT:
282  case MAVLINK_PARSE_STATE_IDLE:
283  if (c == MAVLINK_STX)
284  {
285  status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
286  rxmsg->len = 0;
287  rxmsg->magic = c;
288  mavlink_start_checksum(rxmsg);
289  }
290  break;
291 
292  case MAVLINK_PARSE_STATE_GOT_STX:
293  if (status->msg_received
294 /* Support shorter buffers than the
295  default maximum packet size */
296 #if (MAVLINK_MAX_PAYLOAD_LEN < 255)
297  || c > MAVLINK_MAX_PAYLOAD_LEN
298 #endif
299  )
300  {
301  status->buffer_overrun++;
302  status->parse_error++;
303  status->msg_received = 0;
304  status->parse_state = MAVLINK_PARSE_STATE_IDLE;
305  }
306  else
307  {
308  // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2
309  rxmsg->len = c;
310  status->packet_idx = 0;
311  mavlink_update_checksum(rxmsg, c);
312  status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH;
313  }
314  break;
315 
316  case MAVLINK_PARSE_STATE_GOT_LENGTH:
317  rxmsg->seq = c;
318  mavlink_update_checksum(rxmsg, c);
319  status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ;
320  break;
321 
322  case MAVLINK_PARSE_STATE_GOT_SEQ:
323  rxmsg->sysid = c;
324  mavlink_update_checksum(rxmsg, c);
325  status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID;
326  break;
327 
328  case MAVLINK_PARSE_STATE_GOT_SYSID:
329  rxmsg->compid = c;
330  mavlink_update_checksum(rxmsg, c);
331  status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID;
332  break;
333 
334  case MAVLINK_PARSE_STATE_GOT_COMPID:
335 #ifdef MAVLINK_CHECK_MESSAGE_LENGTH
336  if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(c))
337  {
338  status->parse_error++;
339  status->parse_state = MAVLINK_PARSE_STATE_IDLE;
340  break;
341  if (c == MAVLINK_STX)
342  {
343  status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
344  mavlink_start_checksum(rxmsg);
345  }
346  }
347 #endif
348  rxmsg->msgid = c;
349  mavlink_update_checksum(rxmsg, c);
350  if (rxmsg->len == 0)
351  {
352  status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
353  }
354  else
355  {
356  status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID;
357  }
358  break;
359 
360  case MAVLINK_PARSE_STATE_GOT_MSGID:
361  _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c;
362  mavlink_update_checksum(rxmsg, c);
363  if (status->packet_idx == rxmsg->len)
364  {
365  status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
366  }
367  break;
368 
369  case MAVLINK_PARSE_STATE_GOT_PAYLOAD:
370 #if MAVLINK_CRC_EXTRA
371  mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid));
372 #endif
373  if (c != (rxmsg->checksum & 0xFF)) {
374  // Check first checksum byte
375  status->parse_error++;
376  status->msg_received = 0;
377  status->parse_state = MAVLINK_PARSE_STATE_IDLE;
378  if (c == MAVLINK_STX)
379  {
380  status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
381  rxmsg->len = 0;
382  mavlink_start_checksum(rxmsg);
383  }
384  }
385  else
386  {
387  status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1;
388  _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c;
389  }
390  break;
391 
392  case MAVLINK_PARSE_STATE_GOT_CRC1:
393  if (c != (rxmsg->checksum >> 8)) {
394  // Check second checksum byte
395  status->parse_error++;
396  status->msg_received = 0;
397  status->parse_state = MAVLINK_PARSE_STATE_IDLE;
398  if (c == MAVLINK_STX)
399  {
400  status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
401  rxmsg->len = 0;
402  mavlink_start_checksum(rxmsg);
403  }
404  }
405  else
406  {
407  // Successfully got message
408  status->msg_received = 1;
409  status->parse_state = MAVLINK_PARSE_STATE_IDLE;
410  _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c;
411  memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
412  }
413  break;
414  }
415 
416  bufferIndex++;
417  // If a message has been sucessfully decoded, check index
418  if (status->msg_received == 1)
419  {
420  //while(status->current_seq != rxmsg->seq)
421  //{
422  // status->packet_rx_drop_count++;
423  // status->current_seq++;
424  //}
425  status->current_rx_seq = rxmsg->seq;
426  // Initial condition: If no packet has been received so far, drop count is undefined
427  if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0;
428  // Count this packet as received
429  status->packet_rx_success_count++;
430  }
431 
432  r_mavlink_status->current_rx_seq = status->current_rx_seq+1;
433  r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count;
434  r_mavlink_status->packet_rx_drop_count = status->parse_error;
435  status->parse_error = 0;
436  return status->msg_received;
437 }
438 
449 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)
450 {
451  uint16_t bits_remain = bits;
452  // Transform number into network order
453  int32_t v;
454  uint8_t i_bit_index, i_byte_index, curr_bits_n;
455 #if MAVLINK_NEED_BYTE_SWAP
456  union {
457  int32_t i;
458  uint8_t b[4];
459  } bin, bout;
460  bin.i = b;
461  bout.b[0] = bin.b[3];
462  bout.b[1] = bin.b[2];
463  bout.b[2] = bin.b[1];
464  bout.b[3] = bin.b[0];
465  v = bout.i;
466 #else
467  v = b;
468 #endif
469 
470  // buffer in
471  // 01100000 01000000 00000000 11110001
472  // buffer out
473  // 11110001 00000000 01000000 01100000
474 
475  // Existing partly filled byte (four free slots)
476  // 0111xxxx
477 
478  // Mask n free bits
479  // 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1
480  // = ((uint32_t)(1 << n)) - 1; // = 2^n - 1
481 
482  // Shift n bits into the right position
483  // out = in >> n;
484 
485  // Mask and shift bytes
486  i_bit_index = bit_index;
487  i_byte_index = packet_index;
488  if (bit_index > 0)
489  {
490  // If bits were available at start, they were available
491  // in the byte before the current index
492  i_byte_index--;
493  }
494 
495  // While bits have not been packed yet
496  while (bits_remain > 0)
497  {
498  // Bits still have to be packed
499  // there can be more than 8 bits, so
500  // we might have to pack them into more than one byte
501 
502  // First pack everything we can into the current 'open' byte
503  //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8
504  //FIXME
505  if (bits_remain <= (uint8_t)(8 - i_bit_index))
506  {
507  // Enough space
508  curr_bits_n = (uint8_t)bits_remain;
509  }
510  else
511  {
512  curr_bits_n = (8 - i_bit_index);
513  }
514 
515  // Pack these n bits into the current byte
516  // Mask out whatever was at that position with ones (xxx11111)
517  buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n));
518  // Put content to this position, by masking out the non-used part
519  buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v);
520 
521  // Increment the bit index
522  i_bit_index += curr_bits_n;
523 
524  // Now proceed to the next byte, if necessary
525  bits_remain -= curr_bits_n;
526  if (bits_remain > 0)
527  {
528  // Offer another 8 bits / one byte
529  i_byte_index++;
530  i_bit_index = 0;
531  }
532  }
533 
534  *r_bit_index = i_bit_index;
535  // If a partly filled byte is present, mark this as consumed
536  if (i_bit_index != 7) i_byte_index++;
537  return i_byte_index - packet_index;
538 }
539 
540 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
541 
542 // To make MAVLink work on your MCU, define comm_send_ch() if you wish
543 // to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a
544 // whole packet at a time
545 
546 /*
547 
548 #include "mavlink_types.h"
549 
550 void comm_send_ch(mavlink_channel_t chan, uint8_t ch)
551 {
552  if (chan == MAVLINK_COMM_0)
553  {
554  uart0_transmit(ch);
555  }
556  if (chan == MAVLINK_COMM_1)
557  {
558  uart1_transmit(ch);
559  }
560 }
561  */
562 
563 MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len)
564 {
565 #ifdef MAVLINK_SEND_UART_BYTES
566  /* this is the more efficient approach, if the platform
567  defines it */
568  MAVLINK_SEND_UART_BYTES(chan, (const uint8_t *)buf, len);
569 #else
570  /* fallback to one byte at a time */
571  uint16_t i;
572  for (i = 0; i < len; i++) {
573  comm_send_ch(chan, (uint8_t)buf[i]);
574  }
575 #endif
576 }
577 #endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
578 
579 #endif /* _MAVLINK_HELPERS_H_ */