Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Drop messages when connection send buffer limit has been reached #126

Merged
merged 3 commits into from
Jan 3, 2023
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ Parameters are provided to configure the behavior of the bridge. These parameter
* __certfile__: Path to the certificate to use for TLS. Required when __tls__ is set to `true`. Defaults to `""`.
* __keyfile__: Path to the private key to use for TLS. Required when __tls__ is set to `true`. Defaults to `""`.
* __topic_whitelist__: List of regular expressions ([ECMAScript grammar](https://en.cppreference.com/w/cpp/regex/ecmascript)) of whitelisted topic names. Defaults to `[".*"]`.
* __send_buffer_limit__: Connection send buffer limit in bytes. Messages will be dropped when a connection's send buffer reaches this limit to avoid a queue of outdated messages building up. Defaults to `10000000` (10 MB).
* (ROS 1) __max_update_ms__: The maximum number of milliseconds to wait in between polling `roscore` for new topics, services, or parameters. Defaults to `5000`.
* (ROS 2) __num_threads__: The number of threads to use for the ROS node executor. This controls the number of subscriptions that can be processed in parallel. 0 means one thread per CPU core. Defaults to `0`.
* (ROS 2) __max_qos_depth__: Maximum depth used for the QoS profile of subscriptions. Defaults to `10`.
Expand Down
25 changes: 23 additions & 2 deletions foxglove_bridge_base/include/foxglove_bridge/websocket_server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,11 @@ using ConnHandle = websocketpp::connection_hdl;
using OpCode = websocketpp::frame::opcode::value;

static const websocketpp::log::level APP = websocketpp::log::alevel::app;
static const websocketpp::log::level WARNING = websocketpp::log::elevel::warn;
static const websocketpp::log::level RECOVERABLE = websocketpp::log::elevel::rerror;

constexpr size_t DEFAULT_SEND_BUFFER_LIMIT_BYTES = 10000000UL; // 10 MB

constexpr uint32_t Integer(const std::string_view str) {
uint32_t result = 0x811C9DC5; // FNV-1a 32-bit algorithm
for (char c : str) {
Expand Down Expand Up @@ -167,8 +170,9 @@ class Server final : public ServerInterface {
static bool USES_TLS;

explicit Server(std::string name, LogCallback logger,
const std::vector<std::string>& capabilities, const std::string& certfile = "",
const std::string& keyfile = "");
const std::vector<std::string>& capabilities,
size_t send_buffer_limit_bytes = DEFAULT_SEND_BUFFER_LIMIT_BYTES,
const std::string& certfile = "", const std::string& keyfile = "");
virtual ~Server();

Server(const Server&) = delete;
Expand Down Expand Up @@ -213,6 +217,7 @@ class Server final : public ServerInterface {
std::string _name;
LogCallback _logger;
std::vector<std::string> _capabilities;
size_t _send_buffer_limit_bytes;
std::string _certfile;
std::string _keyfile;
ServerType _server;
Expand Down Expand Up @@ -248,10 +253,12 @@ class Server final : public ServerInterface {
template <typename ServerConfiguration>
inline Server<ServerConfiguration>::Server(std::string name, LogCallback logger,
const std::vector<std::string>& capabilities,
size_t send_buffer_limit_bytes,
const std::string& certfile, const std::string& keyfile)
: _name(std::move(name))
, _logger(logger)
, _capabilities(capabilities)
, _send_buffer_limit_bytes(send_buffer_limit_bytes)
, _certfile(certfile)
, _keyfile(keyfile) {
// Redirect logging
Expand Down Expand Up @@ -800,6 +807,20 @@ inline void Server<ServerConfiguration>::broadcastChannels() {
template <typename ServerConfiguration>
inline void Server<ServerConfiguration>::sendMessage(ConnHandle clientHandle, ChannelId chanId,
uint64_t timestamp, std::string_view data) {
std::error_code ec;
const auto con = _server.get_con_from_hdl(clientHandle, ec);
if (ec || !con) {
return;
}

const auto bufferSizeinBytes = con->get_buffered_amount();
if (bufferSizeinBytes >= _send_buffer_limit_bytes) {
_server.get_elog().write(WARNING,
"Send buffer for client '" + remoteEndpointString(clientHandle) +
"' is full, dropping message on channel " + std::to_string(chanId));
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Remove this

return;
}

SubscriptionId subId = std::numeric_limits<SubscriptionId>::max();

{
Expand Down
7 changes: 5 additions & 2 deletions ros1_foxglove_bridge/src/ros1_foxglove_bridge_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,8 @@ class FoxgloveBridge : public nodelet::Nodelet {
auto& nhp = getPrivateNodeHandle();
const auto address = nhp.param<std::string>("address", DEFAULT_ADDRESS);
const int port = nhp.param<int>("port", DEFAULT_PORT);
const auto send_buffer_limit = static_cast<size_t>(
nhp.param<int>("send_buffer_limit", foxglove::DEFAULT_SEND_BUFFER_LIMIT_BYTES));
const auto useTLS = nhp.param<bool>("tls", false);
const auto certfile = nhp.param<std::string>("certfile", "");
const auto keyfile = nhp.param<std::string>("keyfile", "");
Expand Down Expand Up @@ -73,10 +75,11 @@ class FoxgloveBridge : public nodelet::Nodelet {
std::bind(&FoxgloveBridge::logHandler, this, std::placeholders::_1, std::placeholders::_2);
if (useTLS) {
_server = std::make_unique<foxglove::Server<foxglove::WebSocketTls>>(
"foxglove_bridge", std::move(logHandler), serverCapabilities, certfile, keyfile);
"foxglove_bridge", std::move(logHandler), serverCapabilities, send_buffer_limit, certfile,
keyfile);
} else {
_server = std::make_unique<foxglove::Server<foxglove::WebSocketNoTls>>(
"foxglove_bridge", std::move(logHandler), serverCapabilities);
"foxglove_bridge", std::move(logHandler), serverCapabilities, send_buffer_limit);
}

_server->setSubscribeHandler(std::bind(&FoxgloveBridge::subscribeHandler, this,
Expand Down
21 changes: 19 additions & 2 deletions ros2_foxglove_bridge/src/ros2_foxglove_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,20 @@ class FoxgloveBridge : public rclcpp::Node {
this->declare_parameter<std::vector<std::string>>(
topicWhiteListDescription.name, std::vector<std::string>({".*"}), topicWhiteListDescription);

auto sendBufferLimit = rcl_interfaces::msg::ParameterDescriptor{};
sendBufferLimit.name = "send_buffer_limit";
sendBufferLimit.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
sendBufferLimit.description =
"Connection send buffer limit in bytes. Messages will be dropped when a connection's send "
"buffer reaches this limit to avoid a queue of outdated messages building up.";
sendBufferLimit.integer_range.resize(1);
sendBufferLimit.integer_range[0].from_value = 0;
sendBufferLimit.integer_range[0].to_value = std::numeric_limits<int64_t>::max();
sendBufferLimit.read_only = true;
this->declare_parameter(sendBufferLimit.name,
static_cast<int64_t>(foxglove::DEFAULT_SEND_BUFFER_LIMIT_BYTES),
sendBufferLimit);

const auto regexPatterns =
this->get_parameter(topicWhiteListDescription.name).as_string_array();
_topicWhitelistPatterns.reserve(regexPatterns.size());
Expand All @@ -112,6 +126,8 @@ class FoxgloveBridge : public rclcpp::Node {
}
}

const auto send_buffer_limit =
static_cast<size_t>(this->get_parameter("send_buffer_limit").as_int());
const auto useTLS = this->get_parameter("tls").as_bool();
const auto certfile = this->get_parameter("certfile").as_string();
const auto keyfile = this->get_parameter("keyfile").as_string();
Expand All @@ -127,10 +143,11 @@ class FoxgloveBridge : public rclcpp::Node {

if (useTLS) {
_server = std::make_unique<foxglove::Server<foxglove::WebSocketTls>>(
"foxglove_bridge", std::move(logHandler), serverCapabilities, certfile, keyfile);
"foxglove_bridge", std::move(logHandler), serverCapabilities, send_buffer_limit, certfile,
keyfile);
} else {
_server = std::make_unique<foxglove::Server<foxglove::WebSocketNoTls>>(
"foxglove_bridge", std::move(logHandler), serverCapabilities);
"foxglove_bridge", std::move(logHandler), serverCapabilities, send_buffer_limit);
}
_server->setSubscribeHandler(std::bind(&FoxgloveBridge::subscribeHandler, this, _1, _2));
_server->setUnsubscribeHandler(std::bind(&FoxgloveBridge::unsubscribeHandler, this, _1, _2));
Expand Down