Now instead of requiring the buffer to fill completely before we can
detect it is not draining, we use a time based mechanism to detect
when none of the first few bytes are transmitted after sitting in our
buffer a half second or more after flow control is enabled. This
huristic is reliable only for the first several chracters because we
believe that the radio must still have plenty of room in it's own
buffers at that time even if it is not able to transmit them to the
other radio yet. Note that the original algorithm made the same
assumption.
The new algorithm is especially helpful for cases where only keepalive
messages are transmitted before other packets can be requested by the
GCS. In this situation, the original code required almost 2 minutes
to disable flow control and allow communication with the GCS.
This commit changes the way libraries headers are included in source files:
- If the header is in the same directory the source belongs to, so the
notation '#include ""' is used with the path relative to the directory
containing the source.
- If the header is outside the directory containing the source, then we use
the notation '#include <>' with the path relative to libraries folder.
Some of the advantages of such approach:
- Only one search path for libraries headers.
- OSs like Windows may have a better lookup time.
The modification allows the read and write functions to be called by any thread but the calling thread must be the last one that called the begin() function.
this does the IO in the timer thread, and uses buffers in the main
task to avoid system call costs in the flight code.
The cost of PX4 read and write system calls is quite high - about 10
to 15 usec. We can't afford to pay that per byte