Skip to content

Commit

Permalink
Handle deadline, lifespan, and liveliness
Browse files Browse the repository at this point in the history
- Always use automatic liveliness
- Use max of deadline policies
- Use max of lifespan policies

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
jacobperron committed Mar 16, 2021
1 parent c780649 commit c62b3a1
Show file tree
Hide file tree
Showing 3 changed files with 105 additions and 12 deletions.
16 changes: 16 additions & 0 deletions doc/design.md
Original file line number Diff line number Diff line change
Expand Up @@ -117,11 +117,24 @@ The QoS settings of a publisher can be queried by the bridge.
With this information, the bridge can create a subscription using the same QoS settings for receiving data.
The bridge can also create a publisher for the domain being bridged with the same QoS settings.
In this way, for the single publisher case, the QoS settings are preserved from one domain to another domain.
However, there are issues related to the *liveliness* policy as well as multiple publishers per topic that are discussed below.

We must consider the scenario when the domain bridge starts *after* the publisher of a bridged topic becomes available.
In this case, the bridge cannot know what QoS settings to use for the bridged topic.
The solution is to have the bridge wait until a publisher becomes available before creating it's own subscription and publisher for that topic.

#### Liveliness

The liveliness QoS policy can either be set to "automatic" or "manual by topic".
If it is "automatic", the system will use the published messages as a heartbeat to consider if the publishers node is alive.
If it is "manual by topic", the node needs to manually call a publisher API to assert it is alive.

This poses a problem for the domain bridge.
If the liveliness of a publisher is "manual by topic", then the bridge cannot mimic the QoS behavior into another domain.
It would require the bridge to know when the original publisher is asserting its liveliness (i.e. calling the publisher API).
Since there is no mechanism in ROS 2 to get this information at the subscription site, the bridge cannot support "manual by topic" liveliness.
Therefore, the bridge will always use "automatic" liveliness, regardless of the original publishers policy.

#### Multiple publishers

As mentioned in the requirements, if there are multiple publishers on the same topic, it would be nice if the bridge could preserve multiple streams of data, each with their own QoS settings.
Expand All @@ -140,6 +153,9 @@ The bridge will evaluate the QoS settings of all publishers and modifiy the QoS
such that it matches the majority of the available publishers for a given topic.
For example, given publisher *A* and publisher *B* from the aforementioned scenario, the bridge would select a reliability setting of best effort since it matches with both publishers.

For *deadline* and *lifespan* policies, the bridge will use the max value given the policy value for all publishers.
For example, if a publisher *A* has a larger deadline than publisher *B* (and *A* and *B* publish to the same topic), then the bridge will use the deadline value of publisher *A*.

The bridge will decide on the QoS settings as soon as one or more publishers is available.
This means it is possible that publishers joining after the topic bridge is created may have compatibility issues, and fail to have their messages bridged.
For example, in the following scenario, messages coming from publisher *B* will not be bridged:
Expand Down
33 changes: 23 additions & 10 deletions src/domain_bridge/wait_for_qos_handler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,12 +37,8 @@ namespace domain_bridge
*/
struct QosMatchInfo
{
explicit QosMatchInfo(const rclcpp::QoS & init_qos)
: qos(init_qos)
{}

/// A matching QoS
rclcpp::QoS qos;
rclcpp::QoS qos{10}; // the depth value should be overridden later

/// Any warning messages about the matching QoS
std::vector<std::string> warnings;
Expand Down Expand Up @@ -152,21 +148,35 @@ class WaitForQosHandler
return {};
}

// Initialize QoS arbitrarily
QosMatchInfo result_qos(endpoint_info_vec[0].qos_profile());
// Initialize QoS
QosMatchInfo result_qos;
// Default reliability and durability to value of first endpoint
result_qos.qos.reliability(endpoint_info_vec[0].qos_profile().reliability());
result_qos.qos.durability(endpoint_info_vec[0].qos_profile().durability());
// Always use automatic liveliness
result_qos.qos.liveliness(rclcpp::LivelinessPolicy::Automatic);

// Reliability and durability policies can cause trouble with enpoint matching
// Count number of "reliable" publishers and number of "transient local" publishers
std::size_t reliable_count = 0u;
std::size_t transient_local_count = 0u;
// For duration-based policies, note the largest value to ensure matching all publishers
rclcpp::Duration max_deadline(0, 0u);
rclcpp::Duration max_lifespan(0, 0u);
for (const auto & info : endpoint_info_vec) {
const auto & profile = info.qos_profile().get_rmw_qos_profile();
if (profile.reliability == RMW_QOS_POLICY_RELIABILITY_RELIABLE) {
const auto & profile = info.qos_profile();
if (profile.reliability() == rclcpp::ReliabilityPolicy::Reliable) {
reliable_count++;
}
if (profile.durability == RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL) {
if (profile.durability() == rclcpp::DurabilityPolicy::TransientLocal) {
transient_local_count++;
}
if (profile.deadline() > max_deadline) {
max_deadline = profile.deadline();
}
if (profile.lifespan() > max_lifespan) {
max_lifespan = profile.lifespan();
}
}

// If not all publishers have a "reliable" policy, then use a "best effort" policy
Expand All @@ -191,6 +201,9 @@ class WaitForQosHandler
result_qos.warnings.push_back(warning);
}

result_qos.qos.deadline(max_deadline);
result_qos.qos.lifespan(max_lifespan);

return result_qos;
}

Expand Down
68 changes: 66 additions & 2 deletions test/domain_bridge/test_qos_matching.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -170,7 +170,7 @@ TEST_F(TestDomainBridgeQosMatching, qos_matches_topic_exists_multiple_publishers
{
const std::string topic_name("test_topic_exists_multiple_publishers");

// Create two publisher on domain 1
// Create two publishers on domain 1
auto node_1 = std::make_shared<rclcpp::Node>(
"test_topic_exists_multiple_publishers_node_1", node_options_1_);
rclcpp::QoS qos(1);
Expand All @@ -194,7 +194,7 @@ TEST_F(TestDomainBridgeQosMatching, qos_matches_topic_exists_multiple_publishers
ASSERT_TRUE(wait_for_publisher(node_2, topic_name));

// Assert the QoS of the bridged publishers matches both publishers
// I.e. it should have bes teffort reliability and volatile durability
// I.e. it should have best effort reliability and volatile durability
std::vector<rclcpp::TopicEndpointInfo> endpoint_info_vec =
node_2->get_publishers_info_by_topic(topic_name);
ASSERT_EQ(endpoint_info_vec.size(), 1u);
Expand All @@ -219,3 +219,67 @@ TEST_F(TestDomainBridgeQosMatching, qos_matches_topic_does_not_exist)
"test_topic_does_not_exist_node_2", node_options_2_);
ASSERT_FALSE(wait_for_publisher(node_2, topic_name, std::chrono::seconds(1)));
}

TEST_F(TestDomainBridgeQosMatching, qos_matches_always_automatic_liveliness)
{
const std::string topic_name("test_always_automatic_liveliness");

// Create a publisher on domain 1 with liveliness set to "manual by topic"
auto node_1 = std::make_shared<rclcpp::Node>(
"test_always_automatic_liveliness_node_1", node_options_1_);
rclcpp::QoS qos(1);
qos.liveliness(rclcpp::LivelinessPolicy::ManualByTopic);
auto pub = node_1->create_publisher<test_msgs::msg::BasicTypes>(topic_name, qos);

// Bridge the publisher topic to domain 2
domain_bridge::DomainBridge bridge;
bridge.bridge_topic(topic_name, "test_msgs/msg/BasicTypes", domain_1_, domain_2_);

// Wait for bridge publisher to appear on domain 2
auto node_2 = std::make_shared<rclcpp::Node>(
"test_always_automatic_liveliness_node_2", node_options_2_);
ASSERT_TRUE(wait_for_publisher(node_2, topic_name));

// Assert the liveliness policy is "automatic", not "manual by topic"
std::vector<rclcpp::TopicEndpointInfo> endpoint_info_vec =
node_2->get_publishers_info_by_topic(topic_name);
ASSERT_EQ(endpoint_info_vec.size(), 1u);
const rclcpp::QoS & bridged_qos = endpoint_info_vec[0].qos_profile();
EXPECT_EQ(bridged_qos.liveliness(), rclcpp::LivelinessPolicy::Automatic);
}

TEST_F(TestDomainBridgeQosMatching, qos_matches_max_of_duration_policy)
{
const std::string topic_name("test_max_of_duration_policy");

// Create two publishers on domain 1
// The first deadline will be greater than the second deadline
// The second lifespan will be greater than the first lifespan
auto node_1 = std::make_shared<rclcpp::Node>(
"test_max_of_duration_policy_node_1", node_options_1_);
rclcpp::QoS qos_1(1);
qos_1.deadline(rclcpp::Duration(554, 321u))
.lifespan(rclcpp::Duration(123, 456u));
rclcpp::QoS qos_2(1);
qos_2.deadline(rclcpp::Duration(123, 456u))
.lifespan(rclcpp::Duration(554, 321u));
auto pub_1 = node_1->create_publisher<test_msgs::msg::BasicTypes>(topic_name, qos_1);
auto pub_2 = node_1->create_publisher<test_msgs::msg::BasicTypes>(topic_name, qos_2);

// Bridge the publisher topic to domain 2
domain_bridge::DomainBridge bridge;
bridge.bridge_topic(topic_name, "test_msgs/msg/BasicTypes", domain_1_, domain_2_);

// Wait for bridge publisher to appear on domain 2
auto node_2 = std::make_shared<rclcpp::Node>(
"test_max_of_duration_policy_node_2", node_options_2_);
ASSERT_TRUE(wait_for_publisher(node_2, topic_name));

// Assert max of the two deadline and lifespan policies are used for the bridge QoS
std::vector<rclcpp::TopicEndpointInfo> endpoint_info_vec =
node_2->get_publishers_info_by_topic(topic_name);
ASSERT_EQ(endpoint_info_vec.size(), 1u);
const rclcpp::QoS & bridged_qos = endpoint_info_vec[0].qos_profile();
EXPECT_EQ(bridged_qos.deadline(), rclcpp::Duration(554, 321u));
EXPECT_EQ(bridged_qos.lifespan(), rclcpp::Duration(554, 321u));
}

0 comments on commit c62b3a1

Please sign in to comment.