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 parameter for minimum subscription QoS depth #211

Merged
merged 2 commits into from
Apr 11, 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
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -78,6 +78,7 @@ Parameters are provided to configure the behavior of the bridge. These parameter
* __use_compression__: Use websocket compression (permessage-deflate). Suited for connections with smaller bandwith, at the cost of additional CPU load.
* (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]`.

Expand Down
2 changes: 2 additions & 0 deletions ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ constexpr char PARAM_SEND_BUFFER_LIMIT[] = "send_buffer_limit";
constexpr char PARAM_USETLS[] = "tls";
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_TOPIC_WHITELIST[] = "topic_whitelist";
constexpr char PARAM_SERVICE_WHITELIST[] = "service_whitelist";
Expand All @@ -25,6 +26,7 @@ constexpr char PARAM_CLIENT_TOPIC_WHITELIST[] = "client_topic_whitelist";
constexpr int64_t DEFAULT_PORT = 8765;
constexpr char DEFAULT_ADDRESS[] = "0.0.0.0";
constexpr int64_t DEFAULT_SEND_BUFFER_LIMIT = 10000000;
constexpr int64_t DEFAULT_MIN_QOS_DEPTH = 1;
constexpr int64_t DEFAULT_MAX_QOS_DEPTH = 10;

void declareParameters(rclcpp::Node* node);
Expand Down
2 changes: 2 additions & 0 deletions ros2_foxglove_bridge/launch/foxglove_bridge_launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
<arg name="param_whitelist" default="['.*']" />
<arg name="service_whitelist" default="['.*']" />
<arg name="client_topic_whitelist" default="['.*']" />
<arg name="min_qos_depth" default="1" />
<arg name="max_qos_depth" default="10" />
<arg name="num_threads" default="0" />
<arg name="send_buffer_limit" default="10000000" />
Expand All @@ -24,6 +25,7 @@
<param name="service_whitelist" value="$(var service_whitelist)" />
<param name="param_whitelist" value="$(var param_whitelist)" />
<param name="client_topic_whitelist" value="$(var client_topic_whitelist)" />
<param name="min_qos_depth" value="$(var min_qos_depth)" />
<param name="max_qos_depth" value="$(var max_qos_depth)" />
<param name="num_threads" value="$(var num_threads)" />
<param name="send_buffer_limit" value="$(var send_buffer_limit)" />
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 @@ -60,6 +60,18 @@ void declareParameters(rclcpp::Node* node) {
keyfileDescription.read_only = true;
node->declare_parameter(PARAM_KEYFILE, "", keyfileDescription);

auto minQosDepthDescription = rcl_interfaces::msg::ParameterDescriptor{};
minQosDepthDescription.name = PARAM_MIN_QOS_DEPTH;
minQosDepthDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
minQosDepthDescription.description = "Minimum depth used for the QoS profile of subscriptions.";
minQosDepthDescription.read_only = true;
minQosDepthDescription.additional_constraints = "Must be a non-negative integer";
minQosDepthDescription.integer_range.resize(1);
minQosDepthDescription.integer_range[0].from_value = 0;
minQosDepthDescription.integer_range[0].to_value = INT32_MAX;
minQosDepthDescription.integer_range[0].step = 1;
node->declare_parameter(PARAM_MIN_QOS_DEPTH, DEFAULT_MIN_QOS_DEPTH, minQosDepthDescription);

auto maxQosDepthDescription = rcl_interfaces::msg::ParameterDescriptor{};
maxQosDepthDescription.name = PARAM_MAX_QOS_DEPTH;
maxQosDepthDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
Expand Down
4 changes: 3 additions & 1 deletion ros2_foxglove_bridge/src/ros2_foxglove_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@ class FoxgloveBridge : public rclcpp::Node {
const auto useTLS = this->get_parameter(PARAM_USETLS).as_bool();
const auto certfile = this->get_parameter(PARAM_CERTFILE).as_string();
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 topicWhiteList = this->get_parameter(PARAM_TOPIC_WHITELIST).as_string_array();
_topicWhitelistPatterns = parseRegexStrings(this, topicWhiteList);
Expand Down Expand Up @@ -441,6 +442,7 @@ class FoxgloveBridge : public rclcpp::Node {
std::mutex _clientAdvertisementsMutex;
std::mutex _servicesMutex;
std::unique_ptr<std::thread> _rosgraphPollThread;
size_t _minQosDepth = DEFAULT_MIN_QOS_DEPTH;
size_t _maxQosDepth = DEFAULT_MAX_QOS_DEPTH;
std::shared_ptr<rclcpp::Subscription<rosgraph_msgs::msg::Clock>> _clockSubscription;
bool _useSimTime = false;
Expand Down Expand Up @@ -556,7 +558,7 @@ class FoxgloveBridge : public rclcpp::Node {
depth = std::min(_maxQosDepth, depth + qos.depth());
}

rclcpp::QoS qos{rclcpp::KeepLast(std::max(depth, 1lu))};
rclcpp::QoS qos{rclcpp::KeepLast(std::max(depth, _minQosDepth))};

// If all endpoints are reliable, ask for reliable
if (reliabilityReliableEndpointsCount == publisherInfo.size()) {
Expand Down