Skip to content

Commit

Permalink
add best_effort_qos_topic_whitelist param (#329)
Browse files Browse the repository at this point in the history
### Changelog
Adds a `qos_reliablity` param to the ros2 bridge that allows the default
reliability to be set via param. Defaults to "automatic" to retain
existing behavior.

### Docs

N/A

### Description

The web-socket bridge runs on TCP which causes issues on flakey internet
connections. There is some discussion here:
https://github.com/orgs/foxglove/discussions/15

This PR adds the ability to specify "qos_reliability" of "best_effort"
which is useful when running a bridge on a different computer to the
robot for example:

**ROBOT COMPUTER** -> DDS/UDP -> **REMOTE COMPUTER** -> Websocket/TCP ->
Foxglove / Browser

---------

Co-authored-by: Hans-Joachim Krauch <[email protected]>
  • Loading branch information
MrBlenny and achim-k authored Jan 28, 2025
1 parent ff853d8 commit 2fba8a3
Show file tree
Hide file tree
Showing 5 changed files with 27 additions and 4 deletions.
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,7 @@ Parameters are provided to configure the behavior of the bridge. These parameter
* (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) __min_qos_depth__: Minimum depth used for the QoS profile of subscriptions. Defaults to `1`. This is to set a lower limit for a subscriber's QoS depth which is computed by summing up depths of all publishers. See also [#208](https://github.com/foxglove/ros-foxglove-bridge/issues/208).
* (ROS 2) __max_qos_depth__: Maximum depth used for the QoS profile of subscriptions. Defaults to `25`.
* (ROS 2) __best_effort_qos_topic_whitelist__: List of regular expressions (ECMAScript) for topics that should be forced to use 'best_effort' QoS. Unmatched topics will use 'reliable' QoS if ALL publishers are 'reliable', 'best_effort' if any publishers are 'best_effort'. Defaults to `["(?!)"]` (match nothing).
* (ROS 2) __include_hidden__: Include hidden topics and services. Defaults to `false`.
* (ROS 2) __disable_load_message__: Do not publish as loaned message when publishing a client message. Defaults to `true`.

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ constexpr char PARAM_CERTFILE[] = "certfile";
constexpr char PARAM_KEYFILE[] = "keyfile";
constexpr char PARAM_MIN_QOS_DEPTH[] = "min_qos_depth";
constexpr char PARAM_MAX_QOS_DEPTH[] = "max_qos_depth";
constexpr char PARAM_BEST_EFFORT_QOS_TOPIC_WHITELIST[] = "best_effort_qos_topic_whitelist";
constexpr char PARAM_TOPIC_WHITELIST[] = "topic_whitelist";
constexpr char PARAM_SERVICE_WHITELIST[] = "service_whitelist";
constexpr char PARAM_PARAMETER_WHITELIST[] = "param_whitelist";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,7 @@ class FoxgloveBridge : public rclcpp::Node {
std::vector<std::regex> _topicWhitelistPatterns;
std::vector<std::regex> _serviceWhitelistPatterns;
std::vector<std::regex> _assetUriAllowlistPatterns;
std::vector<std::regex> _bestEffortQosTopicWhiteListPatterns;
std::shared_ptr<ParameterInterface> _paramInterface;
std::unordered_map<foxglove::ChannelId, foxglove::ChannelWithoutId> _advertisedTopics;
std::unordered_map<foxglove::ServiceId, foxglove::ServiceWithoutId> _advertisedServices;
Expand Down
12 changes: 12 additions & 0 deletions ros2_foxglove_bridge/src/param_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,18 @@ void declareParameters(rclcpp::Node* node) {
maxQosDepthDescription.integer_range[0].step = 1;
node->declare_parameter(PARAM_MAX_QOS_DEPTH, DEFAULT_MAX_QOS_DEPTH, maxQosDepthDescription);

auto bestEffortQosTopicWhiteListDescription = rcl_interfaces::msg::ParameterDescriptor{};
bestEffortQosTopicWhiteListDescription.name = PARAM_BEST_EFFORT_QOS_TOPIC_WHITELIST;
bestEffortQosTopicWhiteListDescription.type =
rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY;
bestEffortQosTopicWhiteListDescription.description =
"List of regular expressions (ECMAScript) for topics that should be forced to use "
"'best_effort' QoS. Unmatched topics will use 'reliable' QoS if ALL publishers are 'reliable', "
"'best_effort' if any publishers are 'best_effort'.";
bestEffortQosTopicWhiteListDescription.read_only = true;
node->declare_parameter(PARAM_BEST_EFFORT_QOS_TOPIC_WHITELIST, std::vector<std::string>({"(?!)"}),
bestEffortQosTopicWhiteListDescription);

auto topicWhiteListDescription = rcl_interfaces::msg::ParameterDescriptor{};
topicWhiteListDescription.name = PARAM_TOPIC_WHITELIST;
topicWhiteListDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY;
Expand Down
16 changes: 12 additions & 4 deletions ros2_foxglove_bridge/src/ros2_foxglove_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,9 @@ FoxgloveBridge::FoxgloveBridge(const rclcpp::NodeOptions& options)
const auto keyfile = this->get_parameter(PARAM_KEYFILE).as_string();
_minQosDepth = static_cast<size_t>(this->get_parameter(PARAM_MIN_QOS_DEPTH).as_int());
_maxQosDepth = static_cast<size_t>(this->get_parameter(PARAM_MAX_QOS_DEPTH).as_int());
const auto bestEffortQosTopicWhiteList =
this->get_parameter(PARAM_BEST_EFFORT_QOS_TOPIC_WHITELIST).as_string_array();
_bestEffortQosTopicWhiteListPatterns = parseRegexStrings(this, bestEffortQosTopicWhiteList);
const auto topicWhiteList = this->get_parameter(PARAM_TOPIC_WHITELIST).as_string_array();
_topicWhitelistPatterns = parseRegexStrings(this, topicWhiteList);
const auto serviceWhiteList = this->get_parameter(PARAM_SERVICE_WHITELIST).as_string_array();
Expand Down Expand Up @@ -495,8 +498,11 @@ void FoxgloveBridge::subscribe(foxglove::ChannelId channelId, ConnectionHandle c

rclcpp::QoS qos{rclcpp::KeepLast(depth)};

// If all endpoints are reliable, ask for reliable
if (!publisherInfo.empty() && reliabilityReliableEndpointsCount == publisherInfo.size()) {
// Force the QoS to be "best_effort" if in the whitelist
if (isWhitelisted(topic, _bestEffortQosTopicWhiteListPatterns)) {
qos.best_effort();
} else if (!publisherInfo.empty() && reliabilityReliableEndpointsCount == publisherInfo.size()) {
// If all endpoints are reliable, ask for reliable
qos.reliable();
} else {
if (reliabilityReliableEndpointsCount > 0) {
Expand Down Expand Up @@ -524,8 +530,10 @@ void FoxgloveBridge::subscribe(foxglove::ChannelId channelId, ConnectionHandle c
}

if (firstSubscription) {
RCLCPP_INFO(this->get_logger(), "Subscribing to topic \"%s\" (%s) on channel %d", topic.c_str(),
datatype.c_str(), channelId);
RCLCPP_INFO(
this->get_logger(), "Subscribing to topic \"%s\" (%s) on channel %d with reliablity \"%s\"",
topic.c_str(), datatype.c_str(), channelId,
qos.reliability() == rclcpp::ReliabilityPolicy::Reliable ? "reliable" : "best_effort");

} else {
RCLCPP_INFO(this->get_logger(), "Adding subscriber #%zu to topic \"%s\" (%s) on channel %d",
Expand Down

0 comments on commit 2fba8a3

Please sign in to comment.