Skip to content

Commit

Permalink
Allow to whitelist topics via a ROS paramater (#108)
Browse files Browse the repository at this point in the history
**Public-Facing Changes**
Allow to whitelist topics via a ROS paramater


**Description**
Allows the user to explicitly set the topics which should be exposed
over the websocket server

Fixes the topic part of #105
  • Loading branch information
achim-k committed Dec 6, 2022
1 parent 8fdef72 commit be99da4
Show file tree
Hide file tree
Showing 3 changed files with 79 additions and 10 deletions.
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,7 @@ Parameters are provided to configure the behavior of the bridge. These parameter
* __tls__: If `true`, use Transport Layer Security (TLS) for encrypted communication. Defaults to `false`.
* __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 `[".*"]`.
* (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
35 changes: 31 additions & 4 deletions ros1_foxglove_bridge/src/ros1_foxglove_bridge_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
#include <functional>
#include <memory>
#include <mutex>
#include <regex>
#include <shared_mutex>
#include <string>
#include <unordered_set>
Expand Down Expand Up @@ -46,6 +47,17 @@ 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));

const auto regexPatterns = nhp.param<std::vector<std::string>>("topic_whitelist", {".*"});
_topicWhitelistPatterns.reserve(regexPatterns.size());
for (const auto& pattern : regexPatterns) {
try {
_topicWhitelistPatterns.push_back(
std::regex(pattern, std::regex_constants::ECMAScript | std::regex_constants::icase));
} catch (const std::exception& ex) {
ROS_ERROR("Ignoring invalid regular expression '%s': %s", pattern.c_str(), ex.what());
}
}

ROS_INFO("Starting %s with %s", ros::this_node::getName().c_str(),
foxglove::WebSocketUserAgent());

Expand Down Expand Up @@ -318,12 +330,26 @@ class FoxgloveBridge : public nodelet::Nodelet {
std::unordered_set<TopicAndDatatype, PairHash> latestTopics;
latestTopics.reserve(topicNamesAndTypes.size());
bool hasClockTopic = false;
for (const auto& [topicName, datatype] : topicNamesAndTypes) {
for (const auto& topicNameAndType : topicNamesAndTypes) {
const auto& topicName = topicNameAndType.name;
const auto& datatype = topicNameAndType.datatype;

// Check if a /clock topic is published
if (topicName == "/clock" && datatype == "rosgraph_msgs/Clock") {
hasClockTopic = true;
hasClockTopic = hasClockTopic || (topicName == "/clock" && datatype == "rosgraph_msgs/Clock");

// Ignore the topic if it is not on the topic whitelist
if (std::find_if(_topicWhitelistPatterns.begin(), _topicWhitelistPatterns.end(),
[&topicName](const auto& regex) {
return std::regex_match(topicName, regex);
}) != _topicWhitelistPatterns.end()) {
latestTopics.emplace(topicName, datatype);
}
latestTopics.emplace(topicName, datatype);
}

if (const auto numIgnoredTopics = topicNamesAndTypes.size() - latestTopics.size()) {
ROS_DEBUG(
"%zu topics have been ignored as they do not match any pattern on the topic whitelist",
numIgnoredTopics);
}

// Enable or disable simulated time based on the presence of a /clock topic
Expand Down Expand Up @@ -457,6 +483,7 @@ class FoxgloveBridge : public nodelet::Nodelet {

std::unique_ptr<foxglove::ServerInterface> _server;
ros_babel_fish::IntegratedDescriptionProvider _rosTypeInfoProvider;
std::vector<std::regex> _topicWhitelistPatterns;
std::unordered_map<TopicAndDatatype, foxglove::Channel, PairHash> _advertisedTopics;
std::unordered_map<foxglove::ChannelId, TopicAndDatatype> _channelToTopicAndDatatype;
std::unordered_map<foxglove::ChannelId, SubscriptionsByClient> _subscriptions;
Expand Down
53 changes: 47 additions & 6 deletions ros2_foxglove_bridge/src/ros2_foxglove_bridge.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#include <atomic>
#include <chrono>
#include <memory>
#include <regex>
#include <thread>
#include <unordered_set>

Expand Down Expand Up @@ -90,6 +91,28 @@ class FoxgloveBridge : public rclcpp::Node {
maxQosDepthDescription.integer_range[0].step = 1;
this->declare_parameter("max_qos_depth", int(DEFAULT_MAX_QOS_DEPTH), maxQosDepthDescription);

auto topicWhiteListDescription = rcl_interfaces::msg::ParameterDescriptor{};
topicWhiteListDescription.name = "topic_whitelist";
topicWhiteListDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY;
topicWhiteListDescription.description =
"List of regular expressions (ECMAScript) of whitelisted topic names.";
topicWhiteListDescription.read_only = true;
this->declare_parameter<std::vector<std::string>>(
topicWhiteListDescription.name, std::vector<std::string>({".*"}), topicWhiteListDescription);

const auto regexPatterns =
this->get_parameter(topicWhiteListDescription.name).as_string_array();
_topicWhitelistPatterns.reserve(regexPatterns.size());
for (const auto& pattern : regexPatterns) {
try {
_topicWhitelistPatterns.push_back(
std::regex(pattern, std::regex_constants::ECMAScript | std::regex_constants::icase));
} catch (const std::exception& ex) {
RCLCPP_ERROR(this->get_logger(), "Ignoring invalid regular expression '%s': %s",
pattern.c_str(), ex.what());
}
}

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 Down Expand Up @@ -167,16 +190,33 @@ class FoxgloveBridge : public rclcpp::Node {
std::unordered_set<TopicAndDatatype, PairHash> latestTopics;
latestTopics.reserve(topicNamesAndTypes.size());
bool hasClockTopic = false;
for (const auto& [topicName, datatypes] : topicNamesAndTypes) {
for (const auto& datatype : datatypes) {
// Check if a /clock topic is published
if (topicName == "/clock" && datatype == "rosgraph_msgs/msg/Clock") {
hasClockTopic = true;
for (const auto& topicNamesAndType : topicNamesAndTypes) {
const auto& topicName = topicNamesAndType.first;
const auto& datatypes = topicNamesAndType.second;

// Check if a /clock topic is published
hasClockTopic = hasClockTopic || (topicName == "/clock" &&
std::find(datatypes.begin(), datatypes.end(),
"rosgraph_msgs/msg/Clock") != datatypes.end());

// Ignore the topic if it is not on the topic whitelist
if (std::find_if(_topicWhitelistPatterns.begin(), _topicWhitelistPatterns.end(),
[&topicName](const auto& regex) {
return std::regex_match(topicName, regex);
}) != _topicWhitelistPatterns.end()) {
for (const auto& datatype : datatypes) {
latestTopics.emplace(topicName, datatype);
}
latestTopics.emplace(topicName, datatype);
}
}

if (const auto numIgnoredTopics = topicNamesAndTypes.size() - latestTopics.size()) {
RCLCPP_DEBUG(
this->get_logger(),
"%zu topics have been ignored as they do not match any pattern on the topic whitelist",
numIgnoredTopics);
}

// Enable or disable simulated time based on the presence of a /clock topic
if (!_useSimTime && hasClockTopic) {
RCLCPP_INFO(this->get_logger(), "/clock topic found, using simulated time");
Expand Down Expand Up @@ -288,6 +328,7 @@ class FoxgloveBridge : public rclcpp::Node {

std::unique_ptr<foxglove::ServerInterface> _server;
foxglove::MessageDefinitionCache _messageDefinitionCache;
std::vector<std::regex> _topicWhitelistPatterns;
std::unordered_map<TopicAndDatatype, foxglove::Channel, PairHash> _advertisedTopics;
std::unordered_map<foxglove::ChannelId, TopicAndDatatype> _channelToTopicAndDatatype;
std::unordered_map<foxglove::ChannelId, SubscriptionsByClient> _subscriptions;
Expand Down

0 comments on commit be99da4

Please sign in to comment.