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

Add sessionId to serverInfo #153

Merged
merged 4 commits into from
Feb 8, 2023
Merged
Show file tree
Hide file tree
Changes from all 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
54 changes: 24 additions & 30 deletions foxglove_bridge_base/include/foxglove_bridge/websocket_server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -187,6 +187,16 @@ class ServerInterface {
virtual void setupTlsHandler() = 0;
};

struct ServerOptions {
std::vector<std::string> capabilities;
std::vector<std::string> supportedEncodings;
std::unordered_map<std::string, std::string> metadata;
size_t sendBufferLimitBytes = DEFAULT_SEND_BUFFER_LIMIT_BYTES;
std::string certfile = "";
std::string keyfile = "";
std::string sessionId;
};

template <typename ServerConfiguration>
class Server final : public ServerInterface {
public:
Expand All @@ -196,12 +206,7 @@ class Server final : public ServerInterface {

static bool USES_TLS;

explicit Server(std::string name, LogCallback logger,
const std::vector<std::string>& capabilities,
const std::vector<std::string>& supportedEncodings = {},
const std::unordered_map<std::string, std::string>& metadata = {},
size_t send_buffer_limit_bytes = DEFAULT_SEND_BUFFER_LIMIT_BYTES,
const std::string& certfile = "", const std::string& keyfile = "");
explicit Server(std::string name, LogCallback logger, const ServerOptions& options);
virtual ~Server();

Server(const Server&) = delete;
Expand Down Expand Up @@ -255,12 +260,7 @@ class Server final : public ServerInterface {

std::string _name;
LogCallback _logger;
std::vector<std::string> _capabilities;
std::vector<std::string> _supportedEncodings;
std::unordered_map<std::string, std::string> _metadata;
size_t _send_buffer_limit_bytes;
std::string _certfile;
std::string _keyfile;
ServerOptions _options;
ServerType _server;
std::unique_ptr<std::thread> _serverThread;

Expand Down Expand Up @@ -306,19 +306,11 @@ class Server final : public ServerInterface {
};

template <typename ServerConfiguration>
inline Server<ServerConfiguration>::Server(
std::string name, LogCallback logger, const std::vector<std::string>& capabilities,
const std::vector<std::string>& supportedEncodings,
const std::unordered_map<std::string, std::string>& metadata, size_t send_buffer_limit_bytes,
const std::string& certfile, const std::string& keyfile)
inline Server<ServerConfiguration>::Server(std::string name, LogCallback logger,
const ServerOptions& options)
: _name(std::move(name))
, _logger(logger)
, _capabilities(capabilities)
, _supportedEncodings(supportedEncodings)
, _metadata(metadata)
, _send_buffer_limit_bytes(send_buffer_limit_bytes)
, _certfile(certfile)
, _keyfile(keyfile) {
, _options(options) {
// Redirect logging
_server.get_alog().set_callback(_logger);
_server.get_elog().set_callback(_logger);
Expand Down Expand Up @@ -382,9 +374,10 @@ inline void Server<ServerConfiguration>::handleConnectionOpened(ConnHandle hdl)
con->send(json({
{"op", "serverInfo"},
{"name", _name},
{"capabilities", _capabilities},
{"supportedEncodings", _supportedEncodings},
{"metadata", _metadata},
{"capabilities", _options.capabilities},
{"supportedEncodings", _options.supportedEncodings},
{"metadata", _options.metadata},
{"sessionId", _options.sessionId},
})
.dump());

Expand Down Expand Up @@ -1108,7 +1101,7 @@ inline void Server<ServerConfiguration>::sendMessage(ConnHandle clientHandle, Ch
}

const auto bufferSizeinBytes = con->get_buffered_amount();
if (bufferSizeinBytes >= _send_buffer_limit_bytes) {
if (bufferSizeinBytes >= _options.sendBufferLimitBytes) {
FOXGLOVE_DEBOUNCE(
[this]() {
_server.get_elog().write(
Expand Down Expand Up @@ -1219,7 +1212,8 @@ inline void Server<ServerConfiguration>::unsubscribeParamsWithoutSubscriptions(

template <typename ServerConfiguration>
inline bool Server<ServerConfiguration>::hasCapability(const std::string& capability) const {
return std::find(_capabilities.begin(), _capabilities.end(), capability) != _capabilities.end();
return std::find(_options.capabilities.begin(), _options.capabilities.end(), capability) !=
_options.capabilities.end();
}

template <>
Expand All @@ -1244,8 +1238,8 @@ inline void Server<WebSocketTls>::setupTlsHandler() {
try {
ctx->set_options(asio::ssl::context::default_workarounds | asio::ssl::context::no_tlsv1 |
asio::ssl::context::no_sslv2 | asio::ssl::context::no_sslv3);
ctx->use_certificate_chain_file(_certfile);
ctx->use_private_key_file(_keyfile, asio::ssl::context::pem);
ctx->use_certificate_chain_file(_options.certfile);
ctx->use_private_key_file(_options.keyfile, asio::ssl::context::pem);

// Ciphers are taken from the websocketpp example echo tls server:
// https://github.com/zaphoyd/websocketpp/blob/1b11fd301/examples/echo_server_tls/echo_server_tls.cpp#L119
Expand Down
23 changes: 13 additions & 10 deletions ros1_foxglove_bridge/src/ros1_foxglove_bridge_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@ class FoxgloveBridge : public nodelet::Nodelet {
const auto keyfile = nhp.param<std::string>("keyfile", "");
_maxUpdateMs = static_cast<size_t>(nhp.param<int>("max_update_ms", DEFAULT_MAX_UPDATE_MS));
_useSimTime = nhp.param<bool>("/use_sim_time", false);
const auto sessionId = nhp.param<std::string>("/run_id", std::to_string(std::time(nullptr)));

const auto topicWhitelistPatterns =
nhp.param<std::vector<std::string>>("topic_whitelist", {".*"});
Expand All @@ -76,29 +77,31 @@ class FoxgloveBridge : public nodelet::Nodelet {
foxglove::WebSocketUserAgent());

try {
std::vector<std::string> serverCapabilities = {
foxglove::ServerOptions serverOptions;
serverOptions.capabilities = {
foxglove::CAPABILITY_CLIENT_PUBLISH,
foxglove::CAPABILITY_PARAMETERS,
foxglove::CAPABILITY_PARAMETERS_SUBSCRIBE,
foxglove::CAPABILITY_SERVICES,
};
if (_useSimTime) {
serverCapabilities.push_back(foxglove::CAPABILITY_TIME);
serverOptions.capabilities.push_back(foxglove::CAPABILITY_TIME);
}
const std::vector<std::string> supportedEncodings = {ROS1_CHANNEL_ENCODING};
const std::unordered_map<std::string, std::string> metadata = {
{"ROS_DISTRO", std::getenv("ROS_DISTRO")}};
serverOptions.supportedEncodings = {ROS1_CHANNEL_ENCODING};
serverOptions.metadata = {{"ROS_DISTRO", std::getenv("ROS_DISTRO")}};
serverOptions.sendBufferLimitBytes = send_buffer_limit;
serverOptions.sessionId = sessionId;

const auto logHandler =
std::bind(&FoxgloveBridge::logHandler, this, std::placeholders::_1, std::placeholders::_2);
if (useTLS) {
serverOptions.certfile = certfile;
serverOptions.keyfile = keyfile;
_server = std::make_unique<foxglove::Server<foxglove::WebSocketTls>>(
"foxglove_bridge", std::move(logHandler), serverCapabilities, supportedEncodings,
metadata, send_buffer_limit, certfile, keyfile);
"foxglove_bridge", std::move(logHandler), serverOptions);
} else {
_server = std::make_unique<foxglove::Server<foxglove::WebSocketNoTls>>(
"foxglove_bridge", std::move(logHandler), serverCapabilities, supportedEncodings,
metadata, send_buffer_limit);
"foxglove_bridge", std::move(logHandler), serverOptions);
}

_server->setSubscribeHandler(std::bind(&FoxgloveBridge::subscribeHandler, this,
Expand Down Expand Up @@ -525,7 +528,7 @@ class FoxgloveBridge : public nodelet::Nodelet {

// Advertise new services
std::vector<foxglove::ServiceWithoutId> newServices;
for (const auto serviceName : serviceNames) {
for (const auto& serviceName : serviceNames) {
if (std::find_if(_advertisedServices.begin(), _advertisedServices.end(),
[&serviceName](const auto& idWithService) {
return idWithService.second.name == serviceName;
Expand Down
20 changes: 11 additions & 9 deletions ros2_foxglove_bridge/src/ros2_foxglove_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,27 +57,29 @@ class FoxgloveBridge : public rclcpp::Node {
_paramInterface = std::make_shared<ParameterInterface>(this, paramWhitelistPatterns);

const auto logHandler = std::bind(&FoxgloveBridge::logHandler, this, _1, _2);
std::vector<std::string> serverCapabilities = {
foxglove::ServerOptions serverOptions;
serverOptions.capabilities = {
foxglove::CAPABILITY_CLIENT_PUBLISH,
foxglove::CAPABILITY_PARAMETERS,
foxglove::CAPABILITY_PARAMETERS_SUBSCRIBE,
foxglove::CAPABILITY_SERVICES,
};
if (_useSimTime) {
serverCapabilities.push_back(foxglove::CAPABILITY_TIME);
serverOptions.capabilities.push_back(foxglove::CAPABILITY_TIME);
}
const std::vector<std::string> supportedEncodings = {"cdr"};
const std::unordered_map<std::string, std::string> metadata = {
{"ROS_DISTRO", std::getenv("ROS_DISTRO")}};
serverOptions.supportedEncodings = {"cdr"};
serverOptions.metadata = {{"ROS_DISTRO", std::getenv("ROS_DISTRO")}};
serverOptions.sendBufferLimitBytes = send_buffer_limit;
serverOptions.sessionId = std::to_string(std::time(nullptr));

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