diff --git a/README.md b/README.md
index 2ab7dc486b..55ff4c66a9 100644
--- a/README.md
+++ b/README.md
@@ -76,11 +76,12 @@ Parameters are provided to configure the behavior of the bridge. These parameter
* __client_topic_whitelist__: List of regular expressions ([ECMAScript grammar](https://en.cppreference.com/w/cpp/regex/ecmascript)) of whitelisted client-published 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).
* __use_compression__: Use websocket compression (permessage-deflate). Suited for connections with smaller bandwith, at the cost of additional CPU load.
+ * __capabilities__: List of supported [server capabilities](https://github.com/foxglove/ws-protocol/blob/main/docs/spec.md). Defaults to `[clientPublish,parameters,parametersSubscribe,services,connectionGraph]`.
* (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) __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 `10`.
- * (ROS 2) __capabilities__: List of supported [server capabilities](https://github.com/foxglove/ws-protocol/blob/main/docs/spec.md). Defaults to `[clientPublish,parameters,parametersSubscribe,services,connectionGraph]`.
+ * (ROS 2) __include_hidden__: Include hidden topics and services. Defaults to `false`.
## Building from source
diff --git a/ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp b/ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp
index 805639a0de..d42bb1b7cb 100644
--- a/ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp
+++ b/ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp
@@ -22,6 +22,7 @@ constexpr char PARAM_PARAMETER_WHITELIST[] = "param_whitelist";
constexpr char PARAM_USE_COMPRESSION[] = "use_compression";
constexpr char PARAM_CAPABILITIES[] = "capabilities";
constexpr char PARAM_CLIENT_TOPIC_WHITELIST[] = "client_topic_whitelist";
+constexpr char PARAM_INCLUDE_HIDDEN[] = "include_hidden";
constexpr int64_t DEFAULT_PORT = 8765;
constexpr char DEFAULT_ADDRESS[] = "0.0.0.0";
diff --git a/ros2_foxglove_bridge/launch/foxglove_bridge_launch.xml b/ros2_foxglove_bridge/launch/foxglove_bridge_launch.xml
index 5524bb04a7..576dbe2f9a 100644
--- a/ros2_foxglove_bridge/launch/foxglove_bridge_launch.xml
+++ b/ros2_foxglove_bridge/launch/foxglove_bridge_launch.xml
@@ -14,6 +14,7 @@
+
@@ -31,5 +32,6 @@
+
diff --git a/ros2_foxglove_bridge/src/param_utils.cpp b/ros2_foxglove_bridge/src/param_utils.cpp
index becf88c7e3..a8d5dcd92b 100644
--- a/ros2_foxglove_bridge/src/param_utils.cpp
+++ b/ros2_foxglove_bridge/src/param_utils.cpp
@@ -139,6 +139,13 @@ void declareParameters(rclcpp::Node* node) {
clientTopicWhiteListDescription.read_only = true;
node->declare_parameter(PARAM_CLIENT_TOPIC_WHITELIST, std::vector({".*"}),
paramWhiteListDescription);
+
+ auto includeHiddenDescription = rcl_interfaces::msg::ParameterDescriptor{};
+ includeHiddenDescription.name = PARAM_INCLUDE_HIDDEN;
+ includeHiddenDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL;
+ includeHiddenDescription.description = "Include hidden topics and services";
+ includeHiddenDescription.read_only = true;
+ node->declare_parameter(PARAM_INCLUDE_HIDDEN, false, includeHiddenDescription);
}
std::vector parseRegexStrings(rclcpp::Node* node,
diff --git a/ros2_foxglove_bridge/src/ros2_foxglove_bridge.cpp b/ros2_foxglove_bridge/src/ros2_foxglove_bridge.cpp
index b0b450ee1d..6aafba2c40 100644
--- a/ros2_foxglove_bridge/src/ros2_foxglove_bridge.cpp
+++ b/ros2_foxglove_bridge/src/ros2_foxglove_bridge.cpp
@@ -30,6 +30,15 @@ using ClientPublications = std::unordered_map>;
using foxglove::isWhitelisted;
+namespace {
+inline bool isHiddenTopicOrService(const std::string& name) {
+ if (name.empty()) {
+ throw std::invalid_argument("Topic or service name can't be empty");
+ }
+ return name.front() == '_' || name.find("/_") != std::string::npos;
+}
+} // namespace
+
namespace foxglove_bridge {
class FoxgloveBridge : public rclcpp::Node {
@@ -66,6 +75,7 @@ class FoxgloveBridge : public rclcpp::Node {
const auto clientTopicWhiteList =
this->get_parameter(PARAM_CLIENT_TOPIC_WHITELIST).as_string_array();
const auto clientTopicWhiteListPatterns = parseRegexStrings(this, clientTopicWhiteList);
+ _includeHidden = this->get_parameter(PARAM_INCLUDE_HIDDEN).as_bool();
const auto logHandler = std::bind(&FoxgloveBridge::logHandler, this, _1, _2);
foxglove::ServerOptions serverOptions;
@@ -193,6 +203,11 @@ class FoxgloveBridge : public rclcpp::Node {
const auto& topicName = topicNamesAndType.first;
const auto& datatypes = topicNamesAndType.second;
+ // Ignore hidden topics if not explicitly included
+ if (!_includeHidden && isHiddenTopicOrService(topicName)) {
+ continue;
+ }
+
// Ignore the topic if it is not on the topic whitelist
if (isWhitelisted(topicName, _topicWhitelistPatterns)) {
for (const auto& datatype : datatypes) {
@@ -326,6 +341,11 @@ class FoxgloveBridge : public rclcpp::Node {
continue;
}
+ // Ignore hidden services if not explicitly included
+ if (!_includeHidden && isHiddenTopicOrService(serviceName)) {
+ continue;
+ }
+
// Ignore the service if it is not on the service whitelist
if (!isWhitelisted(serviceName, _serviceWhitelistPatterns)) {
continue;
@@ -448,6 +468,7 @@ class FoxgloveBridge : public rclcpp::Node {
bool _useSimTime = false;
std::vector _capabilities;
std::atomic _subscribeGraphUpdates = false;
+ bool _includeHidden = false;
void subscribeHandler(foxglove::ChannelId channelId, ConnectionHandle hdl) {
_handlerCallbackQueue->addCallback(std::bind(&FoxgloveBridge::subscribe, this, channelId, hdl));