aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/mavlink_main.cpp
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-04-20 21:04:05 +0200
committerLorenz Meier <lm@inf.ethz.ch>2014-04-20 21:04:05 +0200
commit906abbcbb6215e9ae30c51efe3b813a71a963615 (patch)
treea777b178882a6d87439e5dfb73d163b5f7837999 /src/modules/mavlink/mavlink_main.cpp
parentf8232fa2698b37983f4c3f05926c9d6a7a107acf (diff)
downloadpx4-firmware-906abbcbb6215e9ae30c51efe3b813a71a963615.tar.gz
px4-firmware-906abbcbb6215e9ae30c51efe3b813a71a963615.tar.bz2
px4-firmware-906abbcbb6215e9ae30c51efe3b813a71a963615.zip
mavlink: Only write to TX buf if space is available. This is working around a NuttX issue where overflowing the TX buf leads to being unable to send any further data
Diffstat (limited to 'src/modules/mavlink/mavlink_main.cpp')
-rw-r--r--src/modules/mavlink/mavlink_main.cpp13
1 files changed, 11 insertions, 2 deletions
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index a9f5f4de7..2d71bdce6 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -189,9 +189,18 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length
/* If the wait until transmit flag is on, only transmit after we've received messages.
Otherwise, transmit all the time. */
if (instance->should_transmit()) {
- ssize_t ret = write(uart, ch, desired);
+
+ /* check if there is space in the buffer, let it overflow else */
+ if (!ioctl(uart, FIONWRITE, (unsigned long)&buf_free)) {
+
+ if (desired > buf_free) {
+ desired = buf_free;
+ }
+ }
+
+ ssize_t ret = write(uart, ch, desired);
if (ret != desired) {
- // XXX do something here, but change to using FIONWRITE and OS buf size for detection
+ warnx("TX FAIL");
}
}