Skip to content

Commit

Permalink
platforms/nuttx: Serial change fsync to tcdrain
Browse files Browse the repository at this point in the history
Calling serial::write() in quick succession was blowing away the previous buffer, fsync does not guarantee that data is transmitted on serial lines. On the other hand tcdrain waits until the output buffer is empty.
  • Loading branch information
dakejahl authored Sep 25, 2024
1 parent b2c8f05 commit ba75b9c
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion platforms/nuttx/src/px4/common/SerialImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -339,7 +339,7 @@ ssize_t SerialImpl::write(const void *buffer, size_t buffer_size)
}

int written = ::write(_serial_fd, buffer, buffer_size);
::fsync(_serial_fd);
tcdrain(_serial_fd); // Wait until all output is transmitted

if (written < 0) {
PX4_ERR("%s write error %d", _port, written);
Expand Down

0 comments on commit ba75b9c

Please sign in to comment.