/* support for sending UDP packets on MAVLink packet boundaries. */ #include #if HAL_GCS_ENABLED #include "packetise.h" /* return the number of bytes to send for a packetised connection */ uint16_t mavlink_packetise(ByteBuffer &writebuf, uint16_t n) { int16_t b = writebuf.peek(0); if (b != MAVLINK_STX_MAVLINK1 && b != MAVLINK_STX) { /* we have a non-mavlink packet at the start of the buffer. Look ahead for a MAVLink start byte, up to 256 bytes ahead */ uint16_t limit = n>256?256:n; uint16_t i; for (i=0; i len+min_length) { // send just 1 packet at a time (so MAVLink packets // are aligned on UDP boundaries) n = len+min_length; } return n; } #endif // HAL_GCS_ENABLED