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

feat: add qos_reliablity param #329

Open
wants to merge 5 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 1 commit
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 @@ -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) __qos_reliability__: The default QoS reliability setting for subscriptions the bridge creates. Can be 'reliable', 'best_effort', or 'automatic'. Defaults to `automatic`.
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Would be good to explain what the automatic setting does under the hood.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I've added a description of all options and another best_effort_if_volatile.
I know this is borderline but... this is a very useful default if running the bridge remote as transient_local topics are typically not things that should be thrown away.

A better option would probably be to have a regex matcher on topics that specifies which QoS foxglove should use when in subscribes.

* (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
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 @@ -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_QOS_RELIABILITY[] = "qos_reliability";
constexpr char PARAM_TOPIC_WHITELIST[] = "topic_whitelist";
constexpr char PARAM_SERVICE_WHITELIST[] = "service_whitelist";
constexpr char PARAM_PARAMETER_WHITELIST[] = "param_whitelist";
Expand All @@ -31,6 +32,7 @@ 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 = 25;
constexpr char DEFAULT_QOS_RELIABILITY[] = "automatic";

void declareParameters(rclcpp::Node* node);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,7 @@ class FoxgloveBridge : public rclcpp::Node {
std::unique_ptr<std::thread> _rosgraphPollThread;
size_t _minQosDepth = DEFAULT_MIN_QOS_DEPTH;
size_t _maxQosDepth = DEFAULT_MAX_QOS_DEPTH;
std::string _qosReliability = DEFAULT_QOS_RELIABILITY;
std::shared_ptr<rclcpp::Subscription<rosgraph_msgs::msg::Clock>> _clockSubscription;
bool _useSimTime = false;
std::vector<std::string> _capabilities;
Expand Down
9 changes: 9 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,15 @@ void declareParameters(rclcpp::Node* node) {
maxQosDepthDescription.integer_range[0].step = 1;
node->declare_parameter(PARAM_MAX_QOS_DEPTH, DEFAULT_MAX_QOS_DEPTH, maxQosDepthDescription);

auto qosReliabilityDescription = rcl_interfaces::msg::ParameterDescriptor{};
qosReliabilityDescription.name = PARAM_QOS_RELIABILITY;
qosReliabilityDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING;
qosReliabilityDescription.description =
"The default QoS reliability setting for subscriptions the bridge "
"creates. Can be 'reliable', 'best_effort', or 'automatic'.";
qosReliabilityDescription.read_only = true;
node->declare_parameter(PARAM_QOS_RELIABILITY, DEFAULT_QOS_RELIABILITY,
qosReliabilityDescription);
auto topicWhiteListDescription = rcl_interfaces::msg::ParameterDescriptor{};
topicWhiteListDescription.name = PARAM_TOPIC_WHITELIST;
topicWhiteListDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY;
Expand Down
26 changes: 17 additions & 9 deletions ros2_foxglove_bridge/src/ros2_foxglove_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@ 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());
_qosReliability = this->get_parameter(PARAM_QOS_RELIABILITY).as_string();
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,18 +496,25 @@ 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()) {
// Handle the QoS reliability setting
if (_qosReliability == "reliable") {
qos.reliable();
} else if (_qosReliability == "best_effort") {
qos.best_effort();
} else {
if (reliabilityReliableEndpointsCount > 0) {
RCLCPP_WARN(
this->get_logger(),
"Some, but not all, publishers on topic '%s' are offering QoSReliabilityPolicy.RELIABLE. "
"Falling back to QoSReliabilityPolicy.BEST_EFFORT as it will connect to all publishers",
topic.c_str());
// If all endpoints are reliable, ask for reliable
if (!publisherInfo.empty() && reliabilityReliableEndpointsCount == publisherInfo.size()) {
qos.reliable();
} else {
if (reliabilityReliableEndpointsCount > 0) {
RCLCPP_WARN(
this->get_logger(),
"Some, but not all, publishers on topic '%s' are offering QoSReliabilityPolicy.RELIABLE. "
"Falling back to QoSReliabilityPolicy.BEST_EFFORT as it will connect to all publishers",
topic.c_str());
}
qos.best_effort();
}
qos.best_effort();
}

// If all endpoints are transient_local, ask for transient_local
Expand Down
Loading