diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2014-07-19 23:39:02 +0200 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2014-07-19 23:39:02 +0200 |
commit | cd8a0cd21771fb3a6fb8cddfc3da322eb04f10db (patch) | |
tree | 8a92bc5a7e39a380f1b542d508c4bb2e25c82e59 /src/modules/mavlink/mavlink_main.h | |
parent | cbfbdd27883b4f038032aff907f67544fddd090c (diff) | |
download | px4-firmware-cd8a0cd21771fb3a6fb8cddfc3da322eb04f10db.tar.gz px4-firmware-cd8a0cd21771fb3a6fb8cddfc3da322eb04f10db.tar.bz2 px4-firmware-cd8a0cd21771fb3a6fb8cddfc3da322eb04f10db.zip |
mavlink: Only send event-based messages if there is space in the buffer
Diffstat (limited to 'src/modules/mavlink/mavlink_main.h')
-rw-r--r-- | src/modules/mavlink/mavlink_main.h | 17 |
1 files changed, 16 insertions, 1 deletions
diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 70d13acb0..e9d6b9c86 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -248,6 +248,13 @@ public: void count_rxbytes(unsigned n) { _bytes_rx += n; }; /** + * Get the free space in the transmit buffer + * + * @return free space in the UART TX buffer + */ + unsigned get_free_tx_buf(); + + /** * Get the receive status of this MAVLink link */ struct telemetry_status_s& get_rx_status() { return _rstatus; } @@ -292,7 +299,8 @@ private: bool _ftp_on; int _uart_fd; int _baudrate; - int _datarate; + int _datarate; ///< data rate for normal streams (attitude, position, etc.) + int _datarate_events; ///< data rate for params, waypoints, text messages /** * If the queue index is not at 0, the queue sending @@ -385,6 +393,13 @@ private: int configure_stream(const char *stream_name, const float rate); + /** + * Adjust the stream rates based on the current rate + * + * @param multiplier if greater than 1, the transmission rate will increase, if smaller than one decrease + */ + void adjust_stream_rates(const float multiplier); + int message_buffer_init(int size); void message_buffer_destroy(); |