Skip to content

Commit

Permalink
Add test for GenericPublisher
Browse files Browse the repository at this point in the history
Signed-off-by: Emerson Knapp <emerson.b.knapp@gmail.com>
  • Loading branch information
emersonknapp committed Mar 30, 2020
1 parent 0e612e7 commit 72f78ff
Showing 1 changed file with 31 additions and 0 deletions.
31 changes: 31 additions & 0 deletions rosbag2_transport/test/rosbag2_transport/test_rosbag2_node.cpp
Expand Up @@ -166,6 +166,37 @@ TEST_F(RosBag2NodeFixture, generic_subscription_uses_qos)
EXPECT_THAT(subscribed_messages[0], StrEq("Hello World"));
}

TEST_F(RosBag2NodeFixture, generic_publisher_uses_qos)
{
// If the GenericPublisher does not use the provided QoS profile,
// its offer will be incompatible with the Subscription's request and no messages will be passed.
using namespace std::chrono_literals;
std::vector<std::string> test_messages = {"Hello World", "Hello World"};
std::string topic_name = "string_topic";
std::string type = "test_msgs/Strings";
// If the Subscription requests Transient Local Durability and the publisher offers the
// default (Volatile Durability), there will be no match.
rclcpp::QoS qos = rosbag2_transport::Rosbag2QoS().transient_local();
auto publisher = node_->create_generic_publisher(topic_name, type, qos);

auto subscriber_future_ = std::async(
std::launch::async, [this, topic_name, type, qos] {
return subscribe_raw_messages(1, topic_name, type, qos);
});
// Give time to the subscriber to start.
std::this_thread::sleep_for(std::chrono::milliseconds(100));

for (const auto & message : test_messages) {
publisher->publish(serialize_string_message(message));
// This is necessary because sometimes, the subscriber is initialized very late
std::this_thread::sleep_for(std::chrono::milliseconds(100));
}

auto subscribed_messages = subscriber_future_.get();
ASSERT_THAT(subscribed_messages, SizeIs(Not(0)));
EXPECT_THAT(subscribed_messages[0], StrEq("Hello World"));
}

TEST_F(RosBag2NodeFixture, get_topics_with_types_returns_empty_if_topic_does_not_exist) {
create_publisher("string_topic");

Expand Down

0 comments on commit 72f78ff

Please sign in to comment.