Skip to content

Commit

Permalink
Improve test time by adding an optional argument to SubscriptionManag…
Browse files Browse the repository at this point in the history
…er::spin_subscriptions()

- Reduces test_play_for execution time from 50s to 6s approximately.
  • Loading branch information
agalbachicar committed Mar 22, 2022
1 parent 1453615 commit c52e2e3
Show file tree
Hide file tree
Showing 2 changed files with 25 additions and 19 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -117,13 +117,15 @@ class SubscriptionManager
return matched;
}

std::future<void> spin_subscriptions()
std::future<void> spin_subscriptions(int maximum_time_spinning_sec = 10)
{
return async(
std::launch::async, [this]() {
std::launch::async, [this, maximum_time_spinning_sec]() {
rclcpp::executors::SingleThreadedExecutor exec;
auto start = std::chrono::high_resolution_clock::now();
while (rclcpp::ok() && continue_spinning(expected_topics_with_size_, start)) {
while (rclcpp::ok() &&
continue_spinning(expected_topics_with_size_, start, maximum_time_spinning_sec))
{
exec.spin_node_some(subscriber_node_);
}
});
Expand All @@ -132,10 +134,11 @@ class SubscriptionManager
private:
bool continue_spinning(
const std::unordered_map<std::string, size_t> & expected_topics_with_sizes,
std::chrono::time_point<std::chrono::high_resolution_clock> start_time)
std::chrono::time_point<std::chrono::high_resolution_clock> start_time,
int maximum_time_spinning_sec = 10)
{
auto current = std::chrono::high_resolution_clock::now();
if (current - start_time > std::chrono::seconds(10)) {
if (current - start_time > std::chrono::seconds(maximum_time_spinning_sec)) {
return false;
}

Expand Down
31 changes: 17 additions & 14 deletions rosbag2_transport/test/rosbag2_transport/test_play_for.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,8 @@ constexpr bool kBool1Value{false};
constexpr bool kBool2Value{true};
constexpr bool kBool3Value{false};

constexpr int kMaximumTimeSpinningSec{1};

#define EVAL_REPLAYED_PRIMITIVES(replayed_primitives) \
EXPECT_THAT( \
replayed_primitives, \
Expand Down Expand Up @@ -104,12 +106,12 @@ class RosBag2PlayForTestFixture : public RosBag2PlayTestFixture
// around without any knowledge about message chronology. It just picks
// the next one Make sure to keep the list in order or sort it!
std::vector<std::shared_ptr<rosbag2_storage::SerializedBagMessage>> messages =
{serialize_test_message(kTopic1Name, 500, primitive_message1),
serialize_test_message(kTopic2Name, 550, complex_message1),
serialize_test_message(kTopic1Name, 700, primitive_message1),
serialize_test_message(kTopic2Name, 750, complex_message1),
serialize_test_message(kTopic1Name, 900, primitive_message1),
serialize_test_message(kTopic2Name, 950, complex_message1)};
{serialize_test_message(kTopic1Name, 100, primitive_message1),
serialize_test_message(kTopic2Name, 120, complex_message1),
serialize_test_message(kTopic1Name, 200, primitive_message1),
serialize_test_message(kTopic2Name, 220, complex_message1),
serialize_test_message(kTopic1Name, 300, primitive_message1),
serialize_test_message(kTopic2Name, 320, complex_message1)};
// @}
return messages;
}
Expand All @@ -128,11 +130,12 @@ class RosBag2PlayForTestFixture : public RosBag2PlayTestFixture

play_options_.playback_duration = rclcpp::Duration(std::chrono::milliseconds(milliseconds));
player_ = std::make_shared<MockPlayer>(std::move(reader), storage_options_, play_options_);

// Wait for discovery to match publishers with subscribers
ASSERT_TRUE(
sub_->spin_and_wait_for_matched(player_->get_list_of_publishers(), std::chrono::seconds(5)));

auto await_received_messages = sub_->spin_subscriptions();
auto await_received_messages = sub_->spin_subscriptions(kMaximumTimeSpinningSec);

ASSERT_TRUE(player_->play());

Expand All @@ -145,7 +148,7 @@ class RosBag2PlayForTestFixture : public RosBag2PlayTestFixture

TEST_F(RosBag2PlayForTestFixture, play_for_all_are_played_due_to_duration)
{
InitPlayerWithPlaybackDurationAndPlay(1000);
InitPlayerWithPlaybackDurationAndPlay(350);

auto replayed_test_primitives = sub_->get_received_messages<test_msgs::msg::BasicTypes>(
kTopic1);
Expand All @@ -161,7 +164,7 @@ TEST_F(RosBag2PlayForTestFixture, play_for_all_are_played_due_to_duration)

TEST_F(RosBag2PlayForTestFixture, play_for_none_are_played_due_to_duration)
{
InitPlayerWithPlaybackDurationAndPlay(300);
InitPlayerWithPlaybackDurationAndPlay(50);

auto replayed_test_primitives = sub_->get_received_messages<test_msgs::msg::BasicTypes>(
kTopic1);
Expand All @@ -174,7 +177,7 @@ TEST_F(RosBag2PlayForTestFixture, play_for_none_are_played_due_to_duration)

TEST_F(RosBag2PlayForTestFixture, play_for_less_than_the_total_duration)
{
InitPlayerWithPlaybackDurationAndPlay(800);
InitPlayerWithPlaybackDurationAndPlay(270);

auto replayed_test_primitives = sub_->get_received_messages<test_msgs::msg::BasicTypes>(
kTopic1);
Expand Down Expand Up @@ -202,7 +205,7 @@ TEST_F(
RosBag2PlayForFilteredTopicTestFixture,
play_for_full_duration_recorded_messages_with_filtered_topics)
{
InitPlayerWithPlaybackDurationAndPlay(1000);
InitPlayerWithPlaybackDurationAndPlay(400);

auto replayed_test_primitives =
sub_->get_received_messages<test_msgs::msg::BasicTypes>("/topic1");
Expand All @@ -220,7 +223,7 @@ TEST_F(
RosBag2PlayForFilteredTopicTestFixture,
play_for_short_duration_recorded_messages_with_filtered_topics)
{
InitPlayerWithPlaybackDurationAndPlay(300);
InitPlayerWithPlaybackDurationAndPlay(50);

auto replayed_test_primitives =
sub_->get_received_messages<test_msgs::msg::BasicTypes>("/topic1");
Expand All @@ -236,7 +239,7 @@ TEST_F(
RosBag2PlayForFilteredTopicTestFixture,
play_for_intermediate_duration_recorded_messages_with_filtered_topics)
{
InitPlayerWithPlaybackDurationAndPlay(800);
InitPlayerWithPlaybackDurationAndPlay(270);

auto replayed_test_primitives =
sub_->get_received_messages<test_msgs::msg::BasicTypes>("/topic1");
Expand Down Expand Up @@ -301,7 +304,7 @@ TEST_F(
ASSERT_TRUE(
sub_->spin_and_wait_for_matched(player_->get_list_of_publishers(), std::chrono::seconds(5)));

auto await_received_messages = sub_->spin_subscriptions();
auto await_received_messages = sub_->spin_subscriptions(kMaximumTimeSpinningSec);
player_->pause();
auto player_future = std::async(std::launch::async, [player_]() {return player_->play();});
player_->wait_for_playback_to_start();
Expand Down

0 comments on commit c52e2e3

Please sign in to comment.